Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 1 | #include "frc971/vision/target_mapper.h" |
| 2 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 3 | #include "absl/strings/str_format.h" |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 4 | #include "frc971/control_loops/control_loop.h" |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 5 | #include "frc971/vision/ceres/pose_graph_3d_error_term.h" |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 6 | #include "frc971/vision/geometry.h" |
| 7 | |
| 8 | DEFINE_uint64(max_num_iterations, 100, |
| 9 | "Maximum number of iterations for the ceres solver"); |
| 10 | |
| 11 | namespace frc971::vision { |
| 12 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 13 | Eigen::Affine3d PoseUtils::Pose3dToAffine3d( |
| 14 | const ceres::examples::Pose3d &pose3d) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 15 | Eigen::Affine3d H_world_pose = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 16 | Eigen::Translation3d(pose3d.p(0), pose3d.p(1), pose3d.p(2)) * pose3d.q; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 17 | return H_world_pose; |
| 18 | } |
| 19 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 20 | ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) { |
| 21 | return ceres::examples::Pose3d{.p = H.translation(), |
| 22 | .q = Eigen::Quaterniond(H.rotation())}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 23 | } |
| 24 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 25 | ceres::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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 30 | |
| 31 | // Get the location of 2 in the 1 frame |
| 32 | Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 33 | return Affine3dToPose3d(H_1_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 34 | } |
| 35 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 36 | ceres::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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 41 | auto H_world_2 = H_world_1 * H_1_2; |
| 42 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 43 | return Affine3dToPose3d(H_world_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 44 | } |
| 45 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 46 | Eigen::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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 53 | } |
| 54 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 55 | Eigen::Vector3d PoseUtils::QuaternionToEulerAngles( |
| 56 | const Eigen::Quaterniond &q) { |
| 57 | return RotationMatrixToEulerAngles(q.toRotationMatrix()); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 58 | } |
| 59 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 60 | Eigen::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-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 69 | flatbuffers::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 | |
| 82 | TargetMapper::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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 95 | ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections( |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 96 | const std::vector<DataAdapter::TimestampedDetection> |
| 97 | ×tamped_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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 103 | ceres::examples::VectorOfConstraints target_constraints; |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 104 | 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 Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 120 | auto confidence = ComputeConfidence(last_detection.time, it->time, |
| 121 | last_detection.distance_from_camera, |
| 122 | it->distance_from_camera); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 123 | target_constraints.emplace_back( |
| 124 | ComputeTargetConstraint(last_detection, *it, confidence)); |
| 125 | } |
| 126 | |
| 127 | return target_constraints; |
| 128 | } |
| 129 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 130 | TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence( |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 131 | aos::distributed_clock::time_point start, |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 132 | aos::distributed_clock::time_point end, double distance_from_camera_start, |
| 133 | double distance_from_camera_end) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 134 | constexpr size_t kX = 0; |
| 135 | constexpr size_t kY = 1; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 136 | constexpr size_t kZ = 2; |
| 137 | constexpr size_t kOrientation1 = 3; |
| 138 | constexpr size_t kOrientation2 = 4; |
| 139 | constexpr size_t kOrientation3 = 5; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 140 | |
| 141 | // Uncertainty matrix between start and end |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 142 | TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 143 | |
| 144 | { |
| 145 | // Noise for odometry-based robot position measurements |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 146 | TargetMapper::ConfidenceMatrix Q_odometry = |
| 147 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 148 | Q_odometry(kX, kX) = std::pow(0.045, 2); |
| 149 | Q_odometry(kY, kY) = std::pow(0.045, 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 150 | 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 154 | |
| 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 Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 161 | // 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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 164 | TargetMapper::ConfidenceMatrix Q_vision = |
| 165 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 166 | Q_vision(kX, kX) = std::pow(0.045, 2); |
| 167 | Q_vision(kY, kY) = std::pow(0.045, 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 168 | 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 172 | |
| 173 | // Add uncertainty for the 2 vision measurements (1 at start and 1 at end) |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 174 | P += Q_vision * std::pow(distance_from_camera_start, 2); |
| 175 | P += Q_vision * std::pow(distance_from_camera_end, 2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 176 | } |
| 177 | |
| 178 | return P.inverse(); |
| 179 | } |
| 180 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 181 | ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint( |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 182 | const TimestampedDetection &target_detection_start, |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 183 | const TimestampedDetection &target_detection_end, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 184 | const TargetMapper::ConfidenceMatrix &confidence) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 185 | // Compute the relative pose (constraint) between the two targets |
| 186 | Eigen::Affine3d H_targetstart_targetend = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 187 | target_detection_start.H_robot_target.inverse() * |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 188 | target_detection_end.H_robot_target; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 189 | ceres::examples::Pose3d target_constraint = |
| 190 | PoseUtils::Affine3dToPose3d(H_targetstart_targetend); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 191 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame^] | 192 | const auto constraint_3d = |
| 193 | ceres::examples::Constraint3d{target_detection_start.id, |
| 194 | target_detection_end.id, |
| 195 | {target_constraint.p, target_constraint.q}, |
| 196 | confidence}; |
| 197 | |
| 198 | VLOG(2) << "Computed constraint: " << constraint_3d; |
| 199 | return constraint_3d; |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 200 | } |
| 201 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 202 | TargetMapper::TargetMapper( |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 203 | std::string_view target_poses_path, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 204 | const ceres::examples::VectorOfConstraints &target_constraints) |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 205 | : target_constraints_(target_constraints) { |
| 206 | aos::FlatbufferDetachedBuffer<TargetMap> target_map = |
| 207 | aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path); |
| 208 | for (const auto *target_pose_fbs : *target_map.message().target_poses()) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 209 | target_poses_[target_pose_fbs->id()] = |
| 210 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose; |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 211 | } |
| 212 | } |
| 213 | |
| 214 | TargetMapper::TargetMapper( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 215 | const ceres::examples::MapOfPoses &target_poses, |
| 216 | const ceres::examples::VectorOfConstraints &target_constraints) |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 217 | : target_poses_(target_poses), target_constraints_(target_constraints) {} |
| 218 | |
| 219 | std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById( |
| 220 | std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) { |
| 221 | for (auto target_pose : target_poses) { |
| 222 | if (target_pose.id == target_id) { |
| 223 | return target_pose; |
| 224 | } |
| 225 | } |
| 226 | |
| 227 | return std::nullopt; |
| 228 | } |
| 229 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 230 | // Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc |
| 231 | // Constructs the nonlinear least squares optimization problem from the pose |
| 232 | // graph constraints. |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 233 | void TargetMapper::BuildOptimizationProblem( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 234 | const ceres::examples::VectorOfConstraints &constraints, |
| 235 | ceres::examples::MapOfPoses *poses, ceres::Problem *problem) { |
| 236 | CHECK(poses != nullptr); |
| 237 | CHECK(problem != nullptr); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 238 | if (constraints.empty()) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 239 | LOG(INFO) << "No constraints, no problem to optimize."; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 240 | return; |
| 241 | } |
| 242 | |
milind-u | 13ff1a5 | 2023-01-22 17:10:49 -0800 | [diff] [blame] | 243 | ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 244 | ceres::LocalParameterization *quaternion_local_parameterization = |
| 245 | new ceres::EigenQuaternionParameterization; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 246 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 247 | for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter = |
| 248 | constraints.begin(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 249 | constraints_iter != constraints.end(); ++constraints_iter) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 250 | const ceres::examples::Constraint3d &constraint = *constraints_iter; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 251 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 252 | ceres::examples::MapOfPoses::iterator pose_begin_iter = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 253 | poses->find(constraint.id_begin); |
| 254 | CHECK(pose_begin_iter != poses->end()) |
| 255 | << "Pose with ID: " << constraint.id_begin << " not found."; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 256 | ceres::examples::MapOfPoses::iterator pose_end_iter = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 257 | poses->find(constraint.id_end); |
| 258 | CHECK(pose_end_iter != poses->end()) |
| 259 | << "Pose with ID: " << constraint.id_end << " not found."; |
| 260 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 261 | const Eigen::Matrix<double, 6, 6> sqrt_information = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 262 | constraint.information.llt().matrixL(); |
| 263 | // Ceres will take ownership of the pointer. |
| 264 | ceres::CostFunction *cost_function = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 265 | ceres::examples::PoseGraph3dErrorTerm::Create(constraint.t_be, |
| 266 | sqrt_information); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 267 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 268 | problem->AddResidualBlock(cost_function, loss_function, |
| 269 | pose_begin_iter->second.p.data(), |
| 270 | pose_begin_iter->second.q.coeffs().data(), |
| 271 | pose_end_iter->second.p.data(), |
| 272 | pose_end_iter->second.q.coeffs().data()); |
| 273 | |
| 274 | problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(), |
| 275 | quaternion_local_parameterization); |
| 276 | problem->SetParameterization(pose_end_iter->second.q.coeffs().data(), |
| 277 | quaternion_local_parameterization); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 278 | } |
| 279 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 280 | // The pose graph optimization problem has six DOFs that are not fully |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 281 | // constrained. This is typically referred to as gauge freedom. You can |
| 282 | // apply a rigid body transformation to all the nodes and the optimization |
| 283 | // problem will still have the exact same cost. The Levenberg-Marquardt |
| 284 | // algorithm has internal damping which mitigates this issue, but it is |
| 285 | // better to properly constrain the gauge freedom. This can be done by |
| 286 | // setting one of the poses as constant so the optimizer cannot change it. |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 287 | ceres::examples::MapOfPoses::iterator pose_start_iter = poses->begin(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 288 | CHECK(pose_start_iter != poses->end()) << "There are no poses."; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 289 | problem->SetParameterBlockConstant(pose_start_iter->second.p.data()); |
| 290 | problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data()); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 291 | } |
| 292 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 293 | // Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 294 | bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) { |
| 295 | CHECK_NOTNULL(problem); |
| 296 | |
| 297 | ceres::Solver::Options options; |
| 298 | options.max_num_iterations = FLAGS_max_num_iterations; |
| 299 | options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; |
| 300 | |
| 301 | ceres::Solver::Summary summary; |
| 302 | ceres::Solve(options, problem, &summary); |
| 303 | |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 304 | LOG(INFO) << summary.FullReport() << '\n'; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 305 | |
| 306 | return summary.IsSolutionUsable(); |
| 307 | } |
| 308 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 309 | void TargetMapper::Solve(std::string_view field_name, |
| 310 | std::optional<std::string_view> output_dir) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 311 | ceres::Problem problem; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 312 | BuildOptimizationProblem(target_constraints_, &target_poses_, &problem); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 313 | |
| 314 | CHECK(SolveOptimizationProblem(&problem)) |
| 315 | << "The solve was not successful, exiting."; |
| 316 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 317 | auto map_json = MapToJson(field_name); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 318 | VLOG(1) << "Solved target poses: " << map_json; |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 319 | |
| 320 | if (output_dir.has_value()) { |
| 321 | std::string output_path = |
| 322 | absl::StrCat(output_dir.value(), "/", field_name, ".json"); |
| 323 | LOG(INFO) << "Writing map to file: " << output_path; |
| 324 | aos::util::WriteStringToFileOrDie(output_path, map_json); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 325 | } |
| 326 | } |
| 327 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 328 | std::string TargetMapper::MapToJson(std::string_view field_name) const { |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 329 | flatbuffers::FlatBufferBuilder fbb; |
| 330 | |
| 331 | // Convert poses to flatbuffers |
| 332 | std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs; |
| 333 | for (const auto &[id, pose] : target_poses_) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 334 | target_poses_fbs.emplace_back( |
| 335 | PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb)); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 336 | } |
| 337 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 338 | const auto field_name_offset = fbb.CreateString(field_name); |
| 339 | flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap( |
| 340 | fbb, fbb.CreateVector(target_poses_fbs), field_name_offset); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 341 | |
| 342 | return aos::FlatbufferToJson( |
| 343 | flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset), |
| 344 | {.multi_line = true}); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 345 | } |
| 346 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 347 | std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) { |
| 348 | auto rpy = PoseUtils::QuaternionToEulerAngles(pose.q); |
| 349 | os << absl::StrFormat( |
| 350 | "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: " |
| 351 | "%.3f, yaw: %.3f}", |
| 352 | pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2)); |
| 353 | return os; |
| 354 | } |
| 355 | |
| 356 | std::ostream &operator<<(std::ostream &os, |
| 357 | ceres::examples::Constraint3d constraint) { |
| 358 | os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ", |
| 359 | constraint.id_begin, constraint.id_end) |
| 360 | << constraint.t_be << "}"; |
| 361 | return os; |
| 362 | } |
| 363 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 364 | } // namespace frc971::vision |