blob: d0dcdc8ecde2b0966acd3dccccfaa86ba9adc515 [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");
milind-ud62f80a2023-03-04 16:37:09 -080010DEFINE_double(distortion_noise_scalar, 1.0,
11 "Scale the target pose distortion factor by this when computing "
12 "the noise.");
Milind Upadhyay7c205222022-11-16 18:20:58 -080013
14namespace frc971::vision {
15
Milind Upadhyayc5beba12022-12-17 17:41:20 -080016Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
17 const ceres::examples::Pose3d &pose3d) {
Milind Upadhyay7c205222022-11-16 18:20:58 -080018 Eigen::Affine3d H_world_pose =
Milind Upadhyayc5beba12022-12-17 17:41:20 -080019 Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q;
Milind Upadhyay7c205222022-11-16 18:20:58 -080020 return H_world_pose;
21}
22
Milind Upadhyayc5beba12022-12-17 17:41:20 -080023ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) {
24 return ceres::examples::Pose3d{.p = H.translation(),
25 .q = Eigen::Quaterniond(H.rotation())};
Milind Upadhyay7c205222022-11-16 18:20:58 -080026}
27
Milind Upadhyayc5beba12022-12-17 17:41:20 -080028ceres::examples::Pose3d PoseUtils::ComputeRelativePose(
29 const ceres::examples::Pose3d &pose_1,
30 const ceres::examples::Pose3d &pose_2) {
31 Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1);
32 Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080033
34 // Get the location of 2 in the 1 frame
35 Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080036 return Affine3dToPose3d(H_1_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080037}
38
Milind Upadhyayc5beba12022-12-17 17:41:20 -080039ceres::examples::Pose3d PoseUtils::ComputeOffsetPose(
40 const ceres::examples::Pose3d &pose_1,
41 const ceres::examples::Pose3d &pose_2_relative) {
42 auto H_world_1 = Pose3dToAffine3d(pose_1);
43 auto H_1_2 = Pose3dToAffine3d(pose_2_relative);
Milind Upadhyay7c205222022-11-16 18:20:58 -080044 auto H_world_2 = H_world_1 * H_1_2;
45
Milind Upadhyayc5beba12022-12-17 17:41:20 -080046 return Affine3dToPose3d(H_world_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -080047}
48
Milind Upadhyayc5beba12022-12-17 17:41:20 -080049Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion(
50 const Eigen::Vector3d &rpy) {
51 Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX());
52 Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY());
53 Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ());
54
55 return yaw_angle * pitch_angle * roll_angle;
Milind Upadhyay7c205222022-11-16 18:20:58 -080056}
57
Milind Upadhyayc5beba12022-12-17 17:41:20 -080058Eigen::Vector3d PoseUtils::QuaternionToEulerAngles(
59 const Eigen::Quaterniond &q) {
60 return RotationMatrixToEulerAngles(q.toRotationMatrix());
Milind Upadhyay7c205222022-11-16 18:20:58 -080061}
62
Milind Upadhyayc5beba12022-12-17 17:41:20 -080063Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles(
64 const Eigen::Matrix3d &R) {
65 double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2)));
66 double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0)));
67 double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0)));
68
69 return Eigen::Vector3d(roll, pitch, yaw);
70}
71
milind-u3f5f83c2023-01-29 15:23:51 -080072flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs(
73 const TargetMapper::TargetPose &target_pose,
74 flatbuffers::FlatBufferBuilder *fbb) {
75 const auto position_offset =
76 CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1),
77 target_pose.pose.p(2));
78 const auto orientation_offset =
79 CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(),
80 target_pose.pose.q.y(), target_pose.pose.q.z());
81 return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset,
82 orientation_offset);
83}
84
85TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs(
86 const TargetPoseFbs &target_pose_fbs) {
87 return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()),
88 .pose = ceres::examples::Pose3d{
89 Eigen::Vector3d(target_pose_fbs.position()->x(),
90 target_pose_fbs.position()->y(),
91 target_pose_fbs.position()->z()),
92 Eigen::Quaterniond(target_pose_fbs.orientation()->w(),
93 target_pose_fbs.orientation()->x(),
94 target_pose_fbs.orientation()->y(),
95 target_pose_fbs.orientation()->z())}};
96}
97
Milind Upadhyayc5beba12022-12-17 17:41:20 -080098ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections(
Milind Upadhyayec493912022-12-18 21:33:15 -080099 const std::vector<DataAdapter::TimestampedDetection>
100 &timestamped_target_detections,
101 aos::distributed_clock::duration max_dt) {
102 CHECK_GE(timestamped_target_detections.size(), 2ul)
103 << "Must have at least 2 detections";
104
105 // Match consecutive detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800106 ceres::examples::VectorOfConstraints target_constraints;
milind-ud62f80a2023-03-04 16:37:09 -0800107 for (auto detection = timestamped_target_detections.begin() + 1;
108 detection < timestamped_target_detections.end(); detection++) {
109 auto last_detection = detection - 1;
Milind Upadhyayec493912022-12-18 21:33:15 -0800110
111 // Skip two consecutive detections of the same target, because the solver
112 // doesn't allow this
milind-ud62f80a2023-03-04 16:37:09 -0800113 if (detection->id == last_detection->id) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800114 continue;
115 }
116
117 // Don't take into account constraints too far apart in time, because the
118 // recording device could have moved too much
milind-ud62f80a2023-03-04 16:37:09 -0800119 if ((detection->time - last_detection->time) > max_dt) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800120 continue;
121 }
122
milind-ud62f80a2023-03-04 16:37:09 -0800123 auto confidence = ComputeConfidence(*last_detection, *detection);
Milind Upadhyayec493912022-12-18 21:33:15 -0800124 target_constraints.emplace_back(
milind-ud62f80a2023-03-04 16:37:09 -0800125 ComputeTargetConstraint(*last_detection, *detection, confidence));
Milind Upadhyayec493912022-12-18 21:33:15 -0800126 }
127
128 return target_constraints;
129}
130
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800131TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence(
milind-ud62f80a2023-03-04 16:37:09 -0800132 const TimestampedDetection &detection_start,
133 const TimestampedDetection &detection_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
milind-ud62f80a2023-03-04 16:37:09 -0800156 int iterations = (detection_end.time - detection_start.time) /
157 frc971::controls::kLoopFrequency;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800158 P += static_cast<double>(iterations) * Q_odometry;
159 }
160
161 {
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800162 // Noise for vision-based target localizations. Multiplying this matrix by
163 // the distance from camera to target squared results in the uncertainty in
164 // that measurement
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800165 TargetMapper::ConfidenceMatrix Q_vision =
166 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800167 Q_vision(kX, kX) = std::pow(0.045, 2);
168 Q_vision(kY, kY) = std::pow(0.045, 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800169 Q_vision(kZ, kZ) = std::pow(0.045, 2);
170 Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2);
171 Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2);
172 Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800173
174 // Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
milind-ud62f80a2023-03-04 16:37:09 -0800175 P += Q_vision * std::pow(detection_start.distance_from_camera, 2) *
176 (1.0 +
177 FLAGS_distortion_noise_scalar * detection_start.distortion_factor);
178 P +=
179 Q_vision * std::pow(detection_end.distance_from_camera, 2) *
180 (1.0 + FLAGS_distortion_noise_scalar * detection_end.distortion_factor);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800181 }
182
183 return P.inverse();
184}
185
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800186ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint(
Milind Upadhyay7c205222022-11-16 18:20:58 -0800187 const TimestampedDetection &target_detection_start,
Milind Upadhyay7c205222022-11-16 18:20:58 -0800188 const TimestampedDetection &target_detection_end,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800189 const TargetMapper::ConfidenceMatrix &confidence) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800190 // Compute the relative pose (constraint) between the two targets
191 Eigen::Affine3d H_targetstart_targetend =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800192 target_detection_start.H_robot_target.inverse() *
Milind Upadhyay7c205222022-11-16 18:20:58 -0800193 target_detection_end.H_robot_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800194 ceres::examples::Pose3d target_constraint =
195 PoseUtils::Affine3dToPose3d(H_targetstart_targetend);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800196
milind-uf3ab8ba2023-02-04 17:56:16 -0800197 const auto constraint_3d =
198 ceres::examples::Constraint3d{target_detection_start.id,
199 target_detection_end.id,
200 {target_constraint.p, target_constraint.q},
201 confidence};
202
203 VLOG(2) << "Computed constraint: " << constraint_3d;
204 return constraint_3d;
Milind Upadhyayec493912022-12-18 21:33:15 -0800205}
206
Milind Upadhyay7c205222022-11-16 18:20:58 -0800207TargetMapper::TargetMapper(
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800208 std::string_view target_poses_path,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800209 const ceres::examples::VectorOfConstraints &target_constraints)
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800210 : target_constraints_(target_constraints) {
211 aos::FlatbufferDetachedBuffer<TargetMap> target_map =
212 aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path);
213 for (const auto *target_pose_fbs : *target_map.message().target_poses()) {
milind-u3f5f83c2023-01-29 15:23:51 -0800214 target_poses_[target_pose_fbs->id()] =
215 PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose;
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800216 }
217}
218
219TargetMapper::TargetMapper(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800220 const ceres::examples::MapOfPoses &target_poses,
221 const ceres::examples::VectorOfConstraints &target_constraints)
Milind Upadhyay7c205222022-11-16 18:20:58 -0800222 : target_poses_(target_poses), target_constraints_(target_constraints) {}
223
224std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
225 std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) {
226 for (auto target_pose : target_poses) {
227 if (target_pose.id == target_id) {
228 return target_pose;
229 }
230 }
231
232 return std::nullopt;
233}
234
Jim Ostrowski49be8232023-03-23 01:00:14 -0700235std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById(
236 TargetId target_id) {
237 if (target_poses_.count(target_id) > 0) {
238 return TargetMapper::TargetPose{target_id, target_poses_[target_id]};
239 }
240
241 return std::nullopt;
242}
243
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800244// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
245// Constructs the nonlinear least squares optimization problem from the pose
246// graph constraints.
Milind Upadhyay7c205222022-11-16 18:20:58 -0800247void TargetMapper::BuildOptimizationProblem(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800248 const ceres::examples::VectorOfConstraints &constraints,
249 ceres::examples::MapOfPoses *poses, ceres::Problem *problem) {
250 CHECK(poses != nullptr);
251 CHECK(problem != nullptr);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800252 if (constraints.empty()) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800253 LOG(INFO) << "No constraints, no problem to optimize.";
Milind Upadhyay7c205222022-11-16 18:20:58 -0800254 return;
255 }
256
milind-u13ff1a52023-01-22 17:10:49 -0800257 ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800258 ceres::LocalParameterization *quaternion_local_parameterization =
259 new ceres::EigenQuaternionParameterization;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800260
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800261 for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter =
262 constraints.begin();
Milind Upadhyay7c205222022-11-16 18:20:58 -0800263 constraints_iter != constraints.end(); ++constraints_iter) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800264 const ceres::examples::Constraint3d &constraint = *constraints_iter;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800265
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800266 ceres::examples::MapOfPoses::iterator pose_begin_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800267 poses->find(constraint.id_begin);
268 CHECK(pose_begin_iter != poses->end())
269 << "Pose with ID: " << constraint.id_begin << " not found.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800270 ceres::examples::MapOfPoses::iterator pose_end_iter =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800271 poses->find(constraint.id_end);
272 CHECK(pose_end_iter != poses->end())
273 << "Pose with ID: " << constraint.id_end << " not found.";
274
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800275 const Eigen::Matrix<double, 6, 6> sqrt_information =
Milind Upadhyay7c205222022-11-16 18:20:58 -0800276 constraint.information.llt().matrixL();
277 // Ceres will take ownership of the pointer.
278 ceres::CostFunction *cost_function =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800279 ceres::examples::PoseGraph3dErrorTerm::Create(constraint.t_be,
280 sqrt_information);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800281
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800282 problem->AddResidualBlock(cost_function, loss_function,
283 pose_begin_iter->second.p.data(),
284 pose_begin_iter->second.q.coeffs().data(),
285 pose_end_iter->second.p.data(),
286 pose_end_iter->second.q.coeffs().data());
287
288 problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(),
289 quaternion_local_parameterization);
290 problem->SetParameterization(pose_end_iter->second.q.coeffs().data(),
291 quaternion_local_parameterization);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800292 }
293
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800294 // The pose graph optimization problem has six DOFs that are not fully
milind-u3f5f83c2023-01-29 15:23:51 -0800295 // constrained. This is typically referred to as gauge freedom. You can
296 // apply a rigid body transformation to all the nodes and the optimization
297 // problem will still have the exact same cost. The Levenberg-Marquardt
298 // algorithm has internal damping which mitigates this issue, but it is
299 // better to properly constrain the gauge freedom. This can be done by
300 // setting one of the poses as constant so the optimizer cannot change it.
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800301 ceres::examples::MapOfPoses::iterator pose_start_iter = poses->begin();
Jim Ostrowski49be8232023-03-23 01:00:14 -0700302 // TODO<Jim>: This fixes first target, but breaks optimizer if we don't have
303 // an observation on the first target. We may want to allow other targets as
304 // fixed
Milind Upadhyay7c205222022-11-16 18:20:58 -0800305 CHECK(pose_start_iter != poses->end()) << "There are no poses.";
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800306 problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
307 problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
Milind Upadhyay7c205222022-11-16 18:20:58 -0800308}
309
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800310// Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc
Milind Upadhyay7c205222022-11-16 18:20:58 -0800311bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) {
312 CHECK_NOTNULL(problem);
313
314 ceres::Solver::Options options;
315 options.max_num_iterations = FLAGS_max_num_iterations;
316 options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700317 options.minimizer_progress_to_stdout = true;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800318
319 ceres::Solver::Summary summary;
320 ceres::Solve(options, problem, &summary);
321
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800322 LOG(INFO) << summary.FullReport() << '\n';
Milind Upadhyay7c205222022-11-16 18:20:58 -0800323
324 return summary.IsSolutionUsable();
325}
326
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800327void TargetMapper::Solve(std::string_view field_name,
328 std::optional<std::string_view> output_dir) {
Milind Upadhyay7c205222022-11-16 18:20:58 -0800329 ceres::Problem problem;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800330 BuildOptimizationProblem(target_constraints_, &target_poses_, &problem);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800331
332 CHECK(SolveOptimizationProblem(&problem))
333 << "The solve was not successful, exiting.";
334
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800335 auto map_json = MapToJson(field_name);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800336 VLOG(1) << "Solved target poses: " << map_json;
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800337
338 if (output_dir.has_value()) {
339 std::string output_path =
340 absl::StrCat(output_dir.value(), "/", field_name, ".json");
341 LOG(INFO) << "Writing map to file: " << output_path;
342 aos::util::WriteStringToFileOrDie(output_path, map_json);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800343 }
344}
345
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800346std::string TargetMapper::MapToJson(std::string_view field_name) const {
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800347 flatbuffers::FlatBufferBuilder fbb;
348
349 // Convert poses to flatbuffers
350 std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs;
351 for (const auto &[id, pose] : target_poses_) {
milind-u3f5f83c2023-01-29 15:23:51 -0800352 target_poses_fbs.emplace_back(
353 PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb));
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800354 }
355
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800356 const auto field_name_offset = fbb.CreateString(field_name);
357 flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap(
358 fbb, fbb.CreateVector(target_poses_fbs), field_name_offset);
Milind Upadhyaycd677a32022-12-04 13:06:43 -0800359
360 return aos::FlatbufferToJson(
361 flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset),
362 {.multi_line = true});
Milind Upadhyay7c205222022-11-16 18:20:58 -0800363}
364
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800365std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
366 auto rpy = PoseUtils::QuaternionToEulerAngles(pose.q);
367 os << absl::StrFormat(
368 "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
369 "%.3f, yaw: %.3f}",
370 pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
371 return os;
372}
373
374std::ostream &operator<<(std::ostream &os,
375 ceres::examples::Constraint3d constraint) {
376 os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
377 constraint.id_begin, constraint.id_end)
378 << constraint.t_be << "}";
379 return os;
380}
381
Milind Upadhyay7c205222022-11-16 18:20:58 -0800382} // namespace frc971::vision