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"); |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 10 | DEFINE_double(distortion_noise_scalar, 1.0, |
| 11 | "Scale the target pose distortion factor by this when computing " |
| 12 | "the noise."); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 13 | |
| 14 | namespace frc971::vision { |
| 15 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 16 | Eigen::Affine3d PoseUtils::Pose3dToAffine3d( |
| 17 | const ceres::examples::Pose3d &pose3d) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 18 | Eigen::Affine3d H_world_pose = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 19 | 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] | 20 | return H_world_pose; |
| 21 | } |
| 22 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 23 | ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) { |
| 24 | return ceres::examples::Pose3d{.p = H.translation(), |
| 25 | .q = Eigen::Quaterniond(H.rotation())}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 26 | } |
| 27 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 28 | ceres::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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 33 | |
| 34 | // Get the location of 2 in the 1 frame |
| 35 | Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 36 | return Affine3dToPose3d(H_1_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 37 | } |
| 38 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 39 | ceres::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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 44 | auto H_world_2 = H_world_1 * H_1_2; |
| 45 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 46 | return Affine3dToPose3d(H_world_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 47 | } |
| 48 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 49 | Eigen::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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 56 | } |
| 57 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 58 | Eigen::Vector3d PoseUtils::QuaternionToEulerAngles( |
| 59 | const Eigen::Quaterniond &q) { |
| 60 | return RotationMatrixToEulerAngles(q.toRotationMatrix()); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 61 | } |
| 62 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 63 | Eigen::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-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 72 | flatbuffers::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 | |
| 85 | TargetMapper::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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 98 | ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections( |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 99 | const std::vector<DataAdapter::TimestampedDetection> |
| 100 | ×tamped_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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 106 | ceres::examples::VectorOfConstraints target_constraints; |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 107 | for (auto detection = timestamped_target_detections.begin() + 1; |
| 108 | detection < timestamped_target_detections.end(); detection++) { |
| 109 | auto last_detection = detection - 1; |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 110 | |
| 111 | // Skip two consecutive detections of the same target, because the solver |
| 112 | // doesn't allow this |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 113 | if (detection->id == last_detection->id) { |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 114 | 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-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 119 | if ((detection->time - last_detection->time) > max_dt) { |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 120 | continue; |
| 121 | } |
| 122 | |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 123 | auto confidence = ComputeConfidence(*last_detection, *detection); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 124 | target_constraints.emplace_back( |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 125 | ComputeTargetConstraint(*last_detection, *detection, confidence)); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 126 | } |
| 127 | |
| 128 | return target_constraints; |
| 129 | } |
| 130 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 131 | TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence( |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 132 | const TimestampedDetection &detection_start, |
| 133 | const TimestampedDetection &detection_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 |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 156 | int iterations = (detection_end.time - detection_start.time) / |
| 157 | frc971::controls::kLoopFrequency; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 158 | P += static_cast<double>(iterations) * Q_odometry; |
| 159 | } |
| 160 | |
| 161 | { |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 162 | // 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 Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 165 | TargetMapper::ConfidenceMatrix Q_vision = |
| 166 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 167 | Q_vision(kX, kX) = std::pow(0.045, 2); |
| 168 | Q_vision(kY, kY) = std::pow(0.045, 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 169 | 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 173 | |
| 174 | // Add uncertainty for the 2 vision measurements (1 at start and 1 at end) |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame^] | 175 | 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 Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 181 | } |
| 182 | |
| 183 | return P.inverse(); |
| 184 | } |
| 185 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 186 | ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint( |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 187 | const TimestampedDetection &target_detection_start, |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 188 | const TimestampedDetection &target_detection_end, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 189 | const TargetMapper::ConfidenceMatrix &confidence) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 190 | // Compute the relative pose (constraint) between the two targets |
| 191 | Eigen::Affine3d H_targetstart_targetend = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 192 | target_detection_start.H_robot_target.inverse() * |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 193 | target_detection_end.H_robot_target; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 194 | ceres::examples::Pose3d target_constraint = |
| 195 | PoseUtils::Affine3dToPose3d(H_targetstart_targetend); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 196 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 197 | 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 Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 205 | } |
| 206 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 207 | TargetMapper::TargetMapper( |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 208 | std::string_view target_poses_path, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 209 | const ceres::examples::VectorOfConstraints &target_constraints) |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 210 | : 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-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 214 | target_poses_[target_pose_fbs->id()] = |
| 215 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose; |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 216 | } |
| 217 | } |
| 218 | |
| 219 | TargetMapper::TargetMapper( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 220 | const ceres::examples::MapOfPoses &target_poses, |
| 221 | const ceres::examples::VectorOfConstraints &target_constraints) |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 222 | : target_poses_(target_poses), target_constraints_(target_constraints) {} |
| 223 | |
| 224 | std::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 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 235 | // Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc |
| 236 | // Constructs the nonlinear least squares optimization problem from the pose |
| 237 | // graph constraints. |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 238 | void TargetMapper::BuildOptimizationProblem( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 239 | const ceres::examples::VectorOfConstraints &constraints, |
| 240 | ceres::examples::MapOfPoses *poses, ceres::Problem *problem) { |
| 241 | CHECK(poses != nullptr); |
| 242 | CHECK(problem != nullptr); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 243 | if (constraints.empty()) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 244 | LOG(INFO) << "No constraints, no problem to optimize."; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 245 | return; |
| 246 | } |
| 247 | |
milind-u | 13ff1a5 | 2023-01-22 17:10:49 -0800 | [diff] [blame] | 248 | ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 249 | ceres::LocalParameterization *quaternion_local_parameterization = |
| 250 | new ceres::EigenQuaternionParameterization; |
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 | for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter = |
| 253 | constraints.begin(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 254 | constraints_iter != constraints.end(); ++constraints_iter) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 255 | const ceres::examples::Constraint3d &constraint = *constraints_iter; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 256 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 257 | ceres::examples::MapOfPoses::iterator pose_begin_iter = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 258 | poses->find(constraint.id_begin); |
| 259 | CHECK(pose_begin_iter != poses->end()) |
| 260 | << "Pose with ID: " << constraint.id_begin << " not found."; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 261 | ceres::examples::MapOfPoses::iterator pose_end_iter = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 262 | poses->find(constraint.id_end); |
| 263 | CHECK(pose_end_iter != poses->end()) |
| 264 | << "Pose with ID: " << constraint.id_end << " not found."; |
| 265 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 266 | const Eigen::Matrix<double, 6, 6> sqrt_information = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 267 | constraint.information.llt().matrixL(); |
| 268 | // Ceres will take ownership of the pointer. |
| 269 | ceres::CostFunction *cost_function = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 270 | ceres::examples::PoseGraph3dErrorTerm::Create(constraint.t_be, |
| 271 | sqrt_information); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 272 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 273 | problem->AddResidualBlock(cost_function, loss_function, |
| 274 | pose_begin_iter->second.p.data(), |
| 275 | pose_begin_iter->second.q.coeffs().data(), |
| 276 | pose_end_iter->second.p.data(), |
| 277 | pose_end_iter->second.q.coeffs().data()); |
| 278 | |
| 279 | problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(), |
| 280 | quaternion_local_parameterization); |
| 281 | problem->SetParameterization(pose_end_iter->second.q.coeffs().data(), |
| 282 | quaternion_local_parameterization); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 283 | } |
| 284 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 285 | // The pose graph optimization problem has six DOFs that are not fully |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 286 | // constrained. This is typically referred to as gauge freedom. You can |
| 287 | // apply a rigid body transformation to all the nodes and the optimization |
| 288 | // problem will still have the exact same cost. The Levenberg-Marquardt |
| 289 | // algorithm has internal damping which mitigates this issue, but it is |
| 290 | // better to properly constrain the gauge freedom. This can be done by |
| 291 | // 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] | 292 | ceres::examples::MapOfPoses::iterator pose_start_iter = poses->begin(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 293 | CHECK(pose_start_iter != poses->end()) << "There are no poses."; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 294 | problem->SetParameterBlockConstant(pose_start_iter->second.p.data()); |
| 295 | problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data()); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 296 | } |
| 297 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 298 | // Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 299 | bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) { |
| 300 | CHECK_NOTNULL(problem); |
| 301 | |
| 302 | ceres::Solver::Options options; |
| 303 | options.max_num_iterations = FLAGS_max_num_iterations; |
| 304 | options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; |
| 305 | |
| 306 | ceres::Solver::Summary summary; |
| 307 | ceres::Solve(options, problem, &summary); |
| 308 | |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 309 | LOG(INFO) << summary.FullReport() << '\n'; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 310 | |
| 311 | return summary.IsSolutionUsable(); |
| 312 | } |
| 313 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 314 | void TargetMapper::Solve(std::string_view field_name, |
| 315 | std::optional<std::string_view> output_dir) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 316 | ceres::Problem problem; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 317 | BuildOptimizationProblem(target_constraints_, &target_poses_, &problem); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 318 | |
| 319 | CHECK(SolveOptimizationProblem(&problem)) |
| 320 | << "The solve was not successful, exiting."; |
| 321 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 322 | auto map_json = MapToJson(field_name); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 323 | VLOG(1) << "Solved target poses: " << map_json; |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 324 | |
| 325 | if (output_dir.has_value()) { |
| 326 | std::string output_path = |
| 327 | absl::StrCat(output_dir.value(), "/", field_name, ".json"); |
| 328 | LOG(INFO) << "Writing map to file: " << output_path; |
| 329 | aos::util::WriteStringToFileOrDie(output_path, map_json); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 330 | } |
| 331 | } |
| 332 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 333 | std::string TargetMapper::MapToJson(std::string_view field_name) const { |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 334 | flatbuffers::FlatBufferBuilder fbb; |
| 335 | |
| 336 | // Convert poses to flatbuffers |
| 337 | std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs; |
| 338 | for (const auto &[id, pose] : target_poses_) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 339 | target_poses_fbs.emplace_back( |
| 340 | PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb)); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 341 | } |
| 342 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 343 | const auto field_name_offset = fbb.CreateString(field_name); |
| 344 | flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap( |
| 345 | fbb, fbb.CreateVector(target_poses_fbs), field_name_offset); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 346 | |
| 347 | return aos::FlatbufferToJson( |
| 348 | flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset), |
| 349 | {.multi_line = true}); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 350 | } |
| 351 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 352 | std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) { |
| 353 | auto rpy = PoseUtils::QuaternionToEulerAngles(pose.q); |
| 354 | os << absl::StrFormat( |
| 355 | "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: " |
| 356 | "%.3f, yaw: %.3f}", |
| 357 | pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2)); |
| 358 | return os; |
| 359 | } |
| 360 | |
| 361 | std::ostream &operator<<(std::ostream &os, |
| 362 | ceres::examples::Constraint3d constraint) { |
| 363 | os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ", |
| 364 | constraint.id_begin, constraint.id_end) |
| 365 | << constraint.t_be << "}"; |
| 366 | return os; |
| 367 | } |
| 368 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 369 | } // namespace frc971::vision |