blob: 8077f1632221cbd283d196a9bcb7af7f65eba333 [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(),
107 target_pose_fbs.orientation()->z())}};
108}
109
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800110ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -0800111 const std::vector<DataAdapter::TimestampedDetection>
112 &timestamped_target_detections,
113 aos::distributed_clock::duration max_dt) {
114 CHECK_GE(timestamped_target_detections.size(), 2ul)
115 << "Must have at least 2 detections";
116
117 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800118 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -0800119 for (auto detection = timestamped_target_detections.begin() + 1;
120 detection < timestamped_target_detections.end(); detection++) {
121 auto last_detection = detection - 1;
Milind Upadhyayec493912022-12-18 21:33:15 -0800122
123 // Skip two consecutive detections of the same target, because the solver
124 // doesn't allow this
milind-ud62f80a2023-03-04 16:37:09 -0800125 if (detection->id == last_detection->id) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800126 continue;
127 }
128
129 // Don't take into account constraints too far apart in time, because the
130 // recording device could have moved too much
milind-ud62f80a2023-03-04 16:37:09 -0800131 if ((detection->time - last_detection->time) > max_dt) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800132 continue;
133 }
134
milind-ud62f80a2023-03-04 16:37:09 -0800135 auto confidence = ComputeConfidence(*last_detection, *detection);
Milind Upadhyayec493912022-12-18 21:33:15 -0800136 target_constraints.emplace_back(
milind-ud62f80a2023-03-04 16:37:09 -0800137 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -0800138 }
139
140 return target_constraints;
141}
142
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800143TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800144 const TimestampedDetection &detection_start,
145 const TimestampedDetection &detection_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800146 constexpr size_t kX = 0;
147 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800148 constexpr size_t kZ = 2;
149 constexpr size_t kOrientation1 = 3;
150 constexpr size_t kOrientation2 = 4;
151 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800152
153 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800154 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800155
156 {
157 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800158 TargetMapper::ConfidenceMatrix Q_odometry =
159 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800160 Q_odometry(kX, kX) = std::pow(0.045, 2);
161 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800162 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
163 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
164 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
165 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800166
167 // Add uncertainty for robot position measurements from start to end
milind-ud62f80a2023-03-04 16:37:09 -0800168 int iterations = (detection_end.time - detection_start.time) /
169 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800170 P += static_cast<double>(iterations) * Q_odometry;
171 }
172
173 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800174 // Noise for vision-based target localizations. Multiplying this matrix by
milind-u6ff399f2023-03-24 18:33:38 -0700175 // the distance from camera to target squared results in the uncertainty
176 // in that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800177 TargetMapper::ConfidenceMatrix Q_vision =
178 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800179 Q_vision(kX, kX) = std::pow(0.045, 2);
180 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800181 Q_vision(kZ, kZ) = std::pow(0.045, 2);
182 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
183 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
184 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800185
186 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
milind-ufbc5c812023-04-06 21:24:29 -0700187 P += Q_vision * std::pow(detection_start.distance_from_camera *
188 (1.0 + FLAGS_distortion_noise_scalar *
189 detection_start.distortion_factor),
190 2);
191 P += Q_vision * std::pow(detection_end.distance_from_camera *
192 (1.0 + FLAGS_distortion_noise_scalar *
193 detection_end.distortion_factor),
194 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800195 }
196
197 return P.inverse();
198}
199
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800200ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800201 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800202 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800203 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800204 // Compute the relative pose (constraint) between the two targets
205 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800206 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800207 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800208 ceres::examples::Pose3d target_constraint =
209 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800210
milind-uf3ab8ba2023-02-04 17:56:16 -0800211 const auto constraint_3d =
212 ceres::examples::Constraint3d{target_detection_start.id,
213 target_detection_end.id,
214 {target_constraint.p, target_constraint.q},
215 confidence};
216
217 VLOG(2) << "Computed constraint: " << constraint_3d;
218 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800219}
220
Milind Upadhyay7c205222022-11-16 18:20:58 -0800221TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800222 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800223 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700224 : target_constraints_(target_constraints),
225 T_frozen_actual_(Eigen::Vector3d::Zero()),
226 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700227 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800228 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
229 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
230 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u8f4e43e2023-04-09 17:11:19 -0700231 ideal_target_poses_[target_pose_fbs->id()] =
milind-u3f5f83c2023-01-29 15:23:51 -0800232 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800233 }
milind-u8f4e43e2023-04-09 17:11:19 -0700234 target_poses_ = ideal_target_poses_;
milind-u526d5672023-04-17 20:09:10 -0700235 CountConstraints();
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800236}
237
238TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800239 const ceres::examples::MapOfPoses &target_poses,
240 const ceres::examples::VectorOfConstraints &target_constraints)
milind-u8f4e43e2023-04-09 17:11:19 -0700241 : ideal_target_poses_(target_poses),
242 target_poses_(ideal_target_poses_),
243 target_constraints_(target_constraints),
244 T_frozen_actual_(Eigen::Vector3d::Zero()),
245 R_frozen_actual_(Eigen::Quaterniond::Identity()),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700246 vis_robot_(cv::Size(kImageWidth_, kImageHeight_)) {
milind-u526d5672023-04-17 20:09:10 -0700247 CountConstraints();
248}
249
250namespace {
251std::pair<TargetMapper::TargetId, TargetMapper::TargetId> MakeIdPair(
252 const ceres::examples::Constraint3d &constraint) {
253 auto min_id = std::min(constraint.id_begin, constraint.id_end);
254 auto max_id = std::max(constraint.id_begin, constraint.id_end);
255 return std::make_pair(min_id, max_id);
256}
257} // namespace
258
259void TargetMapper::CountConstraints() {
260 for (const auto &constraint : target_constraints_) {
261 auto id_pair = MakeIdPair(constraint);
262 if (constraint_counts_.count(id_pair) == 0) {
263 constraint_counts_[id_pair] = 0;
264 }
265 constraint_counts_[id_pair]++;
266 }
267}
Milind Upadhyay7c205222022-11-16 18:20:58 -0800268
269std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
270 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
271 for (auto target_pose : target_poses) {
272 if (target_pose.id == target_id) {
273 return target_pose;
274 }
275 }
276
277 return std::nullopt;
278}
279
Jim Ostrowski49be8232023-03-23 01:00:14 -0700280std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
milind-u2ab4db12023-03-25 21:59:23 -0700281 TargetId target_id) const {
Jim Ostrowski49be8232023-03-23 01:00:14 -0700282 if (target_poses_.count(target_id) > 0) {
milind-u2ab4db12023-03-25 21:59:23 -0700283 return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700284 }
285
286 return std::nullopt;
287}
288
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800289// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
290// Constructs the nonlinear least squares optimization problem from the pose
291// graph constraints.
milind-u8f4e43e2023-04-09 17:11:19 -0700292void TargetMapper::BuildTargetPoseOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800293 const ceres::examples::VectorOfConstraints &constraints,
294 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
295 CHECK(poses != nullptr);
296 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800297 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800298 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800299 return;
300 }
301
milind-u13ff1a52023-01-22 17:10:49 -0800302 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800303 ceres::LocalParameterization *quaternion_local_parameterization =
304 new ceres::EigenQuaternionParameterization;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800305
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700306 int min_constraint_id = std::numeric_limits<int>::max();
307 int max_constraint_id = std::numeric_limits<int>::min();
308
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800309 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
310 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800311 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800312 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800313
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800314 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800315 poses->find(constraint.id_begin);
316 CHECK(pose_begin_iter != poses->end())
317 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800318 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800319 poses->find(constraint.id_end);
320 CHECK(pose_end_iter != poses->end())
321 << "Pose with ID: " << constraint.id_end << " not found.";
322
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800323 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800324 constraint.information.llt().matrixL();
milind-u526d5672023-04-17 20:09:10 -0700325
326 auto id_pair = MakeIdPair(constraint);
327 CHECK_GT(constraint_counts_.count(id_pair), 0ul)
328 << "Should have counted constraints for " << id_pair.first << "->"
329 << id_pair.second;
330
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700331 VLOG(1) << "Adding constraint pair: " << id_pair.first << " and "
332 << id_pair.second;
333 // Store min & max id's; assumes first id < second id
334 if (id_pair.first < min_constraint_id) {
335 min_constraint_id = id_pair.first;
336 }
337 if (id_pair.second > max_constraint_id) {
338 max_constraint_id = id_pair.second;
339 }
milind-u526d5672023-04-17 20:09:10 -0700340 // Normalize constraint cost by occurances
341 size_t constraint_count = constraint_counts_[id_pair];
342 // Scale all costs so the total cost comes out to more reasonable numbers
343 constexpr double kGlobalWeight = 1000.0;
344 double constraint_weight =
345 kGlobalWeight / static_cast<double>(constraint_count);
346
Milind Upadhyay7c205222022-11-16 18:20:58 -0800347 // Ceres will take ownership of the pointer.
348 ceres::CostFunction *cost_function =
milind-u526d5672023-04-17 20:09:10 -0700349 ceres::examples::PoseGraph3dErrorTerm::Create(
350 constraint.t_be, sqrt_information, constraint_weight);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800351
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800352 problem->AddResidualBlock(cost_function, loss_function,
353 pose_begin_iter->second.p.data(),
354 pose_begin_iter->second.q.coeffs().data(),
355 pose_end_iter->second.p.data(),
356 pose_end_iter->second.q.coeffs().data());
357
358 problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
359 quaternion_local_parameterization);
360 problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
361 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800362 }
363
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800364 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800365 // constrained. This is typically referred to as gauge freedom. You can
366 // apply a rigid body transformation to all the nodes and the optimization
367 // problem will still have the exact same cost. The Levenberg-Marquardt
368 // algorithm has internal damping which mitigates this issue, but it is
369 // better to properly constrain the gauge freedom. This can be done by
370 // setting one of the poses as constant so the optimizer cannot change it.
milind-u6ff399f2023-03-24 18:33:38 -0700371 CHECK_NE(poses->count(FLAGS_frozen_target_id), 0ul)
372 << "Got no poses for frozen target id " << FLAGS_frozen_target_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700373 CHECK_GE(FLAGS_frozen_target_id, min_constraint_id)
374 << "target to freeze index " << FLAGS_frozen_target_id
375 << " must be in range of constraints, > " << min_constraint_id;
376 CHECK_LE(FLAGS_frozen_target_id, max_constraint_id)
377 << "target to freeze index " << FLAGS_frozen_target_id
378 << " must be in range of constraints, < " << max_constraint_id;
milind-u6ff399f2023-03-24 18:33:38 -0700379 ceres::examples::MapOfPoses::iterator pose_start_iter =
380 poses->find(FLAGS_frozen_target_id);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800381 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800382 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
383 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800384}
385
milind-u401de982023-04-14 17:32:03 -0700386std::unique_ptr<ceres::CostFunction>
387TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) {
Philipp Schradera6712522023-07-05 20:25:11 -0700388 // Set up robot visualization.
milind-u8f4e43e2023-04-09 17:11:19 -0700389 vis_robot_.ClearImage();
Jim Ostrowski68e56172023-09-17 23:44:15 -0700390 // Compute focal length so that image shows field with viewpoint at 10m above
391 // it (default for viewer)
392 const double kFocalLength = kImageWidth_ * 10.0 / kFieldWidth_;
393 vis_robot_.SetDefaultViewpoint(kImageWidth_, kFocalLength);
milind-u8f4e43e2023-04-09 17:11:19 -0700394
395 const size_t num_targets = FLAGS_max_target_id - FLAGS_min_target_id;
396 // Translation and rotation error for each target
397 const size_t num_residuals = num_targets * 6;
398 // Set up the only cost function (also known as residual). This uses
399 // auto-differentiation to obtain the derivative (jacobian).
milind-u401de982023-04-14 17:32:03 -0700400 std::unique_ptr<ceres::CostFunction> cost_function = std::make_unique<
401 ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>>(
402 this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP);
milind-u8f4e43e2023-04-09 17:11:19 -0700403
404 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
405 ceres::LocalParameterization *quaternion_local_parameterization =
406 new ceres::EigenQuaternionParameterization;
407
milind-u401de982023-04-14 17:32:03 -0700408 problem->AddResidualBlock(cost_function.get(), loss_function,
milind-u8f4e43e2023-04-09 17:11:19 -0700409 T_frozen_actual_.vector().data(),
410 R_frozen_actual_.coeffs().data());
411 problem->SetParameterization(R_frozen_actual_.coeffs().data(),
412 quaternion_local_parameterization);
milind-u401de982023-04-14 17:32:03 -0700413 return cost_function;
milind-u8f4e43e2023-04-09 17:11:19 -0700414}
415
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800416// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800417bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
418 CHECK_NOTNULL(problem);
419
420 ceres::Solver::Options options;
421 options.max_num_iterations = FLAGS_max_num_iterations;
422 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
milind-u401de982023-04-14 17:32:03 -0700423 options.minimizer_progress_to_stdout = false;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800424
425 ceres::Solver::Summary summary;
426 ceres::Solve(options, problem, &summary);
427
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800428 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800429
430 return summary.IsSolutionUsable();
431}
432
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800433void TargetMapper::Solve(std::string_view field_name,
434 std::optional<std::string_view> output_dir) {
milind-u401de982023-04-14 17:32:03 -0700435 ceres::Problem target_pose_problem_1;
milind-u8f4e43e2023-04-09 17:11:19 -0700436 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
milind-u401de982023-04-14 17:32:03 -0700437 &target_pose_problem_1);
438 CHECK(SolveOptimizationProblem(&target_pose_problem_1))
439 << "The target pose solve 1 was not successful, exiting.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800440
milind-u401de982023-04-14 17:32:03 -0700441 RemoveOutlierConstraints();
442
443 // Solve again once we've thrown out bad constraints
444 ceres::Problem target_pose_problem_2;
445 BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_,
446 &target_pose_problem_2);
447 CHECK(SolveOptimizationProblem(&target_pose_problem_2))
448 << "The target pose solve 2 was not successful, exiting.";
449
Jim Ostrowski68e56172023-09-17 23:44:15 -0700450 LOG(INFO) << "Solving the overall map's best alignment to the previous map";
milind-u401de982023-04-14 17:32:03 -0700451 ceres::Problem map_fitting_problem(
452 {.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
453 std::unique_ptr<ceres::CostFunction> map_fitting_cost_function =
454 BuildMapFittingOptimizationProblem(&map_fitting_problem);
milind-u8f4e43e2023-04-09 17:11:19 -0700455 CHECK(SolveOptimizationProblem(&map_fitting_problem))
456 << "The map fitting solve was not successful, exiting.";
milind-u401de982023-04-14 17:32:03 -0700457 map_fitting_cost_function.release();
milind-u8f4e43e2023-04-09 17:11:19 -0700458
459 Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_;
460 LOG(INFO) << "H_frozen_actual: "
461 << PoseUtils::Affine3dToPose3d(H_frozen_actual);
462
463 auto H_world_frozen =
464 PoseUtils::Pose3dToAffine3d(target_poses_[FLAGS_frozen_target_id]);
465 auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
466
467 // Offset the solved poses to become the actual ones
468 for (auto &[id, pose] : target_poses_) {
469 // Don't offset targets we didn't solve for
470 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
471 continue;
472 }
473
474 // Take the delta between the frozen target and the solved target, and put
475 // that on top of the actual pose of the frozen target
476 auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose);
477 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
478 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
479 pose = PoseUtils::Affine3dToPose3d(H_world_actual);
480 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800481
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800482 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800483 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800484
485 if (output_dir.has_value()) {
486 std::string output_path =
487 absl::StrCat(output_dir.value(), "/", field_name, ".json");
488 LOG(INFO) << "Writing map to file: " << output_path;
489 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800490 }
milind-u401de982023-04-14 17:32:03 -0700491
492 for (TargetId id_start = FLAGS_min_target_id; id_start < FLAGS_max_target_id;
493 id_start++) {
494 for (TargetId id_end = id_start + 1; id_end <= FLAGS_max_target_id;
495 id_end++) {
496 auto H_start_end =
497 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
498 PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
499 auto constraint = PoseUtils::Affine3dToPose3d(H_start_end);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700500 VLOG(1) << id_start << "->" << id_end << ": " << constraint.p.norm()
501 << " meters";
milind-u401de982023-04-14 17:32:03 -0700502 }
503 }
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800504}
505
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800506std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800507 flatbuffers::FlatBufferBuilder fbb;
508
509 // Convert poses to flatbuffers
510 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
511 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800512 target_poses_fbs.emplace_back(
513 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800514 }
515
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800516 const auto field_name_offset = fbb.CreateString(field_name);
517 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
518 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800519
520 return aos::FlatbufferToJson(
521 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
522 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800523}
524
milind-u8f4e43e2023-04-09 17:11:19 -0700525namespace {
milind-u8f4e43e2023-04-09 17:11:19 -0700526// Hacks to extract a double from a scalar, which is either a ceres jet or a
527// double. Only used for debugging and displaying.
528template <typename S>
529double ScalarToDouble(S s) {
530 const double *ptr = reinterpret_cast<double *>(&s);
531 return *ptr;
532}
533
534template <typename S>
535Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) {
536 Eigen::Affine3d H_double;
537 for (size_t i = 0; i < H.rows(); i++) {
538 for (size_t j = 0; j < H.cols(); j++) {
539 H_double(i, j) = ScalarToDouble(H(i, j));
540 }
541 }
542 return H_double;
543}
544
545} // namespace
546
547template <typename S>
548bool TargetMapper::operator()(const S *const translation,
549 const S *const rotation, S *residual) const {
550 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
551 Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2],
552 rotation[0]);
553 Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1],
554 translation[2]);
555 // Actual target pose in the frame of the fixed pose.
556 Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual;
557 VLOG(2) << "H_frozen_actual: "
558 << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
559
560 Affine3s H_world_frozen =
561 PoseUtils::Pose3dToAffine3d(target_poses_.at(FLAGS_frozen_target_id))
562 .cast<S>();
563 Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
564
565 size_t residual_index = 0;
566 if (FLAGS_visualize_solver) {
567 vis_robot_.ClearImage();
568 }
569
570 for (const auto &[id, solved_pose] : target_poses_) {
571 if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
572 continue;
573 }
574
575 Affine3s H_world_ideal =
576 PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>();
577 Affine3s H_world_solved =
578 PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>();
579 // Take the delta between the frozen target and the solved target, and put
580 // that on top of the actual pose of the frozen target
581 auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved;
582 auto H_world_actual = H_world_frozenactual * H_frozen_solved;
583 VLOG(2) << id << ": " << H_world_actual.translation();
584 Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual;
585 auto T_ideal_actual = H_ideal_actual.translation();
586 VLOG(2) << "T_ideal_actual: " << T_ideal_actual;
587 VLOG(2);
588 auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation());
589
milind-u401de982023-04-14 17:32:03 -0700590 // Weight translation errors higher than rotation.
591 // 1 m in position error = 0.01 radian (or ~0.573 degrees)
592 constexpr double kTranslationScalar = 1000.0;
593 constexpr double kRotationScalar = 100.0;
milind-u8f4e43e2023-04-09 17:11:19 -0700594
595 // Penalize based on how much our actual poses matches the ideal
596 // ones. We've already solved for the relative poses, now figure out
597 // where all of them fit in the world.
598 residual[residual_index++] = kTranslationScalar * T_ideal_actual(0);
599 residual[residual_index++] = kTranslationScalar * T_ideal_actual(1);
600 residual[residual_index++] = kTranslationScalar * T_ideal_actual(2);
601 residual[residual_index++] =
602 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x();
603 residual[residual_index++] =
604 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y();
605 residual[residual_index++] =
606 kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
607
608 if (FLAGS_visualize_solver) {
Jim Ostrowski68e56172023-09-17 23:44:15 -0700609 LOG(INFO) << std::to_string(id) + std::string("-est") << " at "
610 << ScalarAffineToDouble(H_world_actual).matrix();
milind-u8f4e43e2023-04-09 17:11:19 -0700611 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
Jim Ostrowski68e56172023-09-17 23:44:15 -0700612 std::to_string(id) + std::string("-est"),
613 cv::Scalar(0, 255, 0));
milind-u8f4e43e2023-04-09 17:11:19 -0700614 vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal),
615 std::to_string(id), cv::Scalar(255, 255, 255));
616 }
617 }
618 if (FLAGS_visualize_solver) {
619 cv::imshow("Target maps", vis_robot_.image_);
620 cv::waitKey(0);
621 }
622
623 // Ceres can't handle residual values of exactly zero
624 for (size_t i = 0; i < residual_index; i++) {
625 if (residual[i] == S(0)) {
626 residual[i] = S(1e-9);
627 }
628 }
629
630 return true;
631}
632
milind-u401de982023-04-14 17:32:03 -0700633TargetMapper::PoseError TargetMapper::ComputeError(
634 const ceres::examples::Constraint3d &constraint) const {
635 // Compute the difference between the map-based transform of the end target
636 // in the start target frame, to the one from this constraint
637 auto H_start_end_map =
638 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_begin))
639 .inverse() *
640 PoseUtils::Pose3dToAffine3d(target_poses_.at(constraint.id_end));
641 auto H_start_end_constraint = PoseUtils::Pose3dToAffine3d(constraint.t_be);
642 ceres::examples::Pose3d delta_pose = PoseUtils::Affine3dToPose3d(
643 H_start_end_map.inverse() * H_start_end_constraint);
644 double distance = delta_pose.p.norm();
645 Eigen::AngleAxisd err_angle(delta_pose.q);
646 double angle = std::abs(err_angle.angle());
647 return {.angle = angle, .distance = distance};
648}
649
650TargetMapper::Stats TargetMapper::ComputeStats() const {
651 Stats stats{.avg_err = {.angle = 0.0, .distance = 0.0},
652 .std_dev = {.angle = 0.0, .distance = 0.0},
653 .max_err = {.angle = 0.0, .distance = 0.0}};
654
655 for (const auto &constraint : target_constraints_) {
656 PoseError err = ComputeError(constraint);
657
658 // Update our statistics
659 stats.avg_err.distance += err.distance;
660 if (err.distance > stats.max_err.distance) {
661 stats.max_err.distance = err.distance;
662 }
663
664 stats.avg_err.angle += err.angle;
665 if (err.angle > stats.max_err.angle) {
666 stats.max_err.angle = err.angle;
667 }
668 }
669
670 stats.avg_err.distance /= static_cast<double>(target_constraints_.size());
671 stats.avg_err.angle /= static_cast<double>(target_constraints_.size());
672
673 for (const auto &constraint : target_constraints_) {
674 PoseError err = ComputeError(constraint);
675
676 // Update our statistics
677 stats.std_dev.distance +=
678 std::pow(err.distance - stats.avg_err.distance, 2);
679
680 stats.std_dev.angle += std::pow(err.angle - stats.avg_err.angle, 2);
681 }
682
683 stats.std_dev.distance = std::sqrt(
684 stats.std_dev.distance / static_cast<double>(target_constraints_.size()));
685 stats.std_dev.angle = std::sqrt(
686 stats.std_dev.angle / static_cast<double>(target_constraints_.size()));
687
688 return stats;
689}
690
691void TargetMapper::RemoveOutlierConstraints() {
692 stats_with_outliers_ = ComputeStats();
693 size_t original_size = target_constraints_.size();
694 target_constraints_.erase(
695 std::remove_if(
696 target_constraints_.begin(), target_constraints_.end(),
697 [&](const auto &constraint) {
698 PoseError err = ComputeError(constraint);
699 // Remove constraints with errors significantly above
700 // the average
701 if (err.distance > stats_with_outliers_.avg_err.distance +
702 FLAGS_outlier_std_devs *
703 stats_with_outliers_.std_dev.distance) {
704 return true;
705 }
706 if (err.angle > stats_with_outliers_.avg_err.angle +
707 FLAGS_outlier_std_devs *
708 stats_with_outliers_.std_dev.angle) {
709 return true;
710 }
711 return false;
712 }),
713 target_constraints_.end());
714
715 LOG(INFO) << "Removed " << (original_size - target_constraints_.size())
716 << " outlier constraints out of " << original_size << " total";
717}
718
719void TargetMapper::DumpStats(std::string_view path) const {
720 LOG(INFO) << "Dumping mapping stats to " << path;
721 Stats stats = ComputeStats();
722 std::ofstream fout(path.data());
723 fout << "Stats after outlier rejection: " << std::endl;
724 fout << "Average error - angle: " << stats.avg_err.angle
725 << ", distance: " << stats.avg_err.distance << std::endl
726 << std::endl;
727 fout << "Standard deviation - angle: " << stats.std_dev.angle
728 << ", distance: " << stats.std_dev.distance << std::endl
729 << std::endl;
730 fout << "Max error - angle: " << stats.max_err.angle
731 << ", distance: " << stats.max_err.distance << std::endl;
732
733 fout << std::endl << "Stats before outlier rejection:" << std::endl;
734 fout << "Average error - angle: " << stats_with_outliers_.avg_err.angle
735 << ", distance: " << stats_with_outliers_.avg_err.distance << std::endl
736 << std::endl;
737 fout << "Standard deviation - angle: " << stats_with_outliers_.std_dev.angle
738 << ", distance: " << stats_with_outliers_.std_dev.distance << std::endl
739 << std::endl;
740 fout << "Max error - angle: " << stats_with_outliers_.max_err.angle
741 << ", distance: " << stats_with_outliers_.max_err.distance << std::endl;
742
743 fout.flush();
744 fout.close();
745}
746
747void TargetMapper::DumpConstraints(std::string_view path) const {
748 LOG(INFO) << "Dumping target constraints to " << path;
749 std::ofstream fout(path.data());
750 for (const auto &constraint : target_constraints_) {
751 fout << constraint << std::endl;
752 }
753 fout.flush();
754 fout.close();
755}
756
milind-ufbc5c812023-04-06 21:24:29 -0700757} // namespace frc971::vision
758
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800759std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
milind-ufbc5c812023-04-06 21:24:29 -0700760 auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800761 os << absl::StrFormat(
762 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
763 "%.3f, yaw: %.3f}",
764 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
765 return os;
766}
767
768std::ostream &operator<<(std::ostream &os,
769 ceres::examples::Constraint3d constraint) {
770 os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
771 constraint.id_begin, constraint.id_end)
772 << constraint.t_be << "}";
773 return os;
774}