blob: 92220391a8f1ddb7319fee5ac394431e858ec61e [file] [log] [blame]
Milind Upadhyay7c205222022-11-16 18:20:58 -08001#include "frc971/vision/target_mapper.h"
2
3#include "frc971/control_loops/control_loop.h"
4#include "frc971/vision/ceres/angle_local_parameterization.h"
5#include "frc971/vision/ceres/normalize_angle.h"
6#include "frc971/vision/ceres/pose_graph_2d_error_term.h"
7#include "frc971/vision/geometry.h"
8
9DEFINE_uint64(max_num_iterations, 100,
10 "Maximum number of iterations for the ceres solver");
11
12namespace frc971::vision {
13
14Eigen::Affine3d PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d pose2d) {
15 Eigen::Affine3d H_world_pose =
16 Eigen::Translation3d(pose2d.x, pose2d.y, 0.0) *
17 Eigen::AngleAxisd(pose2d.yaw_radians, Eigen::Vector3d::UnitZ());
18 return H_world_pose;
19}
20
21ceres::examples::Pose2d PoseUtils::Affine3dToPose2d(Eigen::Affine3d H) {
22 Eigen::Vector3d T = H.translation();
23 double heading = std::atan2(H.rotation()(1, 0), H.rotation()(0, 0));
24 return ceres::examples::Pose2d{T[0], T[1],
25 ceres::examples::NormalizeAngle(heading)};
26}
27
28ceres::examples::Pose2d PoseUtils::ComputeRelativePose(
29 ceres::examples::Pose2d pose_1, ceres::examples::Pose2d pose_2) {
30 Eigen::Affine3d H_world_1 = Pose2dToAffine3d(pose_1);
31 Eigen::Affine3d H_world_2 = Pose2dToAffine3d(pose_2);
32
33 // Get the location of 2 in the 1 frame
34 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
35 return Affine3dToPose2d(H_1_2);
36}
37
38ceres::examples::Pose2d PoseUtils::ComputeOffsetPose(
39 ceres::examples::Pose2d pose_1, ceres::examples::Pose2d pose_2_relative) {
40 auto H_world_1 = Pose2dToAffine3d(pose_1);
41 auto H_1_2 = Pose2dToAffine3d(pose_2_relative);
42 auto H_world_2 = H_world_1 * H_1_2;
43
44 return Affine3dToPose2d(H_world_2);
45}
46
47namespace {
48double ExponentiatedSinTerm(double theta) {
49 return (theta == 0.0 ? 1.0 : std::sin(theta) / theta);
50}
51
52double ExponentiatedCosTerm(double theta) {
53 return (theta == 0.0 ? 0.0 : (1 - std::cos(theta)) / theta);
54}
55} // namespace
56
57ceres::examples::Pose2d DataAdapter::InterpolatePose(
58 const TimestampedPose &pose_start, const TimestampedPose &pose_end,
59 aos::distributed_clock::time_point time) {
60 auto delta_pose =
61 PoseUtils::ComputeRelativePose(pose_start.pose, pose_end.pose);
62 // Time from start of period, on the scale 0-1 where 1 is the end.
63 double interpolation_scalar =
64 static_cast<double>((time - pose_start.time).count()) /
65 static_cast<double>((pose_end.time - pose_start.time).count());
66
67 double theta = delta_pose.yaw_radians;
68 // Take the log of the transformation matrix:
69 // https://mathoverflow.net/questions/118533/how-to-compute-se2-group-exponential-and-logarithm
70 StdFormLine dx_line = {.a = ExponentiatedSinTerm(theta),
71 .b = -ExponentiatedCosTerm(theta),
72 .c = delta_pose.x};
73 StdFormLine dy_line = {.a = ExponentiatedCosTerm(theta),
74 .b = ExponentiatedSinTerm(theta),
75 .c = delta_pose.y};
76
77 std::optional<cv::Point2d> solution = dx_line.Intersection(dy_line);
78 CHECK(solution.has_value());
79
80 // Re-exponentiate with the new values scaled by the interpolation scalar to
81 // get an interpolated tranformation matrix
82 double a = solution->x * interpolation_scalar;
83 double b = solution->y * interpolation_scalar;
84 double alpha = theta * interpolation_scalar;
85
86 ceres::examples::Pose2d interpolated_pose = {
87 .x = a * ExponentiatedSinTerm(theta) - b * ExponentiatedCosTerm(theta),
88 .y = a * ExponentiatedCosTerm(theta) + b * ExponentiatedSinTerm(theta),
89 .yaw_radians = alpha};
90
91 return PoseUtils::ComputeOffsetPose(pose_start.pose, interpolated_pose);
92} // namespace frc971::vision
93
94std::pair<std::vector<ceres::examples::Constraint2d>,
95 std::vector<ceres::examples::Pose2d>>
96DataAdapter::MatchTargetDetections(
97 const std::vector<TimestampedPose> &timestamped_robot_poses,
98 const std::vector<TimestampedDetection> &timestamped_target_detections) {
99 // Interpolate robot poses
100 std::map<aos::distributed_clock::time_point, ceres::examples::Pose2d>
101 interpolated_poses;
102
103 CHECK_GT(timestamped_robot_poses.size(), 1ul)
104 << "Need more than 1 robot pose";
105 auto robot_pose_it = timestamped_robot_poses.begin();
106 for (const auto &timestamped_detection : timestamped_target_detections) {
107 aos::distributed_clock::time_point target_time = timestamped_detection.time;
Milind Upadhyay81420a22022-12-14 21:13:06 -0800108
109 // Skip this target detection if we have no robot poses before it
110 if (robot_pose_it->time > target_time) {
111 continue;
112 }
113
Milind Upadhyay7c205222022-11-16 18:20:58 -0800114 // Find the robot point right before this localization
115 while (robot_pose_it->time > target_time ||
116 (robot_pose_it + 1)->time <= target_time) {
117 robot_pose_it++;
118 CHECK(robot_pose_it < timestamped_robot_poses.end() - 1)
119 << "Need a robot pose before and after every target detection";
120 }
121
122 auto start = robot_pose_it;
123 auto end = robot_pose_it + 1;
124 interpolated_poses.emplace(target_time,
125 InterpolatePose(*start, *end, target_time));
126 }
127
Milind Upadhyay81420a22022-12-14 21:13:06 -0800128 // In the case that all target detections were before the first robot
129 // detection, we would have no interpolated poses at this point
130 CHECK_GT(interpolated_poses.size(), 0ul)
131 << "Need a robot pose before and after every target detection";
132
Milind Upadhyay7c205222022-11-16 18:20:58 -0800133 // Match consecutive detections
134 std::vector<ceres::examples::Constraint2d> target_constraints;
135 std::vector<ceres::examples::Pose2d> robot_delta_poses;
136
137 auto last_detection = timestamped_target_detections[0];
138 auto last_robot_pose =
139 interpolated_poses[timestamped_target_detections[0].time];
140
141 for (auto it = timestamped_target_detections.begin() + 1;
142 it < timestamped_target_detections.end(); it++) {
143 // Skip two consecutive detections of the same target, because the solver
144 // doesn't allow this
145 if (it->id == last_detection.id) {
146 continue;
147 }
148
149 auto robot_pose = interpolated_poses[it->time];
150 auto robot_delta_pose =
151 PoseUtils::ComputeRelativePose(last_robot_pose, robot_pose);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800152 auto confidence = ComputeConfidence(last_detection.time, it->time,
153 last_detection.distance_from_camera,
154 it->distance_from_camera);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800155
156 target_constraints.emplace_back(ComputeTargetConstraint(
157 last_detection, PoseUtils::Pose2dToAffine3d(robot_delta_pose), *it,
158 confidence));
159 robot_delta_poses.emplace_back(robot_delta_pose);
160
161 last_detection = *it;
162 last_robot_pose = robot_pose;
163 }
164
165 return {target_constraints, robot_delta_poses};
166}
167
Milind Upadhyayec493912022-12-18 21:33:15 -0800168std::vector<ceres::examples::Constraint2d> DataAdapter::MatchTargetDetections(
169 const std::vector<DataAdapter::TimestampedDetection>
170 &timestamped_target_detections,
171 aos::distributed_clock::duration max_dt) {
172 CHECK_GE(timestamped_target_detections.size(), 2ul)
173 << "Must have at least 2 detections";
174
175 // Match consecutive detections
176 std::vector<ceres::examples::Constraint2d> target_constraints;
177 for (auto it = timestamped_target_detections.begin() + 1;
178 it < timestamped_target_detections.end(); it++) {
179 auto last_detection = *(it - 1);
180
181 // Skip two consecutive detections of the same target, because the solver
182 // doesn't allow this
183 if (it->id == last_detection.id) {
184 continue;
185 }
186
187 // Don't take into account constraints too far apart in time, because the
188 // recording device could have moved too much
189 if ((it->time - last_detection.time) > max_dt) {
190 continue;
191 }
192
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800193 auto confidence = ComputeConfidence(last_detection.time, it->time,
194 last_detection.distance_from_camera,
195 it->distance_from_camera);
Milind Upadhyayec493912022-12-18 21:33:15 -0800196 target_constraints.emplace_back(
197 ComputeTargetConstraint(last_detection, *it, confidence));
198 }
199
200 return target_constraints;
201}
202
Milind Upadhyay7c205222022-11-16 18:20:58 -0800203Eigen::Matrix3d DataAdapter::ComputeConfidence(
204 aos::distributed_clock::time_point start,
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800205 aos::distributed_clock::time_point end, double distance_from_camera_start,
206 double distance_from_camera_end) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800207 constexpr size_t kX = 0;
208 constexpr size_t kY = 1;
209 constexpr size_t kTheta = 2;
210
211 // Uncertainty matrix between start and end
212 Eigen::Matrix3d P = Eigen::Matrix3d::Zero();
213
214 {
215 // Noise for odometry-based robot position measurements
216 Eigen::Matrix3d Q_odometry = Eigen::Matrix3d::Zero();
217 Q_odometry(kX, kX) = std::pow(0.045, 2);
218 Q_odometry(kY, kY) = std::pow(0.045, 2);
219 Q_odometry(kTheta, kTheta) = std::pow(0.01, 2);
220
221 // Add uncertainty for robot position measurements from start to end
222 int iterations = (end - start) / frc971::controls::kLoopFrequency;
223 P += static_cast<double>(iterations) * Q_odometry;
224 }
225
226 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800227 // Noise for vision-based target localizations. Multiplying this matrix by
228 // the distance from camera to target squared results in the uncertainty in
229 // that measurement
Milind Upadhyay7c205222022-11-16 18:20:58 -0800230 Eigen::Matrix3d Q_vision = Eigen::Matrix3d::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800231 Q_vision(kX, kX) = std::pow(0.045, 2);
232 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800233 Q_vision(kTheta, kTheta) = std::pow(0.02, 2);
234
235 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800236 P += Q_vision * std::pow(distance_from_camera_start, 2);
237 P += Q_vision * std::pow(distance_from_camera_end, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800238 }
239
240 return P.inverse();
241}
242
243ceres::examples::Constraint2d DataAdapter::ComputeTargetConstraint(
244 const TimestampedDetection &target_detection_start,
245 const Eigen::Affine3d &H_robotstart_robotend,
246 const TimestampedDetection &target_detection_end,
247 const Eigen::Matrix3d &confidence) {
248 // Compute the relative pose (constraint) between the two targets
249 Eigen::Affine3d H_targetstart_targetend =
250 target_detection_start.H_robot_target.inverse() * H_robotstart_robotend *
251 target_detection_end.H_robot_target;
252 ceres::examples::Pose2d target_constraint =
253 PoseUtils::Affine3dToPose2d(H_targetstart_targetend);
254
255 return ceres::examples::Constraint2d{
256 target_detection_start.id, target_detection_end.id,
257 target_constraint.x, target_constraint.y,
258 target_constraint.yaw_radians, confidence};
259}
260
Milind Upadhyayec493912022-12-18 21:33:15 -0800261ceres::examples::Constraint2d DataAdapter::ComputeTargetConstraint(
262 const TimestampedDetection &target_detection_start,
263 const TimestampedDetection &target_detection_end,
264 const Eigen::Matrix3d &confidence) {
265 return ComputeTargetConstraint(target_detection_start,
266 Eigen::Affine3d(Eigen::Matrix4d::Identity()),
267 target_detection_end, confidence);
268}
269
Milind Upadhyay7c205222022-11-16 18:20:58 -0800270TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800271 std::string_view target_poses_path,
272 std::vector<ceres::examples::Constraint2d> target_constraints)
273 : target_constraints_(target_constraints) {
274 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
275 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
276 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
277 target_poses_[target_pose_fbs->id()] = ceres::examples::Pose2d{
278 target_pose_fbs->x(), target_pose_fbs->y(), target_pose_fbs->yaw()};
279 }
280}
281
282TargetMapper::TargetMapper(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800283 std::map<TargetId, ceres::examples::Pose2d> target_poses,
284 std::vector<ceres::examples::Constraint2d> target_constraints)
285 : target_poses_(target_poses), target_constraints_(target_constraints) {}
286
287std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
288 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
289 for (auto target_pose : target_poses) {
290 if (target_pose.id == target_id) {
291 return target_pose;
292 }
293 }
294
295 return std::nullopt;
296}
297
298// Taken from ceres/examples/slam/pose_graph_2d/pose_graph_2d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800299void TargetMapper::BuildOptimizationProblem(
300 std::map<int, ceres::examples::Pose2d> *poses,
301 const std::vector<ceres::examples::Constraint2d> &constraints,
302 ceres::Problem *problem) {
303 CHECK_NOTNULL(poses);
304 CHECK_NOTNULL(problem);
305 if (constraints.empty()) {
306 LOG(WARNING) << "No constraints, no problem to optimize.";
307 return;
308 }
309
310 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
311 ceres::LocalParameterization *angle_local_parameterization =
312 ceres::examples::AngleLocalParameterization::Create();
313
314 for (std::vector<ceres::examples::Constraint2d>::const_iterator
315 constraints_iter = constraints.begin();
316 constraints_iter != constraints.end(); ++constraints_iter) {
317 const ceres::examples::Constraint2d &constraint = *constraints_iter;
318
319 std::map<int, ceres::examples::Pose2d>::iterator pose_begin_iter =
320 poses->find(constraint.id_begin);
321 CHECK(pose_begin_iter != poses->end())
322 << "Pose with ID: " << constraint.id_begin << " not found.";
323 std::map<int, ceres::examples::Pose2d>::iterator pose_end_iter =
324 poses->find(constraint.id_end);
325 CHECK(pose_end_iter != poses->end())
326 << "Pose with ID: " << constraint.id_end << " not found.";
327
328 const Eigen::Matrix3d sqrt_information =
329 constraint.information.llt().matrixL();
330 // Ceres will take ownership of the pointer.
331 ceres::CostFunction *cost_function =
332 ceres::examples::PoseGraph2dErrorTerm::Create(
333 constraint.x, constraint.y, constraint.yaw_radians,
334 sqrt_information);
335 problem->AddResidualBlock(
336 cost_function, loss_function, &pose_begin_iter->second.x,
337 &pose_begin_iter->second.y, &pose_begin_iter->second.yaw_radians,
338 &pose_end_iter->second.x, &pose_end_iter->second.y,
339 &pose_end_iter->second.yaw_radians);
340
341 problem->SetParameterization(&pose_begin_iter->second.yaw_radians,
342 angle_local_parameterization);
343 problem->SetParameterization(&pose_end_iter->second.yaw_radians,
344 angle_local_parameterization);
345 }
346
347 // The pose graph optimization problem has three DOFs that are not fully
348 // constrained. This is typically referred to as gauge freedom. You can apply
349 // a rigid body transformation to all the nodes and the optimization problem
350 // will still have the exact same cost. The Levenberg-Marquardt algorithm has
351 // internal damping which mitigates this issue, but it is better to properly
352 // constrain the gauge freedom. This can be done by setting one of the poses
353 // as constant so the optimizer cannot change it.
354 std::map<int, ceres::examples::Pose2d>::iterator pose_start_iter =
355 poses->begin();
356 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
357 problem->SetParameterBlockConstant(&pose_start_iter->second.x);
358 problem->SetParameterBlockConstant(&pose_start_iter->second.y);
359 problem->SetParameterBlockConstant(&pose_start_iter->second.yaw_radians);
360}
361
362// Taken from ceres/examples/slam/pose_graph_2d/pose_graph_2d.cc
363bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
364 CHECK_NOTNULL(problem);
365
366 ceres::Solver::Options options;
367 options.max_num_iterations = FLAGS_max_num_iterations;
368 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
369
370 ceres::Solver::Summary summary;
371 ceres::Solve(options, problem, &summary);
372
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800373 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800374
375 return summary.IsSolutionUsable();
376}
377
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800378void TargetMapper::Solve(std::string_view field_name,
379 std::optional<std::string_view> output_dir) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800380 ceres::Problem problem;
381 BuildOptimizationProblem(&target_poses_, target_constraints_, &problem);
382
383 CHECK(SolveOptimizationProblem(&problem))
384 << "The solve was not successful, exiting.";
385
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800386 // TODO(milind): add origin to first target offset to all poses
387
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800388 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800389 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800390
391 if (output_dir.has_value()) {
392 std::string output_path =
393 absl::StrCat(output_dir.value(), "/", field_name, ".json");
394 LOG(INFO) << "Writing map to file: " << output_path;
395 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800396 }
397}
398
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800399std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800400 flatbuffers::FlatBufferBuilder fbb;
401
402 // Convert poses to flatbuffers
403 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
404 for (const auto &[id, pose] : target_poses_) {
405 TargetPoseFbs::Builder target_pose_builder(fbb);
406 target_pose_builder.add_id(id);
Milind Upadhyaycf757772022-12-14 20:57:36 -0800407 target_pose_builder.add_x(pose.x);
408 target_pose_builder.add_y(pose.y);
409 target_pose_builder.add_yaw(pose.yaw_radians);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800410
411 target_poses_fbs.emplace_back(target_pose_builder.Finish());
412 }
413
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800414 const auto field_name_offset = fbb.CreateString(field_name);
415 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
416 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800417
418 return aos::FlatbufferToJson(
419 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
420 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800421}
422
423} // namespace frc971::vision