blob: ccaa805daa632f7866620fd72f730fd6195d819a [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;
108 // Find the robot point right before this localization
109 while (robot_pose_it->time > target_time ||
110 (robot_pose_it + 1)->time <= target_time) {
111 robot_pose_it++;
112 CHECK(robot_pose_it < timestamped_robot_poses.end() - 1)
113 << "Need a robot pose before and after every target detection";
114 }
115
116 auto start = robot_pose_it;
117 auto end = robot_pose_it + 1;
118 interpolated_poses.emplace(target_time,
119 InterpolatePose(*start, *end, target_time));
120 }
121
122 // Match consecutive detections
123 std::vector<ceres::examples::Constraint2d> target_constraints;
124 std::vector<ceres::examples::Pose2d> robot_delta_poses;
125
126 auto last_detection = timestamped_target_detections[0];
127 auto last_robot_pose =
128 interpolated_poses[timestamped_target_detections[0].time];
129
130 for (auto it = timestamped_target_detections.begin() + 1;
131 it < timestamped_target_detections.end(); it++) {
132 // Skip two consecutive detections of the same target, because the solver
133 // doesn't allow this
134 if (it->id == last_detection.id) {
135 continue;
136 }
137
138 auto robot_pose = interpolated_poses[it->time];
139 auto robot_delta_pose =
140 PoseUtils::ComputeRelativePose(last_robot_pose, robot_pose);
141 auto confidence = ComputeConfidence(last_detection.time, it->time);
142
143 target_constraints.emplace_back(ComputeTargetConstraint(
144 last_detection, PoseUtils::Pose2dToAffine3d(robot_delta_pose), *it,
145 confidence));
146 robot_delta_poses.emplace_back(robot_delta_pose);
147
148 last_detection = *it;
149 last_robot_pose = robot_pose;
150 }
151
152 return {target_constraints, robot_delta_poses};
153}
154
155Eigen::Matrix3d DataAdapter::ComputeConfidence(
156 aos::distributed_clock::time_point start,
157 aos::distributed_clock::time_point end) {
158 constexpr size_t kX = 0;
159 constexpr size_t kY = 1;
160 constexpr size_t kTheta = 2;
161
162 // Uncertainty matrix between start and end
163 Eigen::Matrix3d P = Eigen::Matrix3d::Zero();
164
165 {
166 // Noise for odometry-based robot position measurements
167 Eigen::Matrix3d Q_odometry = Eigen::Matrix3d::Zero();
168 Q_odometry(kX, kX) = std::pow(0.045, 2);
169 Q_odometry(kY, kY) = std::pow(0.045, 2);
170 Q_odometry(kTheta, kTheta) = std::pow(0.01, 2);
171
172 // Add uncertainty for robot position measurements from start to end
173 int iterations = (end - start) / frc971::controls::kLoopFrequency;
174 P += static_cast<double>(iterations) * Q_odometry;
175 }
176
177 {
178 // Noise for vision-based target localizations
179 Eigen::Matrix3d Q_vision = Eigen::Matrix3d::Zero();
180 Q_vision(kX, kX) = std::pow(0.09, 2);
181 Q_vision(kY, kY) = std::pow(0.09, 2);
182 Q_vision(kTheta, kTheta) = std::pow(0.02, 2);
183
184 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
185 P += 2.0 * Q_vision;
186 }
187
188 return P.inverse();
189}
190
191ceres::examples::Constraint2d DataAdapter::ComputeTargetConstraint(
192 const TimestampedDetection &target_detection_start,
193 const Eigen::Affine3d &H_robotstart_robotend,
194 const TimestampedDetection &target_detection_end,
195 const Eigen::Matrix3d &confidence) {
196 // Compute the relative pose (constraint) between the two targets
197 Eigen::Affine3d H_targetstart_targetend =
198 target_detection_start.H_robot_target.inverse() * H_robotstart_robotend *
199 target_detection_end.H_robot_target;
200 ceres::examples::Pose2d target_constraint =
201 PoseUtils::Affine3dToPose2d(H_targetstart_targetend);
202
203 return ceres::examples::Constraint2d{
204 target_detection_start.id, target_detection_end.id,
205 target_constraint.x, target_constraint.y,
206 target_constraint.yaw_radians, confidence};
207}
208
209TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800210 std::string_view target_poses_path,
211 std::vector<ceres::examples::Constraint2d> target_constraints)
212 : target_constraints_(target_constraints) {
213 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
214 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
215 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
216 target_poses_[target_pose_fbs->id()] = ceres::examples::Pose2d{
217 target_pose_fbs->x(), target_pose_fbs->y(), target_pose_fbs->yaw()};
218 }
219}
220
221TargetMapper::TargetMapper(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800222 std::map<TargetId, ceres::examples::Pose2d> target_poses,
223 std::vector<ceres::examples::Constraint2d> target_constraints)
224 : target_poses_(target_poses), target_constraints_(target_constraints) {}
225
226std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
227 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
228 for (auto target_pose : target_poses) {
229 if (target_pose.id == target_id) {
230 return target_pose;
231 }
232 }
233
234 return std::nullopt;
235}
236
237// Taken from ceres/examples/slam/pose_graph_2d/pose_graph_2d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800238void TargetMapper::BuildOptimizationProblem(
239 std::map<int, ceres::examples::Pose2d> *poses,
240 const std::vector<ceres::examples::Constraint2d> &constraints,
241 ceres::Problem *problem) {
242 CHECK_NOTNULL(poses);
243 CHECK_NOTNULL(problem);
244 if (constraints.empty()) {
245 LOG(WARNING) << "No constraints, no problem to optimize.";
246 return;
247 }
248
249 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
250 ceres::LocalParameterization *angle_local_parameterization =
251 ceres::examples::AngleLocalParameterization::Create();
252
253 for (std::vector<ceres::examples::Constraint2d>::const_iterator
254 constraints_iter = constraints.begin();
255 constraints_iter != constraints.end(); ++constraints_iter) {
256 const ceres::examples::Constraint2d &constraint = *constraints_iter;
257
258 std::map<int, ceres::examples::Pose2d>::iterator pose_begin_iter =
259 poses->find(constraint.id_begin);
260 CHECK(pose_begin_iter != poses->end())
261 << "Pose with ID: " << constraint.id_begin << " not found.";
262 std::map<int, ceres::examples::Pose2d>::iterator pose_end_iter =
263 poses->find(constraint.id_end);
264 CHECK(pose_end_iter != poses->end())
265 << "Pose with ID: " << constraint.id_end << " not found.";
266
267 const Eigen::Matrix3d sqrt_information =
268 constraint.information.llt().matrixL();
269 // Ceres will take ownership of the pointer.
270 ceres::CostFunction *cost_function =
271 ceres::examples::PoseGraph2dErrorTerm::Create(
272 constraint.x, constraint.y, constraint.yaw_radians,
273 sqrt_information);
274 problem->AddResidualBlock(
275 cost_function, loss_function, &pose_begin_iter->second.x,
276 &pose_begin_iter->second.y, &pose_begin_iter->second.yaw_radians,
277 &pose_end_iter->second.x, &pose_end_iter->second.y,
278 &pose_end_iter->second.yaw_radians);
279
280 problem->SetParameterization(&pose_begin_iter->second.yaw_radians,
281 angle_local_parameterization);
282 problem->SetParameterization(&pose_end_iter->second.yaw_radians,
283 angle_local_parameterization);
284 }
285
286 // The pose graph optimization problem has three DOFs that are not fully
287 // constrained. This is typically referred to as gauge freedom. You can apply
288 // a rigid body transformation to all the nodes and the optimization problem
289 // will still have the exact same cost. The Levenberg-Marquardt algorithm has
290 // internal damping which mitigates this issue, but it is better to properly
291 // constrain the gauge freedom. This can be done by setting one of the poses
292 // as constant so the optimizer cannot change it.
293 std::map<int, ceres::examples::Pose2d>::iterator pose_start_iter =
294 poses->begin();
295 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
296 problem->SetParameterBlockConstant(&pose_start_iter->second.x);
297 problem->SetParameterBlockConstant(&pose_start_iter->second.y);
298 problem->SetParameterBlockConstant(&pose_start_iter->second.yaw_radians);
299}
300
301// Taken from ceres/examples/slam/pose_graph_2d/pose_graph_2d.cc
302bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
303 CHECK_NOTNULL(problem);
304
305 ceres::Solver::Options options;
306 options.max_num_iterations = FLAGS_max_num_iterations;
307 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
308
309 ceres::Solver::Summary summary;
310 ceres::Solve(options, problem, &summary);
311
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800312 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800313
314 return summary.IsSolutionUsable();
315}
316
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800317void TargetMapper::Solve(std::string_view field_name,
318 std::optional<std::string_view> output_dir) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800319 ceres::Problem problem;
320 BuildOptimizationProblem(&target_poses_, target_constraints_, &problem);
321
322 CHECK(SolveOptimizationProblem(&problem))
323 << "The solve was not successful, exiting.";
324
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800325 // TODO(milind): add origin to first target offset to all poses
326
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800327 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800328 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800329
330 if (output_dir.has_value()) {
331 std::string output_path =
332 absl::StrCat(output_dir.value(), "/", field_name, ".json");
333 LOG(INFO) << "Writing map to file: " << output_path;
334 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800335 }
336}
337
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800338std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800339 flatbuffers::FlatBufferBuilder fbb;
340
341 // Convert poses to flatbuffers
342 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
343 for (const auto &[id, pose] : target_poses_) {
344 TargetPoseFbs::Builder target_pose_builder(fbb);
345 target_pose_builder.add_id(id);
346 target_pose_builder.add_x(id);
347 target_pose_builder.add_y(id);
348 target_pose_builder.add_yaw(id);
349
350 target_poses_fbs.emplace_back(target_pose_builder.Finish());
351 }
352
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800353 const auto field_name_offset = fbb.CreateString(field_name);
354 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
355 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800356
357 return aos::FlatbufferToJson(
358 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
359 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800360}
361
362} // namespace frc971::vision