blob: b9b37127f47c5a7749245328382708f82f42d53f [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"
8
9DEFINE_uint64(max_num_iterations, 100,
10 "Maximum number of iterations for the ceres solver");
milind-ud62f80a2023-03-04 16:37:09 -080011DEFINE_double(distortion_noise_scalar, 1.0,
12 "Scale the target pose distortion factor by this when computing "
13 "the noise.");
milind-u8f4e43e2023-04-09 17:11:19 -070014DEFINE_int32(
milind-u6ff399f2023-03-24 18:33:38 -070015 frozen_target_id, 1,
16 "Freeze the pose of this target so the map can have one fixed point.");
milind-u8f4e43e2023-04-09 17:11:19 -070017DEFINE_int32(min_target_id, 1, "Minimum target id to solve for");
18DEFINE_int32(max_target_id, 8, "Maximum target id to solve for");
19DEFINE_bool(visualize_solver, false, "If true, visualize the solving process.");
milind-u401de982023-04-14 17:32:03 -070020// This does seem like a strict threshold for a constaint to be considered an
21// outlier, but most inliers were very close together and this is what worked
22// best for map solving.
23DEFINE_double(outlier_std_devs, 1.0,
24 "Number of standard deviations above average error needed for a "
25 "constraint to be considered an outlier and get removed.");
Jim Ostrowski463ee592024-03-07 00:08:24 -080026DEFINE_bool(do_map_fitting, false,
27 "Whether to do a final fit of the solved map to the original map");
Milind Upadhyay7c205222022-11-16 18:20:58 -080028
29namespace frc971::vision {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080030Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
31 const ceres::examples::Pose3d &pose3d) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080032 Eigen::Affine3d H_world_pose =
Milind Upadhyayc5beba12022-12-17 17:41:20 -080033 Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q;
Milind Upadhyay7c205222022-11-16 18:20:58 -080034 return H_world_pose;
35}
36
Milind Upadhyayc5beba12022-12-17 17:41:20 -080037ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) {
38 return ceres::examples::Pose3d{.p = H.translation(),
39 .q = Eigen::Quaterniond(H.rotation())};
Milind Upadhyay7c205222022-11-16 18:20:58 -080040}
41
Milind Upadhyayc5beba12022-12-17 17:41:20 -080042ceres::examples::Pose3d PoseUtils::ComputeRelativePose(
43 const ceres::examples::Pose3d &pose_1,
44 const ceres::examples::Pose3d &pose_2) {
45 Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1);
46 Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080047
48 // Get the location of 2 in the 1 frame
49 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080050 return Affine3dToPose3d(H_1_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080051}
52
Milind Upadhyayc5beba12022-12-17 17:41:20 -080053ceres::examples::Pose3d PoseUtils::ComputeOffsetPose(
54 const ceres::examples::Pose3d &pose_1,
55 const ceres::examples::Pose3d &pose_2_relative) {
56 auto H_world_1 = Pose3dToAffine3d(pose_1);
57 auto H_1_2 = Pose3dToAffine3d(pose_2_relative);
Milind Upadhyay7c205222022-11-16 18:20:58 -080058 auto H_world_2 = H_world_1 * H_1_2;
59
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060 return Affine3dToPose3d(H_world_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080061}
62
Milind Upadhyayc5beba12022-12-17 17:41:20 -080063Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion(
64 const Eigen::Vector3d &rpy) {
65 Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX());
66 Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY());
67 Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ());
68
69 return yaw_angle * pitch_angle * roll_angle;
Milind Upadhyay7c205222022-11-16 18:20:58 -080070}
71
Milind Upadhyayc5beba12022-12-17 17:41:20 -080072Eigen::Vector3d PoseUtils::QuaternionToEulerAngles(
73 const Eigen::Quaterniond &q) {
74 return RotationMatrixToEulerAngles(q.toRotationMatrix());
Milind Upadhyay7c205222022-11-16 18:20:58 -080075}
76
Milind Upadhyayc5beba12022-12-17 17:41:20 -080077Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles(
78 const Eigen::Matrix3d &R) {
79 double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2)));
80 double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0)));
81 double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0)));
82
83 return Eigen::Vector3d(roll, pitch, yaw);
84}
85
milind-u3f5f83c2023-01-29 15:23:51 -080086flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs(
87 const TargetMapper::TargetPose &target_pose,
88 flatbuffers::FlatBufferBuilder *fbb) {
89 const auto position_offset =
90 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
91 target_pose.pose.p(2));
92 const auto orientation_offset =
93 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
94 target_pose.pose.q.y(), target_pose.pose.q.z());
95 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
96 orientation_offset);
97}
98
99TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs(
100 const TargetPoseFbs &target_pose_fbs) {
101 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
102 .pose = ceres::examples::Pose3d{
103 Eigen::Vector3d(target_pose_fbs.position()->x(),
104 target_pose_fbs.position()->y(),
105 target_pose_fbs.position()->z()),
106 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
107 target_pose_fbs.orientation()->x(),
108 target_pose_fbs.orientation()->y(),
James Kuszmaulfeb89082024-02-21 14:00:15 -0800109 target_pose_fbs.orientation()->z())
110 .normalized()}};
milind-u3f5f83c2023-01-29 15:23:51 -0800111}
112
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800113ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800114 const std::vector<DataAdapter::TimestampedDetection>
115 &timestamped_target_detections,
116 aos::distributed_clock::duration max_dt) {
117 CHECK_GE(timestamped_target_detections.size(), 2ul)
118 << "Must have at least 2 detections";
119
120 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800121 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -0800122 for (auto detection = timestamped_target_detections.begin() + 1;
123 detection < timestamped_target_detections.end(); detection++) {
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700124 for (int past = 1;
125 past <=
126 std::min<int>(4, detection - timestamped_target_detections.begin());
127 ++past) {
128 auto last_detection = detection - past;
Milind Upadhyayec493912022-12-18 21:33:15 -0800129
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700130 // Skip two consecutive detections of the same target, because the solver
131 // doesn't allow this
132 if (detection->id == last_detection->id) {
133 continue;
134 }
135
136 // Don't take into account constraints too far apart in time, because the
137 // recording device could have moved too much
138 if ((detection->time - last_detection->time) > max_dt) {
139 continue;
140 }
141
142 auto confidence = ComputeConfidence(*last_detection, *detection);
143 target_constraints.emplace_back(
144 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -0800145 }
Milind Upadhyayec493912022-12-18 21:33:15 -0800146 }
147
148 return target_constraints;
149}
150
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800151TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800152 const TimestampedDetection &detection_start,
153 const TimestampedDetection &detection_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800154 constexpr size_t kX = 0;
155 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800156 constexpr size_t kZ = 2;
157 constexpr size_t kOrientation1 = 3;
158 constexpr size_t kOrientation2 = 4;
159 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800160
161 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800162 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800163
164 {
165 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800166 TargetMapper::ConfidenceMatrix Q_odometry =
167 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800168 Q_odometry(kX, kX) = std::pow(0.045, 2);
169 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800170 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
171 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
172 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
173 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800174
175 // Add uncertainty for robot position measurements from start to end
milind-ud62f80a2023-03-04 16:37:09 -0800176 int iterations = (detection_end.time - detection_start.time) /
177 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800178 P += static_cast<double>(iterations) * Q_odometry;
179 }
180
181 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800182 // Noise for vision-based target localizations. Multiplying this matrix by
milind-u6ff399f2023-03-24 18:33:38 -0700183 // the distance from camera to target squared results in the uncertainty
184 // in that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800185 TargetMapper::ConfidenceMatrix Q_vision =
186 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800187 Q_vision(kX, kX) = std::pow(0.045, 2);
188 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800189 Q_vision(kZ, kZ) = std::pow(0.045, 2);
190 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
191 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
192 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800193
194 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
milind-ufbc5c812023-04-06 21:24:29 -0700195 P += Q_vision * std::pow(detection_start.distance_from_camera *
196 (1.0 + FLAGS_distortion_noise_scalar *
197 detection_start.distortion_factor),
198 2);
199 P += Q_vision * std::pow(detection_end.distance_from_camera *
200 (1.0 + FLAGS_distortion_noise_scalar *
201 detection_end.distortion_factor),
202 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800203 }
204
205 return P.inverse();
206}
207
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800208ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800209 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800210 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800211 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800212 // Compute the relative pose (constraint) between the two targets
213 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800214 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800215 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800216 ceres::examples::Pose3d target_constraint =
217 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800218
milind-uf3ab8ba2023-02-04 17:56:16 -0800219 const auto constraint_3d =
220 ceres::examples::Constraint3d{target_detection_start.id,
221 target_detection_end.id,
222 {target_constraint.p, target_constraint.q},
223 confidence};
224
225 VLOG(2) << "Computed constraint: " << constraint_3d;
226 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800227}
228
Milind Upadhyay7c205222022-11-16 18:20:58 -0800229TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800230 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800231 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700232 : target_constraints_(target_constraints),
233 T_frozen_actual_(Eigen::Vector3d::Zero()),
234 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700235 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800236 // Compute focal length so that image shows field with viewpoint at 10m above
237 // it (default for viewer)
238 const double focal_length = kImageWidth_ * 10.0 / kFieldWidth_;
239 vis_robot_.SetDefaultViewpoint(kImageWidth_, focal_length);
240
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800241 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
242 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
243 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u8f4e43e2023-04-09 17:11:19 -0700244 ideal_target_poses_[target_pose_fbs->id()] =
milind-u3f5f83c2023-01-29 15:23:51 -0800245 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800246 }
milind-u8f4e43e2023-04-09 17:11:19 -0700247 target_poses_ = ideal_target_poses_;
milind-u526d5672023-04-17 20:09:10 -0700248 CountConstraints();
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800249}
250
251TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800252 const ceres::examples::MapOfPoses &target_poses,
253 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700254 : ideal_target_poses_(target_poses),
255 target_poses_(ideal_target_poses_),
256 target_constraints_(target_constraints),
257 T_frozen_actual_(Eigen::Vector3d::Zero()),
258 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700259 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
milind-u526d5672023-04-17 20:09:10 -0700260 CountConstraints();
261}
262
263namespace {
264std::pair<TargetMapper::TargetId, TargetMapper::TargetId> MakeIdPair(
265 const ceres::examples::Constraint3d &constraint) {
266 auto min_id = std::min(constraint.id_begin, constraint.id_end);
267 auto max_id = std::max(constraint.id_begin, constraint.id_end);
268 return std::make_pair(min_id, max_id);
269}
270} // namespace
271
272void TargetMapper::CountConstraints() {
273 for (const auto &constraint : target_constraints_) {
274 auto id_pair = MakeIdPair(constraint);
275 if (constraint_counts_.count(id_pair) == 0) {
276 constraint_counts_[id_pair] = 0;
277 }
278 constraint_counts_[id_pair]++;
279 }
280}
Milind Upadhyay7c205222022-11-16 18:20:58 -0800281
282std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
283 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
284 for (auto target_pose : target_poses) {
285 if (target_pose.id == target_id) {
286 return target_pose;
287 }
288 }
289
290 return std::nullopt;
291}
292
Jim Ostrowski49be8232023-03-23 01:00:14 -0700293std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
milind-u2ab4db12023-03-25 21:59:23 -0700294 TargetId target_id) const {
Jim Ostrowski49be8232023-03-23 01:00:14 -0700295 if (target_poses_.count(target_id) > 0) {
milind-u2ab4db12023-03-25 21:59:23 -0700296 return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700297 }
298
299 return std::nullopt;
300}
301
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800302// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
303// Constructs the nonlinear least squares optimization problem from the pose
304// graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700305void TargetMapper::BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800306 const ceres::examples::VectorOfConstraints &constraints,
307 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
308 CHECK(poses != nullptr);
309 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800310 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800311 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800312 return;
313 }
314
milind-u13ff1a52023-01-22 17:10:49 -0800315 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800316 ceres::LocalParameterization *quaternion_local_parameterization =
317 new ceres::EigenQuaternionParameterization;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800318
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700319 int min_constraint_id = std::numeric_limits<int>::max();
320 int max_constraint_id = std::numeric_limits<int>::min();
321
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800322 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
323 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800324 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800325 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800326
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800327 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800328 poses->find(constraint.id_begin);
329 CHECK(pose_begin_iter != poses->end())
330 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800331 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800332 poses->find(constraint.id_end);
333 CHECK(pose_end_iter != poses->end())
334 << "Pose with ID: " << constraint.id_end << " not found.";
335
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800336 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800337 constraint.information.llt().matrixL();
milind-u526d5672023-04-17 20:09:10 -0700338
339 auto id_pair = MakeIdPair(constraint);
340 CHECK_GT(constraint_counts_.count(id_pair), 0ul)
341 << "Should have counted constraints for " << id_pair.first << "->"
342 << id_pair.second;
343
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700344 VLOG(1) << "Adding constraint pair: " << id_pair.first << " and "
345 << id_pair.second;
346 // Store min & max id's; assumes first id < second id
347 if (id_pair.first < min_constraint_id) {
348 min_constraint_id = id_pair.first;
349 }
350 if (id_pair.second > max_constraint_id) {
351 max_constraint_id = id_pair.second;
352 }
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800353 // Normalize constraint cost by occurrences
milind-u526d5672023-04-17 20:09:10 -0700354 size_t constraint_count = constraint_counts_[id_pair];
355 // Scale all costs so the total cost comes out to more reasonable numbers
356 constexpr double kGlobalWeight = 1000.0;
357 double constraint_weight =
358 kGlobalWeight / static_cast<double>(constraint_count);
359
Milind Upadhyay7c205222022-11-16 18:20:58 -0800360 // Ceres will take ownership of the pointer.
361 ceres::CostFunction *cost_function =
milind-u526d5672023-04-17 20:09:10 -0700362 ceres::examples::PoseGraph3dErrorTerm::Create(
363 constraint.t_be, sqrt_information, constraint_weight);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800364
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800365 problem->AddResidualBlock(cost_function, loss_function,
366 pose_begin_iter->second.p.data(),
367 pose_begin_iter->second.q.coeffs().data(),
368 pose_end_iter->second.p.data(),
369 pose_end_iter->second.q.coeffs().data());
370
371 problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
372 quaternion_local_parameterization);
373 problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
374 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800375 }
376
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800377 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800378 // constrained. This is typically referred to as gauge freedom. You can
379 // apply a rigid body transformation to all the nodes and the optimization
380 // problem will still have the exact same cost. The Levenberg-Marquardt
381 // algorithm has internal damping which mitigates this issue, but it is
382 // better to properly constrain the gauge freedom. This can be done by
383 // setting one of the poses as constant so the optimizer cannot change it.
milind-u6ff399f2023-03-24 18:33:38 -0700384 CHECK_NE(poses->count(FLAGS_frozen_target_id), 0ul)
385 << "Got no poses for frozen target id " << FLAGS_frozen_target_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700386 CHECK_GE(FLAGS_frozen_target_id, min_constraint_id)
387 << "target to freeze index " << FLAGS_frozen_target_id
388 << " must be in range of constraints, > " << min_constraint_id;
389 CHECK_LE(FLAGS_frozen_target_id, max_constraint_id)
390 << "target to freeze index " << FLAGS_frozen_target_id
391 << " must be in range of constraints, < " << max_constraint_id;
milind-u6ff399f2023-03-24 18:33:38 -0700392 ceres::examples::MapOfPoses::iterator pose_start_iter =
393 poses->find(FLAGS_frozen_target_id);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800394 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800395 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
396 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800397}
398
milind-u401de982023-04-14 17:32:03 -0700399std::unique_ptr<ceres::CostFunction>
400TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
Philipp Schradera6712522023-07-05 20:25:11 -0700401 // Set up robot visualization.
milind-u8f4e43e2023-04-09 17:11:19 -0700402 vis_robot_.ClearImage();
milind-u8f4e43e2023-04-09 17:11:19 -0700403
404 const size_t num_targets = FLAGS_max_target_id - FLAGS_min_target_id;
405 // Translation and rotation error for each target
406 const size_t num_residuals = num_targets * 6;
407 // Set up the only cost function (also known as residual). This uses
408 // auto-differentiation to obtain the derivative (jacobian).
milind-u401de982023-04-14 17:32:03 -0700409 std::unique_ptr<ceres::CostFunction> cost_function = std::make_unique<
410 ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>>(
411 this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
milind-u8f4e43e2023-04-09 17:11:19 -0700412
413 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
414 ceres::LocalParameterization *quaternion_local_parameterization =
415 new ceres::EigenQuaternionParameterization;
416
milind-u401de982023-04-14 17:32:03 -0700417 problem->AddResidualBlock(cost_function.get(), loss_function,
milind-u8f4e43e2023-04-09 17:11:19 -0700418 T_frozen_actual_.vector().data(),
419 R_frozen_actual_.coeffs().data());
420 problem->SetParameterization(R_frozen_actual_.coeffs().data(),
421 quaternion_local_parameterization);
milind-u401de982023-04-14 17:32:03 -0700422 return cost_function;
milind-u8f4e43e2023-04-09 17:11:19 -0700423}
424
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800425void TargetMapper::DisplayConstraintGraph() {
426 vis_robot_.ClearImage();
427 for (auto constraint : constraint_counts_) {
428 Eigen::Vector3d start_line =
429 PoseUtils::Pose3dToAffine3d(
430 ideal_target_poses_.at(constraint.first.first))
431 .translation();
432 Eigen::Vector3d end_line =
433 PoseUtils::Pose3dToAffine3d(
434 ideal_target_poses_.at(constraint.first.second))
435 .translation();
436 // Weight the green intensity by # of constraints
437 // TODO: This could be improved
438 int color_scale =
439 50 + std::min(155, static_cast<int>(constraint.second * 155.0 / 200.0));
440 vis_robot_.DrawLine(start_line, end_line, cv::Scalar(0, color_scale, 0));
441 }
442
443 for (const auto &[id, solved_pose] : target_poses_) {
444 Eigen::Affine3d H_world_ideal =
445 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
446 vis_robot_.DrawFrameAxes(H_world_ideal, std::to_string(id),
447 cv::Scalar(255, 255, 255));
448 }
449 cv::imshow("Constraint graph", vis_robot_.image_);
450 cv::waitKey(0);
451}
452
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700453void TargetMapper::DisplaySolvedVsInitial() {
454 vis_robot_.ClearImage();
455 for (const auto &[id, solved_pose] : target_poses_) {
456 Eigen::Affine3d H_world_initial =
457 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
458 vis_robot_.DrawFrameAxes(H_world_initial, std::to_string(id),
459 cv::Scalar(0, 0, 255));
460 Eigen::Affine3d H_world_solved = PoseUtils::Pose3dToAffine3d(solved_pose);
461 vis_robot_.DrawFrameAxes(H_world_solved, std::to_string(id) + "-est",
462 cv::Scalar(255, 255, 255));
463 }
464 cv::imshow("Solved vs. Initial", vis_robot_.image_);
465 cv::waitKey(0);
466}
467
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800468// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800469bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
470 CHECK_NOTNULL(problem);
471
472 ceres::Solver::Options options;
473 options.max_num_iterations = FLAGS_max_num_iterations;
474 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
milind-u401de982023-04-14 17:32:03 -0700475 options.minimizer_progress_to_stdout = false;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800476
477 ceres::Solver::Summary summary;
478 ceres::Solve(options, problem, &summary);
479
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800480 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800481
482 return summary.IsSolutionUsable();
483}
484
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800485void TargetMapper::Solve(std::string_view field_name,
486 std::optional<std::string_view> output_dir) {
milind-u401de982023-04-14 17:32:03 -0700487 ceres::Problem target_pose_problem_1;
milind-u8f4e43e2023-04-09 17:11:19 -0700488 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
milind-u401de982023-04-14 17:32:03 -0700489 &target_pose_problem_1);
490 CHECK(SolveOptimizationProblem(&target_pose_problem_1))
491 << "The target pose solve 1 was not successful, exiting.";
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700492 if (FLAGS_visualize_solver) {
493 LOG(INFO) << "Displaying constraint graph before removing outliers";
494 DisplayConstraintGraph();
495 DisplaySolvedVsInitial();
496 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800497
milind-u401de982023-04-14 17:32:03 -0700498 RemoveOutlierConstraints();
499
500 // Solve again once we've thrown out bad constraints
501 ceres::Problem target_pose_problem_2;
502 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
503 &target_pose_problem_2);
504 CHECK(SolveOptimizationProblem(&target_pose_problem_2))
505 << "The target pose solve 2 was not successful, exiting.";
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700506 if (FLAGS_visualize_solver) {
507 LOG(INFO) << "Displaying constraint graph before removing outliers";
508 DisplayConstraintGraph();
509 DisplaySolvedVsInitial();
510 }
milind-u401de982023-04-14 17:32:03 -0700511
Jim Ostrowski463ee592024-03-07 00:08:24 -0800512 if (FLAGS_do_map_fitting) {
513 LOG(INFO) << "Solving the overall map's best alignment to the previous map";
514 ceres::Problem map_fitting_problem(
515 {.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
516 std::unique_ptr<ceres::CostFunction> map_fitting_cost_function =
517 BuildMapFittingOptimizationProblem(&map_fitting_problem);
518 CHECK(SolveOptimizationProblem(&map_fitting_problem))
519 << "The map fitting solve was not successful, exiting.";
520 map_fitting_cost_function.release();
milind-u8f4e43e2023-04-09 17:11:19 -0700521
Jim Ostrowski463ee592024-03-07 00:08:24 -0800522 Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_;
523 LOG(INFO) << "H_frozen_actual: "
524 << PoseUtils::Affine3dToPose3d(H_frozen_actual);
milind-u8f4e43e2023-04-09 17:11:19 -0700525
Jim Ostrowski463ee592024-03-07 00:08:24 -0800526 auto H_world_frozen =
527 PoseUtils::Pose3dToAffine3d(target_poses_[FLAGS_frozen_target_id]);
528 auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
milind-u8f4e43e2023-04-09 17:11:19 -0700529
Jim Ostrowski463ee592024-03-07 00:08:24 -0800530 // Offset the solved poses to become the actual ones
531 for (auto &[id, pose] : target_poses_) {
532 // Don't offset targets we didn't solve for
533 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
534 continue;
535 }
536
537 // Take the delta between the frozen target and the solved target, and put
538 // that on top of the actual pose of the frozen target
539 auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose);
540 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
541 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
542 pose = PoseUtils::Affine3dToPose3d(H_world_actual);
milind-u8f4e43e2023-04-09 17:11:19 -0700543 }
milind-u8f4e43e2023-04-09 17:11:19 -0700544 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800545
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800546 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800547 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800548
549 if (output_dir.has_value()) {
550 std::string output_path =
551 absl::StrCat(output_dir.value(), "/", field_name, ".json");
552 LOG(INFO) << "Writing map to file: " << output_path;
553 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800554 }
milind-u401de982023-04-14 17:32:03 -0700555
556 for (TargetId id_start = FLAGS_min_target_id; id_start < FLAGS_max_target_id;
557 id_start++) {
558 for (TargetId id_end = id_start + 1; id_end <= FLAGS_max_target_id;
559 id_end++) {
560 auto H_start_end =
561 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
562 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
563 auto constraint = PoseUtils::Affine3dToPose3d(H_start_end);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700564 VLOG(1) << id_start << "->" << id_end << ": " << constraint.p.norm()
565 << " meters";
milind-u401de982023-04-14 17:32:03 -0700566 }
567 }
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800568}
569
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800570std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800571 flatbuffers::FlatBufferBuilder fbb;
572
573 // Convert poses to flatbuffers
574 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
575 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800576 target_poses_fbs.emplace_back(
577 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800578 }
579
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800580 const auto field_name_offset = fbb.CreateString(field_name);
581 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
582 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800583
584 return aos::FlatbufferToJson(
585 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
586 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800587}
588
milind-u8f4e43e2023-04-09 17:11:19 -0700589namespace {
milind-u8f4e43e2023-04-09 17:11:19 -0700590// Hacks to extract a double from a scalar, which is either a ceres jet or a
591// double. Only used for debugging and displaying.
592template <typename S>
593double ScalarToDouble(S s) {
594 const double *ptr = reinterpret_cast<double *>(&s);
595 return *ptr;
596}
597
598template <typename S>
599Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) {
600 Eigen::Affine3d H_double;
601 for (size_t i = 0; i < H.rows(); i++) {
602 for (size_t j = 0; j < H.cols(); j++) {
603 H_double(i, j) = ScalarToDouble(H(i, j));
604 }
605 }
606 return H_double;
607}
608
609} // namespace
610
611template <typename S>
612bool TargetMapper::operator()(const S *const translation,
613 const S *const rotation, S *residual) const {
614 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
615 Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2],
616 rotation[0]);
617 Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1],
618 translation[2]);
619 // Actual target pose in the frame of the fixed pose.
620 Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual;
621 VLOG(2) << "H_frozen_actual: "
622 << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
623
624 Affine3s H_world_frozen =
625 PoseUtils::Pose3dToAffine3d(target_poses_.at(FLAGS_frozen_target_id))
626 .cast<S>();
627 Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
628
629 size_t residual_index = 0;
630 if (FLAGS_visualize_solver) {
631 vis_robot_.ClearImage();
632 }
633
634 for (const auto &[id, solved_pose] : target_poses_) {
635 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
636 continue;
637 }
638
639 Affine3s H_world_ideal =
640 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>();
641 Affine3s H_world_solved =
642 PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>();
643 // Take the delta between the frozen target and the solved target, and put
644 // that on top of the actual pose of the frozen target
645 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
646 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
647 VLOG(2) << id << ": " << H_world_actual.translation();
648 Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual;
649 auto T_ideal_actual = H_ideal_actual.translation();
650 VLOG(2) << "T_ideal_actual: " << T_ideal_actual;
651 VLOG(2);
652 auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation());
653
milind-u401de982023-04-14 17:32:03 -0700654 // Weight translation errors higher than rotation.
655 // 1 m in position error = 0.01 radian (or ~0.573 degrees)
656 constexpr double kTranslationScalar = 1000.0;
657 constexpr double kRotationScalar = 100.0;
milind-u8f4e43e2023-04-09 17:11:19 -0700658
659 // Penalize based on how much our actual poses matches the ideal
660 // ones. We've already solved for the relative poses, now figure out
661 // where all of them fit in the world.
662 residual[residual_index++] = kTranslationScalar * T_ideal_actual(0);
663 residual[residual_index++] = kTranslationScalar * T_ideal_actual(1);
664 residual[residual_index++] = kTranslationScalar * T_ideal_actual(2);
665 residual[residual_index++] =
666 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x();
667 residual[residual_index++] =
668 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y();
669 residual[residual_index++] =
670 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
671
672 if (FLAGS_visualize_solver) {
Jim Ostrowski68e56172023-09-17 23:44:15 -0700673 LOG(INFO) << std::to_string(id) + std::string("-est") << " at "
674 << ScalarAffineToDouble(H_world_actual).matrix();
milind-u8f4e43e2023-04-09 17:11:19 -0700675 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700676 std::to_string(id) + std::string("-est"),
677 cv::Scalar(0, 255, 0));
milind-u8f4e43e2023-04-09 17:11:19 -0700678 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal),
679 std::to_string(id), cv::Scalar(255, 255, 255));
680 }
681 }
682 if (FLAGS_visualize_solver) {
683 cv::imshow("Target maps", vis_robot_.image_);
684 cv::waitKey(0);
685 }
686
687 // Ceres can't handle residual values of exactly zero
688 for (size_t i = 0; i < residual_index; i++) {
689 if (residual[i] == S(0)) {
690 residual[i] = S(1e-9);
691 }
692 }
693
694 return true;
695}
696
milind-u401de982023-04-14 17:32:03 -0700697TargetMapper::PoseError TargetMapper::ComputeError(
698 const ceres::examples::Constraint3d &constraint) const {
699 // Compute the difference between the map-based transform of the end target
700 // in the start target frame, to the one from this constraint
701 auto H_start_end_map =
702 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_begin))
703 .inverse() *
704 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_end));
705 auto H_start_end_constraint = PoseUtils::Pose3dToAffine3d(constraint.t_be);
706 ceres::examples::Pose3d delta_pose = PoseUtils::Affine3dToPose3d(
707 H_start_end_map.inverse() * H_start_end_constraint);
708 double distance = delta_pose.p.norm();
709 Eigen::AngleAxisd err_angle(delta_pose.q);
710 double angle = std::abs(err_angle.angle());
711 return {.angle = angle, .distance = distance};
712}
713
714TargetMapper::Stats TargetMapper::ComputeStats() const {
715 Stats stats{.avg_err = {.angle = 0.0, .distance = 0.0},
716 .std_dev = {.angle = 0.0, .distance = 0.0},
717 .max_err = {.angle = 0.0, .distance = 0.0}};
718
719 for (const auto &constraint : target_constraints_) {
720 PoseError err = ComputeError(constraint);
721
722 // Update our statistics
723 stats.avg_err.distance += err.distance;
724 if (err.distance > stats.max_err.distance) {
725 stats.max_err.distance = err.distance;
726 }
727
728 stats.avg_err.angle += err.angle;
729 if (err.angle > stats.max_err.angle) {
730 stats.max_err.angle = err.angle;
731 }
732 }
733
734 stats.avg_err.distance /= static_cast<double>(target_constraints_.size());
735 stats.avg_err.angle /= static_cast<double>(target_constraints_.size());
736
737 for (const auto &constraint : target_constraints_) {
738 PoseError err = ComputeError(constraint);
739
740 // Update our statistics
741 stats.std_dev.distance +=
742 std::pow(err.distance - stats.avg_err.distance, 2);
743
744 stats.std_dev.angle += std::pow(err.angle - stats.avg_err.angle, 2);
745 }
746
747 stats.std_dev.distance = std::sqrt(
748 stats.std_dev.distance / static_cast<double>(target_constraints_.size()));
749 stats.std_dev.angle = std::sqrt(
750 stats.std_dev.angle / static_cast<double>(target_constraints_.size()));
751
752 return stats;
753}
754
755void TargetMapper::RemoveOutlierConstraints() {
756 stats_with_outliers_ = ComputeStats();
757 size_t original_size = target_constraints_.size();
758 target_constraints_.erase(
759 std::remove_if(
760 target_constraints_.begin(), target_constraints_.end(),
761 [&](const auto &constraint) {
762 PoseError err = ComputeError(constraint);
763 // Remove constraints with errors significantly above
764 // the average
765 if (err.distance > stats_with_outliers_.avg_err.distance +
766 FLAGS_outlier_std_devs *
767 stats_with_outliers_.std_dev.distance) {
768 return true;
769 }
770 if (err.angle > stats_with_outliers_.avg_err.angle +
771 FLAGS_outlier_std_devs *
772 stats_with_outliers_.std_dev.angle) {
773 return true;
774 }
775 return false;
776 }),
777 target_constraints_.end());
778
779 LOG(INFO) << "Removed " << (original_size - target_constraints_.size())
780 << " outlier constraints out of " << original_size << " total";
781}
782
783void TargetMapper::DumpStats(std::string_view path) const {
784 LOG(INFO) << "Dumping mapping stats to " << path;
785 Stats stats = ComputeStats();
786 std::ofstream fout(path.data());
787 fout << "Stats after outlier rejection: " << std::endl;
788 fout << "Average error - angle: " << stats.avg_err.angle
789 << ", distance: " << stats.avg_err.distance << std::endl
790 << std::endl;
791 fout << "Standard deviation - angle: " << stats.std_dev.angle
792 << ", distance: " << stats.std_dev.distance << std::endl
793 << std::endl;
794 fout << "Max error - angle: " << stats.max_err.angle
795 << ", distance: " << stats.max_err.distance << std::endl;
796
797 fout << std::endl << "Stats before outlier rejection:" << std::endl;
798 fout << "Average error - angle: " << stats_with_outliers_.avg_err.angle
799 << ", distance: " << stats_with_outliers_.avg_err.distance << std::endl
800 << std::endl;
801 fout << "Standard deviation - angle: " << stats_with_outliers_.std_dev.angle
802 << ", distance: " << stats_with_outliers_.std_dev.distance << std::endl
803 << std::endl;
804 fout << "Max error - angle: " << stats_with_outliers_.max_err.angle
805 << ", distance: " << stats_with_outliers_.max_err.distance << std::endl;
806
807 fout.flush();
808 fout.close();
809}
810
811void TargetMapper::DumpConstraints(std::string_view path) const {
812 LOG(INFO) << "Dumping target constraints to " << path;
813 std::ofstream fout(path.data());
814 for (const auto &constraint : target_constraints_) {
815 fout << constraint << std::endl;
816 }
817 fout.flush();
818 fout.close();
819}
820
Jim Ostrowskif41b0942024-03-24 18:05:02 -0700821void TargetMapper::PrintDiffs() const {
822 for (int id = FLAGS_min_target_id; id <= FLAGS_max_target_id; id++) {
823 Eigen::Affine3d H_world_ideal =
824 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
825 Eigen::Affine3d H_world_solved =
826 PoseUtils::Pose3dToAffine3d(target_poses_.at(id));
827 Eigen::Affine3d H_ideal_solved = H_world_ideal.inverse() * H_world_solved;
828 Eigen::Vector3d rpy = PoseUtils::RotationMatrixToEulerAngles(
829 H_ideal_solved.rotation().matrix()) *
830 180.0 / M_PI;
831 Eigen::Vector3d trans = H_ideal_solved.translation();
832
833 LOG(INFO) << "\nOffset from ideal to solved for target " << id
834 << " (in m, deg)"
835 << "\n x: " << trans(0) << ", y: " << trans(1)
836 << ", z: " << trans(2) << ", \n roll: " << rpy(0)
837 << ", pitch: " << rpy(1) << ", yaw: " << rpy(2) << "\n";
838 }
839}
840
milind-ufbc5c812023-04-06 21:24:29 -0700841} // namespace frc971::vision
842
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800843std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
milind-ufbc5c812023-04-06 21:24:29 -0700844 auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800845 os << absl::StrFormat(
846 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
847 "%.3f, yaw: %.3f}",
848 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
849 return os;
850}
851
852std::ostream &operator<<(std::ostream &os,
853 ceres::examples::Constraint3d constraint) {
854 os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
855 constraint.id_begin, constraint.id_end)
856 << constraint.t_be << "}";
857 return os;
858}