blob: c14b0327a674e81cccce03ba809b778e3ce8e973 [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.");
Milind Upadhyay7c205222022-11-16 18:20:58 -080026
27namespace frc971::vision {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080028Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
29 const ceres::examples::Pose3d &pose3d) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080030 Eigen::Affine3d H_world_pose =
Milind Upadhyayc5beba12022-12-17 17:41:20 -080031 Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q;
Milind Upadhyay7c205222022-11-16 18:20:58 -080032 return H_world_pose;
33}
34
Milind Upadhyayc5beba12022-12-17 17:41:20 -080035ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) {
36 return ceres::examples::Pose3d{.p = H.translation(),
37 .q = Eigen::Quaterniond(H.rotation())};
Milind Upadhyay7c205222022-11-16 18:20:58 -080038}
39
Milind Upadhyayc5beba12022-12-17 17:41:20 -080040ceres::examples::Pose3d PoseUtils::ComputeRelativePose(
41 const ceres::examples::Pose3d &pose_1,
42 const ceres::examples::Pose3d &pose_2) {
43 Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1);
44 Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080045
46 // Get the location of 2 in the 1 frame
47 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080048 return Affine3dToPose3d(H_1_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080049}
50
Milind Upadhyayc5beba12022-12-17 17:41:20 -080051ceres::examples::Pose3d PoseUtils::ComputeOffsetPose(
52 const ceres::examples::Pose3d &pose_1,
53 const ceres::examples::Pose3d &pose_2_relative) {
54 auto H_world_1 = Pose3dToAffine3d(pose_1);
55 auto H_1_2 = Pose3dToAffine3d(pose_2_relative);
Milind Upadhyay7c205222022-11-16 18:20:58 -080056 auto H_world_2 = H_world_1 * H_1_2;
57
Milind Upadhyayc5beba12022-12-17 17:41:20 -080058 return Affine3dToPose3d(H_world_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080059}
60
Milind Upadhyayc5beba12022-12-17 17:41:20 -080061Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion(
62 const Eigen::Vector3d &rpy) {
63 Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX());
64 Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY());
65 Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ());
66
67 return yaw_angle * pitch_angle * roll_angle;
Milind Upadhyay7c205222022-11-16 18:20:58 -080068}
69
Milind Upadhyayc5beba12022-12-17 17:41:20 -080070Eigen::Vector3d PoseUtils::QuaternionToEulerAngles(
71 const Eigen::Quaterniond &q) {
72 return RotationMatrixToEulerAngles(q.toRotationMatrix());
Milind Upadhyay7c205222022-11-16 18:20:58 -080073}
74
Milind Upadhyayc5beba12022-12-17 17:41:20 -080075Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles(
76 const Eigen::Matrix3d &R) {
77 double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2)));
78 double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0)));
79 double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0)));
80
81 return Eigen::Vector3d(roll, pitch, yaw);
82}
83
milind-u3f5f83c2023-01-29 15:23:51 -080084flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs(
85 const TargetMapper::TargetPose &target_pose,
86 flatbuffers::FlatBufferBuilder *fbb) {
87 const auto position_offset =
88 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
89 target_pose.pose.p(2));
90 const auto orientation_offset =
91 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
92 target_pose.pose.q.y(), target_pose.pose.q.z());
93 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
94 orientation_offset);
95}
96
97TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs(
98 const TargetPoseFbs &target_pose_fbs) {
99 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
100 .pose = ceres::examples::Pose3d{
101 Eigen::Vector3d(target_pose_fbs.position()->x(),
102 target_pose_fbs.position()->y(),
103 target_pose_fbs.position()->z()),
104 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
105 target_pose_fbs.orientation()->x(),
106 target_pose_fbs.orientation()->y(),
James Kuszmaulfeb89082024-02-21 14:00:15 -0800107 target_pose_fbs.orientation()->z())
108 .normalized()}};
milind-u3f5f83c2023-01-29 15:23:51 -0800109}
110
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800111ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800112 const std::vector<DataAdapter::TimestampedDetection>
113 &timestamped_target_detections,
114 aos::distributed_clock::duration max_dt) {
115 CHECK_GE(timestamped_target_detections.size(), 2ul)
116 << "Must have at least 2 detections";
117
118 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800119 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -0800120 for (auto detection = timestamped_target_detections.begin() + 1;
121 detection < timestamped_target_detections.end(); detection++) {
122 auto last_detection = detection - 1;
Milind Upadhyayec493912022-12-18 21:33:15 -0800123
124 // Skip two consecutive detections of the same target, because the solver
125 // doesn't allow this
milind-ud62f80a2023-03-04 16:37:09 -0800126 if (detection->id == last_detection->id) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800127 continue;
128 }
129
130 // Don't take into account constraints too far apart in time, because the
131 // recording device could have moved too much
milind-ud62f80a2023-03-04 16:37:09 -0800132 if ((detection->time - last_detection->time) > max_dt) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800133 continue;
134 }
135
milind-ud62f80a2023-03-04 16:37:09 -0800136 auto confidence = ComputeConfidence(*last_detection, *detection);
Milind Upadhyayec493912022-12-18 21:33:15 -0800137 target_constraints.emplace_back(
milind-ud62f80a2023-03-04 16:37:09 -0800138 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -0800139 }
140
141 return target_constraints;
142}
143
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800144TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800145 const TimestampedDetection &detection_start,
146 const TimestampedDetection &detection_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800147 constexpr size_t kX = 0;
148 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800149 constexpr size_t kZ = 2;
150 constexpr size_t kOrientation1 = 3;
151 constexpr size_t kOrientation2 = 4;
152 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800153
154 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800155 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800156
157 {
158 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800159 TargetMapper::ConfidenceMatrix Q_odometry =
160 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800161 Q_odometry(kX, kX) = std::pow(0.045, 2);
162 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800163 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
164 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
165 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
166 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800167
168 // Add uncertainty for robot position measurements from start to end
milind-ud62f80a2023-03-04 16:37:09 -0800169 int iterations = (detection_end.time - detection_start.time) /
170 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800171 P += static_cast<double>(iterations) * Q_odometry;
172 }
173
174 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800175 // Noise for vision-based target localizations. Multiplying this matrix by
milind-u6ff399f2023-03-24 18:33:38 -0700176 // the distance from camera to target squared results in the uncertainty
177 // in that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800178 TargetMapper::ConfidenceMatrix Q_vision =
179 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800180 Q_vision(kX, kX) = std::pow(0.045, 2);
181 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800182 Q_vision(kZ, kZ) = std::pow(0.045, 2);
183 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
184 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
185 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800186
187 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
milind-ufbc5c812023-04-06 21:24:29 -0700188 P += Q_vision * std::pow(detection_start.distance_from_camera *
189 (1.0 + FLAGS_distortion_noise_scalar *
190 detection_start.distortion_factor),
191 2);
192 P += Q_vision * std::pow(detection_end.distance_from_camera *
193 (1.0 + FLAGS_distortion_noise_scalar *
194 detection_end.distortion_factor),
195 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800196 }
197
198 return P.inverse();
199}
200
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800201ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800202 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800203 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800204 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800205 // Compute the relative pose (constraint) between the two targets
206 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800207 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800208 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800209 ceres::examples::Pose3d target_constraint =
210 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800211
milind-uf3ab8ba2023-02-04 17:56:16 -0800212 const auto constraint_3d =
213 ceres::examples::Constraint3d{target_detection_start.id,
214 target_detection_end.id,
215 {target_constraint.p, target_constraint.q},
216 confidence};
217
218 VLOG(2) << "Computed constraint: " << constraint_3d;
219 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800220}
221
Milind Upadhyay7c205222022-11-16 18:20:58 -0800222TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800223 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800224 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700225 : target_constraints_(target_constraints),
226 T_frozen_actual_(Eigen::Vector3d::Zero()),
227 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700228 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800229 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
230 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
231 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u8f4e43e2023-04-09 17:11:19 -0700232 ideal_target_poses_[target_pose_fbs->id()] =
milind-u3f5f83c2023-01-29 15:23:51 -0800233 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800234 }
milind-u8f4e43e2023-04-09 17:11:19 -0700235 target_poses_ = ideal_target_poses_;
milind-u526d5672023-04-17 20:09:10 -0700236 CountConstraints();
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800237}
238
239TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800240 const ceres::examples::MapOfPoses &target_poses,
241 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700242 : ideal_target_poses_(target_poses),
243 target_poses_(ideal_target_poses_),
244 target_constraints_(target_constraints),
245 T_frozen_actual_(Eigen::Vector3d::Zero()),
246 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700247 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
milind-u526d5672023-04-17 20:09:10 -0700248 CountConstraints();
249}
250
251namespace {
252std::pair<TargetMapper::TargetId, TargetMapper::TargetId> MakeIdPair(
253 const ceres::examples::Constraint3d &constraint) {
254 auto min_id = std::min(constraint.id_begin, constraint.id_end);
255 auto max_id = std::max(constraint.id_begin, constraint.id_end);
256 return std::make_pair(min_id, max_id);
257}
258} // namespace
259
260void TargetMapper::CountConstraints() {
261 for (const auto &constraint : target_constraints_) {
262 auto id_pair = MakeIdPair(constraint);
263 if (constraint_counts_.count(id_pair) == 0) {
264 constraint_counts_[id_pair] = 0;
265 }
266 constraint_counts_[id_pair]++;
267 }
268}
Milind Upadhyay7c205222022-11-16 18:20:58 -0800269
270std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
271 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
272 for (auto target_pose : target_poses) {
273 if (target_pose.id == target_id) {
274 return target_pose;
275 }
276 }
277
278 return std::nullopt;
279}
280
Jim Ostrowski49be8232023-03-23 01:00:14 -0700281std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
milind-u2ab4db12023-03-25 21:59:23 -0700282 TargetId target_id) const {
Jim Ostrowski49be8232023-03-23 01:00:14 -0700283 if (target_poses_.count(target_id) > 0) {
milind-u2ab4db12023-03-25 21:59:23 -0700284 return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700285 }
286
287 return std::nullopt;
288}
289
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800290// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
291// Constructs the nonlinear least squares optimization problem from the pose
292// graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700293void TargetMapper::BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800294 const ceres::examples::VectorOfConstraints &constraints,
295 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
296 CHECK(poses != nullptr);
297 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800298 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800299 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800300 return;
301 }
302
milind-u13ff1a52023-01-22 17:10:49 -0800303 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800304 ceres::LocalParameterization *quaternion_local_parameterization =
305 new ceres::EigenQuaternionParameterization;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800306
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700307 int min_constraint_id = std::numeric_limits<int>::max();
308 int max_constraint_id = std::numeric_limits<int>::min();
309
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800310 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
311 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800312 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800313 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800314
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800315 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800316 poses->find(constraint.id_begin);
317 CHECK(pose_begin_iter != poses->end())
318 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800319 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800320 poses->find(constraint.id_end);
321 CHECK(pose_end_iter != poses->end())
322 << "Pose with ID: " << constraint.id_end << " not found.";
323
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800324 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800325 constraint.information.llt().matrixL();
milind-u526d5672023-04-17 20:09:10 -0700326
327 auto id_pair = MakeIdPair(constraint);
328 CHECK_GT(constraint_counts_.count(id_pair), 0ul)
329 << "Should have counted constraints for " << id_pair.first << "->"
330 << id_pair.second;
331
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700332 VLOG(1) << "Adding constraint pair: " << id_pair.first << " and "
333 << id_pair.second;
334 // Store min & max id's; assumes first id < second id
335 if (id_pair.first < min_constraint_id) {
336 min_constraint_id = id_pair.first;
337 }
338 if (id_pair.second > max_constraint_id) {
339 max_constraint_id = id_pair.second;
340 }
milind-u526d5672023-04-17 20:09:10 -0700341 // Normalize constraint cost by occurances
342 size_t constraint_count = constraint_counts_[id_pair];
343 // Scale all costs so the total cost comes out to more reasonable numbers
344 constexpr double kGlobalWeight = 1000.0;
345 double constraint_weight =
346 kGlobalWeight / static_cast<double>(constraint_count);
347
Milind Upadhyay7c205222022-11-16 18:20:58 -0800348 // Ceres will take ownership of the pointer.
349 ceres::CostFunction *cost_function =
milind-u526d5672023-04-17 20:09:10 -0700350 ceres::examples::PoseGraph3dErrorTerm::Create(
351 constraint.t_be, sqrt_information, constraint_weight);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800352
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800353 problem->AddResidualBlock(cost_function, loss_function,
354 pose_begin_iter->second.p.data(),
355 pose_begin_iter->second.q.coeffs().data(),
356 pose_end_iter->second.p.data(),
357 pose_end_iter->second.q.coeffs().data());
358
359 problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
360 quaternion_local_parameterization);
361 problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
362 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800363 }
364
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800365 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800366 // constrained. This is typically referred to as gauge freedom. You can
367 // apply a rigid body transformation to all the nodes and the optimization
368 // problem will still have the exact same cost. The Levenberg-Marquardt
369 // algorithm has internal damping which mitigates this issue, but it is
370 // better to properly constrain the gauge freedom. This can be done by
371 // setting one of the poses as constant so the optimizer cannot change it.
milind-u6ff399f2023-03-24 18:33:38 -0700372 CHECK_NE(poses->count(FLAGS_frozen_target_id), 0ul)
373 << "Got no poses for frozen target id " << FLAGS_frozen_target_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700374 CHECK_GE(FLAGS_frozen_target_id, min_constraint_id)
375 << "target to freeze index " << FLAGS_frozen_target_id
376 << " must be in range of constraints, > " << min_constraint_id;
377 CHECK_LE(FLAGS_frozen_target_id, max_constraint_id)
378 << "target to freeze index " << FLAGS_frozen_target_id
379 << " must be in range of constraints, < " << max_constraint_id;
milind-u6ff399f2023-03-24 18:33:38 -0700380 ceres::examples::MapOfPoses::iterator pose_start_iter =
381 poses->find(FLAGS_frozen_target_id);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800382 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800383 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
384 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800385}
386
milind-u401de982023-04-14 17:32:03 -0700387std::unique_ptr<ceres::CostFunction>
388TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
Philipp Schradera6712522023-07-05 20:25:11 -0700389 // Set up robot visualization.
milind-u8f4e43e2023-04-09 17:11:19 -0700390 vis_robot_.ClearImage();
Jim Ostrowski68e56172023-09-17 23:44:15 -0700391 // Compute focal length so that image shows field with viewpoint at 10m above
392 // it (default for viewer)
393 const double kFocalLength = kImageWidth_ * 10.0 / kFieldWidth_;
394 vis_robot_.SetDefaultViewpoint(kImageWidth_, kFocalLength);
milind-u8f4e43e2023-04-09 17:11:19 -0700395
396 const size_t num_targets = FLAGS_max_target_id - FLAGS_min_target_id;
397 // Translation and rotation error for each target
398 const size_t num_residuals = num_targets * 6;
399 // Set up the only cost function (also known as residual). This uses
400 // auto-differentiation to obtain the derivative (jacobian).
milind-u401de982023-04-14 17:32:03 -0700401 std::unique_ptr<ceres::CostFunction> cost_function = std::make_unique<
402 ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>>(
403 this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
milind-u8f4e43e2023-04-09 17:11:19 -0700404
405 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
406 ceres::LocalParameterization *quaternion_local_parameterization =
407 new ceres::EigenQuaternionParameterization;
408
milind-u401de982023-04-14 17:32:03 -0700409 problem->AddResidualBlock(cost_function.get(), loss_function,
milind-u8f4e43e2023-04-09 17:11:19 -0700410 T_frozen_actual_.vector().data(),
411 R_frozen_actual_.coeffs().data());
412 problem->SetParameterization(R_frozen_actual_.coeffs().data(),
413 quaternion_local_parameterization);
milind-u401de982023-04-14 17:32:03 -0700414 return cost_function;
milind-u8f4e43e2023-04-09 17:11:19 -0700415}
416
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800417// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800418bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
419 CHECK_NOTNULL(problem);
420
421 ceres::Solver::Options options;
422 options.max_num_iterations = FLAGS_max_num_iterations;
423 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
milind-u401de982023-04-14 17:32:03 -0700424 options.minimizer_progress_to_stdout = false;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800425
426 ceres::Solver::Summary summary;
427 ceres::Solve(options, problem, &summary);
428
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800429 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800430
431 return summary.IsSolutionUsable();
432}
433
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800434void TargetMapper::Solve(std::string_view field_name,
435 std::optional<std::string_view> output_dir) {
milind-u401de982023-04-14 17:32:03 -0700436 ceres::Problem target_pose_problem_1;
milind-u8f4e43e2023-04-09 17:11:19 -0700437 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
milind-u401de982023-04-14 17:32:03 -0700438 &target_pose_problem_1);
439 CHECK(SolveOptimizationProblem(&target_pose_problem_1))
440 << "The target pose solve 1 was not successful, exiting.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800441
milind-u401de982023-04-14 17:32:03 -0700442 RemoveOutlierConstraints();
443
444 // Solve again once we've thrown out bad constraints
445 ceres::Problem target_pose_problem_2;
446 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
447 &target_pose_problem_2);
448 CHECK(SolveOptimizationProblem(&target_pose_problem_2))
449 << "The target pose solve 2 was not successful, exiting.";
450
Jim Ostrowski68e56172023-09-17 23:44:15 -0700451 LOG(INFO) << "Solving the overall map's best alignment to the previous map";
milind-u401de982023-04-14 17:32:03 -0700452 ceres::Problem map_fitting_problem(
453 {.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
454 std::unique_ptr<ceres::CostFunction> map_fitting_cost_function =
455 BuildMapFittingOptimizationProblem(&map_fitting_problem);
milind-u8f4e43e2023-04-09 17:11:19 -0700456 CHECK(SolveOptimizationProblem(&map_fitting_problem))
457 << "The map fitting solve was not successful, exiting.";
milind-u401de982023-04-14 17:32:03 -0700458 map_fitting_cost_function.release();
milind-u8f4e43e2023-04-09 17:11:19 -0700459
460 Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_;
461 LOG(INFO) << "H_frozen_actual: "
462 << PoseUtils::Affine3dToPose3d(H_frozen_actual);
463
464 auto H_world_frozen =
465 PoseUtils::Pose3dToAffine3d(target_poses_[FLAGS_frozen_target_id]);
466 auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
467
468 // Offset the solved poses to become the actual ones
469 for (auto &[id, pose] : target_poses_) {
470 // Don't offset targets we didn't solve for
471 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
472 continue;
473 }
474
475 // Take the delta between the frozen target and the solved target, and put
476 // that on top of the actual pose of the frozen target
477 auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose);
478 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
479 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
480 pose = PoseUtils::Affine3dToPose3d(H_world_actual);
481 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800482
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800483 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800484 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800485
486 if (output_dir.has_value()) {
487 std::string output_path =
488 absl::StrCat(output_dir.value(), "/", field_name, ".json");
489 LOG(INFO) << "Writing map to file: " << output_path;
490 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800491 }
milind-u401de982023-04-14 17:32:03 -0700492
493 for (TargetId id_start = FLAGS_min_target_id; id_start < FLAGS_max_target_id;
494 id_start++) {
495 for (TargetId id_end = id_start + 1; id_end <= FLAGS_max_target_id;
496 id_end++) {
497 auto H_start_end =
498 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
499 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
500 auto constraint = PoseUtils::Affine3dToPose3d(H_start_end);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700501 VLOG(1) << id_start << "->" << id_end << ": " << constraint.p.norm()
502 << " meters";
milind-u401de982023-04-14 17:32:03 -0700503 }
504 }
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800505}
506
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800507std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800508 flatbuffers::FlatBufferBuilder fbb;
509
510 // Convert poses to flatbuffers
511 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
512 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800513 target_poses_fbs.emplace_back(
514 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800515 }
516
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800517 const auto field_name_offset = fbb.CreateString(field_name);
518 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
519 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800520
521 return aos::FlatbufferToJson(
522 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
523 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800524}
525
milind-u8f4e43e2023-04-09 17:11:19 -0700526namespace {
milind-u8f4e43e2023-04-09 17:11:19 -0700527// Hacks to extract a double from a scalar, which is either a ceres jet or a
528// double. Only used for debugging and displaying.
529template <typename S>
530double ScalarToDouble(S s) {
531 const double *ptr = reinterpret_cast<double *>(&s);
532 return *ptr;
533}
534
535template <typename S>
536Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) {
537 Eigen::Affine3d H_double;
538 for (size_t i = 0; i < H.rows(); i++) {
539 for (size_t j = 0; j < H.cols(); j++) {
540 H_double(i, j) = ScalarToDouble(H(i, j));
541 }
542 }
543 return H_double;
544}
545
546} // namespace
547
548template <typename S>
549bool TargetMapper::operator()(const S *const translation,
550 const S *const rotation, S *residual) const {
551 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
552 Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2],
553 rotation[0]);
554 Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1],
555 translation[2]);
556 // Actual target pose in the frame of the fixed pose.
557 Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual;
558 VLOG(2) << "H_frozen_actual: "
559 << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
560
561 Affine3s H_world_frozen =
562 PoseUtils::Pose3dToAffine3d(target_poses_.at(FLAGS_frozen_target_id))
563 .cast<S>();
564 Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
565
566 size_t residual_index = 0;
567 if (FLAGS_visualize_solver) {
568 vis_robot_.ClearImage();
569 }
570
571 for (const auto &[id, solved_pose] : target_poses_) {
572 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
573 continue;
574 }
575
576 Affine3s H_world_ideal =
577 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>();
578 Affine3s H_world_solved =
579 PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>();
580 // Take the delta between the frozen target and the solved target, and put
581 // that on top of the actual pose of the frozen target
582 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
583 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
584 VLOG(2) << id << ": " << H_world_actual.translation();
585 Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual;
586 auto T_ideal_actual = H_ideal_actual.translation();
587 VLOG(2) << "T_ideal_actual: " << T_ideal_actual;
588 VLOG(2);
589 auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation());
590
milind-u401de982023-04-14 17:32:03 -0700591 // Weight translation errors higher than rotation.
592 // 1 m in position error = 0.01 radian (or ~0.573 degrees)
593 constexpr double kTranslationScalar = 1000.0;
594 constexpr double kRotationScalar = 100.0;
milind-u8f4e43e2023-04-09 17:11:19 -0700595
596 // Penalize based on how much our actual poses matches the ideal
597 // ones. We've already solved for the relative poses, now figure out
598 // where all of them fit in the world.
599 residual[residual_index++] = kTranslationScalar * T_ideal_actual(0);
600 residual[residual_index++] = kTranslationScalar * T_ideal_actual(1);
601 residual[residual_index++] = kTranslationScalar * T_ideal_actual(2);
602 residual[residual_index++] =
603 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x();
604 residual[residual_index++] =
605 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y();
606 residual[residual_index++] =
607 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
608
609 if (FLAGS_visualize_solver) {
Jim Ostrowski68e56172023-09-17 23:44:15 -0700610 LOG(INFO) << std::to_string(id) + std::string("-est") << " at "
611 << ScalarAffineToDouble(H_world_actual).matrix();
milind-u8f4e43e2023-04-09 17:11:19 -0700612 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700613 std::to_string(id) + std::string("-est"),
614 cv::Scalar(0, 255, 0));
milind-u8f4e43e2023-04-09 17:11:19 -0700615 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal),
616 std::to_string(id), cv::Scalar(255, 255, 255));
617 }
618 }
619 if (FLAGS_visualize_solver) {
620 cv::imshow("Target maps", vis_robot_.image_);
621 cv::waitKey(0);
622 }
623
624 // Ceres can't handle residual values of exactly zero
625 for (size_t i = 0; i < residual_index; i++) {
626 if (residual[i] == S(0)) {
627 residual[i] = S(1e-9);
628 }
629 }
630
631 return true;
632}
633
milind-u401de982023-04-14 17:32:03 -0700634TargetMapper::PoseError TargetMapper::ComputeError(
635 const ceres::examples::Constraint3d &constraint) const {
636 // Compute the difference between the map-based transform of the end target
637 // in the start target frame, to the one from this constraint
638 auto H_start_end_map =
639 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_begin))
640 .inverse() *
641 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_end));
642 auto H_start_end_constraint = PoseUtils::Pose3dToAffine3d(constraint.t_be);
643 ceres::examples::Pose3d delta_pose = PoseUtils::Affine3dToPose3d(
644 H_start_end_map.inverse() * H_start_end_constraint);
645 double distance = delta_pose.p.norm();
646 Eigen::AngleAxisd err_angle(delta_pose.q);
647 double angle = std::abs(err_angle.angle());
648 return {.angle = angle, .distance = distance};
649}
650
651TargetMapper::Stats TargetMapper::ComputeStats() const {
652 Stats stats{.avg_err = {.angle = 0.0, .distance = 0.0},
653 .std_dev = {.angle = 0.0, .distance = 0.0},
654 .max_err = {.angle = 0.0, .distance = 0.0}};
655
656 for (const auto &constraint : target_constraints_) {
657 PoseError err = ComputeError(constraint);
658
659 // Update our statistics
660 stats.avg_err.distance += err.distance;
661 if (err.distance > stats.max_err.distance) {
662 stats.max_err.distance = err.distance;
663 }
664
665 stats.avg_err.angle += err.angle;
666 if (err.angle > stats.max_err.angle) {
667 stats.max_err.angle = err.angle;
668 }
669 }
670
671 stats.avg_err.distance /= static_cast<double>(target_constraints_.size());
672 stats.avg_err.angle /= static_cast<double>(target_constraints_.size());
673
674 for (const auto &constraint : target_constraints_) {
675 PoseError err = ComputeError(constraint);
676
677 // Update our statistics
678 stats.std_dev.distance +=
679 std::pow(err.distance - stats.avg_err.distance, 2);
680
681 stats.std_dev.angle += std::pow(err.angle - stats.avg_err.angle, 2);
682 }
683
684 stats.std_dev.distance = std::sqrt(
685 stats.std_dev.distance / static_cast<double>(target_constraints_.size()));
686 stats.std_dev.angle = std::sqrt(
687 stats.std_dev.angle / static_cast<double>(target_constraints_.size()));
688
689 return stats;
690}
691
692void TargetMapper::RemoveOutlierConstraints() {
693 stats_with_outliers_ = ComputeStats();
694 size_t original_size = target_constraints_.size();
695 target_constraints_.erase(
696 std::remove_if(
697 target_constraints_.begin(), target_constraints_.end(),
698 [&](const auto &constraint) {
699 PoseError err = ComputeError(constraint);
700 // Remove constraints with errors significantly above
701 // the average
702 if (err.distance > stats_with_outliers_.avg_err.distance +
703 FLAGS_outlier_std_devs *
704 stats_with_outliers_.std_dev.distance) {
705 return true;
706 }
707 if (err.angle > stats_with_outliers_.avg_err.angle +
708 FLAGS_outlier_std_devs *
709 stats_with_outliers_.std_dev.angle) {
710 return true;
711 }
712 return false;
713 }),
714 target_constraints_.end());
715
716 LOG(INFO) << "Removed " << (original_size - target_constraints_.size())
717 << " outlier constraints out of " << original_size << " total";
718}
719
720void TargetMapper::DumpStats(std::string_view path) const {
721 LOG(INFO) << "Dumping mapping stats to " << path;
722 Stats stats = ComputeStats();
723 std::ofstream fout(path.data());
724 fout << "Stats after outlier rejection: " << std::endl;
725 fout << "Average error - angle: " << stats.avg_err.angle
726 << ", distance: " << stats.avg_err.distance << std::endl
727 << std::endl;
728 fout << "Standard deviation - angle: " << stats.std_dev.angle
729 << ", distance: " << stats.std_dev.distance << std::endl
730 << std::endl;
731 fout << "Max error - angle: " << stats.max_err.angle
732 << ", distance: " << stats.max_err.distance << std::endl;
733
734 fout << std::endl << "Stats before outlier rejection:" << std::endl;
735 fout << "Average error - angle: " << stats_with_outliers_.avg_err.angle
736 << ", distance: " << stats_with_outliers_.avg_err.distance << std::endl
737 << std::endl;
738 fout << "Standard deviation - angle: " << stats_with_outliers_.std_dev.angle
739 << ", distance: " << stats_with_outliers_.std_dev.distance << std::endl
740 << std::endl;
741 fout << "Max error - angle: " << stats_with_outliers_.max_err.angle
742 << ", distance: " << stats_with_outliers_.max_err.distance << std::endl;
743
744 fout.flush();
745 fout.close();
746}
747
748void TargetMapper::DumpConstraints(std::string_view path) const {
749 LOG(INFO) << "Dumping target constraints to " << path;
750 std::ofstream fout(path.data());
751 for (const auto &constraint : target_constraints_) {
752 fout << constraint << std::endl;
753 }
754 fout.flush();
755 fout.close();
756}
757
milind-ufbc5c812023-04-06 21:24:29 -0700758} // namespace frc971::vision
759
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800760std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
milind-ufbc5c812023-04-06 21:24:29 -0700761 auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800762 os << absl::StrFormat(
763 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
764 "%.3f, yaw: %.3f}",
765 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
766 return os;
767}
768
769std::ostream &operator<<(std::ostream &os,
770 ceres::examples::Constraint3d constraint) {
771 os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
772 constraint.id_begin, constraint.id_end)
773 << constraint.t_be << "}";
774 return os;
775}