blob: ab4ee6d5a4f479594899c4c1745768f3fdc5d787 [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);
152 auto confidence = ComputeConfidence(last_detection.time, it->time);
153
154 target_constraints.emplace_back(ComputeTargetConstraint(
155 last_detection, PoseUtils::Pose2dToAffine3d(robot_delta_pose), *it,
156 confidence));
157 robot_delta_poses.emplace_back(robot_delta_pose);
158
159 last_detection = *it;
160 last_robot_pose = robot_pose;
161 }
162
163 return {target_constraints, robot_delta_poses};
164}
165
Milind Upadhyayec493912022-12-18 21:33:15 -0800166std::vector<ceres::examples::Constraint2d> DataAdapter::MatchTargetDetections(
167 const std::vector<DataAdapter::TimestampedDetection>
168 &timestamped_target_detections,
169 aos::distributed_clock::duration max_dt) {
170 CHECK_GE(timestamped_target_detections.size(), 2ul)
171 << "Must have at least 2 detections";
172
173 // Match consecutive detections
174 std::vector<ceres::examples::Constraint2d> target_constraints;
175 for (auto it = timestamped_target_detections.begin() + 1;
176 it < timestamped_target_detections.end(); it++) {
177 auto last_detection = *(it - 1);
178
179 // Skip two consecutive detections of the same target, because the solver
180 // doesn't allow this
181 if (it->id == last_detection.id) {
182 continue;
183 }
184
185 // Don't take into account constraints too far apart in time, because the
186 // recording device could have moved too much
187 if ((it->time - last_detection.time) > max_dt) {
188 continue;
189 }
190
191 // TODO(milind): better way to compute confidence since these detections are
192 // likely very close in time together
193 auto confidence = ComputeConfidence(last_detection.time, it->time);
194 target_constraints.emplace_back(
195 ComputeTargetConstraint(last_detection, *it, confidence));
196 }
197
198 return target_constraints;
199}
200
Milind Upadhyay7c205222022-11-16 18:20:58 -0800201Eigen::Matrix3d DataAdapter::ComputeConfidence(
202 aos::distributed_clock::time_point start,
203 aos::distributed_clock::time_point end) {
204 constexpr size_t kX = 0;
205 constexpr size_t kY = 1;
206 constexpr size_t kTheta = 2;
207
208 // Uncertainty matrix between start and end
209 Eigen::Matrix3d P = Eigen::Matrix3d::Zero();
210
211 {
212 // Noise for odometry-based robot position measurements
213 Eigen::Matrix3d Q_odometry = Eigen::Matrix3d::Zero();
214 Q_odometry(kX, kX) = std::pow(0.045, 2);
215 Q_odometry(kY, kY) = std::pow(0.045, 2);
216 Q_odometry(kTheta, kTheta) = std::pow(0.01, 2);
217
218 // Add uncertainty for robot position measurements from start to end
219 int iterations = (end - start) / frc971::controls::kLoopFrequency;
220 P += static_cast<double>(iterations) * Q_odometry;
221 }
222
223 {
224 // Noise for vision-based target localizations
225 Eigen::Matrix3d Q_vision = Eigen::Matrix3d::Zero();
226 Q_vision(kX, kX) = std::pow(0.09, 2);
227 Q_vision(kY, kY) = std::pow(0.09, 2);
228 Q_vision(kTheta, kTheta) = std::pow(0.02, 2);
229
230 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
231 P += 2.0 * Q_vision;
232 }
233
234 return P.inverse();
235}
236
237ceres::examples::Constraint2d DataAdapter::ComputeTargetConstraint(
238 const TimestampedDetection &target_detection_start,
239 const Eigen::Affine3d &H_robotstart_robotend,
240 const TimestampedDetection &target_detection_end,
241 const Eigen::Matrix3d &confidence) {
242 // Compute the relative pose (constraint) between the two targets
243 Eigen::Affine3d H_targetstart_targetend =
244 target_detection_start.H_robot_target.inverse() * H_robotstart_robotend *
245 target_detection_end.H_robot_target;
246 ceres::examples::Pose2d target_constraint =
247 PoseUtils::Affine3dToPose2d(H_targetstart_targetend);
248
249 return ceres::examples::Constraint2d{
250 target_detection_start.id, target_detection_end.id,
251 target_constraint.x, target_constraint.y,
252 target_constraint.yaw_radians, confidence};
253}
254
Milind Upadhyayec493912022-12-18 21:33:15 -0800255ceres::examples::Constraint2d DataAdapter::ComputeTargetConstraint(
256 const TimestampedDetection &target_detection_start,
257 const TimestampedDetection &target_detection_end,
258 const Eigen::Matrix3d &confidence) {
259 return ComputeTargetConstraint(target_detection_start,
260 Eigen::Affine3d(Eigen::Matrix4d::Identity()),
261 target_detection_end, confidence);
262}
263
Milind Upadhyay7c205222022-11-16 18:20:58 -0800264TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800265 std::string_view target_poses_path,
266 std::vector<ceres::examples::Constraint2d> target_constraints)
267 : target_constraints_(target_constraints) {
268 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
269 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
270 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
271 target_poses_[target_pose_fbs->id()] = ceres::examples::Pose2d{
272 target_pose_fbs->x(), target_pose_fbs->y(), target_pose_fbs->yaw()};
273 }
274}
275
276TargetMapper::TargetMapper(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800277 std::map<TargetId, ceres::examples::Pose2d> target_poses,
278 std::vector<ceres::examples::Constraint2d> target_constraints)
279 : target_poses_(target_poses), target_constraints_(target_constraints) {}
280
281std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
282 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
283 for (auto target_pose : target_poses) {
284 if (target_pose.id == target_id) {
285 return target_pose;
286 }
287 }
288
289 return std::nullopt;
290}
291
292// Taken from ceres/examples/slam/pose_graph_2d/pose_graph_2d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800293void TargetMapper::BuildOptimizationProblem(
294 std::map<int, ceres::examples::Pose2d> *poses,
295 const std::vector<ceres::examples::Constraint2d> &constraints,
296 ceres::Problem *problem) {
297 CHECK_NOTNULL(poses);
298 CHECK_NOTNULL(problem);
299 if (constraints.empty()) {
300 LOG(WARNING) << "No constraints, no problem to optimize.";
301 return;
302 }
303
304 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
305 ceres::LocalParameterization *angle_local_parameterization =
306 ceres::examples::AngleLocalParameterization::Create();
307
308 for (std::vector<ceres::examples::Constraint2d>::const_iterator
309 constraints_iter = constraints.begin();
310 constraints_iter != constraints.end(); ++constraints_iter) {
311 const ceres::examples::Constraint2d &constraint = *constraints_iter;
312
313 std::map<int, ceres::examples::Pose2d>::iterator pose_begin_iter =
314 poses->find(constraint.id_begin);
315 CHECK(pose_begin_iter != poses->end())
316 << "Pose with ID: " << constraint.id_begin << " not found.";
317 std::map<int, ceres::examples::Pose2d>::iterator pose_end_iter =
318 poses->find(constraint.id_end);
319 CHECK(pose_end_iter != poses->end())
320 << "Pose with ID: " << constraint.id_end << " not found.";
321
322 const Eigen::Matrix3d sqrt_information =
323 constraint.information.llt().matrixL();
324 // Ceres will take ownership of the pointer.
325 ceres::CostFunction *cost_function =
326 ceres::examples::PoseGraph2dErrorTerm::Create(
327 constraint.x, constraint.y, constraint.yaw_radians,
328 sqrt_information);
329 problem->AddResidualBlock(
330 cost_function, loss_function, &pose_begin_iter->second.x,
331 &pose_begin_iter->second.y, &pose_begin_iter->second.yaw_radians,
332 &pose_end_iter->second.x, &pose_end_iter->second.y,
333 &pose_end_iter->second.yaw_radians);
334
335 problem->SetParameterization(&pose_begin_iter->second.yaw_radians,
336 angle_local_parameterization);
337 problem->SetParameterization(&pose_end_iter->second.yaw_radians,
338 angle_local_parameterization);
339 }
340
341 // The pose graph optimization problem has three DOFs that are not fully
342 // constrained. This is typically referred to as gauge freedom. You can apply
343 // a rigid body transformation to all the nodes and the optimization problem
344 // will still have the exact same cost. The Levenberg-Marquardt algorithm has
345 // internal damping which mitigates this issue, but it is better to properly
346 // constrain the gauge freedom. This can be done by setting one of the poses
347 // as constant so the optimizer cannot change it.
348 std::map<int, ceres::examples::Pose2d>::iterator pose_start_iter =
349 poses->begin();
350 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
351 problem->SetParameterBlockConstant(&pose_start_iter->second.x);
352 problem->SetParameterBlockConstant(&pose_start_iter->second.y);
353 problem->SetParameterBlockConstant(&pose_start_iter->second.yaw_radians);
354}
355
356// Taken from ceres/examples/slam/pose_graph_2d/pose_graph_2d.cc
357bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
358 CHECK_NOTNULL(problem);
359
360 ceres::Solver::Options options;
361 options.max_num_iterations = FLAGS_max_num_iterations;
362 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
363
364 ceres::Solver::Summary summary;
365 ceres::Solve(options, problem, &summary);
366
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800367 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800368
369 return summary.IsSolutionUsable();
370}
371
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800372void TargetMapper::Solve(std::string_view field_name,
373 std::optional<std::string_view> output_dir) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800374 ceres::Problem problem;
375 BuildOptimizationProblem(&target_poses_, target_constraints_, &problem);
376
377 CHECK(SolveOptimizationProblem(&problem))
378 << "The solve was not successful, exiting.";
379
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800380 // TODO(milind): add origin to first target offset to all poses
381
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800382 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800383 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800384
385 if (output_dir.has_value()) {
386 std::string output_path =
387 absl::StrCat(output_dir.value(), "/", field_name, ".json");
388 LOG(INFO) << "Writing map to file: " << output_path;
389 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800390 }
391}
392
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800393std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800394 flatbuffers::FlatBufferBuilder fbb;
395
396 // Convert poses to flatbuffers
397 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
398 for (const auto &[id, pose] : target_poses_) {
399 TargetPoseFbs::Builder target_pose_builder(fbb);
400 target_pose_builder.add_id(id);
Milind Upadhyaycf757772022-12-14 20:57:36 -0800401 target_pose_builder.add_x(pose.x);
402 target_pose_builder.add_y(pose.y);
403 target_pose_builder.add_yaw(pose.yaw_radians);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800404
405 target_poses_fbs.emplace_back(target_pose_builder.Finish());
406 }
407
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800408 const auto field_name_offset = fbb.CreateString(field_name);
409 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
410 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800411
412 return aos::FlatbufferToJson(
413 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
414 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800415}
416
417} // namespace frc971::vision