blob: fac7e8172bc964bf4b37133951e046dd2d258e7f [file] [log] [blame]
Maxwell Henderson123c8172024-03-01 22:54:16 -08001#include <string>
2
3#include "Eigen/Dense"
4#include "opencv2/aruco.hpp"
5#include "opencv2/calib3d.hpp"
6#include "opencv2/core/eigen.hpp"
7#include "opencv2/features2d.hpp"
8#include "opencv2/highgui.hpp"
9#include "opencv2/highgui/highgui.hpp"
10#include "opencv2/imgproc.hpp"
11
12#include "aos/configuration.h"
13#include "aos/events/logging/log_reader.h"
14#include "aos/events/simulated_event_loop.h"
15#include "aos/init.h"
16#include "aos/util/mcap_logger.h"
17#include "frc971/constants/constants_sender_lib.h"
18#include "frc971/control_loops/pose.h"
19#include "frc971/vision/calibration_generated.h"
20#include "frc971/vision/charuco_lib.h"
21#include "frc971/vision/target_mapper.h"
22#include "frc971/vision/vision_util_lib.h"
23#include "frc971/vision/visualize_robot.h"
24#include "y2024/constants/simulated_constants_sender.h"
25#include "y2024/vision/vision_util.h"
26
27DEFINE_string(config, "",
28 "If set, override the log's config file with this one.");
29DEFINE_string(constants_path, "y2024/constants/constants.json",
30 "Path to the constant file");
31DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
32 "Write the target constraints to this path");
33DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
34 "Write the mapping stats to this path");
Jim Ostrowski5ff3c562024-03-20 20:35:11 -070035DEFINE_string(field_name, "crescendo",
Maxwell Henderson123c8172024-03-01 22:54:16 -080036 "Field name, for the output json filename and flatbuffer field");
37DEFINE_string(json_path, "y2024/vision/maps/target_map.json",
38 "Specify path for json with initial pose guesses.");
39DEFINE_double(max_pose_error, 1e-6,
40 "Throw out target poses with a higher pose error than this");
41DEFINE_double(
42 max_pose_error_ratio, 0.4,
43 "Throw out target poses with a higher pose error ratio than this");
44DEFINE_string(mcap_output_path, "", "Log to output.");
45DEFINE_string(output_dir, "y2024/vision/maps",
46 "Directory to write solved target map to");
Maxwell Henderson9d7b1862024-03-02 11:00:29 -080047DEFINE_double(pause_on_distance, 2.0,
Maxwell Henderson123c8172024-03-01 22:54:16 -080048 "Pause if two consecutive implied robot positions differ by more "
49 "than this many meters");
50DEFINE_string(orin, "orin1",
51 "Orin name to generate mcap log for; defaults to pi1.");
52DEFINE_uint64(skip_to, 1,
53 "Start at combined image of this number (1 is the first image)");
54DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
Jim Ostrowski5ff3c562024-03-20 20:35:11 -070055DEFINE_bool(split_field, false,
56 "Whether to break solve into two sides of field");
Maxwell Henderson123c8172024-03-01 22:54:16 -080057DEFINE_int32(team_number, 0,
58 "Required: Use the calibration for a node with this team number");
59DEFINE_uint64(wait_key, 1,
60 "Time in ms to wait between images, if no click (0 to wait "
61 "indefinitely until click).");
62
63DECLARE_int32(frozen_target_id);
64DECLARE_int32(min_target_id);
65DECLARE_int32(max_target_id);
66DECLARE_bool(visualize_solver);
67
68namespace y2024::vision {
69using frc971::vision::DataAdapter;
70using frc971::vision::ImageCallback;
71using frc971::vision::PoseUtils;
72using frc971::vision::TargetMap;
73using frc971::vision::TargetMapper;
74using frc971::vision::VisualizeRobot;
75namespace calibration = frc971::vision::calibration;
76
77// Class to handle reading target poses from a replayed log,
78// displaying various debug info, and passing the poses to
79// frc971::vision::TargetMapper for field mapping.
80class TargetMapperReplay {
81 public:
82 TargetMapperReplay(aos::logger::LogReader *reader);
83
84 // Solves for the target poses with the accumulated detections if FLAGS_solve.
85 void MaybeSolve();
86
87 private:
88 static constexpr int kImageWidth = 1280;
89 // Map from pi node name to color for drawing
90 static const std::map<std::string, cv::Scalar> kOrinColors;
91 // Contains fixed target poses without solving, for use with visualization
92 static const TargetMapper kFixedTargetMapper;
93
Jim Ostrowski5ff3c562024-03-20 20:35:11 -070094 // Map of TargetId to alliance "color" for splitting field
95 static std::map<uint, std::string> kIdAllianceMap;
96
Maxwell Henderson123c8172024-03-01 22:54:16 -080097 // Change reference frame from camera to robot
98 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
99 Eigen::Affine3d extrinsics);
100
101 // Adds april tag detections into the detection list, and handles
102 // visualization
103 void HandleAprilTags(const TargetMap &map,
104 aos::distributed_clock::time_point node_distributed_time,
105 std::string camera_name, Eigen::Affine3d extrinsics);
Maxwell Henderson123c8172024-03-01 22:54:16 -0800106 // Gets images from the given pi and passes apriltag positions to
107 // HandleAprilTags()
108 void HandleNodeCaptures(
109 aos::EventLoop *mapping_event_loop,
110 frc971::constants::ConstantsFetcher<y2024::Constants> *constants_fetcher,
111 int camera_number);
112
113 aos::logger::LogReader *reader_;
114 // April tag detections from all pis
115 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
116
117 VisualizeRobot vis_robot_;
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700118 // Set of camera names which are currently drawn on the display
119 std::set<std::string> drawn_cameras_;
Maxwell Henderson123c8172024-03-01 22:54:16 -0800120 // Number of frames displayed
121 size_t display_count_;
122 // Last time we drew onto the display image.
123 // This is different from when we actually call imshow() to update
124 // the display window
125 aos::distributed_clock::time_point last_draw_time_;
126
127 Eigen::Affine3d last_H_world_robot_;
128 // Maximum distance between consecutive T_world_robot's in one display frame,
129 // used to determine if we need to pause for the user to see this frame
130 // clearly
131 double max_delta_T_world_robot_;
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700132 double ignore_count_;
133
134 std::map<std::string, int> camera_numbering_map_;
Maxwell Henderson123c8172024-03-01 22:54:16 -0800135
136 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
137
138 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
139 std::unique_ptr<aos::McapLogger> relogger_;
140};
141
142const auto TargetMapperReplay::kOrinColors = std::map<std::string, cv::Scalar>{
143 {"/orin1/camera0", cv::Scalar(255, 0, 255)},
144 {"/orin1/camera1", cv::Scalar(255, 255, 0)},
145 {"/imu/camera0", cv::Scalar(0, 255, 255)},
146 {"/imu/camera1", cv::Scalar(255, 165, 0)},
147};
148
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700149std::map<uint, std::string> TargetMapperReplay::kIdAllianceMap = {
150 {1, "red"}, {2, "red"}, {3, "red"}, {4, "red"},
151 {5, "red"}, {6, "blue"}, {7, "blue"}, {8, "blue"},
152 {9, "blue"}, {10, "blue"}, {11, "red"}, {12, "red"},
153 {13, "red"}, {14, "blue"}, {15, "blue"}, {16, "blue"}};
154
Maxwell Henderson123c8172024-03-01 22:54:16 -0800155const auto TargetMapperReplay::kFixedTargetMapper =
156 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
157
158Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
159 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
160 const Eigen::Affine3d H_robot_camera = extrinsics;
161 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
162 return H_robot_target;
163}
164
165TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
166 : reader_(reader),
167 timestamped_target_detections_(),
168 vis_robot_(cv::Size(1280, 1000)),
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700169 drawn_cameras_(),
Maxwell Henderson123c8172024-03-01 22:54:16 -0800170 display_count_(0),
171 last_draw_time_(aos::distributed_clock::min_time),
172 last_H_world_robot_(Eigen::Matrix4d::Identity()),
173 max_delta_T_world_robot_(0.0) {
174 reader_->RemapLoggedChannel("/orin1/constants", "y2024.Constants");
175 reader_->RemapLoggedChannel("/imu/constants", "y2024.Constants");
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700176 // If it's Box of Orins, don't remap roborio constants
177 if (FLAGS_team_number == 7971) {
178 reader_->RemapLoggedChannel("/roborio/constants", "y2024.Constants");
179 }
Maxwell Henderson123c8172024-03-01 22:54:16 -0800180 reader_->Register();
181
182 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
183 FLAGS_constants_path);
184
185 std::vector<std::string> node_list;
186 node_list.push_back("imu");
187 node_list.push_back("orin1");
188
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700189 int camera_count = 0;
Maxwell Henderson123c8172024-03-01 22:54:16 -0800190 for (std::string node : node_list) {
191 const aos::Node *pi =
192 aos::configuration::GetNode(reader->configuration(), node);
193
194 mapping_event_loops_.emplace_back(
195 reader_->event_loop_factory()->MakeEventLoop(node + "_mapping_camera0",
196 pi));
197 mapping_event_loops_.emplace_back(
198 reader_->event_loop_factory()->MakeEventLoop(node + "_mapping_camera1",
199 pi));
200 frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
201 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
202 HandleNodeCaptures(
203 mapping_event_loops_[mapping_event_loops_.size() - 2].get(),
204 &constants_fetcher, 0);
205 HandleNodeCaptures(
206 mapping_event_loops_[mapping_event_loops_.size() - 1].get(),
207 &constants_fetcher, 1);
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700208 std::string camera0_name = "/" + node + "/camera0";
209 camera_numbering_map_[camera0_name] = camera_count++;
210 std::string camera1_name = "/" + node + "/camera1";
211 camera_numbering_map_[camera1_name] = camera_count++;
Maxwell Henderson123c8172024-03-01 22:54:16 -0800212 }
213
214 if (FLAGS_visualize_solver) {
215 vis_robot_.ClearImage();
216 const double kFocalLength = 500.0;
217 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
218 }
219}
220
221// Add detected apriltag poses relative to the robot to
222// timestamped_target_detections
223void TargetMapperReplay::HandleAprilTags(
224 const TargetMap &map,
225 aos::distributed_clock::time_point node_distributed_time,
226 std::string camera_name, Eigen::Affine3d extrinsics) {
227 bool drew = false;
228 std::stringstream label;
229 label << camera_name << " - ";
230
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700231 if (map.target_poses()->size() == 0) {
232 VLOG(2) << "Got 0 AprilTags for camera " << camera_name;
233 return;
234 }
235
Maxwell Henderson123c8172024-03-01 22:54:16 -0800236 for (const auto *target_pose_fbs : *map.target_poses()) {
237 // Skip detections with invalid ids
238 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
239 FLAGS_min_target_id ||
240 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
241 FLAGS_max_target_id) {
242 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
243 continue;
244 }
245
246 // Skip detections with high pose errors
247 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
248 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
249 << " due to pose error of " << target_pose_fbs->pose_error();
250 continue;
251 }
252 // Skip detections with high pose error ratios
253 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
254 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
255 << " due to pose error ratio of "
256 << target_pose_fbs->pose_error_ratio();
257 continue;
258 }
259
260 const TargetMapper::TargetPose target_pose =
261 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
262
263 Eigen::Affine3d H_camera_target =
264 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
265 Eigen::Affine3d H_robot_target =
266 CameraToRobotDetection(H_camera_target, extrinsics);
267
268 ceres::examples::Pose3d target_pose_camera =
269 PoseUtils::Affine3dToPose3d(H_camera_target);
270 double distance_from_camera = target_pose_camera.p.norm();
271 double distortion_factor = target_pose_fbs->distortion_factor();
272
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700273 double distance_threshold = 5.0;
274 if (distance_from_camera > distance_threshold) {
275 ignore_count_++;
276 LOG(INFO) << "Ignored " << ignore_count_ << " AprilTags with distance "
277 << distance_from_camera << " > " << distance_threshold;
Maxwell Henderson123c8172024-03-01 22:54:16 -0800278 continue;
279 }
280
281 CHECK(map.has_monotonic_timestamp_ns())
282 << "Need detection timestamps for mapping";
283
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700284 // Detection is usable, so store it
Maxwell Henderson123c8172024-03-01 22:54:16 -0800285 timestamped_target_detections_.emplace_back(
286 DataAdapter::TimestampedDetection{
287 .time = node_distributed_time,
288 .H_robot_target = H_robot_target,
289 .distance_from_camera = distance_from_camera,
290 .distortion_factor = distortion_factor,
291 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
292
293 if (FLAGS_visualize_solver) {
294 // If we've already drawn this camera_name in the current image,
295 // display the image before clearing and adding the new poses
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700296 if (drawn_cameras_.count(camera_name) != 0) {
Maxwell Henderson123c8172024-03-01 22:54:16 -0800297 display_count_++;
298 cv::putText(vis_robot_.image_,
299 "Poses #" + std::to_string(display_count_),
300 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
301 cv::Scalar(255, 255, 255));
302
303 if (display_count_ >= FLAGS_skip_to) {
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700304 VLOG(1) << "Showing image for camera " << camera_name
Maxwell Henderson123c8172024-03-01 22:54:16 -0800305 << " since we've drawn it already";
306 cv::imshow("View", vis_robot_.image_);
307 // Pause if delta_T is too large, but only after first image (to make
308 // sure the delta's are correct
309 if (max_delta_T_world_robot_ > FLAGS_pause_on_distance &&
310 display_count_ > 1) {
311 LOG(INFO) << "Pausing since the delta between robot estimates is "
312 << max_delta_T_world_robot_ << " which is > threshold of "
313 << FLAGS_pause_on_distance;
314 cv::waitKey(0);
315 } else {
316 cv::waitKey(FLAGS_wait_key);
317 }
318 max_delta_T_world_robot_ = 0.0;
319 } else {
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700320 VLOG(2) << "At poses #" << std::to_string(display_count_);
Maxwell Henderson123c8172024-03-01 22:54:16 -0800321 }
322 vis_robot_.ClearImage();
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700323 drawn_cameras_.clear();
Maxwell Henderson123c8172024-03-01 22:54:16 -0800324 }
325
326 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
327 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
328 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
329 VLOG(2) << camera_name << ", id " << target_pose_fbs->id()
330 << ", t = " << node_distributed_time
331 << ", pose_error = " << target_pose_fbs->pose_error()
332 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
333 << ", robot_pos (x,y,z) = "
334 << H_world_robot.translation().transpose();
335
336 label << "id " << target_pose_fbs->id() << ": err (% of max): "
337 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
338 << " err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
339
340 vis_robot_.DrawRobotOutline(H_world_robot, camera_name,
341 kOrinColors.at(camera_name));
342 vis_robot_.DrawFrameAxes(H_world_target,
343 std::to_string(target_pose_fbs->id()),
344 kOrinColors.at(camera_name));
345
346 double delta_T_world_robot =
347 (H_world_robot.translation() - last_H_world_robot_.translation())
348 .norm();
349 max_delta_T_world_robot_ =
350 std::max(delta_T_world_robot, max_delta_T_world_robot_);
351
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700352 VLOG(1) << "Drew in info for camera " << camera_name << " and target #"
Maxwell Henderson123c8172024-03-01 22:54:16 -0800353 << target_pose_fbs->id();
354 drew = true;
355 last_draw_time_ = node_distributed_time;
356 last_H_world_robot_ = H_world_robot;
357 }
358 }
Maxwell Henderson123c8172024-03-01 22:54:16 -0800359 if (FLAGS_visualize_solver) {
360 if (drew) {
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700361 // Collect all the labels from a given camera, and add the text
362 // TODO: Need to fix this one
363 int position_number = camera_numbering_map_[camera_name];
Maxwell Henderson123c8172024-03-01 22:54:16 -0800364 cv::putText(vis_robot_.image_, label.str(),
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700365 cv::Point(10, 10 + 20 * position_number),
366 cv::FONT_HERSHEY_PLAIN, 1.0, kOrinColors.at(camera_name));
Maxwell Henderson123c8172024-03-01 22:54:16 -0800367
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700368 drawn_cameras_.emplace(camera_name);
Maxwell Henderson123c8172024-03-01 22:54:16 -0800369 } else if (node_distributed_time - last_draw_time_ >
370 std::chrono::milliseconds(30) &&
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700371 display_count_ >= FLAGS_skip_to && drew) {
372 // TODO: Check on 30ms value-- does this make sense?
373 double delta_t = (node_distributed_time - last_draw_time_).count() / 1e6;
374 VLOG(1) << "Last result was " << delta_t << "ms ago";
375 cv::putText(vis_robot_.image_, "No detections in last 30ms",
376 cv::Point(10, 0), cv::FONT_HERSHEY_PLAIN, 1.0,
377 kOrinColors.at(camera_name));
Maxwell Henderson123c8172024-03-01 22:54:16 -0800378 // Display and clear the image if we haven't draw in a while
379 VLOG(1) << "Displaying image due to time lapse";
380 cv::imshow("View", vis_robot_.image_);
381 cv::waitKey(FLAGS_wait_key);
382 vis_robot_.ClearImage();
383 max_delta_T_world_robot_ = 0.0;
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700384 drawn_cameras_.clear();
Maxwell Henderson123c8172024-03-01 22:54:16 -0800385 }
386 }
387}
388
389void TargetMapperReplay::HandleNodeCaptures(
390 aos::EventLoop *mapping_event_loop,
391 frc971::constants::ConstantsFetcher<y2024::Constants> *constants_fetcher,
392 int camera_number) {
393 // Get the camera extrinsics
394 const auto *calibration = FindCameraCalibration(
395 constants_fetcher->constants(),
396 mapping_event_loop->node()->name()->string_view(), camera_number);
397 cv::Mat extrinsics_cv = frc971::vision::CameraExtrinsics(calibration).value();
398 Eigen::Matrix4d extrinsics_matrix;
399 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
400 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
401 std::string camera_name = absl::StrFormat(
402 "/%s/camera%d", mapping_event_loop->node()->name()->str(), camera_number);
403
404 mapping_event_loop->MakeWatcher(
405 camera_name.c_str(), [this, mapping_event_loop, extrinsics,
406 camera_name](const TargetMap &map) {
407 aos::distributed_clock::time_point node_distributed_time =
408 reader_->event_loop_factory()
409 ->GetNodeEventLoopFactory(mapping_event_loop->node())
410 ->ToDistributedClock(aos::monotonic_clock::time_point(
411 aos::monotonic_clock::duration(
412 map.monotonic_timestamp_ns())));
413
414 HandleAprilTags(map, node_distributed_time, camera_name, extrinsics);
415 });
416}
417
418void TargetMapperReplay::MaybeSolve() {
419 if (FLAGS_solve) {
420 auto target_constraints =
421 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
422
Jim Ostrowski5ff3c562024-03-20 20:35:11 -0700423 if (FLAGS_split_field) {
424 // Remove constraints between the two sides of the field - these are
425 // basically garbage because of how far the camera is. We will use seeding
426 // below to connect the two sides
427 target_constraints.erase(
428 std::remove_if(
429 target_constraints.begin(), target_constraints.end(),
430 [](const auto &constraint) {
431 return (
432 kIdAllianceMap[static_cast<uint>(constraint.id_begin)] !=
433 kIdAllianceMap[static_cast<uint>(constraint.id_end)]);
434 }),
435 target_constraints.end());
436 }
Maxwell Henderson123c8172024-03-01 22:54:16 -0800437
438 LOG(INFO) << "Solving for locations of tags with "
439 << target_constraints.size() << " constraints";
440 TargetMapper mapper(FLAGS_json_path, target_constraints);
441 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
442
443 if (!FLAGS_dump_constraints_to.empty()) {
444 mapper.DumpConstraints(FLAGS_dump_constraints_to);
445 }
446 if (!FLAGS_dump_stats_to.empty()) {
447 mapper.DumpStats(FLAGS_dump_stats_to);
448 }
449 }
450}
451
452void MappingMain(int argc, char *argv[]) {
453 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
454
455 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
456 (FLAGS_config.empty()
457 ? std::nullopt
458 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
459
460 // Open logfiles
461 aos::logger::LogReader reader(
462 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
463 config.has_value() ? &config->message() : nullptr);
464
465 TargetMapperReplay mapper_replay(&reader);
466 reader.event_loop_factory()->Run();
467 mapper_replay.MaybeSolve();
468}
469
470} // namespace y2024::vision
471
472int main(int argc, char **argv) {
473 aos::InitGoogle(&argc, &argv);
474 y2024::vision::MappingMain(argc, argv);
475}