blob: 99b67d2cdf8cc7d1118a1591898fd44e4c8f4e5c [file] [log] [blame]
Milind Upadhyay7c205222022-11-16 18:20:58 -08001#include "frc971/vision/target_mapper.h"
2
Milind Upadhyayc5beba12022-12-17 17:41:20 -08003#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07004
Milind Upadhyay7c205222022-11-16 18:20:58 -08005#include "frc971/control_loops/control_loop.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08006#include "frc971/vision/ceres/pose_graph_3d_error_term.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08007#include "frc971/vision/geometry.h"
Jim Ostrowski6d242d52024-04-03 20:39:03 -07008#include "frc971/vision/vision_util_lib.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08009
Austin Schuh99f7c6a2024-06-25 22:07:44 -070010ABSL_FLAG(uint64_t, max_num_iterations, 100,
11 "Maximum number of iterations for the ceres solver");
12ABSL_FLAG(double, distortion_noise_scalar, 1.0,
13 "Scale the target pose distortion factor by this when computing "
14 "the noise.");
15ABSL_FLAG(
16 int32_t, frozen_target_id, 1,
milind-u6ff399f2023-03-24 18:33:38 -070017 "Freeze the pose of this target so the map can have one fixed point.");
Austin Schuh99f7c6a2024-06-25 22:07:44 -070018ABSL_FLAG(int32_t, min_target_id, 1, "Minimum target id to solve for");
19ABSL_FLAG(int32_t, max_target_id, 8, "Maximum target id to solve for");
20ABSL_FLAG(bool, visualize_solver, false,
21 "If true, visualize the solving process.");
milind-u401de982023-04-14 17:32:03 -070022// This does seem like a strict threshold for a constaint to be considered an
23// outlier, but most inliers were very close together and this is what worked
24// best for map solving.
Austin Schuh99f7c6a2024-06-25 22:07:44 -070025ABSL_FLAG(double, outlier_std_devs, 1.0,
26 "Number of standard deviations above average error needed for a "
27 "constraint to be considered an outlier and get removed.");
28ABSL_FLAG(bool, do_map_fitting, false,
29 "Whether to do a final fit of the solved map to the original map");
Milind Upadhyay7c205222022-11-16 18:20:58 -080030
31namespace frc971::vision {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080032ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -080033 const std::vector<DataAdapter::TimestampedDetection>
34 &timestamped_target_detections,
35 aos::distributed_clock::duration max_dt) {
36 CHECK_GE(timestamped_target_detections.size(), 2ul)
37 << "Must have at least 2 detections";
38
39 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -080040 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -080041 for (auto detection = timestamped_target_detections.begin() + 1;
42 detection < timestamped_target_detections.end(); detection++) {
Maxwell Henderson9beb5692024-03-17 18:36:11 -070043 for (int past = 1;
44 past <=
45 std::min<int>(4, detection - timestamped_target_detections.begin());
46 ++past) {
47 auto last_detection = detection - past;
Milind Upadhyayec493912022-12-18 21:33:15 -080048
Maxwell Henderson9beb5692024-03-17 18:36:11 -070049 // Skip two consecutive detections of the same target, because the solver
50 // doesn't allow this
51 if (detection->id == last_detection->id) {
52 continue;
53 }
54
55 // Don't take into account constraints too far apart in time, because the
56 // recording device could have moved too much
57 if ((detection->time - last_detection->time) > max_dt) {
58 continue;
59 }
60
61 auto confidence = ComputeConfidence(*last_detection, *detection);
62 target_constraints.emplace_back(
63 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -080064 }
Milind Upadhyayec493912022-12-18 21:33:15 -080065 }
66
67 return target_constraints;
68}
69
Milind Upadhyayc5beba12022-12-17 17:41:20 -080070TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -080071 const TimestampedDetection &detection_start,
72 const TimestampedDetection &detection_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080073 constexpr size_t kX = 0;
74 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080075 constexpr size_t kZ = 2;
76 constexpr size_t kOrientation1 = 3;
77 constexpr size_t kOrientation2 = 4;
78 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -080079
80 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -080081 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -080082
83 {
84 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -080085 TargetMapper::ConfidenceMatrix Q_odometry =
86 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -080087 Q_odometry(kX, kX) = std::pow(0.045, 2);
88 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080089 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
90 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
91 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
92 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080093
94 // Add uncertainty for robot position measurements from start to end
milind-ud62f80a2023-03-04 16:37:09 -080095 int iterations = (detection_end.time - detection_start.time) /
96 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -080097 P += static_cast<double>(iterations) * Q_odometry;
98 }
99
100 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800101 // Noise for vision-based target localizations. Multiplying this matrix by
milind-u6ff399f2023-03-24 18:33:38 -0700102 // the distance from camera to target squared results in the uncertainty
103 // in that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800104 TargetMapper::ConfidenceMatrix Q_vision =
105 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800106 Q_vision(kX, kX) = std::pow(0.045, 2);
107 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800108 Q_vision(kZ, kZ) = std::pow(0.045, 2);
109 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
110 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
111 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800112
113 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700114 P += Q_vision *
115 std::pow(detection_start.distance_from_camera *
116 (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
117 detection_start.distortion_factor),
118 2);
119 P += Q_vision *
120 std::pow(detection_end.distance_from_camera *
121 (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
122 detection_end.distortion_factor),
123 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800124 }
125
126 return P.inverse();
127}
128
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800129ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800130 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800131 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800132 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800133 // Compute the relative pose (constraint) between the two targets
134 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800135 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800136 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800137 ceres::examples::Pose3d target_constraint =
138 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800139
milind-uf3ab8ba2023-02-04 17:56:16 -0800140 const auto constraint_3d =
141 ceres::examples::Constraint3d{target_detection_start.id,
142 target_detection_end.id,
143 {target_constraint.p, target_constraint.q},
144 confidence};
145
146 VLOG(2) << "Computed constraint: " << constraint_3d;
147 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800148}
149
Milind Upadhyay7c205222022-11-16 18:20:58 -0800150TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800151 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800152 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700153 : target_constraints_(target_constraints),
154 T_frozen_actual_(Eigen::Vector3d::Zero()),
155 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700156 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800157 // Compute focal length so that image shows field with viewpoint at 10m above
158 // it (default for viewer)
159 const double focal_length = kImageWidth_ * 10.0 / kFieldWidth_;
160 vis_robot_.SetDefaultViewpoint(kImageWidth_, focal_length);
161
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800162 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
163 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
164 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u8f4e43e2023-04-09 17:11:19 -0700165 ideal_target_poses_[target_pose_fbs->id()] =
Jim Ostrowski6d242d52024-04-03 20:39:03 -0700166 TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800167 }
milind-u8f4e43e2023-04-09 17:11:19 -0700168 target_poses_ = ideal_target_poses_;
milind-u526d5672023-04-17 20:09:10 -0700169 CountConstraints();
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800170}
171
172TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800173 const ceres::examples::MapOfPoses &target_poses,
174 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700175 : ideal_target_poses_(target_poses),
176 target_poses_(ideal_target_poses_),
177 target_constraints_(target_constraints),
178 T_frozen_actual_(Eigen::Vector3d::Zero()),
179 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700180 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
milind-u526d5672023-04-17 20:09:10 -0700181 CountConstraints();
182}
183
Jim Ostrowski6d242d52024-04-03 20:39:03 -0700184flatbuffers::Offset<TargetPoseFbs> TargetMapper::TargetPoseToFbs(
185 const TargetMapper::TargetPose &target_pose,
186 flatbuffers::FlatBufferBuilder *fbb) {
187 const auto position_offset =
188 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
189 target_pose.pose.p(2));
190 const auto orientation_offset =
191 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
192 target_pose.pose.q.y(), target_pose.pose.q.z());
193 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
194 orientation_offset);
195}
196
197TargetMapper::TargetPose TargetMapper::TargetPoseFromFbs(
198 const TargetPoseFbs &target_pose_fbs) {
199 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
200 .pose = ceres::examples::Pose3d{
201 Eigen::Vector3d(target_pose_fbs.position()->x(),
202 target_pose_fbs.position()->y(),
203 target_pose_fbs.position()->z()),
204 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
205 target_pose_fbs.orientation()->x(),
206 target_pose_fbs.orientation()->y(),
207 target_pose_fbs.orientation()->z())
208 .normalized()}};
209}
210
milind-u526d5672023-04-17 20:09:10 -0700211namespace {
212std::pair<TargetMapper::TargetId, TargetMapper::TargetId> MakeIdPair(
213 const ceres::examples::Constraint3d &constraint) {
214 auto min_id = std::min(constraint.id_begin, constraint.id_end);
215 auto max_id = std::max(constraint.id_begin, constraint.id_end);
216 return std::make_pair(min_id, max_id);
217}
218} // namespace
219
220void TargetMapper::CountConstraints() {
221 for (const auto &constraint : target_constraints_) {
222 auto id_pair = MakeIdPair(constraint);
223 if (constraint_counts_.count(id_pair) == 0) {
224 constraint_counts_[id_pair] = 0;
225 }
226 constraint_counts_[id_pair]++;
227 }
228}
Milind Upadhyay7c205222022-11-16 18:20:58 -0800229
230std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
231 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
232 for (auto target_pose : target_poses) {
233 if (target_pose.id == target_id) {
234 return target_pose;
235 }
236 }
237
238 return std::nullopt;
239}
240
Jim Ostrowski49be8232023-03-23 01:00:14 -0700241std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
milind-u2ab4db12023-03-25 21:59:23 -0700242 TargetId target_id) const {
Jim Ostrowski49be8232023-03-23 01:00:14 -0700243 if (target_poses_.count(target_id) > 0) {
milind-u2ab4db12023-03-25 21:59:23 -0700244 return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700245 }
246
247 return std::nullopt;
248}
249
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800250// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
251// Constructs the nonlinear least squares optimization problem from the pose
252// graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700253void TargetMapper::BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800254 const ceres::examples::VectorOfConstraints &constraints,
255 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
256 CHECK(poses != nullptr);
257 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800258 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800259 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800260 return;
261 }
262
milind-u13ff1a52023-01-22 17:10:49 -0800263 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Austin Schuh31f99a22024-06-25 18:30:13 -0700264 ceres::Manifold *quaternion_local_parameterization =
265 new ceres::EigenQuaternionManifold();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800266
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700267 int min_constraint_id = std::numeric_limits<int>::max();
268 int max_constraint_id = std::numeric_limits<int>::min();
269
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800270 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
271 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800272 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800273 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800274
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800275 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800276 poses->find(constraint.id_begin);
277 CHECK(pose_begin_iter != poses->end())
278 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800279 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800280 poses->find(constraint.id_end);
281 CHECK(pose_end_iter != poses->end())
282 << "Pose with ID: " << constraint.id_end << " not found.";
283
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800284 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800285 constraint.information.llt().matrixL();
milind-u526d5672023-04-17 20:09:10 -0700286
287 auto id_pair = MakeIdPair(constraint);
288 CHECK_GT(constraint_counts_.count(id_pair), 0ul)
289 << "Should have counted constraints for " << id_pair.first << "->"
290 << id_pair.second;
291
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700292 VLOG(1) << "Adding constraint pair: " << id_pair.first << " and "
293 << id_pair.second;
294 // Store min & max id's; assumes first id < second id
295 if (id_pair.first < min_constraint_id) {
296 min_constraint_id = id_pair.first;
297 }
298 if (id_pair.second > max_constraint_id) {
299 max_constraint_id = id_pair.second;
300 }
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800301 // Normalize constraint cost by occurrences
milind-u526d5672023-04-17 20:09:10 -0700302 size_t constraint_count = constraint_counts_[id_pair];
303 // Scale all costs so the total cost comes out to more reasonable numbers
304 constexpr double kGlobalWeight = 1000.0;
305 double constraint_weight =
306 kGlobalWeight / static_cast<double>(constraint_count);
307
Milind Upadhyay7c205222022-11-16 18:20:58 -0800308 // Ceres will take ownership of the pointer.
309 ceres::CostFunction *cost_function =
milind-u526d5672023-04-17 20:09:10 -0700310 ceres::examples::PoseGraph3dErrorTerm::Create(
311 constraint.t_be, sqrt_information, constraint_weight);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800312
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800313 problem->AddResidualBlock(cost_function, loss_function,
314 pose_begin_iter->second.p.data(),
315 pose_begin_iter->second.q.coeffs().data(),
316 pose_end_iter->second.p.data(),
317 pose_end_iter->second.q.coeffs().data());
318
Austin Schuh31f99a22024-06-25 18:30:13 -0700319 problem->SetManifold(pose_begin_iter->second.q.coeffs().data(),
320 quaternion_local_parameterization);
321 problem->SetManifold(pose_end_iter->second.q.coeffs().data(),
322 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800323 }
324
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800325 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800326 // constrained. This is typically referred to as gauge freedom. You can
327 // apply a rigid body transformation to all the nodes and the optimization
328 // problem will still have the exact same cost. The Levenberg-Marquardt
329 // algorithm has internal damping which mitigates this issue, but it is
330 // better to properly constrain the gauge freedom. This can be done by
331 // setting one of the poses as constant so the optimizer cannot change it.
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700332 CHECK_NE(poses->count(absl::GetFlag(FLAGS_frozen_target_id)), 0ul)
333 << "Got no poses for frozen target id "
334 << absl::GetFlag(FLAGS_frozen_target_id);
335 CHECK_GE(absl::GetFlag(FLAGS_frozen_target_id), min_constraint_id)
336 << "target to freeze index " << absl::GetFlag(FLAGS_frozen_target_id)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700337 << " must be in range of constraints, > " << min_constraint_id;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700338 CHECK_LE(absl::GetFlag(FLAGS_frozen_target_id), max_constraint_id)
339 << "target to freeze index " << absl::GetFlag(FLAGS_frozen_target_id)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700340 << " must be in range of constraints, < " << max_constraint_id;
milind-u6ff399f2023-03-24 18:33:38 -0700341 ceres::examples::MapOfPoses::iterator pose_start_iter =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700342 poses->find(absl::GetFlag(FLAGS_frozen_target_id));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800343 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800344 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
345 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800346}
347
milind-u401de982023-04-14 17:32:03 -0700348std::unique_ptr<ceres::CostFunction>
349TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
Philipp Schradera6712522023-07-05 20:25:11 -0700350 // Set up robot visualization.
milind-u8f4e43e2023-04-09 17:11:19 -0700351 vis_robot_.ClearImage();
milind-u8f4e43e2023-04-09 17:11:19 -0700352
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700353 const size_t num_targets =
354 absl::GetFlag(FLAGS_max_target_id) - absl::GetFlag(FLAGS_min_target_id);
milind-u8f4e43e2023-04-09 17:11:19 -0700355 // Translation and rotation error for each target
356 const size_t num_residuals = num_targets * 6;
357 // Set up the only cost function (also known as residual). This uses
358 // auto-differentiation to obtain the derivative (jacobian).
milind-u401de982023-04-14 17:32:03 -0700359 std::unique_ptr<ceres::CostFunction> cost_function = std::make_unique<
360 ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>>(
361 this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
milind-u8f4e43e2023-04-09 17:11:19 -0700362
363 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Austin Schuh31f99a22024-06-25 18:30:13 -0700364 ceres::Manifold *quaternion_local_parameterization =
365 new ceres::EigenQuaternionManifold();
milind-u8f4e43e2023-04-09 17:11:19 -0700366
milind-u401de982023-04-14 17:32:03 -0700367 problem->AddResidualBlock(cost_function.get(), loss_function,
milind-u8f4e43e2023-04-09 17:11:19 -0700368 T_frozen_actual_.vector().data(),
369 R_frozen_actual_.coeffs().data());
Austin Schuh31f99a22024-06-25 18:30:13 -0700370 problem->SetManifold(R_frozen_actual_.coeffs().data(),
371 quaternion_local_parameterization);
milind-u401de982023-04-14 17:32:03 -0700372 return cost_function;
milind-u8f4e43e2023-04-09 17:11:19 -0700373}
374
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800375void TargetMapper::DisplayConstraintGraph() {
376 vis_robot_.ClearImage();
377 for (auto constraint : constraint_counts_) {
378 Eigen::Vector3d start_line =
379 PoseUtils::Pose3dToAffine3d(
380 ideal_target_poses_.at(constraint.first.first))
381 .translation();
382 Eigen::Vector3d end_line =
383 PoseUtils::Pose3dToAffine3d(
384 ideal_target_poses_.at(constraint.first.second))
385 .translation();
386 // Weight the green intensity by # of constraints
387 // TODO: This could be improved
388 int color_scale =
389 50 + std::min(155, static_cast<int>(constraint.second * 155.0 / 200.0));
390 vis_robot_.DrawLine(start_line, end_line, cv::Scalar(0, color_scale, 0));
391 }
392
393 for (const auto &[id, solved_pose] : target_poses_) {
394 Eigen::Affine3d H_world_ideal =
395 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
396 vis_robot_.DrawFrameAxes(H_world_ideal, std::to_string(id),
397 cv::Scalar(255, 255, 255));
398 }
399 cv::imshow("Constraint graph", vis_robot_.image_);
400 cv::waitKey(0);
401}
402
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700403void TargetMapper::DisplaySolvedVsInitial() {
404 vis_robot_.ClearImage();
405 for (const auto &[id, solved_pose] : target_poses_) {
406 Eigen::Affine3d H_world_initial =
407 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
408 vis_robot_.DrawFrameAxes(H_world_initial, std::to_string(id),
409 cv::Scalar(0, 0, 255));
410 Eigen::Affine3d H_world_solved = PoseUtils::Pose3dToAffine3d(solved_pose);
411 vis_robot_.DrawFrameAxes(H_world_solved, std::to_string(id) + "-est",
412 cv::Scalar(255, 255, 255));
413 }
414 cv::imshow("Solved vs. Initial", vis_robot_.image_);
415 cv::waitKey(0);
416}
417
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800418// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800419bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
Austin Schuh6bdcc372024-06-27 14:49:11 -0700420 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800421
422 ceres::Solver::Options options;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700423 options.max_num_iterations = absl::GetFlag(FLAGS_max_num_iterations);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800424 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
milind-u401de982023-04-14 17:32:03 -0700425 options.minimizer_progress_to_stdout = false;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800426
427 ceres::Solver::Summary summary;
428 ceres::Solve(options, problem, &summary);
429
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800430 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800431
432 return summary.IsSolutionUsable();
433}
434
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800435void TargetMapper::Solve(std::string_view field_name,
436 std::optional<std::string_view> output_dir) {
milind-u401de982023-04-14 17:32:03 -0700437 ceres::Problem target_pose_problem_1;
milind-u8f4e43e2023-04-09 17:11:19 -0700438 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
milind-u401de982023-04-14 17:32:03 -0700439 &target_pose_problem_1);
440 CHECK(SolveOptimizationProblem(&target_pose_problem_1))
441 << "The target pose solve 1 was not successful, exiting.";
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700442 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700443 LOG(INFO) << "Displaying constraint graph before removing outliers";
444 DisplayConstraintGraph();
445 DisplaySolvedVsInitial();
446 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800447
milind-u401de982023-04-14 17:32:03 -0700448 RemoveOutlierConstraints();
449
450 // Solve again once we've thrown out bad constraints
451 ceres::Problem target_pose_problem_2;
452 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
453 &target_pose_problem_2);
454 CHECK(SolveOptimizationProblem(&target_pose_problem_2))
455 << "The target pose solve 2 was not successful, exiting.";
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700456 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700457 LOG(INFO) << "Displaying constraint graph before removing outliers";
458 DisplayConstraintGraph();
459 DisplaySolvedVsInitial();
460 }
milind-u401de982023-04-14 17:32:03 -0700461
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700462 if (absl::GetFlag(FLAGS_do_map_fitting)) {
Jim Ostrowski463ee592024-03-07 00:08:24 -0800463 LOG(INFO) << "Solving the overall map's best alignment to the previous map";
464 ceres::Problem map_fitting_problem(
465 {.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
466 std::unique_ptr<ceres::CostFunction> map_fitting_cost_function =
467 BuildMapFittingOptimizationProblem(&map_fitting_problem);
468 CHECK(SolveOptimizationProblem(&map_fitting_problem))
469 << "The map fitting solve was not successful, exiting.";
470 map_fitting_cost_function.release();
milind-u8f4e43e2023-04-09 17:11:19 -0700471
Jim Ostrowski463ee592024-03-07 00:08:24 -0800472 Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_;
473 LOG(INFO) << "H_frozen_actual: "
474 << PoseUtils::Affine3dToPose3d(H_frozen_actual);
milind-u8f4e43e2023-04-09 17:11:19 -0700475
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700476 auto H_world_frozen = PoseUtils::Pose3dToAffine3d(
477 target_poses_[absl::GetFlag(FLAGS_frozen_target_id)]);
Jim Ostrowski463ee592024-03-07 00:08:24 -0800478 auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
milind-u8f4e43e2023-04-09 17:11:19 -0700479
Jim Ostrowski463ee592024-03-07 00:08:24 -0800480 // Offset the solved poses to become the actual ones
481 for (auto &[id, pose] : target_poses_) {
482 // Don't offset targets we didn't solve for
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700483 if (id < absl::GetFlag(FLAGS_min_target_id) ||
484 id > absl::GetFlag(FLAGS_max_target_id)) {
Jim Ostrowski463ee592024-03-07 00:08:24 -0800485 continue;
486 }
487
488 // Take the delta between the frozen target and the solved target, and put
489 // that on top of the actual pose of the frozen target
490 auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose);
491 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
492 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
493 pose = PoseUtils::Affine3dToPose3d(H_world_actual);
milind-u8f4e43e2023-04-09 17:11:19 -0700494 }
milind-u8f4e43e2023-04-09 17:11:19 -0700495 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800496
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800497 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800498 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800499
500 if (output_dir.has_value()) {
501 std::string output_path =
502 absl::StrCat(output_dir.value(), "/", field_name, ".json");
503 LOG(INFO) << "Writing map to file: " << output_path;
504 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800505 }
milind-u401de982023-04-14 17:32:03 -0700506
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700507 for (TargetId id_start = absl::GetFlag(FLAGS_min_target_id);
508 id_start < absl::GetFlag(FLAGS_max_target_id); id_start++) {
509 for (TargetId id_end = id_start + 1;
510 id_end <= absl::GetFlag(FLAGS_max_target_id); id_end++) {
milind-u401de982023-04-14 17:32:03 -0700511 auto H_start_end =
512 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
513 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
514 auto constraint = PoseUtils::Affine3dToPose3d(H_start_end);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700515 VLOG(1) << id_start << "->" << id_end << ": " << constraint.p.norm()
516 << " meters";
milind-u401de982023-04-14 17:32:03 -0700517 }
518 }
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800519}
520
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800521std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800522 flatbuffers::FlatBufferBuilder fbb;
523
524 // Convert poses to flatbuffers
525 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
526 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800527 target_poses_fbs.emplace_back(
Jim Ostrowski6d242d52024-04-03 20:39:03 -0700528 TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800529 }
530
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800531 const auto field_name_offset = fbb.CreateString(field_name);
532 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
533 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800534
535 return aos::FlatbufferToJson(
536 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
537 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800538}
539
milind-u8f4e43e2023-04-09 17:11:19 -0700540namespace {
milind-u8f4e43e2023-04-09 17:11:19 -0700541// Hacks to extract a double from a scalar, which is either a ceres jet or a
542// double. Only used for debugging and displaying.
543template <typename S>
544double ScalarToDouble(S s) {
545 const double *ptr = reinterpret_cast<double *>(&s);
546 return *ptr;
547}
548
549template <typename S>
550Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) {
551 Eigen::Affine3d H_double;
552 for (size_t i = 0; i < H.rows(); i++) {
553 for (size_t j = 0; j < H.cols(); j++) {
554 H_double(i, j) = ScalarToDouble(H(i, j));
555 }
556 }
557 return H_double;
558}
559
560} // namespace
561
562template <typename S>
563bool TargetMapper::operator()(const S *const translation,
564 const S *const rotation, S *residual) const {
565 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
566 Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2],
567 rotation[0]);
568 Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1],
569 translation[2]);
570 // Actual target pose in the frame of the fixed pose.
571 Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual;
572 VLOG(2) << "H_frozen_actual: "
573 << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
574
575 Affine3s H_world_frozen =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700576 PoseUtils::Pose3dToAffine3d(
577 target_poses_.at(absl::GetFlag(FLAGS_frozen_target_id)))
milind-u8f4e43e2023-04-09 17:11:19 -0700578 .cast<S>();
579 Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
580
581 size_t residual_index = 0;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700582 if (absl::GetFlag(FLAGS_visualize_solver)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700583 vis_robot_.ClearImage();
584 }
585
586 for (const auto &[id, solved_pose] : target_poses_) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700587 if (id < absl::GetFlag(FLAGS_min_target_id) ||
588 id > absl::GetFlag(FLAGS_max_target_id)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700589 continue;
590 }
591
592 Affine3s H_world_ideal =
593 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>();
594 Affine3s H_world_solved =
595 PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>();
596 // Take the delta between the frozen target and the solved target, and put
597 // that on top of the actual pose of the frozen target
598 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
599 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
600 VLOG(2) << id << ": " << H_world_actual.translation();
601 Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual;
602 auto T_ideal_actual = H_ideal_actual.translation();
603 VLOG(2) << "T_ideal_actual: " << T_ideal_actual;
604 VLOG(2);
605 auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation());
606
milind-u401de982023-04-14 17:32:03 -0700607 // Weight translation errors higher than rotation.
608 // 1 m in position error = 0.01 radian (or ~0.573 degrees)
609 constexpr double kTranslationScalar = 1000.0;
610 constexpr double kRotationScalar = 100.0;
milind-u8f4e43e2023-04-09 17:11:19 -0700611
612 // Penalize based on how much our actual poses matches the ideal
613 // ones. We've already solved for the relative poses, now figure out
614 // where all of them fit in the world.
615 residual[residual_index++] = kTranslationScalar * T_ideal_actual(0);
616 residual[residual_index++] = kTranslationScalar * T_ideal_actual(1);
617 residual[residual_index++] = kTranslationScalar * T_ideal_actual(2);
618 residual[residual_index++] =
619 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x();
620 residual[residual_index++] =
621 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y();
622 residual[residual_index++] =
623 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
624
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700625 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowski68e56172023-09-17 23:44:15 -0700626 LOG(INFO) << std::to_string(id) + std::string("-est") << " at "
627 << ScalarAffineToDouble(H_world_actual).matrix();
milind-u8f4e43e2023-04-09 17:11:19 -0700628 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700629 std::to_string(id) + std::string("-est"),
630 cv::Scalar(0, 255, 0));
milind-u8f4e43e2023-04-09 17:11:19 -0700631 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal),
632 std::to_string(id), cv::Scalar(255, 255, 255));
633 }
634 }
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700635 if (absl::GetFlag(FLAGS_visualize_solver)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700636 cv::imshow("Target maps", vis_robot_.image_);
637 cv::waitKey(0);
638 }
639
640 // Ceres can't handle residual values of exactly zero
641 for (size_t i = 0; i < residual_index; i++) {
642 if (residual[i] == S(0)) {
643 residual[i] = S(1e-9);
644 }
645 }
646
647 return true;
648}
649
milind-u401de982023-04-14 17:32:03 -0700650TargetMapper::PoseError TargetMapper::ComputeError(
651 const ceres::examples::Constraint3d &constraint) const {
652 // Compute the difference between the map-based transform of the end target
653 // in the start target frame, to the one from this constraint
654 auto H_start_end_map =
655 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_begin))
656 .inverse() *
657 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_end));
658 auto H_start_end_constraint = PoseUtils::Pose3dToAffine3d(constraint.t_be);
659 ceres::examples::Pose3d delta_pose = PoseUtils::Affine3dToPose3d(
660 H_start_end_map.inverse() * H_start_end_constraint);
661 double distance = delta_pose.p.norm();
662 Eigen::AngleAxisd err_angle(delta_pose.q);
663 double angle = std::abs(err_angle.angle());
664 return {.angle = angle, .distance = distance};
665}
666
667TargetMapper::Stats TargetMapper::ComputeStats() const {
668 Stats stats{.avg_err = {.angle = 0.0, .distance = 0.0},
669 .std_dev = {.angle = 0.0, .distance = 0.0},
670 .max_err = {.angle = 0.0, .distance = 0.0}};
671
672 for (const auto &constraint : target_constraints_) {
673 PoseError err = ComputeError(constraint);
674
675 // Update our statistics
676 stats.avg_err.distance += err.distance;
677 if (err.distance > stats.max_err.distance) {
678 stats.max_err.distance = err.distance;
679 }
680
681 stats.avg_err.angle += err.angle;
682 if (err.angle > stats.max_err.angle) {
683 stats.max_err.angle = err.angle;
684 }
685 }
686
687 stats.avg_err.distance /= static_cast<double>(target_constraints_.size());
688 stats.avg_err.angle /= static_cast<double>(target_constraints_.size());
689
690 for (const auto &constraint : target_constraints_) {
691 PoseError err = ComputeError(constraint);
692
693 // Update our statistics
694 stats.std_dev.distance +=
695 std::pow(err.distance - stats.avg_err.distance, 2);
696
697 stats.std_dev.angle += std::pow(err.angle - stats.avg_err.angle, 2);
698 }
699
700 stats.std_dev.distance = std::sqrt(
701 stats.std_dev.distance / static_cast<double>(target_constraints_.size()));
702 stats.std_dev.angle = std::sqrt(
703 stats.std_dev.angle / static_cast<double>(target_constraints_.size()));
704
705 return stats;
706}
707
708void TargetMapper::RemoveOutlierConstraints() {
709 stats_with_outliers_ = ComputeStats();
710 size_t original_size = target_constraints_.size();
711 target_constraints_.erase(
712 std::remove_if(
713 target_constraints_.begin(), target_constraints_.end(),
714 [&](const auto &constraint) {
715 PoseError err = ComputeError(constraint);
716 // Remove constraints with errors significantly above
717 // the average
718 if (err.distance > stats_with_outliers_.avg_err.distance +
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700719 absl::GetFlag(FLAGS_outlier_std_devs) *
milind-u401de982023-04-14 17:32:03 -0700720 stats_with_outliers_.std_dev.distance) {
721 return true;
722 }
723 if (err.angle > stats_with_outliers_.avg_err.angle +
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700724 absl::GetFlag(FLAGS_outlier_std_devs) *
milind-u401de982023-04-14 17:32:03 -0700725 stats_with_outliers_.std_dev.angle) {
726 return true;
727 }
728 return false;
729 }),
730 target_constraints_.end());
731
732 LOG(INFO) << "Removed " << (original_size - target_constraints_.size())
733 << " outlier constraints out of " << original_size << " total";
734}
735
736void TargetMapper::DumpStats(std::string_view path) const {
737 LOG(INFO) << "Dumping mapping stats to " << path;
738 Stats stats = ComputeStats();
739 std::ofstream fout(path.data());
740 fout << "Stats after outlier rejection: " << std::endl;
741 fout << "Average error - angle: " << stats.avg_err.angle
742 << ", distance: " << stats.avg_err.distance << std::endl
743 << std::endl;
744 fout << "Standard deviation - angle: " << stats.std_dev.angle
745 << ", distance: " << stats.std_dev.distance << std::endl
746 << std::endl;
747 fout << "Max error - angle: " << stats.max_err.angle
748 << ", distance: " << stats.max_err.distance << std::endl;
749
750 fout << std::endl << "Stats before outlier rejection:" << std::endl;
751 fout << "Average error - angle: " << stats_with_outliers_.avg_err.angle
752 << ", distance: " << stats_with_outliers_.avg_err.distance << std::endl
753 << std::endl;
754 fout << "Standard deviation - angle: " << stats_with_outliers_.std_dev.angle
755 << ", distance: " << stats_with_outliers_.std_dev.distance << std::endl
756 << std::endl;
757 fout << "Max error - angle: " << stats_with_outliers_.max_err.angle
758 << ", distance: " << stats_with_outliers_.max_err.distance << std::endl;
759
760 fout.flush();
761 fout.close();
762}
763
764void TargetMapper::DumpConstraints(std::string_view path) const {
765 LOG(INFO) << "Dumping target constraints to " << path;
766 std::ofstream fout(path.data());
767 for (const auto &constraint : target_constraints_) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700768 fout << absl::StrCat("", constraint) << std::endl;
milind-u401de982023-04-14 17:32:03 -0700769 }
770 fout.flush();
771 fout.close();
772}
773
Jim Ostrowskif41b0942024-03-24 18:05:02 -0700774void TargetMapper::PrintDiffs() const {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700775 for (int id = absl::GetFlag(FLAGS_min_target_id);
776 id <= absl::GetFlag(FLAGS_max_target_id); id++) {
Jim Ostrowskif41b0942024-03-24 18:05:02 -0700777 Eigen::Affine3d H_world_ideal =
778 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
779 Eigen::Affine3d H_world_solved =
780 PoseUtils::Pose3dToAffine3d(target_poses_.at(id));
781 Eigen::Affine3d H_ideal_solved = H_world_ideal.inverse() * H_world_solved;
782 Eigen::Vector3d rpy = PoseUtils::RotationMatrixToEulerAngles(
783 H_ideal_solved.rotation().matrix()) *
784 180.0 / M_PI;
785 Eigen::Vector3d trans = H_ideal_solved.translation();
786
787 LOG(INFO) << "\nOffset from ideal to solved for target " << id
788 << " (in m, deg)"
789 << "\n x: " << trans(0) << ", y: " << trans(1)
790 << ", z: " << trans(2) << ", \n roll: " << rpy(0)
791 << ", pitch: " << rpy(1) << ", yaw: " << rpy(2) << "\n";
792 }
793}
794
milind-ufbc5c812023-04-06 21:24:29 -0700795} // namespace frc971::vision