blob: 36f0a29557defbc6f1508a621b762eadbc3454ed [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
Austin Schuh99f7c6a2024-06-25 22:07:44 -07009ABSL_FLAG(uint64_t, max_num_iterations, 100,
10 "Maximum number of iterations for the ceres solver");
11ABSL_FLAG(double, distortion_noise_scalar, 1.0,
12 "Scale the target pose distortion factor by this when computing "
13 "the noise.");
14ABSL_FLAG(
15 int32_t, frozen_target_id, 1,
milind-u6ff399f2023-03-24 18:33:38 -070016 "Freeze the pose of this target so the map can have one fixed point.");
Austin Schuh99f7c6a2024-06-25 22:07:44 -070017ABSL_FLAG(int32_t, min_target_id, 1, "Minimum target id to solve for");
18ABSL_FLAG(int32_t, max_target_id, 8, "Maximum target id to solve for");
19ABSL_FLAG(bool, visualize_solver, false,
20 "If true, visualize the solving process.");
milind-u401de982023-04-14 17:32:03 -070021// This does seem like a strict threshold for a constaint to be considered an
22// outlier, but most inliers were very close together and this is what worked
23// best for map solving.
Austin Schuh99f7c6a2024-06-25 22:07:44 -070024ABSL_FLAG(double, outlier_std_devs, 1.0,
25 "Number of standard deviations above average error needed for a "
26 "constraint to be considered an outlier and get removed.");
27ABSL_FLAG(bool, do_map_fitting, false,
28 "Whether to do a final fit of the solved map to the original map");
Milind Upadhyay7c205222022-11-16 18:20:58 -080029
30namespace frc971::vision {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080031Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
32 const ceres::examples::Pose3d &pose3d) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080033 Eigen::Affine3d H_world_pose =
Milind Upadhyayc5beba12022-12-17 17:41:20 -080034 Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q;
Milind Upadhyay7c205222022-11-16 18:20:58 -080035 return H_world_pose;
36}
37
Milind Upadhyayc5beba12022-12-17 17:41:20 -080038ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) {
39 return ceres::examples::Pose3d{.p = H.translation(),
40 .q = Eigen::Quaterniond(H.rotation())};
Milind Upadhyay7c205222022-11-16 18:20:58 -080041}
42
Milind Upadhyayc5beba12022-12-17 17:41:20 -080043ceres::examples::Pose3d PoseUtils::ComputeRelativePose(
44 const ceres::examples::Pose3d &pose_1,
45 const ceres::examples::Pose3d &pose_2) {
46 Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1);
47 Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080048
49 // Get the location of 2 in the 1 frame
50 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080051 return Affine3dToPose3d(H_1_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080052}
53
Milind Upadhyayc5beba12022-12-17 17:41:20 -080054ceres::examples::Pose3d PoseUtils::ComputeOffsetPose(
55 const ceres::examples::Pose3d &pose_1,
56 const ceres::examples::Pose3d &pose_2_relative) {
57 auto H_world_1 = Pose3dToAffine3d(pose_1);
58 auto H_1_2 = Pose3dToAffine3d(pose_2_relative);
Milind Upadhyay7c205222022-11-16 18:20:58 -080059 auto H_world_2 = H_world_1 * H_1_2;
60
Milind Upadhyayc5beba12022-12-17 17:41:20 -080061 return Affine3dToPose3d(H_world_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080062}
63
Milind Upadhyayc5beba12022-12-17 17:41:20 -080064Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion(
65 const Eigen::Vector3d &rpy) {
66 Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX());
67 Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY());
68 Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ());
69
70 return yaw_angle * pitch_angle * roll_angle;
Milind Upadhyay7c205222022-11-16 18:20:58 -080071}
72
Milind Upadhyayc5beba12022-12-17 17:41:20 -080073Eigen::Vector3d PoseUtils::QuaternionToEulerAngles(
74 const Eigen::Quaterniond &q) {
75 return RotationMatrixToEulerAngles(q.toRotationMatrix());
Milind Upadhyay7c205222022-11-16 18:20:58 -080076}
77
Milind Upadhyayc5beba12022-12-17 17:41:20 -080078Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles(
79 const Eigen::Matrix3d &R) {
80 double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2)));
81 double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0)));
82 double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0)));
83
84 return Eigen::Vector3d(roll, pitch, yaw);
85}
86
milind-u3f5f83c2023-01-29 15:23:51 -080087flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs(
88 const TargetMapper::TargetPose &target_pose,
89 flatbuffers::FlatBufferBuilder *fbb) {
90 const auto position_offset =
91 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
92 target_pose.pose.p(2));
93 const auto orientation_offset =
94 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
95 target_pose.pose.q.y(), target_pose.pose.q.z());
96 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
97 orientation_offset);
98}
99
100TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs(
101 const TargetPoseFbs &target_pose_fbs) {
102 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
103 .pose = ceres::examples::Pose3d{
104 Eigen::Vector3d(target_pose_fbs.position()->x(),
105 target_pose_fbs.position()->y(),
106 target_pose_fbs.position()->z()),
107 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
108 target_pose_fbs.orientation()->x(),
109 target_pose_fbs.orientation()->y(),
James Kuszmaulfeb89082024-02-21 14:00:15 -0800110 target_pose_fbs.orientation()->z())
111 .normalized()}};
milind-u3f5f83c2023-01-29 15:23:51 -0800112}
113
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800114ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800115 const std::vector<DataAdapter::TimestampedDetection>
116 &timestamped_target_detections,
117 aos::distributed_clock::duration max_dt) {
118 CHECK_GE(timestamped_target_detections.size(), 2ul)
119 << "Must have at least 2 detections";
120
121 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800122 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -0800123 for (auto detection = timestamped_target_detections.begin() + 1;
124 detection < timestamped_target_detections.end(); detection++) {
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700125 for (int past = 1;
126 past <=
127 std::min<int>(4, detection - timestamped_target_detections.begin());
128 ++past) {
129 auto last_detection = detection - past;
Milind Upadhyayec493912022-12-18 21:33:15 -0800130
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700131 // Skip two consecutive detections of the same target, because the solver
132 // doesn't allow this
133 if (detection->id == last_detection->id) {
134 continue;
135 }
136
137 // Don't take into account constraints too far apart in time, because the
138 // recording device could have moved too much
139 if ((detection->time - last_detection->time) > max_dt) {
140 continue;
141 }
142
143 auto confidence = ComputeConfidence(*last_detection, *detection);
144 target_constraints.emplace_back(
145 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -0800146 }
Milind Upadhyayec493912022-12-18 21:33:15 -0800147 }
148
149 return target_constraints;
150}
151
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800152TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800153 const TimestampedDetection &detection_start,
154 const TimestampedDetection &detection_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800155 constexpr size_t kX = 0;
156 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800157 constexpr size_t kZ = 2;
158 constexpr size_t kOrientation1 = 3;
159 constexpr size_t kOrientation2 = 4;
160 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800161
162 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800163 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800164
165 {
166 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800167 TargetMapper::ConfidenceMatrix Q_odometry =
168 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800169 Q_odometry(kX, kX) = std::pow(0.045, 2);
170 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800171 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
172 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
173 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
174 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800175
176 // Add uncertainty for robot position measurements from start to end
milind-ud62f80a2023-03-04 16:37:09 -0800177 int iterations = (detection_end.time - detection_start.time) /
178 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800179 P += static_cast<double>(iterations) * Q_odometry;
180 }
181
182 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800183 // Noise for vision-based target localizations. Multiplying this matrix by
milind-u6ff399f2023-03-24 18:33:38 -0700184 // the distance from camera to target squared results in the uncertainty
185 // in that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800186 TargetMapper::ConfidenceMatrix Q_vision =
187 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800188 Q_vision(kX, kX) = std::pow(0.045, 2);
189 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800190 Q_vision(kZ, kZ) = std::pow(0.045, 2);
191 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
192 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
193 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800194
195 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700196 P += Q_vision *
197 std::pow(detection_start.distance_from_camera *
198 (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
199 detection_start.distortion_factor),
200 2);
201 P += Q_vision *
202 std::pow(detection_end.distance_from_camera *
203 (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
204 detection_end.distortion_factor),
205 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800206 }
207
208 return P.inverse();
209}
210
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800211ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800212 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800213 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800214 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800215 // Compute the relative pose (constraint) between the two targets
216 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800217 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800218 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800219 ceres::examples::Pose3d target_constraint =
220 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800221
milind-uf3ab8ba2023-02-04 17:56:16 -0800222 const auto constraint_3d =
223 ceres::examples::Constraint3d{target_detection_start.id,
224 target_detection_end.id,
225 {target_constraint.p, target_constraint.q},
226 confidence};
227
228 VLOG(2) << "Computed constraint: " << constraint_3d;
229 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800230}
231
Milind Upadhyay7c205222022-11-16 18:20:58 -0800232TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800233 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800234 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700235 : target_constraints_(target_constraints),
236 T_frozen_actual_(Eigen::Vector3d::Zero()),
237 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700238 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800239 // Compute focal length so that image shows field with viewpoint at 10m above
240 // it (default for viewer)
241 const double focal_length = kImageWidth_ * 10.0 / kFieldWidth_;
242 vis_robot_.SetDefaultViewpoint(kImageWidth_, focal_length);
243
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800244 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
245 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
246 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u8f4e43e2023-04-09 17:11:19 -0700247 ideal_target_poses_[target_pose_fbs->id()] =
milind-u3f5f83c2023-01-29 15:23:51 -0800248 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800249 }
milind-u8f4e43e2023-04-09 17:11:19 -0700250 target_poses_ = ideal_target_poses_;
milind-u526d5672023-04-17 20:09:10 -0700251 CountConstraints();
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800252}
253
254TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800255 const ceres::examples::MapOfPoses &target_poses,
256 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700257 : ideal_target_poses_(target_poses),
258 target_poses_(ideal_target_poses_),
259 target_constraints_(target_constraints),
260 T_frozen_actual_(Eigen::Vector3d::Zero()),
261 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700262 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
milind-u526d5672023-04-17 20:09:10 -0700263 CountConstraints();
264}
265
266namespace {
267std::pair<TargetMapper::TargetId, TargetMapper::TargetId> MakeIdPair(
268 const ceres::examples::Constraint3d &constraint) {
269 auto min_id = std::min(constraint.id_begin, constraint.id_end);
270 auto max_id = std::max(constraint.id_begin, constraint.id_end);
271 return std::make_pair(min_id, max_id);
272}
273} // namespace
274
275void TargetMapper::CountConstraints() {
276 for (const auto &constraint : target_constraints_) {
277 auto id_pair = MakeIdPair(constraint);
278 if (constraint_counts_.count(id_pair) == 0) {
279 constraint_counts_[id_pair] = 0;
280 }
281 constraint_counts_[id_pair]++;
282 }
283}
Milind Upadhyay7c205222022-11-16 18:20:58 -0800284
285std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
286 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
287 for (auto target_pose : target_poses) {
288 if (target_pose.id == target_id) {
289 return target_pose;
290 }
291 }
292
293 return std::nullopt;
294}
295
Jim Ostrowski49be8232023-03-23 01:00:14 -0700296std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
milind-u2ab4db12023-03-25 21:59:23 -0700297 TargetId target_id) const {
Jim Ostrowski49be8232023-03-23 01:00:14 -0700298 if (target_poses_.count(target_id) > 0) {
milind-u2ab4db12023-03-25 21:59:23 -0700299 return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700300 }
301
302 return std::nullopt;
303}
304
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800305// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
306// Constructs the nonlinear least squares optimization problem from the pose
307// graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700308void TargetMapper::BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800309 const ceres::examples::VectorOfConstraints &constraints,
310 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
311 CHECK(poses != nullptr);
312 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800313 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800314 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800315 return;
316 }
317
milind-u13ff1a52023-01-22 17:10:49 -0800318 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Austin Schuh31f99a22024-06-25 18:30:13 -0700319 ceres::Manifold *quaternion_local_parameterization =
320 new ceres::EigenQuaternionManifold();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800321
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700322 int min_constraint_id = std::numeric_limits<int>::max();
323 int max_constraint_id = std::numeric_limits<int>::min();
324
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800325 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
326 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800327 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800328 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800329
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800330 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800331 poses->find(constraint.id_begin);
332 CHECK(pose_begin_iter != poses->end())
333 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800334 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800335 poses->find(constraint.id_end);
336 CHECK(pose_end_iter != poses->end())
337 << "Pose with ID: " << constraint.id_end << " not found.";
338
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800339 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800340 constraint.information.llt().matrixL();
milind-u526d5672023-04-17 20:09:10 -0700341
342 auto id_pair = MakeIdPair(constraint);
343 CHECK_GT(constraint_counts_.count(id_pair), 0ul)
344 << "Should have counted constraints for " << id_pair.first << "->"
345 << id_pair.second;
346
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700347 VLOG(1) << "Adding constraint pair: " << id_pair.first << " and "
348 << id_pair.second;
349 // Store min & max id's; assumes first id < second id
350 if (id_pair.first < min_constraint_id) {
351 min_constraint_id = id_pair.first;
352 }
353 if (id_pair.second > max_constraint_id) {
354 max_constraint_id = id_pair.second;
355 }
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800356 // Normalize constraint cost by occurrences
milind-u526d5672023-04-17 20:09:10 -0700357 size_t constraint_count = constraint_counts_[id_pair];
358 // Scale all costs so the total cost comes out to more reasonable numbers
359 constexpr double kGlobalWeight = 1000.0;
360 double constraint_weight =
361 kGlobalWeight / static_cast<double>(constraint_count);
362
Milind Upadhyay7c205222022-11-16 18:20:58 -0800363 // Ceres will take ownership of the pointer.
364 ceres::CostFunction *cost_function =
milind-u526d5672023-04-17 20:09:10 -0700365 ceres::examples::PoseGraph3dErrorTerm::Create(
366 constraint.t_be, sqrt_information, constraint_weight);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800367
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800368 problem->AddResidualBlock(cost_function, loss_function,
369 pose_begin_iter->second.p.data(),
370 pose_begin_iter->second.q.coeffs().data(),
371 pose_end_iter->second.p.data(),
372 pose_end_iter->second.q.coeffs().data());
373
Austin Schuh31f99a22024-06-25 18:30:13 -0700374 problem->SetManifold(pose_begin_iter->second.q.coeffs().data(),
375 quaternion_local_parameterization);
376 problem->SetManifold(pose_end_iter->second.q.coeffs().data(),
377 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800378 }
379
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800380 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800381 // constrained. This is typically referred to as gauge freedom. You can
382 // apply a rigid body transformation to all the nodes and the optimization
383 // problem will still have the exact same cost. The Levenberg-Marquardt
384 // algorithm has internal damping which mitigates this issue, but it is
385 // better to properly constrain the gauge freedom. This can be done by
386 // setting one of the poses as constant so the optimizer cannot change it.
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700387 CHECK_NE(poses->count(absl::GetFlag(FLAGS_frozen_target_id)), 0ul)
388 << "Got no poses for frozen target id "
389 << absl::GetFlag(FLAGS_frozen_target_id);
390 CHECK_GE(absl::GetFlag(FLAGS_frozen_target_id), min_constraint_id)
391 << "target to freeze index " << absl::GetFlag(FLAGS_frozen_target_id)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700392 << " must be in range of constraints, > " << min_constraint_id;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700393 CHECK_LE(absl::GetFlag(FLAGS_frozen_target_id), max_constraint_id)
394 << "target to freeze index " << absl::GetFlag(FLAGS_frozen_target_id)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700395 << " must be in range of constraints, < " << max_constraint_id;
milind-u6ff399f2023-03-24 18:33:38 -0700396 ceres::examples::MapOfPoses::iterator pose_start_iter =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700397 poses->find(absl::GetFlag(FLAGS_frozen_target_id));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800398 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800399 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
400 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800401}
402
milind-u401de982023-04-14 17:32:03 -0700403std::unique_ptr<ceres::CostFunction>
404TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
Philipp Schradera6712522023-07-05 20:25:11 -0700405 // Set up robot visualization.
milind-u8f4e43e2023-04-09 17:11:19 -0700406 vis_robot_.ClearImage();
milind-u8f4e43e2023-04-09 17:11:19 -0700407
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700408 const size_t num_targets =
409 absl::GetFlag(FLAGS_max_target_id) - absl::GetFlag(FLAGS_min_target_id);
milind-u8f4e43e2023-04-09 17:11:19 -0700410 // Translation and rotation error for each target
411 const size_t num_residuals = num_targets * 6;
412 // Set up the only cost function (also known as residual). This uses
413 // auto-differentiation to obtain the derivative (jacobian).
milind-u401de982023-04-14 17:32:03 -0700414 std::unique_ptr<ceres::CostFunction> cost_function = std::make_unique<
415 ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>>(
416 this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
milind-u8f4e43e2023-04-09 17:11:19 -0700417
418 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Austin Schuh31f99a22024-06-25 18:30:13 -0700419 ceres::Manifold *quaternion_local_parameterization =
420 new ceres::EigenQuaternionManifold();
milind-u8f4e43e2023-04-09 17:11:19 -0700421
milind-u401de982023-04-14 17:32:03 -0700422 problem->AddResidualBlock(cost_function.get(), loss_function,
milind-u8f4e43e2023-04-09 17:11:19 -0700423 T_frozen_actual_.vector().data(),
424 R_frozen_actual_.coeffs().data());
Austin Schuh31f99a22024-06-25 18:30:13 -0700425 problem->SetManifold(R_frozen_actual_.coeffs().data(),
426 quaternion_local_parameterization);
milind-u401de982023-04-14 17:32:03 -0700427 return cost_function;
milind-u8f4e43e2023-04-09 17:11:19 -0700428}
429
Jim Ostrowski4527dd72024-03-07 00:20:15 -0800430void TargetMapper::DisplayConstraintGraph() {
431 vis_robot_.ClearImage();
432 for (auto constraint : constraint_counts_) {
433 Eigen::Vector3d start_line =
434 PoseUtils::Pose3dToAffine3d(
435 ideal_target_poses_.at(constraint.first.first))
436 .translation();
437 Eigen::Vector3d end_line =
438 PoseUtils::Pose3dToAffine3d(
439 ideal_target_poses_.at(constraint.first.second))
440 .translation();
441 // Weight the green intensity by # of constraints
442 // TODO: This could be improved
443 int color_scale =
444 50 + std::min(155, static_cast<int>(constraint.second * 155.0 / 200.0));
445 vis_robot_.DrawLine(start_line, end_line, cv::Scalar(0, color_scale, 0));
446 }
447
448 for (const auto &[id, solved_pose] : target_poses_) {
449 Eigen::Affine3d H_world_ideal =
450 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
451 vis_robot_.DrawFrameAxes(H_world_ideal, std::to_string(id),
452 cv::Scalar(255, 255, 255));
453 }
454 cv::imshow("Constraint graph", vis_robot_.image_);
455 cv::waitKey(0);
456}
457
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700458void TargetMapper::DisplaySolvedVsInitial() {
459 vis_robot_.ClearImage();
460 for (const auto &[id, solved_pose] : target_poses_) {
461 Eigen::Affine3d H_world_initial =
462 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
463 vis_robot_.DrawFrameAxes(H_world_initial, std::to_string(id),
464 cv::Scalar(0, 0, 255));
465 Eigen::Affine3d H_world_solved = PoseUtils::Pose3dToAffine3d(solved_pose);
466 vis_robot_.DrawFrameAxes(H_world_solved, std::to_string(id) + "-est",
467 cv::Scalar(255, 255, 255));
468 }
469 cv::imshow("Solved vs. Initial", vis_robot_.image_);
470 cv::waitKey(0);
471}
472
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800473// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800474bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
Austin Schuh6bdcc372024-06-27 14:49:11 -0700475 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800476
477 ceres::Solver::Options options;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700478 options.max_num_iterations = absl::GetFlag(FLAGS_max_num_iterations);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800479 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
milind-u401de982023-04-14 17:32:03 -0700480 options.minimizer_progress_to_stdout = false;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800481
482 ceres::Solver::Summary summary;
483 ceres::Solve(options, problem, &summary);
484
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800485 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800486
487 return summary.IsSolutionUsable();
488}
489
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800490void TargetMapper::Solve(std::string_view field_name,
491 std::optional<std::string_view> output_dir) {
milind-u401de982023-04-14 17:32:03 -0700492 ceres::Problem target_pose_problem_1;
milind-u8f4e43e2023-04-09 17:11:19 -0700493 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
milind-u401de982023-04-14 17:32:03 -0700494 &target_pose_problem_1);
495 CHECK(SolveOptimizationProblem(&target_pose_problem_1))
496 << "The target pose solve 1 was not successful, exiting.";
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700497 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700498 LOG(INFO) << "Displaying constraint graph before removing outliers";
499 DisplayConstraintGraph();
500 DisplaySolvedVsInitial();
501 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800502
milind-u401de982023-04-14 17:32:03 -0700503 RemoveOutlierConstraints();
504
505 // Solve again once we've thrown out bad constraints
506 ceres::Problem target_pose_problem_2;
507 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
508 &target_pose_problem_2);
509 CHECK(SolveOptimizationProblem(&target_pose_problem_2))
510 << "The target pose solve 2 was not successful, exiting.";
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700511 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowskiefc3bde2024-03-23 16:34:06 -0700512 LOG(INFO) << "Displaying constraint graph before removing outliers";
513 DisplayConstraintGraph();
514 DisplaySolvedVsInitial();
515 }
milind-u401de982023-04-14 17:32:03 -0700516
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700517 if (absl::GetFlag(FLAGS_do_map_fitting)) {
Jim Ostrowski463ee592024-03-07 00:08:24 -0800518 LOG(INFO) << "Solving the overall map's best alignment to the previous map";
519 ceres::Problem map_fitting_problem(
520 {.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
521 std::unique_ptr<ceres::CostFunction> map_fitting_cost_function =
522 BuildMapFittingOptimizationProblem(&map_fitting_problem);
523 CHECK(SolveOptimizationProblem(&map_fitting_problem))
524 << "The map fitting solve was not successful, exiting.";
525 map_fitting_cost_function.release();
milind-u8f4e43e2023-04-09 17:11:19 -0700526
Jim Ostrowski463ee592024-03-07 00:08:24 -0800527 Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_;
528 LOG(INFO) << "H_frozen_actual: "
529 << PoseUtils::Affine3dToPose3d(H_frozen_actual);
milind-u8f4e43e2023-04-09 17:11:19 -0700530
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700531 auto H_world_frozen = PoseUtils::Pose3dToAffine3d(
532 target_poses_[absl::GetFlag(FLAGS_frozen_target_id)]);
Jim Ostrowski463ee592024-03-07 00:08:24 -0800533 auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
milind-u8f4e43e2023-04-09 17:11:19 -0700534
Jim Ostrowski463ee592024-03-07 00:08:24 -0800535 // Offset the solved poses to become the actual ones
536 for (auto &[id, pose] : target_poses_) {
537 // Don't offset targets we didn't solve for
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700538 if (id < absl::GetFlag(FLAGS_min_target_id) ||
539 id > absl::GetFlag(FLAGS_max_target_id)) {
Jim Ostrowski463ee592024-03-07 00:08:24 -0800540 continue;
541 }
542
543 // Take the delta between the frozen target and the solved target, and put
544 // that on top of the actual pose of the frozen target
545 auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose);
546 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
547 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
548 pose = PoseUtils::Affine3dToPose3d(H_world_actual);
milind-u8f4e43e2023-04-09 17:11:19 -0700549 }
milind-u8f4e43e2023-04-09 17:11:19 -0700550 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800551
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800552 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800553 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800554
555 if (output_dir.has_value()) {
556 std::string output_path =
557 absl::StrCat(output_dir.value(), "/", field_name, ".json");
558 LOG(INFO) << "Writing map to file: " << output_path;
559 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800560 }
milind-u401de982023-04-14 17:32:03 -0700561
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700562 for (TargetId id_start = absl::GetFlag(FLAGS_min_target_id);
563 id_start < absl::GetFlag(FLAGS_max_target_id); id_start++) {
564 for (TargetId id_end = id_start + 1;
565 id_end <= absl::GetFlag(FLAGS_max_target_id); id_end++) {
milind-u401de982023-04-14 17:32:03 -0700566 auto H_start_end =
567 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
568 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
569 auto constraint = PoseUtils::Affine3dToPose3d(H_start_end);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700570 VLOG(1) << id_start << "->" << id_end << ": " << constraint.p.norm()
571 << " meters";
milind-u401de982023-04-14 17:32:03 -0700572 }
573 }
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800574}
575
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800576std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800577 flatbuffers::FlatBufferBuilder fbb;
578
579 // Convert poses to flatbuffers
580 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
581 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800582 target_poses_fbs.emplace_back(
583 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800584 }
585
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800586 const auto field_name_offset = fbb.CreateString(field_name);
587 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
588 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800589
590 return aos::FlatbufferToJson(
591 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
592 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800593}
594
milind-u8f4e43e2023-04-09 17:11:19 -0700595namespace {
milind-u8f4e43e2023-04-09 17:11:19 -0700596// Hacks to extract a double from a scalar, which is either a ceres jet or a
597// double. Only used for debugging and displaying.
598template <typename S>
599double ScalarToDouble(S s) {
600 const double *ptr = reinterpret_cast<double *>(&s);
601 return *ptr;
602}
603
604template <typename S>
605Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) {
606 Eigen::Affine3d H_double;
607 for (size_t i = 0; i < H.rows(); i++) {
608 for (size_t j = 0; j < H.cols(); j++) {
609 H_double(i, j) = ScalarToDouble(H(i, j));
610 }
611 }
612 return H_double;
613}
614
615} // namespace
616
617template <typename S>
618bool TargetMapper::operator()(const S *const translation,
619 const S *const rotation, S *residual) const {
620 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
621 Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2],
622 rotation[0]);
623 Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1],
624 translation[2]);
625 // Actual target pose in the frame of the fixed pose.
626 Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual;
627 VLOG(2) << "H_frozen_actual: "
628 << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
629
630 Affine3s H_world_frozen =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700631 PoseUtils::Pose3dToAffine3d(
632 target_poses_.at(absl::GetFlag(FLAGS_frozen_target_id)))
milind-u8f4e43e2023-04-09 17:11:19 -0700633 .cast<S>();
634 Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
635
636 size_t residual_index = 0;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700637 if (absl::GetFlag(FLAGS_visualize_solver)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700638 vis_robot_.ClearImage();
639 }
640
641 for (const auto &[id, solved_pose] : target_poses_) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700642 if (id < absl::GetFlag(FLAGS_min_target_id) ||
643 id > absl::GetFlag(FLAGS_max_target_id)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700644 continue;
645 }
646
647 Affine3s H_world_ideal =
648 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>();
649 Affine3s H_world_solved =
650 PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>();
651 // Take the delta between the frozen target and the solved target, and put
652 // that on top of the actual pose of the frozen target
653 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
654 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
655 VLOG(2) << id << ": " << H_world_actual.translation();
656 Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual;
657 auto T_ideal_actual = H_ideal_actual.translation();
658 VLOG(2) << "T_ideal_actual: " << T_ideal_actual;
659 VLOG(2);
660 auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation());
661
milind-u401de982023-04-14 17:32:03 -0700662 // Weight translation errors higher than rotation.
663 // 1 m in position error = 0.01 radian (or ~0.573 degrees)
664 constexpr double kTranslationScalar = 1000.0;
665 constexpr double kRotationScalar = 100.0;
milind-u8f4e43e2023-04-09 17:11:19 -0700666
667 // Penalize based on how much our actual poses matches the ideal
668 // ones. We've already solved for the relative poses, now figure out
669 // where all of them fit in the world.
670 residual[residual_index++] = kTranslationScalar * T_ideal_actual(0);
671 residual[residual_index++] = kTranslationScalar * T_ideal_actual(1);
672 residual[residual_index++] = kTranslationScalar * T_ideal_actual(2);
673 residual[residual_index++] =
674 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x();
675 residual[residual_index++] =
676 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y();
677 residual[residual_index++] =
678 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
679
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700680 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowski68e56172023-09-17 23:44:15 -0700681 LOG(INFO) << std::to_string(id) + std::string("-est") << " at "
682 << ScalarAffineToDouble(H_world_actual).matrix();
milind-u8f4e43e2023-04-09 17:11:19 -0700683 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700684 std::to_string(id) + std::string("-est"),
685 cv::Scalar(0, 255, 0));
milind-u8f4e43e2023-04-09 17:11:19 -0700686 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal),
687 std::to_string(id), cv::Scalar(255, 255, 255));
688 }
689 }
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700690 if (absl::GetFlag(FLAGS_visualize_solver)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700691 cv::imshow("Target maps", vis_robot_.image_);
692 cv::waitKey(0);
693 }
694
695 // Ceres can't handle residual values of exactly zero
696 for (size_t i = 0; i < residual_index; i++) {
697 if (residual[i] == S(0)) {
698 residual[i] = S(1e-9);
699 }
700 }
701
702 return true;
703}
704
milind-u401de982023-04-14 17:32:03 -0700705TargetMapper::PoseError TargetMapper::ComputeError(
706 const ceres::examples::Constraint3d &constraint) const {
707 // Compute the difference between the map-based transform of the end target
708 // in the start target frame, to the one from this constraint
709 auto H_start_end_map =
710 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_begin))
711 .inverse() *
712 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_end));
713 auto H_start_end_constraint = PoseUtils::Pose3dToAffine3d(constraint.t_be);
714 ceres::examples::Pose3d delta_pose = PoseUtils::Affine3dToPose3d(
715 H_start_end_map.inverse() * H_start_end_constraint);
716 double distance = delta_pose.p.norm();
717 Eigen::AngleAxisd err_angle(delta_pose.q);
718 double angle = std::abs(err_angle.angle());
719 return {.angle = angle, .distance = distance};
720}
721
722TargetMapper::Stats TargetMapper::ComputeStats() const {
723 Stats stats{.avg_err = {.angle = 0.0, .distance = 0.0},
724 .std_dev = {.angle = 0.0, .distance = 0.0},
725 .max_err = {.angle = 0.0, .distance = 0.0}};
726
727 for (const auto &constraint : target_constraints_) {
728 PoseError err = ComputeError(constraint);
729
730 // Update our statistics
731 stats.avg_err.distance += err.distance;
732 if (err.distance > stats.max_err.distance) {
733 stats.max_err.distance = err.distance;
734 }
735
736 stats.avg_err.angle += err.angle;
737 if (err.angle > stats.max_err.angle) {
738 stats.max_err.angle = err.angle;
739 }
740 }
741
742 stats.avg_err.distance /= static_cast<double>(target_constraints_.size());
743 stats.avg_err.angle /= static_cast<double>(target_constraints_.size());
744
745 for (const auto &constraint : target_constraints_) {
746 PoseError err = ComputeError(constraint);
747
748 // Update our statistics
749 stats.std_dev.distance +=
750 std::pow(err.distance - stats.avg_err.distance, 2);
751
752 stats.std_dev.angle += std::pow(err.angle - stats.avg_err.angle, 2);
753 }
754
755 stats.std_dev.distance = std::sqrt(
756 stats.std_dev.distance / static_cast<double>(target_constraints_.size()));
757 stats.std_dev.angle = std::sqrt(
758 stats.std_dev.angle / static_cast<double>(target_constraints_.size()));
759
760 return stats;
761}
762
763void TargetMapper::RemoveOutlierConstraints() {
764 stats_with_outliers_ = ComputeStats();
765 size_t original_size = target_constraints_.size();
766 target_constraints_.erase(
767 std::remove_if(
768 target_constraints_.begin(), target_constraints_.end(),
769 [&](const auto &constraint) {
770 PoseError err = ComputeError(constraint);
771 // Remove constraints with errors significantly above
772 // the average
773 if (err.distance > stats_with_outliers_.avg_err.distance +
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700774 absl::GetFlag(FLAGS_outlier_std_devs) *
milind-u401de982023-04-14 17:32:03 -0700775 stats_with_outliers_.std_dev.distance) {
776 return true;
777 }
778 if (err.angle > stats_with_outliers_.avg_err.angle +
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700779 absl::GetFlag(FLAGS_outlier_std_devs) *
milind-u401de982023-04-14 17:32:03 -0700780 stats_with_outliers_.std_dev.angle) {
781 return true;
782 }
783 return false;
784 }),
785 target_constraints_.end());
786
787 LOG(INFO) << "Removed " << (original_size - target_constraints_.size())
788 << " outlier constraints out of " << original_size << " total";
789}
790
791void TargetMapper::DumpStats(std::string_view path) const {
792 LOG(INFO) << "Dumping mapping stats to " << path;
793 Stats stats = ComputeStats();
794 std::ofstream fout(path.data());
795 fout << "Stats after outlier rejection: " << std::endl;
796 fout << "Average error - angle: " << stats.avg_err.angle
797 << ", distance: " << stats.avg_err.distance << std::endl
798 << std::endl;
799 fout << "Standard deviation - angle: " << stats.std_dev.angle
800 << ", distance: " << stats.std_dev.distance << std::endl
801 << std::endl;
802 fout << "Max error - angle: " << stats.max_err.angle
803 << ", distance: " << stats.max_err.distance << std::endl;
804
805 fout << std::endl << "Stats before outlier rejection:" << std::endl;
806 fout << "Average error - angle: " << stats_with_outliers_.avg_err.angle
807 << ", distance: " << stats_with_outliers_.avg_err.distance << std::endl
808 << std::endl;
809 fout << "Standard deviation - angle: " << stats_with_outliers_.std_dev.angle
810 << ", distance: " << stats_with_outliers_.std_dev.distance << std::endl
811 << std::endl;
812 fout << "Max error - angle: " << stats_with_outliers_.max_err.angle
813 << ", distance: " << stats_with_outliers_.max_err.distance << std::endl;
814
815 fout.flush();
816 fout.close();
817}
818
819void TargetMapper::DumpConstraints(std::string_view path) const {
820 LOG(INFO) << "Dumping target constraints to " << path;
821 std::ofstream fout(path.data());
822 for (const auto &constraint : target_constraints_) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700823 fout << absl::StrCat("", constraint) << std::endl;
milind-u401de982023-04-14 17:32:03 -0700824 }
825 fout.flush();
826 fout.close();
827}
828
Jim Ostrowskif41b0942024-03-24 18:05:02 -0700829void TargetMapper::PrintDiffs() const {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700830 for (int id = absl::GetFlag(FLAGS_min_target_id);
831 id <= absl::GetFlag(FLAGS_max_target_id); id++) {
Jim Ostrowskif41b0942024-03-24 18:05:02 -0700832 Eigen::Affine3d H_world_ideal =
833 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
834 Eigen::Affine3d H_world_solved =
835 PoseUtils::Pose3dToAffine3d(target_poses_.at(id));
836 Eigen::Affine3d H_ideal_solved = H_world_ideal.inverse() * H_world_solved;
837 Eigen::Vector3d rpy = PoseUtils::RotationMatrixToEulerAngles(
838 H_ideal_solved.rotation().matrix()) *
839 180.0 / M_PI;
840 Eigen::Vector3d trans = H_ideal_solved.translation();
841
842 LOG(INFO) << "\nOffset from ideal to solved for target " << id
843 << " (in m, deg)"
844 << "\n x: " << trans(0) << ", y: " << trans(1)
845 << ", z: " << trans(2) << ", \n roll: " << rpy(0)
846 << ", pitch: " << rpy(1) << ", yaw: " << rpy(2) << "\n";
847 }
848}
849
milind-ufbc5c812023-04-06 21:24:29 -0700850} // namespace frc971::vision