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-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 13 | DEFINE_int32( |
milind-u | 6ff399f | 2023-03-24 18:33:38 -0700 | [diff] [blame] | 14 | frozen_target_id, 1, |
| 15 | "Freeze the pose of this target so the map can have one fixed point."); |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 16 | DEFINE_int32(min_target_id, 1, "Minimum target id to solve for"); |
| 17 | DEFINE_int32(max_target_id, 8, "Maximum target id to solve for"); |
| 18 | DEFINE_bool(visualize_solver, false, "If true, visualize the solving process."); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 19 | |
| 20 | namespace frc971::vision { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 21 | Eigen::Affine3d PoseUtils::Pose3dToAffine3d( |
| 22 | const ceres::examples::Pose3d &pose3d) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 23 | Eigen::Affine3d H_world_pose = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 24 | 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] | 25 | return H_world_pose; |
| 26 | } |
| 27 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 28 | ceres::examples::Pose3d PoseUtils::Affine3dToPose3d(const Eigen::Affine3d &H) { |
| 29 | return ceres::examples::Pose3d{.p = H.translation(), |
| 30 | .q = Eigen::Quaterniond(H.rotation())}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 31 | } |
| 32 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 33 | ceres::examples::Pose3d PoseUtils::ComputeRelativePose( |
| 34 | const ceres::examples::Pose3d &pose_1, |
| 35 | const ceres::examples::Pose3d &pose_2) { |
| 36 | Eigen::Affine3d H_world_1 = Pose3dToAffine3d(pose_1); |
| 37 | Eigen::Affine3d H_world_2 = Pose3dToAffine3d(pose_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 38 | |
| 39 | // Get the location of 2 in the 1 frame |
| 40 | Eigen::Affine3d H_1_2 = H_world_1.inverse() * H_world_2; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 41 | return Affine3dToPose3d(H_1_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 42 | } |
| 43 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 44 | ceres::examples::Pose3d PoseUtils::ComputeOffsetPose( |
| 45 | const ceres::examples::Pose3d &pose_1, |
| 46 | const ceres::examples::Pose3d &pose_2_relative) { |
| 47 | auto H_world_1 = Pose3dToAffine3d(pose_1); |
| 48 | auto H_1_2 = Pose3dToAffine3d(pose_2_relative); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 49 | auto H_world_2 = H_world_1 * H_1_2; |
| 50 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 51 | return Affine3dToPose3d(H_world_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 52 | } |
| 53 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 54 | Eigen::Quaterniond PoseUtils::EulerAnglesToQuaternion( |
| 55 | const Eigen::Vector3d &rpy) { |
| 56 | Eigen::AngleAxisd roll_angle(rpy.x(), Eigen::Vector3d::UnitX()); |
| 57 | Eigen::AngleAxisd pitch_angle(rpy.y(), Eigen::Vector3d::UnitY()); |
| 58 | Eigen::AngleAxisd yaw_angle(rpy.z(), Eigen::Vector3d::UnitZ()); |
| 59 | |
| 60 | return yaw_angle * pitch_angle * roll_angle; |
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::QuaternionToEulerAngles( |
| 64 | const Eigen::Quaterniond &q) { |
| 65 | return RotationMatrixToEulerAngles(q.toRotationMatrix()); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 66 | } |
| 67 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 68 | Eigen::Vector3d PoseUtils::RotationMatrixToEulerAngles( |
| 69 | const Eigen::Matrix3d &R) { |
| 70 | double roll = aos::math::NormalizeAngle(std::atan2(R(2, 1), R(2, 2))); |
| 71 | double pitch = aos::math::NormalizeAngle(-std::asin(R(2, 0))); |
| 72 | double yaw = aos::math::NormalizeAngle(std::atan2(R(1, 0), R(0, 0))); |
| 73 | |
| 74 | return Eigen::Vector3d(roll, pitch, yaw); |
| 75 | } |
| 76 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 77 | flatbuffers::Offset<TargetPoseFbs> PoseUtils::TargetPoseToFbs( |
| 78 | const TargetMapper::TargetPose &target_pose, |
| 79 | flatbuffers::FlatBufferBuilder *fbb) { |
| 80 | const auto position_offset = |
| 81 | CreatePosition(*fbb, target_pose.pose.p(0), target_pose.pose.p(1), |
| 82 | target_pose.pose.p(2)); |
| 83 | const auto orientation_offset = |
| 84 | CreateQuaternion(*fbb, target_pose.pose.q.w(), target_pose.pose.q.x(), |
| 85 | target_pose.pose.q.y(), target_pose.pose.q.z()); |
| 86 | return CreateTargetPoseFbs(*fbb, target_pose.id, position_offset, |
| 87 | orientation_offset); |
| 88 | } |
| 89 | |
| 90 | TargetMapper::TargetPose PoseUtils::TargetPoseFromFbs( |
| 91 | const TargetPoseFbs &target_pose_fbs) { |
| 92 | return {.id = static_cast<TargetMapper::TargetId>(target_pose_fbs.id()), |
| 93 | .pose = ceres::examples::Pose3d{ |
| 94 | Eigen::Vector3d(target_pose_fbs.position()->x(), |
| 95 | target_pose_fbs.position()->y(), |
| 96 | target_pose_fbs.position()->z()), |
| 97 | Eigen::Quaterniond(target_pose_fbs.orientation()->w(), |
| 98 | target_pose_fbs.orientation()->x(), |
| 99 | target_pose_fbs.orientation()->y(), |
| 100 | target_pose_fbs.orientation()->z())}}; |
| 101 | } |
| 102 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 103 | ceres::examples::VectorOfConstraints DataAdapter::MatchTargetDetections( |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 104 | const std::vector<DataAdapter::TimestampedDetection> |
| 105 | ×tamped_target_detections, |
| 106 | aos::distributed_clock::duration max_dt) { |
| 107 | CHECK_GE(timestamped_target_detections.size(), 2ul) |
| 108 | << "Must have at least 2 detections"; |
| 109 | |
| 110 | // Match consecutive detections |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 111 | ceres::examples::VectorOfConstraints target_constraints; |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 112 | for (auto detection = timestamped_target_detections.begin() + 1; |
| 113 | detection < timestamped_target_detections.end(); detection++) { |
| 114 | auto last_detection = detection - 1; |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 115 | |
| 116 | // Skip two consecutive detections of the same target, because the solver |
| 117 | // doesn't allow this |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 118 | if (detection->id == last_detection->id) { |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 119 | continue; |
| 120 | } |
| 121 | |
| 122 | // Don't take into account constraints too far apart in time, because the |
| 123 | // recording device could have moved too much |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 124 | if ((detection->time - last_detection->time) > max_dt) { |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 125 | continue; |
| 126 | } |
| 127 | |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 128 | auto confidence = ComputeConfidence(*last_detection, *detection); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 129 | target_constraints.emplace_back( |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 130 | ComputeTargetConstraint(*last_detection, *detection, confidence)); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 131 | } |
| 132 | |
| 133 | return target_constraints; |
| 134 | } |
| 135 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 136 | TargetMapper::ConfidenceMatrix DataAdapter::ComputeConfidence( |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 137 | const TimestampedDetection &detection_start, |
| 138 | const TimestampedDetection &detection_end) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 139 | constexpr size_t kX = 0; |
| 140 | constexpr size_t kY = 1; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 141 | constexpr size_t kZ = 2; |
| 142 | constexpr size_t kOrientation1 = 3; |
| 143 | constexpr size_t kOrientation2 = 4; |
| 144 | constexpr size_t kOrientation3 = 5; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 145 | |
| 146 | // Uncertainty matrix between start and end |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 147 | TargetMapper::ConfidenceMatrix P = TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 148 | |
| 149 | { |
| 150 | // Noise for odometry-based robot position measurements |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 151 | TargetMapper::ConfidenceMatrix Q_odometry = |
| 152 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 153 | Q_odometry(kX, kX) = std::pow(0.045, 2); |
| 154 | Q_odometry(kY, kY) = std::pow(0.045, 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 155 | Q_odometry(kZ, kZ) = std::pow(0.045, 2); |
| 156 | Q_odometry(kOrientation1, kOrientation1) = std::pow(0.01, 2); |
| 157 | Q_odometry(kOrientation2, kOrientation2) = std::pow(0.01, 2); |
| 158 | Q_odometry(kOrientation3, kOrientation3) = std::pow(0.01, 2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 159 | |
| 160 | // Add uncertainty for robot position measurements from start to end |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 161 | int iterations = (detection_end.time - detection_start.time) / |
| 162 | frc971::controls::kLoopFrequency; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 163 | P += static_cast<double>(iterations) * Q_odometry; |
| 164 | } |
| 165 | |
| 166 | { |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 167 | // Noise for vision-based target localizations. Multiplying this matrix by |
milind-u | 6ff399f | 2023-03-24 18:33:38 -0700 | [diff] [blame] | 168 | // the distance from camera to target squared results in the uncertainty |
| 169 | // in that measurement |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 170 | TargetMapper::ConfidenceMatrix Q_vision = |
| 171 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 172 | Q_vision(kX, kX) = std::pow(0.045, 2); |
| 173 | Q_vision(kY, kY) = std::pow(0.045, 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 174 | Q_vision(kZ, kZ) = std::pow(0.045, 2); |
| 175 | Q_vision(kOrientation1, kOrientation1) = std::pow(0.02, 2); |
| 176 | Q_vision(kOrientation2, kOrientation2) = std::pow(0.02, 2); |
| 177 | Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 178 | |
| 179 | // Add uncertainty for the 2 vision measurements (1 at start and 1 at end) |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 180 | P += Q_vision * std::pow(detection_start.distance_from_camera * |
| 181 | (1.0 + FLAGS_distortion_noise_scalar * |
| 182 | detection_start.distortion_factor), |
| 183 | 2); |
| 184 | P += Q_vision * std::pow(detection_end.distance_from_camera * |
| 185 | (1.0 + FLAGS_distortion_noise_scalar * |
| 186 | detection_end.distortion_factor), |
| 187 | 2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 188 | } |
| 189 | |
| 190 | return P.inverse(); |
| 191 | } |
| 192 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 193 | ceres::examples::Constraint3d DataAdapter::ComputeTargetConstraint( |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 194 | const TimestampedDetection &target_detection_start, |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 195 | const TimestampedDetection &target_detection_end, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 196 | const TargetMapper::ConfidenceMatrix &confidence) { |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 197 | // Compute the relative pose (constraint) between the two targets |
| 198 | Eigen::Affine3d H_targetstart_targetend = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 199 | target_detection_start.H_robot_target.inverse() * |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 200 | target_detection_end.H_robot_target; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 201 | ceres::examples::Pose3d target_constraint = |
| 202 | PoseUtils::Affine3dToPose3d(H_targetstart_targetend); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 203 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 204 | const auto constraint_3d = |
| 205 | ceres::examples::Constraint3d{target_detection_start.id, |
| 206 | target_detection_end.id, |
| 207 | {target_constraint.p, target_constraint.q}, |
| 208 | confidence}; |
| 209 | |
| 210 | VLOG(2) << "Computed constraint: " << constraint_3d; |
| 211 | return constraint_3d; |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 212 | } |
| 213 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 214 | TargetMapper::TargetMapper( |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 215 | std::string_view target_poses_path, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 216 | const ceres::examples::VectorOfConstraints &target_constraints) |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 217 | : target_constraints_(target_constraints), |
| 218 | T_frozen_actual_(Eigen::Vector3d::Zero()), |
| 219 | R_frozen_actual_(Eigen::Quaterniond::Identity()), |
| 220 | vis_robot_(cv::Size(1280, 1000)) { |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 221 | aos::FlatbufferDetachedBuffer<TargetMap> target_map = |
| 222 | aos::JsonFileToFlatbuffer<TargetMap>(target_poses_path); |
| 223 | for (const auto *target_pose_fbs : *target_map.message().target_poses()) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 224 | ideal_target_poses_[target_pose_fbs->id()] = |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 225 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs).pose; |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 226 | } |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 227 | target_poses_ = ideal_target_poses_; |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 228 | } |
| 229 | |
| 230 | TargetMapper::TargetMapper( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 231 | const ceres::examples::MapOfPoses &target_poses, |
| 232 | const ceres::examples::VectorOfConstraints &target_constraints) |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 233 | : ideal_target_poses_(target_poses), |
| 234 | target_poses_(ideal_target_poses_), |
| 235 | target_constraints_(target_constraints), |
| 236 | T_frozen_actual_(Eigen::Vector3d::Zero()), |
| 237 | R_frozen_actual_(Eigen::Quaterniond::Identity()), |
| 238 | vis_robot_(cv::Size(1280, 1000)) {} |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 239 | |
| 240 | std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById( |
| 241 | std::vector<TargetMapper::TargetPose> target_poses, TargetId target_id) { |
| 242 | for (auto target_pose : target_poses) { |
| 243 | if (target_pose.id == target_id) { |
| 244 | return target_pose; |
| 245 | } |
| 246 | } |
| 247 | |
| 248 | return std::nullopt; |
| 249 | } |
| 250 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 251 | std::optional<TargetMapper::TargetPose> TargetMapper::GetTargetPoseById( |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 252 | TargetId target_id) const { |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 253 | if (target_poses_.count(target_id) > 0) { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 254 | return TargetMapper::TargetPose{target_id, target_poses_.at(target_id)}; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 255 | } |
| 256 | |
| 257 | return std::nullopt; |
| 258 | } |
| 259 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 260 | // Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc |
| 261 | // Constructs the nonlinear least squares optimization problem from the pose |
| 262 | // graph constraints. |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 263 | void TargetMapper::BuildTargetPoseOptimizationProblem( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 264 | const ceres::examples::VectorOfConstraints &constraints, |
| 265 | ceres::examples::MapOfPoses *poses, ceres::Problem *problem) { |
| 266 | CHECK(poses != nullptr); |
| 267 | CHECK(problem != nullptr); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 268 | if (constraints.empty()) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 269 | LOG(INFO) << "No constraints, no problem to optimize."; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 270 | return; |
| 271 | } |
| 272 | |
milind-u | 13ff1a5 | 2023-01-22 17:10:49 -0800 | [diff] [blame] | 273 | ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 274 | ceres::LocalParameterization *quaternion_local_parameterization = |
| 275 | new ceres::EigenQuaternionParameterization; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 276 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 277 | for (ceres::examples::VectorOfConstraints::const_iterator constraints_iter = |
| 278 | constraints.begin(); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 279 | constraints_iter != constraints.end(); ++constraints_iter) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 280 | const ceres::examples::Constraint3d &constraint = *constraints_iter; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 281 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 282 | ceres::examples::MapOfPoses::iterator pose_begin_iter = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 283 | poses->find(constraint.id_begin); |
| 284 | CHECK(pose_begin_iter != poses->end()) |
| 285 | << "Pose with ID: " << constraint.id_begin << " not found."; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 286 | ceres::examples::MapOfPoses::iterator pose_end_iter = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 287 | poses->find(constraint.id_end); |
| 288 | CHECK(pose_end_iter != poses->end()) |
| 289 | << "Pose with ID: " << constraint.id_end << " not found."; |
| 290 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 291 | const Eigen::Matrix<double, 6, 6> sqrt_information = |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 292 | constraint.information.llt().matrixL(); |
| 293 | // Ceres will take ownership of the pointer. |
| 294 | ceres::CostFunction *cost_function = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 295 | ceres::examples::PoseGraph3dErrorTerm::Create(constraint.t_be, |
| 296 | sqrt_information); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 297 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 298 | problem->AddResidualBlock(cost_function, loss_function, |
| 299 | pose_begin_iter->second.p.data(), |
| 300 | pose_begin_iter->second.q.coeffs().data(), |
| 301 | pose_end_iter->second.p.data(), |
| 302 | pose_end_iter->second.q.coeffs().data()); |
| 303 | |
| 304 | problem->SetParameterization(pose_begin_iter->second.q.coeffs().data(), |
| 305 | quaternion_local_parameterization); |
| 306 | problem->SetParameterization(pose_end_iter->second.q.coeffs().data(), |
| 307 | quaternion_local_parameterization); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 308 | } |
| 309 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 310 | // The pose graph optimization problem has six DOFs that are not fully |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 311 | // constrained. This is typically referred to as gauge freedom. You can |
| 312 | // apply a rigid body transformation to all the nodes and the optimization |
| 313 | // problem will still have the exact same cost. The Levenberg-Marquardt |
| 314 | // algorithm has internal damping which mitigates this issue, but it is |
| 315 | // better to properly constrain the gauge freedom. This can be done by |
| 316 | // setting one of the poses as constant so the optimizer cannot change it. |
milind-u | 6ff399f | 2023-03-24 18:33:38 -0700 | [diff] [blame] | 317 | CHECK_NE(poses->count(FLAGS_frozen_target_id), 0ul) |
| 318 | << "Got no poses for frozen target id " << FLAGS_frozen_target_id; |
| 319 | ceres::examples::MapOfPoses::iterator pose_start_iter = |
| 320 | poses->find(FLAGS_frozen_target_id); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 321 | CHECK(pose_start_iter != poses->end()) << "There are no poses."; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 322 | problem->SetParameterBlockConstant(pose_start_iter->second.p.data()); |
| 323 | problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data()); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 324 | } |
| 325 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 326 | void TargetMapper::BuildMapFittingOptimizationProblem(ceres::Problem *problem) { |
| 327 | // Setup robot visualization |
| 328 | vis_robot_.ClearImage(); |
| 329 | constexpr int kImageWidth = 1280; |
| 330 | constexpr double kFocalLength = 500.0; |
| 331 | vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength); |
| 332 | |
| 333 | const size_t num_targets = FLAGS_max_target_id - FLAGS_min_target_id; |
| 334 | // Translation and rotation error for each target |
| 335 | const size_t num_residuals = num_targets * 6; |
| 336 | // Set up the only cost function (also known as residual). This uses |
| 337 | // auto-differentiation to obtain the derivative (jacobian). |
| 338 | ceres::CostFunction *cost_function = |
| 339 | new ceres::AutoDiffCostFunction<TargetMapper, ceres::DYNAMIC, 3, 4>( |
| 340 | this, num_residuals, ceres::DO_NOT_TAKE_OWNERSHIP); |
| 341 | |
| 342 | ceres::LossFunction *loss_function = new ceres::HuberLoss(2.0); |
| 343 | ceres::LocalParameterization *quaternion_local_parameterization = |
| 344 | new ceres::EigenQuaternionParameterization; |
| 345 | |
| 346 | problem->AddResidualBlock(cost_function, loss_function, |
| 347 | T_frozen_actual_.vector().data(), |
| 348 | R_frozen_actual_.coeffs().data()); |
| 349 | problem->SetParameterization(R_frozen_actual_.coeffs().data(), |
| 350 | quaternion_local_parameterization); |
| 351 | } |
| 352 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 353 | // Taken from ceres/examples/slam/pose_graph_3d/pose_graph_3d.cc |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 354 | bool TargetMapper::SolveOptimizationProblem(ceres::Problem *problem) { |
| 355 | CHECK_NOTNULL(problem); |
| 356 | |
| 357 | ceres::Solver::Options options; |
| 358 | options.max_num_iterations = FLAGS_max_num_iterations; |
| 359 | options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 360 | options.minimizer_progress_to_stdout = true; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 361 | |
| 362 | ceres::Solver::Summary summary; |
| 363 | ceres::Solve(options, problem, &summary); |
| 364 | |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 365 | LOG(INFO) << summary.FullReport() << '\n'; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 366 | |
| 367 | return summary.IsSolutionUsable(); |
| 368 | } |
| 369 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 370 | void TargetMapper::Solve(std::string_view field_name, |
| 371 | std::optional<std::string_view> output_dir) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 372 | ceres::Problem target_pose_problem; |
| 373 | BuildTargetPoseOptimizationProblem(target_constraints_, &target_poses_, |
| 374 | &target_pose_problem); |
| 375 | CHECK(SolveOptimizationProblem(&target_pose_problem)) |
| 376 | << "The target pose solve was not successful, exiting."; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 377 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 378 | ceres::Problem map_fitting_problem; |
| 379 | BuildMapFittingOptimizationProblem(&map_fitting_problem); |
| 380 | CHECK(SolveOptimizationProblem(&map_fitting_problem)) |
| 381 | << "The map fitting solve was not successful, exiting."; |
| 382 | |
| 383 | Eigen::Affine3d H_frozen_actual = T_frozen_actual_ * R_frozen_actual_; |
| 384 | LOG(INFO) << "H_frozen_actual: " |
| 385 | << PoseUtils::Affine3dToPose3d(H_frozen_actual); |
| 386 | |
| 387 | auto H_world_frozen = |
| 388 | PoseUtils::Pose3dToAffine3d(target_poses_[FLAGS_frozen_target_id]); |
| 389 | auto H_world_frozenactual = H_world_frozen * H_frozen_actual; |
| 390 | |
| 391 | // Offset the solved poses to become the actual ones |
| 392 | for (auto &[id, pose] : target_poses_) { |
| 393 | // Don't offset targets we didn't solve for |
| 394 | if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) { |
| 395 | continue; |
| 396 | } |
| 397 | |
| 398 | // Take the delta between the frozen target and the solved target, and put |
| 399 | // that on top of the actual pose of the frozen target |
| 400 | auto H_world_solved = PoseUtils::Pose3dToAffine3d(pose); |
| 401 | auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved; |
| 402 | auto H_world_actual = H_world_frozenactual * H_frozen_solved; |
| 403 | pose = PoseUtils::Affine3dToPose3d(H_world_actual); |
| 404 | } |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 405 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 406 | auto map_json = MapToJson(field_name); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 407 | VLOG(1) << "Solved target poses: " << map_json; |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 408 | |
| 409 | if (output_dir.has_value()) { |
| 410 | std::string output_path = |
| 411 | absl::StrCat(output_dir.value(), "/", field_name, ".json"); |
| 412 | LOG(INFO) << "Writing map to file: " << output_path; |
| 413 | aos::util::WriteStringToFileOrDie(output_path, map_json); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 414 | } |
| 415 | } |
| 416 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 417 | std::string TargetMapper::MapToJson(std::string_view field_name) const { |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 418 | flatbuffers::FlatBufferBuilder fbb; |
| 419 | |
| 420 | // Convert poses to flatbuffers |
| 421 | std::vector<flatbuffers::Offset<TargetPoseFbs>> target_poses_fbs; |
| 422 | for (const auto &[id, pose] : target_poses_) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 423 | target_poses_fbs.emplace_back( |
| 424 | PoseUtils::TargetPoseToFbs(TargetPose{.id = id, .pose = pose}, &fbb)); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 425 | } |
| 426 | |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 427 | const auto field_name_offset = fbb.CreateString(field_name); |
| 428 | flatbuffers::Offset<TargetMap> target_map_offset = CreateTargetMap( |
| 429 | fbb, fbb.CreateVector(target_poses_fbs), field_name_offset); |
Milind Upadhyay | cd677a3 | 2022-12-04 13:06:43 -0800 | [diff] [blame] | 430 | |
| 431 | return aos::FlatbufferToJson( |
| 432 | flatbuffers::GetMutableTemporaryPointer(fbb, target_map_offset), |
| 433 | {.multi_line = true}); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 434 | } |
| 435 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 436 | namespace { |
| 437 | |
| 438 | // Hacks to extract a double from a scalar, which is either a ceres jet or a |
| 439 | // double. Only used for debugging and displaying. |
| 440 | template <typename S> |
| 441 | double ScalarToDouble(S s) { |
| 442 | const double *ptr = reinterpret_cast<double *>(&s); |
| 443 | return *ptr; |
| 444 | } |
| 445 | |
| 446 | template <typename S> |
| 447 | Eigen::Affine3d ScalarAffineToDouble(Eigen::Transform<S, 3, Eigen::Affine> H) { |
| 448 | Eigen::Affine3d H_double; |
| 449 | for (size_t i = 0; i < H.rows(); i++) { |
| 450 | for (size_t j = 0; j < H.cols(); j++) { |
| 451 | H_double(i, j) = ScalarToDouble(H(i, j)); |
| 452 | } |
| 453 | } |
| 454 | return H_double; |
| 455 | } |
| 456 | |
| 457 | } // namespace |
| 458 | |
| 459 | template <typename S> |
| 460 | bool TargetMapper::operator()(const S *const translation, |
| 461 | const S *const rotation, S *residual) const { |
| 462 | using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>; |
| 463 | Eigen::Quaternion<S> R_frozen_actual(rotation[3], rotation[1], rotation[2], |
| 464 | rotation[0]); |
| 465 | Eigen::Translation<S, 3> T_frozen_actual(translation[0], translation[1], |
| 466 | translation[2]); |
| 467 | // Actual target pose in the frame of the fixed pose. |
| 468 | Affine3s H_frozen_actual = T_frozen_actual * R_frozen_actual; |
| 469 | VLOG(2) << "H_frozen_actual: " |
| 470 | << PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual)); |
| 471 | |
| 472 | Affine3s H_world_frozen = |
| 473 | PoseUtils::Pose3dToAffine3d(target_poses_.at(FLAGS_frozen_target_id)) |
| 474 | .cast<S>(); |
| 475 | Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual; |
| 476 | |
| 477 | size_t residual_index = 0; |
| 478 | if (FLAGS_visualize_solver) { |
| 479 | vis_robot_.ClearImage(); |
| 480 | } |
| 481 | |
| 482 | for (const auto &[id, solved_pose] : target_poses_) { |
| 483 | if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) { |
| 484 | continue; |
| 485 | } |
| 486 | |
| 487 | Affine3s H_world_ideal = |
| 488 | PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id)).cast<S>(); |
| 489 | Affine3s H_world_solved = |
| 490 | PoseUtils::Pose3dToAffine3d(solved_pose).cast<S>(); |
| 491 | // Take the delta between the frozen target and the solved target, and put |
| 492 | // that on top of the actual pose of the frozen target |
| 493 | auto H_frozen_solved = H_world_frozen.inverse() * H_world_solved; |
| 494 | auto H_world_actual = H_world_frozenactual * H_frozen_solved; |
| 495 | VLOG(2) << id << ": " << H_world_actual.translation(); |
| 496 | Affine3s H_ideal_actual = H_world_ideal.inverse() * H_world_actual; |
| 497 | auto T_ideal_actual = H_ideal_actual.translation(); |
| 498 | VLOG(2) << "T_ideal_actual: " << T_ideal_actual; |
| 499 | VLOG(2); |
| 500 | auto R_ideal_actual = Eigen::AngleAxis<S>(H_ideal_actual.rotation()); |
| 501 | |
| 502 | constexpr double kTranslationScalar = 100.0; |
| 503 | constexpr double kRotationScalar = 1000.0; |
| 504 | |
| 505 | // Penalize based on how much our actual poses matches the ideal |
| 506 | // ones. We've already solved for the relative poses, now figure out |
| 507 | // where all of them fit in the world. |
| 508 | residual[residual_index++] = kTranslationScalar * T_ideal_actual(0); |
| 509 | residual[residual_index++] = kTranslationScalar * T_ideal_actual(1); |
| 510 | residual[residual_index++] = kTranslationScalar * T_ideal_actual(2); |
| 511 | residual[residual_index++] = |
| 512 | kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().x(); |
| 513 | residual[residual_index++] = |
| 514 | kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().y(); |
| 515 | residual[residual_index++] = |
| 516 | kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z(); |
| 517 | |
| 518 | if (FLAGS_visualize_solver) { |
| 519 | vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual), |
| 520 | std::to_string(id), cv::Scalar(0, 255, 0)); |
| 521 | vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_ideal), |
| 522 | std::to_string(id), cv::Scalar(255, 255, 255)); |
| 523 | } |
| 524 | } |
| 525 | if (FLAGS_visualize_solver) { |
| 526 | cv::imshow("Target maps", vis_robot_.image_); |
| 527 | cv::waitKey(0); |
| 528 | } |
| 529 | |
| 530 | // Ceres can't handle residual values of exactly zero |
| 531 | for (size_t i = 0; i < residual_index; i++) { |
| 532 | if (residual[i] == S(0)) { |
| 533 | residual[i] = S(1e-9); |
| 534 | } |
| 535 | } |
| 536 | |
| 537 | return true; |
| 538 | } |
| 539 | |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 540 | } // namespace frc971::vision |
| 541 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 542 | std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) { |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 543 | auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 544 | os << absl::StrFormat( |
| 545 | "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: " |
| 546 | "%.3f, yaw: %.3f}", |
| 547 | pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2)); |
| 548 | return os; |
| 549 | } |
| 550 | |
| 551 | std::ostream &operator<<(std::ostream &os, |
| 552 | ceres::examples::Constraint3d constraint) { |
| 553 | os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ", |
| 554 | constraint.id_begin, constraint.id_end) |
| 555 | << constraint.t_be << "}"; |
| 556 | return os; |
| 557 | } |