blob: b3049e42c0b08077f2e160926b91d9f225ceef1f [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");
10
11namespace frc971::vision {
12
Milind Upadhyayc5beba12022-12-17 17:41:20 -080013Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
14 const ceres::examples::Pose3d &pose3d) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080015 Eigen::Affine3d H_world_pose =
Milind Upadhyayc5beba12022-12-17 17:41:20 -080016 Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q;
Milind Upadhyay7c205222022-11-16 18:20:58 -080017 return H_world_pose;
18}
19
Milind Upadhyayc5beba12022-12-17 17:41:20 -080020ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) {
21 return ceres::examples::Pose3d{.p = H.translation(),
22 .q = Eigen::Quaterniond(H.rotation())};
Milind Upadhyay7c205222022-11-16 18:20:58 -080023}
24
Milind Upadhyayc5beba12022-12-17 17:41:20 -080025ceres::examples::Pose3d PoseUtils::ComputeRelativePose(
26 const ceres::examples::Pose3d &pose_1,
27 const ceres::examples::Pose3d &pose_2) {
28 Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1);
29 Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080030
31 // Get the location of 2 in the 1 frame
32 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080033 return Affine3dToPose3d(H_1_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080034}
35
Milind Upadhyayc5beba12022-12-17 17:41:20 -080036ceres::examples::Pose3d PoseUtils::ComputeOffsetPose(
37 const ceres::examples::Pose3d &pose_1,
38 const ceres::examples::Pose3d &pose_2_relative) {
39 auto H_world_1 = Pose3dToAffine3d(pose_1);
40 auto H_1_2 = Pose3dToAffine3d(pose_2_relative);
Milind Upadhyay7c205222022-11-16 18:20:58 -080041 auto H_world_2 = H_world_1 * H_1_2;
42
Milind Upadhyayc5beba12022-12-17 17:41:20 -080043 return Affine3dToPose3d(H_world_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080044}
45
Milind Upadhyayc5beba12022-12-17 17:41:20 -080046Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion(
47 const Eigen::Vector3d &rpy) {
48 Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX());
49 Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY());
50 Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ());
51
52 return yaw_angle * pitch_angle * roll_angle;
Milind Upadhyay7c205222022-11-16 18:20:58 -080053}
54
Milind Upadhyayc5beba12022-12-17 17:41:20 -080055Eigen::Vector3d PoseUtils::QuaternionToEulerAngles(
56 const Eigen::Quaterniond &q) {
57 return RotationMatrixToEulerAngles(q.toRotationMatrix());
Milind Upadhyay7c205222022-11-16 18:20:58 -080058}
59
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles(
61 const Eigen::Matrix3d &R) {
62 double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2)));
63 double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0)));
64 double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0)));
65
66 return Eigen::Vector3d(roll, pitch, yaw);
67}
68
milind-u3f5f83c2023-01-29 15:23:51 -080069flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs(
70 const TargetMapper::TargetPose &target_pose,
71 flatbuffers::FlatBufferBuilder *fbb) {
72 const auto position_offset =
73 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
74 target_pose.pose.p(2));
75 const auto orientation_offset =
76 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
77 target_pose.pose.q.y(), target_pose.pose.q.z());
78 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
79 orientation_offset);
80}
81
82TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs(
83 const TargetPoseFbs &target_pose_fbs) {
84 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
85 .pose = ceres::examples::Pose3d{
86 Eigen::Vector3d(target_pose_fbs.position()->x(),
87 target_pose_fbs.position()->y(),
88 target_pose_fbs.position()->z()),
89 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
90 target_pose_fbs.orientation()->x(),
91 target_pose_fbs.orientation()->y(),
92 target_pose_fbs.orientation()->z())}};
93}
94
Milind Upadhyayc5beba12022-12-17 17:41:20 -080095ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -080096 const std::vector<DataAdapter::TimestampedDetection>
97 &timestamped_target_detections,
98 aos::distributed_clock::duration max_dt) {
99 CHECK_GE(timestamped_target_detections.size(), 2ul)
100 << "Must have at least 2 detections";
101
102 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800103 ceres::examples::VectorOfConstraints target_constraints;
Milind Upadhyayec493912022-12-18 21:33:15 -0800104 for (auto it = timestamped_target_detections.begin() + 1;
105 it < timestamped_target_detections.end(); it++) {
106 auto last_detection = *(it - 1);
107
108 // Skip two consecutive detections of the same target, because the solver
109 // doesn't allow this
110 if (it->id == last_detection.id) {
111 continue;
112 }
113
114 // Don't take into account constraints too far apart in time, because the
115 // recording device could have moved too much
116 if ((it->time - last_detection.time) > max_dt) {
117 continue;
118 }
119
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800120 auto confidence = ComputeConfidence(last_detection.time, it->time,
121 last_detection.distance_from_camera,
122 it->distance_from_camera);
Milind Upadhyayec493912022-12-18 21:33:15 -0800123 target_constraints.emplace_back(
124 ComputeTargetConstraint(last_detection, *it, confidence));
125 }
126
127 return target_constraints;
128}
129
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800130TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800131 aos::distributed_clock::time_point start,
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800132 aos::distributed_clock::time_point end, double distance_from_camera_start,
133 double distance_from_camera_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800134 constexpr size_t kX = 0;
135 constexpr size_t kY = 1;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800136 constexpr size_t kZ = 2;
137 constexpr size_t kOrientation1 = 3;
138 constexpr size_t kOrientation2 = 4;
139 constexpr size_t kOrientation3 = 5;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800140
141 // Uncertainty matrix between start and end
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800142 TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800143
144 {
145 // Noise for odometry-based robot position measurements
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800146 TargetMapper::ConfidenceMatrix Q_odometry =
147 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800148 Q_odometry(kX, kX) = std::pow(0.045, 2);
149 Q_odometry(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800150 Q_odometry(kZ, kZ) = std::pow(0.045, 2);
151 Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2);
152 Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2);
153 Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800154
155 // Add uncertainty for robot position measurements from start to end
156 int iterations = (end - start) / frc971::controls::kLoopFrequency;
157 P += static_cast<double>(iterations) * Q_odometry;
158 }
159
160 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800161 // Noise for vision-based target localizations. Multiplying this matrix by
162 // the distance from camera to target squared results in the uncertainty in
163 // that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800164 TargetMapper::ConfidenceMatrix Q_vision =
165 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800166 Q_vision(kX, kX) = std::pow(0.045, 2);
167 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800168 Q_vision(kZ, kZ) = std::pow(0.045, 2);
169 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
170 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
171 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800172
173 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800174 P += Q_vision * std::pow(distance_from_camera_start, 2);
175 P += Q_vision * std::pow(distance_from_camera_end, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800176 }
177
178 return P.inverse();
179}
180
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800181ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800182 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800183 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800184 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800185 // Compute the relative pose (constraint) between the two targets
186 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800187 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800188 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800189 ceres::examples::Pose3d target_constraint =
190 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800191
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800192 return ceres::examples::Constraint3d{
193 target_detection_start.id,
194 target_detection_end.id,
195 {target_constraint.p, target_constraint.q},
196 confidence};
Milind Upadhyayec493912022-12-18 21:33:15 -0800197}
198
Milind Upadhyay7c205222022-11-16 18:20:58 -0800199TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800200 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800201 const ceres::examples::VectorOfConstraints &target_constraints)
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800202 : target_constraints_(target_constraints) {
203 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
204 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
205 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u3f5f83c2023-01-29 15:23:51 -0800206 target_poses_[target_pose_fbs->id()] =
207 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800208 }
209}
210
211TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800212 const ceres::examples::MapOfPoses &target_poses,
213 const ceres::examples::VectorOfConstraints &target_constraints)
Milind Upadhyay7c205222022-11-16 18:20:58 -0800214 : target_poses_(target_poses), target_constraints_(target_constraints) {}
215
216std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
217 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
218 for (auto target_pose : target_poses) {
219 if (target_pose.id == target_id) {
220 return target_pose;
221 }
222 }
223
224 return std::nullopt;
225}
226
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800227// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
228// Constructs the nonlinear least squares optimization problem from the pose
229// graph constraints.
Milind Upadhyay7c205222022-11-16 18:20:58 -0800230void TargetMapper::BuildOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800231 const ceres::examples::VectorOfConstraints &constraints,
232 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
233 CHECK(poses != nullptr);
234 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800235 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800236 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800237 return;
238 }
239
milind-u13ff1a52023-01-22 17:10:49 -0800240 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800241 ceres::LocalParameterization *quaternion_local_parameterization =
242 new ceres::EigenQuaternionParameterization;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800243
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800244 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
245 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800246 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800247 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800248
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800249 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800250 poses->find(constraint.id_begin);
251 CHECK(pose_begin_iter != poses->end())
252 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800253 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800254 poses->find(constraint.id_end);
255 CHECK(pose_end_iter != poses->end())
256 << "Pose with ID: " << constraint.id_end << " not found.";
257
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800258 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800259 constraint.information.llt().matrixL();
260 // Ceres will take ownership of the pointer.
261 ceres::CostFunction *cost_function =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800262 ceres::examples::PoseGraph3dErrorTerm::Create(constraint.t_be,
263 sqrt_information);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800264
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800265 problem->AddResidualBlock(cost_function, loss_function,
266 pose_begin_iter->second.p.data(),
267 pose_begin_iter->second.q.coeffs().data(),
268 pose_end_iter->second.p.data(),
269 pose_end_iter->second.q.coeffs().data());
270
271 problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
272 quaternion_local_parameterization);
273 problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
274 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800275 }
276
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800277 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800278 // constrained. This is typically referred to as gauge freedom. You can
279 // apply a rigid body transformation to all the nodes and the optimization
280 // problem will still have the exact same cost. The Levenberg-Marquardt
281 // algorithm has internal damping which mitigates this issue, but it is
282 // better to properly constrain the gauge freedom. This can be done by
283 // setting one of the poses as constant so the optimizer cannot change it.
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800284 ceres::examples::MapOfPoses::iterator pose_start_iter = poses->begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800285 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800286 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
287 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800288}
289
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800290// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800291bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
292 CHECK_NOTNULL(problem);
293
294 ceres::Solver::Options options;
295 options.max_num_iterations = FLAGS_max_num_iterations;
296 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
297
298 ceres::Solver::Summary summary;
299 ceres::Solve(options, problem, &summary);
300
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800301 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800302
303 return summary.IsSolutionUsable();
304}
305
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800306void TargetMapper::Solve(std::string_view field_name,
307 std::optional<std::string_view> output_dir) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800308 ceres::Problem problem;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800309 BuildOptimizationProblem(target_constraints_, &target_poses_, &problem);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800310
311 CHECK(SolveOptimizationProblem(&problem))
312 << "The solve was not successful, exiting.";
313
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800314 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800315 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800316
317 if (output_dir.has_value()) {
318 std::string output_path =
319 absl::StrCat(output_dir.value(), "/", field_name, ".json");
320 LOG(INFO) << "Writing map to file: " << output_path;
321 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800322 }
323}
324
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800325std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800326 flatbuffers::FlatBufferBuilder fbb;
327
328 // Convert poses to flatbuffers
329 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
330 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800331 target_poses_fbs.emplace_back(
332 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800333 }
334
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800335 const auto field_name_offset = fbb.CreateString(field_name);
336 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
337 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800338
339 return aos::FlatbufferToJson(
340 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
341 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800342}
343
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800344std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
345 auto rpy = PoseUtils::QuaternionToEulerAngles(pose.q);
346 os << absl::StrFormat(
347 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
348 "%.3f, yaw: %.3f}",
349 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
350 return os;
351}
352
353std::ostream &operator<<(std::ostream &os,
354 ceres::examples::Constraint3d constraint) {
355 os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
356 constraint.id_begin, constraint.id_end)
357 << constraint.t_be << "}";
358 return os;
359}
360
Milind Upadhyay7c205222022-11-16 18:20:58 -0800361} // namespace frc971::vision