blob: 3ec0c55be1e5559416f9098131fea4e98eb51fad [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"
Milind Upadhyay7c205222022-11-16 18:20:58 -08004#include "frc971/control_loops/control_loop.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08005#include "frc971/vision/ceres/pose_graph_3d_error_term.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08006#include "frc971/vision/geometry.h"
7
8DEFINE_uint64(max_num_iterations, 100,
9 "Maximum number of iterations for the ceres solver");
milind-ud62f80a2023-03-04 16:37:09 -080010DEFINE_double(distortion_noise_scalar, 1.0,
11 "Scale the target pose distortion factor by this when computing "
12 "the noise.");
milind-u8f4e43e2023-04-09 17:11:19 -070013DEFINE_int32(
milind-u6ff399f2023-03-24 18:33:38 -070014 frozen_target_id, 1,
15 "Freeze the pose of this target so the map can have one fixed point.");
milind-u8f4e43e2023-04-09 17:11:19 -070016DEFINE_int32(min_target_id, 1, "Minimum target id to solve for");
17DEFINE_int32(max_target_id, 8, "Maximum target id to solve for");
18DEFINE_bool(visualize_solver, false, "If true, visualize the solving process.");
milind-u401de982023-04-14 17:32:03 -070019// This does seem like a strict threshold for a constaint to be considered an
20// outlier, but most inliers were very close together and this is what worked
21// best for map solving.
22DEFINE_double(outlier_std_devs, 1.0,
23 "Number of standard deviations above average error needed for a "
24 "constraint to be considered an outlier and get removed.");
Milind Upadhyay7c205222022-11-16 18:20:58 -080025
26namespace frc971::vision {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080027Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
28 const ceres::examples::Pose3d &pose3d) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080029 Eigen::Affine3d H_world_pose =
Milind Upadhyayc5beba12022-12-17 17:41:20 -080030 Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q;
Milind Upadhyay7c205222022-11-16 18:20:58 -080031 return H_world_pose;
32}
33
Milind Upadhyayc5beba12022-12-17 17:41:20 -080034ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) {
35 return ceres::examples::Pose3d{.p = H.translation(),
36 .q = Eigen::Quaterniond(H.rotation())};
Milind Upadhyay7c205222022-11-16 18:20:58 -080037}
38
Milind Upadhyayc5beba12022-12-17 17:41:20 -080039ceres::examples::Pose3d PoseUtils::ComputeRelativePose(
40 const ceres::examples::Pose3d &pose_1,
41 const ceres::examples::Pose3d &pose_2) {
42 Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1);
43 Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080044
45 // Get the location of 2 in the 1 frame
46 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080047 return Affine3dToPose3d(H_1_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080048}
49
Milind Upadhyayc5beba12022-12-17 17:41:20 -080050ceres::examples::Pose3d PoseUtils::ComputeOffsetPose(
51 const ceres::examples::Pose3d &pose_1,
52 const ceres::examples::Pose3d &pose_2_relative) {
53 auto H_world_1 = Pose3dToAffine3d(pose_1);
54 auto H_1_2 = Pose3dToAffine3d(pose_2_relative);
Milind Upadhyay7c205222022-11-16 18:20:58 -080055 auto H_world_2 = H_world_1 * H_1_2;
56
Milind Upadhyayc5beba12022-12-17 17:41:20 -080057 return Affine3dToPose3d(H_world_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080058}
59
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion(
61 const Eigen::Vector3d &rpy) {
62 Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX());
63 Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY());
64 Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ());
65
66 return yaw_angle * pitch_angle * roll_angle;
Milind Upadhyay7c205222022-11-16 18:20:58 -080067}
68
Milind Upadhyayc5beba12022-12-17 17:41:20 -080069Eigen::Vector3d PoseUtils::QuaternionToEulerAngles(
70 const Eigen::Quaterniond &q) {
71 return RotationMatrixToEulerAngles(q.toRotationMatrix());
Milind Upadhyay7c205222022-11-16 18:20:58 -080072}
73
Milind Upadhyayc5beba12022-12-17 17:41:20 -080074Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles(
75 const Eigen::Matrix3d &R) {
76 double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2)));
77 double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0)));
78 double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0)));
79
80 return Eigen::Vector3d(roll, pitch, yaw);
81}
82
milind-u3f5f83c2023-01-29 15:23:51 -080083flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs(
84 const TargetMapper::TargetPose &target_pose,
85 flatbuffers::FlatBufferBuilder *fbb) {
86 const auto position_offset =
87 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
88 target_pose.pose.p(2));
89 const auto orientation_offset =
90 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
91 target_pose.pose.q.y(), target_pose.pose.q.z());
92 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
93 orientation_offset);
94}
95
96TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs(
97 const TargetPoseFbs &target_pose_fbs) {
98 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
99 .pose = ceres::examples::Pose3d{
100 Eigen::Vector3d(target_pose_fbs.position()->x(),
101 target_pose_fbs.position()->y(),
102 target_pose_fbs.position()->z()),
103 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
104 target_pose_fbs.orientation()->x(),
105 target_pose_fbs.orientation()->y(),
106 target_pose_fbs.orientation()->z())}};
107}
108
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800109ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800110 const std::vector<DataAdapter::TimestampedDetection>
111 &timestamped_target_detections,
112 aos::distributed_clock::duration max_dt) {
113 CHECK_GE(timestamped_target_detections.size(), 2ul)
114 << "Must have at least 2 detections";
115
116 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800117 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -0800118 for (auto detection = timestamped_target_detections.begin() + 1;
119 detection < timestamped_target_detections.end(); detection++) {
120 auto last_detection = detection - 1;
Milind Upadhyayec493912022-12-18 21:33:15 -0800121
122 // Skip two consecutive detections of the same target, because the solver
123 // doesn't allow this
milind-ud62f80a2023-03-04 16:37:09 -0800124 if (detection->id == last_detection->id) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800125 continue;
126 }
127
128 // Don't take into account constraints too far apart in time, because the
129 // recording device could have moved too much
milind-ud62f80a2023-03-04 16:37:09 -0800130 if ((detection->time - last_detection->time) > max_dt) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800131 continue;
132 }
133
milind-ud62f80a2023-03-04 16:37:09 -0800134 auto confidence = ComputeConfidence(*last_detection, *detection);
Milind Upadhyayec493912022-12-18 21:33:15 -0800135 target_constraints.emplace_back(
milind-ud62f80a2023-03-04 16:37:09 -0800136 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -0800137 }
138
139 return target_constraints;
140}
141
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800142TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800143 const TimestampedDetection &detection_start,
144 const TimestampedDetection &detection_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800145 constexpr size_t kX = 0;
146 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800147 constexpr size_t kZ = 2;
148 constexpr size_t kOrientation1 = 3;
149 constexpr size_t kOrientation2 = 4;
150 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800151
152 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800153 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800154
155 {
156 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800157 TargetMapper::ConfidenceMatrix Q_odometry =
158 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800159 Q_odometry(kX, kX) = std::pow(0.045, 2);
160 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800161 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
162 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
163 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
164 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800165
166 // Add uncertainty for robot position measurements from start to end
milind-ud62f80a2023-03-04 16:37:09 -0800167 int iterations = (detection_end.time - detection_start.time) /
168 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800169 P += static_cast<double>(iterations) * Q_odometry;
170 }
171
172 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800173 // Noise for vision-based target localizations. Multiplying this matrix by
milind-u6ff399f2023-03-24 18:33:38 -0700174 // the distance from camera to target squared results in the uncertainty
175 // in that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800176 TargetMapper::ConfidenceMatrix Q_vision =
177 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800178 Q_vision(kX, kX) = std::pow(0.045, 2);
179 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800180 Q_vision(kZ, kZ) = std::pow(0.045, 2);
181 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
182 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
183 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800184
185 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
milind-ufbc5c812023-04-06 21:24:29 -0700186 P += Q_vision * std::pow(detection_start.distance_from_camera *
187 (1.0 + FLAGS_distortion_noise_scalar *
188 detection_start.distortion_factor),
189 2);
190 P += Q_vision * std::pow(detection_end.distance_from_camera *
191 (1.0 + FLAGS_distortion_noise_scalar *
192 detection_end.distortion_factor),
193 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800194 }
195
196 return P.inverse();
197}
198
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800199ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800200 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800201 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800202 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800203 // Compute the relative pose (constraint) between the two targets
204 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800205 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800206 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800207 ceres::examples::Pose3d target_constraint =
208 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800209
milind-uf3ab8ba2023-02-04 17:56:16 -0800210 const auto constraint_3d =
211 ceres::examples::Constraint3d{target_detection_start.id,
212 target_detection_end.id,
213 {target_constraint.p, target_constraint.q},
214 confidence};
215
216 VLOG(2) << "Computed constraint: " << constraint_3d;
217 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800218}
219
Milind Upadhyay7c205222022-11-16 18:20:58 -0800220TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800221 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800222 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700223 : target_constraints_(target_constraints),
224 T_frozen_actual_(Eigen::Vector3d::Zero()),
225 R_frozen_actual_(Eigen::Quaterniond::Identity()),
226 vis_robot_(cv::Size(1280, 1000)) {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800227 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
228 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
229 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u8f4e43e2023-04-09 17:11:19 -0700230 ideal_target_poses_[target_pose_fbs->id()] =
milind-u3f5f83c2023-01-29 15:23:51 -0800231 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800232 }
milind-u8f4e43e2023-04-09 17:11:19 -0700233 target_poses_ = ideal_target_poses_;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800234}
235
236TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800237 const ceres::examples::MapOfPoses &target_poses,
238 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700239 : ideal_target_poses_(target_poses),
240 target_poses_(ideal_target_poses_),
241 target_constraints_(target_constraints),
242 T_frozen_actual_(Eigen::Vector3d::Zero()),
243 R_frozen_actual_(Eigen::Quaterniond::Identity()),
244 vis_robot_(cv::Size(1280, 1000)) {}
Milind Upadhyay7c205222022-11-16 18:20:58 -0800245
246std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
247 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
248 for (auto target_pose : target_poses) {
249 if (target_pose.id == target_id) {
250 return target_pose;
251 }
252 }
253
254 return std::nullopt;
255}
256
Jim Ostrowski49be8232023-03-23 01:00:14 -0700257std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
milind-u2ab4db12023-03-25 21:59:23 -0700258 TargetId target_id) const {
Jim Ostrowski49be8232023-03-23 01:00:14 -0700259 if (target_poses_.count(target_id) > 0) {
milind-u2ab4db12023-03-25 21:59:23 -0700260 return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700261 }
262
263 return std::nullopt;
264}
265
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800266// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
267// Constructs the nonlinear least squares optimization problem from the pose
268// graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700269void TargetMapper::BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800270 const ceres::examples::VectorOfConstraints &constraints,
271 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
272 CHECK(poses != nullptr);
273 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800274 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800275 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800276 return;
277 }
278
milind-u13ff1a52023-01-22 17:10:49 -0800279 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800280 ceres::LocalParameterization *quaternion_local_parameterization =
281 new ceres::EigenQuaternionParameterization;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800282
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800283 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
284 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800285 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800286 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800287
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800288 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800289 poses->find(constraint.id_begin);
290 CHECK(pose_begin_iter != poses->end())
291 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800292 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800293 poses->find(constraint.id_end);
294 CHECK(pose_end_iter != poses->end())
295 << "Pose with ID: " << constraint.id_end << " not found.";
296
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800297 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800298 constraint.information.llt().matrixL();
299 // Ceres will take ownership of the pointer.
300 ceres::CostFunction *cost_function =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800301 ceres::examples::PoseGraph3dErrorTerm::Create(constraint.t_be,
302 sqrt_information);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800303
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800304 problem->AddResidualBlock(cost_function, loss_function,
305 pose_begin_iter->second.p.data(),
306 pose_begin_iter->second.q.coeffs().data(),
307 pose_end_iter->second.p.data(),
308 pose_end_iter->second.q.coeffs().data());
309
310 problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
311 quaternion_local_parameterization);
312 problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
313 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800314 }
315
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800316 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800317 // constrained. This is typically referred to as gauge freedom. You can
318 // apply a rigid body transformation to all the nodes and the optimization
319 // problem will still have the exact same cost. The Levenberg-Marquardt
320 // algorithm has internal damping which mitigates this issue, but it is
321 // better to properly constrain the gauge freedom. This can be done by
322 // setting one of the poses as constant so the optimizer cannot change it.
milind-u6ff399f2023-03-24 18:33:38 -0700323 CHECK_NE(poses->count(FLAGS_frozen_target_id), 0ul)
324 << "Got no poses for frozen target id " << FLAGS_frozen_target_id;
325 ceres::examples::MapOfPoses::iterator pose_start_iter =
326 poses->find(FLAGS_frozen_target_id);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800327 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800328 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
329 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800330}
331
milind-u401de982023-04-14 17:32:03 -0700332std::unique_ptr<ceres::CostFunction>
333TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
milind-u8f4e43e2023-04-09 17:11:19 -0700334 // Setup robot visualization
335 vis_robot_.ClearImage();
336 constexpr int kImageWidth = 1280;
337 constexpr double kFocalLength = 500.0;
338 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
339
340 const size_t num_targets = FLAGS_max_target_id - FLAGS_min_target_id;
341 // Translation and rotation error for each target
342 const size_t num_residuals = num_targets * 6;
343 // Set up the only cost function (also known as residual). This uses
344 // auto-differentiation to obtain the derivative (jacobian).
milind-u401de982023-04-14 17:32:03 -0700345 std::unique_ptr<ceres::CostFunction> cost_function = std::make_unique<
346 ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>>(
347 this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
milind-u8f4e43e2023-04-09 17:11:19 -0700348
349 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
350 ceres::LocalParameterization *quaternion_local_parameterization =
351 new ceres::EigenQuaternionParameterization;
352
milind-u401de982023-04-14 17:32:03 -0700353 problem->AddResidualBlock(cost_function.get(), loss_function,
milind-u8f4e43e2023-04-09 17:11:19 -0700354 T_frozen_actual_.vector().data(),
355 R_frozen_actual_.coeffs().data());
356 problem->SetParameterization(R_frozen_actual_.coeffs().data(),
357 quaternion_local_parameterization);
milind-u401de982023-04-14 17:32:03 -0700358 return cost_function;
milind-u8f4e43e2023-04-09 17:11:19 -0700359}
360
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800361// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800362bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
363 CHECK_NOTNULL(problem);
364
365 ceres::Solver::Options options;
366 options.max_num_iterations = FLAGS_max_num_iterations;
367 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
milind-u401de982023-04-14 17:32:03 -0700368 options.minimizer_progress_to_stdout = false;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800369
370 ceres::Solver::Summary summary;
371 ceres::Solve(options, problem, &summary);
372
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800373 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800374
375 return summary.IsSolutionUsable();
376}
377
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800378void TargetMapper::Solve(std::string_view field_name,
379 std::optional<std::string_view> output_dir) {
milind-u401de982023-04-14 17:32:03 -0700380 ceres::Problem target_pose_problem_1;
milind-u8f4e43e2023-04-09 17:11:19 -0700381 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
milind-u401de982023-04-14 17:32:03 -0700382 &target_pose_problem_1);
383 CHECK(SolveOptimizationProblem(&target_pose_problem_1))
384 << "The target pose solve 1 was not successful, exiting.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800385
milind-u401de982023-04-14 17:32:03 -0700386 RemoveOutlierConstraints();
387
388 // Solve again once we've thrown out bad constraints
389 ceres::Problem target_pose_problem_2;
390 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
391 &target_pose_problem_2);
392 CHECK(SolveOptimizationProblem(&target_pose_problem_2))
393 << "The target pose solve 2 was not successful, exiting.";
394
395 ceres::Problem map_fitting_problem(
396 {.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
397 std::unique_ptr<ceres::CostFunction> map_fitting_cost_function =
398 BuildMapFittingOptimizationProblem(&map_fitting_problem);
milind-u8f4e43e2023-04-09 17:11:19 -0700399 CHECK(SolveOptimizationProblem(&map_fitting_problem))
400 << "The map fitting solve was not successful, exiting.";
milind-u401de982023-04-14 17:32:03 -0700401 map_fitting_cost_function.release();
milind-u8f4e43e2023-04-09 17:11:19 -0700402
403 Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_;
404 LOG(INFO) << "H_frozen_actual: "
405 << PoseUtils::Affine3dToPose3d(H_frozen_actual);
406
407 auto H_world_frozen =
408 PoseUtils::Pose3dToAffine3d(target_poses_[FLAGS_frozen_target_id]);
409 auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
410
411 // Offset the solved poses to become the actual ones
412 for (auto &[id, pose] : target_poses_) {
413 // Don't offset targets we didn't solve for
414 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
415 continue;
416 }
417
418 // Take the delta between the frozen target and the solved target, and put
419 // that on top of the actual pose of the frozen target
420 auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose);
421 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
422 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
423 pose = PoseUtils::Affine3dToPose3d(H_world_actual);
424 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800425
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800426 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800427 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800428
429 if (output_dir.has_value()) {
430 std::string output_path =
431 absl::StrCat(output_dir.value(), "/", field_name, ".json");
432 LOG(INFO) << "Writing map to file: " << output_path;
433 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800434 }
milind-u401de982023-04-14 17:32:03 -0700435
436 for (TargetId id_start = FLAGS_min_target_id; id_start < FLAGS_max_target_id;
437 id_start++) {
438 for (TargetId id_end = id_start + 1; id_end <= FLAGS_max_target_id;
439 id_end++) {
440 auto H_start_end =
441 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
442 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
443 auto constraint = PoseUtils::Affine3dToPose3d(H_start_end);
444 LOG(INFO) << id_start << "->" << id_end << ": " << constraint.p.norm()
445 << " meters";
446 }
447 }
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800448}
449
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800450std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800451 flatbuffers::FlatBufferBuilder fbb;
452
453 // Convert poses to flatbuffers
454 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
455 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800456 target_poses_fbs.emplace_back(
457 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800458 }
459
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800460 const auto field_name_offset = fbb.CreateString(field_name);
461 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
462 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800463
464 return aos::FlatbufferToJson(
465 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
466 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800467}
468
milind-u8f4e43e2023-04-09 17:11:19 -0700469namespace {
470
471// Hacks to extract a double from a scalar, which is either a ceres jet or a
472// double. Only used for debugging and displaying.
473template <typename S>
474double ScalarToDouble(S s) {
475 const double *ptr = reinterpret_cast<double *>(&s);
476 return *ptr;
477}
478
479template <typename S>
480Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) {
481 Eigen::Affine3d H_double;
482 for (size_t i = 0; i < H.rows(); i++) {
483 for (size_t j = 0; j < H.cols(); j++) {
484 H_double(i, j) = ScalarToDouble(H(i, j));
485 }
486 }
487 return H_double;
488}
489
490} // namespace
491
492template <typename S>
493bool TargetMapper::operator()(const S *const translation,
494 const S *const rotation, S *residual) const {
495 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
496 Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2],
497 rotation[0]);
498 Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1],
499 translation[2]);
500 // Actual target pose in the frame of the fixed pose.
501 Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual;
502 VLOG(2) << "H_frozen_actual: "
503 << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
504
505 Affine3s H_world_frozen =
506 PoseUtils::Pose3dToAffine3d(target_poses_.at(FLAGS_frozen_target_id))
507 .cast<S>();
508 Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
509
510 size_t residual_index = 0;
511 if (FLAGS_visualize_solver) {
512 vis_robot_.ClearImage();
513 }
514
515 for (const auto &[id, solved_pose] : target_poses_) {
516 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
517 continue;
518 }
519
520 Affine3s H_world_ideal =
521 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>();
522 Affine3s H_world_solved =
523 PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>();
524 // Take the delta between the frozen target and the solved target, and put
525 // that on top of the actual pose of the frozen target
526 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
527 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
528 VLOG(2) << id << ": " << H_world_actual.translation();
529 Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual;
530 auto T_ideal_actual = H_ideal_actual.translation();
531 VLOG(2) << "T_ideal_actual: " << T_ideal_actual;
532 VLOG(2);
533 auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation());
534
milind-u401de982023-04-14 17:32:03 -0700535 // Weight translation errors higher than rotation.
536 // 1 m in position error = 0.01 radian (or ~0.573 degrees)
537 constexpr double kTranslationScalar = 1000.0;
538 constexpr double kRotationScalar = 100.0;
milind-u8f4e43e2023-04-09 17:11:19 -0700539
540 // Penalize based on how much our actual poses matches the ideal
541 // ones. We've already solved for the relative poses, now figure out
542 // where all of them fit in the world.
543 residual[residual_index++] = kTranslationScalar * T_ideal_actual(0);
544 residual[residual_index++] = kTranslationScalar * T_ideal_actual(1);
545 residual[residual_index++] = kTranslationScalar * T_ideal_actual(2);
546 residual[residual_index++] =
547 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x();
548 residual[residual_index++] =
549 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y();
550 residual[residual_index++] =
551 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
552
553 if (FLAGS_visualize_solver) {
554 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
555 std::to_string(id), cv::Scalar(0, 255, 0));
556 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal),
557 std::to_string(id), cv::Scalar(255, 255, 255));
558 }
559 }
560 if (FLAGS_visualize_solver) {
561 cv::imshow("Target maps", vis_robot_.image_);
562 cv::waitKey(0);
563 }
564
565 // Ceres can't handle residual values of exactly zero
566 for (size_t i = 0; i < residual_index; i++) {
567 if (residual[i] == S(0)) {
568 residual[i] = S(1e-9);
569 }
570 }
571
572 return true;
573}
574
milind-u401de982023-04-14 17:32:03 -0700575TargetMapper::PoseError TargetMapper::ComputeError(
576 const ceres::examples::Constraint3d &constraint) const {
577 // Compute the difference between the map-based transform of the end target
578 // in the start target frame, to the one from this constraint
579 auto H_start_end_map =
580 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_begin))
581 .inverse() *
582 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_end));
583 auto H_start_end_constraint = PoseUtils::Pose3dToAffine3d(constraint.t_be);
584 ceres::examples::Pose3d delta_pose = PoseUtils::Affine3dToPose3d(
585 H_start_end_map.inverse() * H_start_end_constraint);
586 double distance = delta_pose.p.norm();
587 Eigen::AngleAxisd err_angle(delta_pose.q);
588 double angle = std::abs(err_angle.angle());
589 return {.angle = angle, .distance = distance};
590}
591
592TargetMapper::Stats TargetMapper::ComputeStats() const {
593 Stats stats{.avg_err = {.angle = 0.0, .distance = 0.0},
594 .std_dev = {.angle = 0.0, .distance = 0.0},
595 .max_err = {.angle = 0.0, .distance = 0.0}};
596
597 for (const auto &constraint : target_constraints_) {
598 PoseError err = ComputeError(constraint);
599
600 // Update our statistics
601 stats.avg_err.distance += err.distance;
602 if (err.distance > stats.max_err.distance) {
603 stats.max_err.distance = err.distance;
604 }
605
606 stats.avg_err.angle += err.angle;
607 if (err.angle > stats.max_err.angle) {
608 stats.max_err.angle = err.angle;
609 }
610 }
611
612 stats.avg_err.distance /= static_cast<double>(target_constraints_.size());
613 stats.avg_err.angle /= static_cast<double>(target_constraints_.size());
614
615 for (const auto &constraint : target_constraints_) {
616 PoseError err = ComputeError(constraint);
617
618 // Update our statistics
619 stats.std_dev.distance +=
620 std::pow(err.distance - stats.avg_err.distance, 2);
621
622 stats.std_dev.angle += std::pow(err.angle - stats.avg_err.angle, 2);
623 }
624
625 stats.std_dev.distance = std::sqrt(
626 stats.std_dev.distance / static_cast<double>(target_constraints_.size()));
627 stats.std_dev.angle = std::sqrt(
628 stats.std_dev.angle / static_cast<double>(target_constraints_.size()));
629
630 return stats;
631}
632
633void TargetMapper::RemoveOutlierConstraints() {
634 stats_with_outliers_ = ComputeStats();
635 size_t original_size = target_constraints_.size();
636 target_constraints_.erase(
637 std::remove_if(
638 target_constraints_.begin(), target_constraints_.end(),
639 [&](const auto &constraint) {
640 PoseError err = ComputeError(constraint);
641 // Remove constraints with errors significantly above
642 // the average
643 if (err.distance > stats_with_outliers_.avg_err.distance +
644 FLAGS_outlier_std_devs *
645 stats_with_outliers_.std_dev.distance) {
646 return true;
647 }
648 if (err.angle > stats_with_outliers_.avg_err.angle +
649 FLAGS_outlier_std_devs *
650 stats_with_outliers_.std_dev.angle) {
651 return true;
652 }
653 return false;
654 }),
655 target_constraints_.end());
656
657 LOG(INFO) << "Removed " << (original_size - target_constraints_.size())
658 << " outlier constraints out of " << original_size << " total";
659}
660
661void TargetMapper::DumpStats(std::string_view path) const {
662 LOG(INFO) << "Dumping mapping stats to " << path;
663 Stats stats = ComputeStats();
664 std::ofstream fout(path.data());
665 fout << "Stats after outlier rejection: " << std::endl;
666 fout << "Average error - angle: " << stats.avg_err.angle
667 << ", distance: " << stats.avg_err.distance << std::endl
668 << std::endl;
669 fout << "Standard deviation - angle: " << stats.std_dev.angle
670 << ", distance: " << stats.std_dev.distance << std::endl
671 << std::endl;
672 fout << "Max error - angle: " << stats.max_err.angle
673 << ", distance: " << stats.max_err.distance << std::endl;
674
675 fout << std::endl << "Stats before outlier rejection:" << std::endl;
676 fout << "Average error - angle: " << stats_with_outliers_.avg_err.angle
677 << ", distance: " << stats_with_outliers_.avg_err.distance << std::endl
678 << std::endl;
679 fout << "Standard deviation - angle: " << stats_with_outliers_.std_dev.angle
680 << ", distance: " << stats_with_outliers_.std_dev.distance << std::endl
681 << std::endl;
682 fout << "Max error - angle: " << stats_with_outliers_.max_err.angle
683 << ", distance: " << stats_with_outliers_.max_err.distance << std::endl;
684
685 fout.flush();
686 fout.close();
687}
688
689void TargetMapper::DumpConstraints(std::string_view path) const {
690 LOG(INFO) << "Dumping target constraints to " << path;
691 std::ofstream fout(path.data());
692 for (const auto &constraint : target_constraints_) {
693 fout << constraint << std::endl;
694 }
695 fout.flush();
696 fout.close();
697}
698
milind-ufbc5c812023-04-06 21:24:29 -0700699} // namespace frc971::vision
700
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800701std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
milind-ufbc5c812023-04-06 21:24:29 -0700702 auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800703 os << absl::StrFormat(
704 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
705 "%.3f, yaw: %.3f}",
706 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
707 return os;
708}
709
710std::ostream &operator<<(std::ostream &os,
711 ceres::examples::Constraint3d constraint) {
712 os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
713 constraint.id_begin, constraint.id_end)
714 << constraint.t_be << "}";
715 return os;
716}