Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 1 | #include "frc971/vision/target_mapper.h" |
| 2 | |
| 3 | #include <random> |
| 4 | |
| 5 | #include "aos/events/simulated_event_loop.h" |
| 6 | #include "aos/testing/random_seed.h" |
| 7 | #include "glog/logging.h" |
| 8 | #include "gtest/gtest.h" |
| 9 | |
| 10 | namespace frc971::vision { |
| 11 | |
| 12 | namespace { |
| 13 | constexpr double kToleranceMeters = 0.05; |
| 14 | constexpr double kToleranceRadians = 0.05; |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame^] | 15 | constexpr std::string_view kFieldName = "test"; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 16 | } // namespace |
| 17 | |
| 18 | #define EXPECT_POSE_NEAR(pose1, pose2) \ |
| 19 | EXPECT_NEAR(pose1.x, pose2.x, kToleranceMeters); \ |
| 20 | EXPECT_NEAR(pose1.y, pose2.y, kToleranceMeters); \ |
| 21 | EXPECT_NEAR(pose1.yaw_radians, pose2.yaw_radians, kToleranceRadians); |
| 22 | |
| 23 | #define EXPECT_POSE_EQ(pose1, pose2) \ |
| 24 | EXPECT_DOUBLE_EQ(pose1.x, pose2.x); \ |
| 25 | EXPECT_DOUBLE_EQ(pose1.y, pose2.y); \ |
| 26 | EXPECT_DOUBLE_EQ(pose1.yaw_radians, pose2.yaw_radians); |
| 27 | |
| 28 | #define EXPECT_BETWEEN_EXCLUSIVE(value, a, b) \ |
| 29 | { \ |
| 30 | auto low = std::min(a, b); \ |
| 31 | auto high = std::max(a, b); \ |
| 32 | EXPECT_GT(value, low); \ |
| 33 | EXPECT_LT(value, high); \ |
| 34 | } |
| 35 | |
| 36 | namespace { |
| 37 | // Expects angles to be normalized |
| 38 | double DeltaAngle(double a, double b) { |
| 39 | double delta = std::abs(a - b); |
| 40 | return std::min(delta, (2.0 * M_PI) - delta); |
| 41 | } |
| 42 | } // namespace |
| 43 | |
| 44 | // Expects angles to be normalized |
| 45 | #define EXPECT_ANGLE_BETWEEN_EXCLUSIVE(theta, a, b) \ |
| 46 | EXPECT_LT(DeltaAngle(a, theta), DeltaAngle(a, b)); \ |
| 47 | EXPECT_LT(DeltaAngle(b, theta), DeltaAngle(a, b)); |
| 48 | |
| 49 | #define EXPECT_POSE_IN_RANGE(interpolated_pose, pose_start, pose_end) \ |
| 50 | EXPECT_BETWEEN_EXCLUSIVE(interpolated_pose.x, pose_start.x, pose_end.x); \ |
| 51 | EXPECT_BETWEEN_EXCLUSIVE(interpolated_pose.y, pose_start.y, pose_end.y); \ |
| 52 | EXPECT_ANGLE_BETWEEN_EXCLUSIVE(interpolated_pose.yaw_radians, \ |
| 53 | pose_start.yaw_radians, \ |
| 54 | pose_end.yaw_radians); |
| 55 | |
| 56 | // Both confidence matrixes should have the same dimensions and be square |
| 57 | #define EXPECT_CONFIDENCE_GT(confidence1, confidence2) \ |
| 58 | { \ |
| 59 | ASSERT_EQ(confidence1.rows(), confidence2.rows()); \ |
| 60 | ASSERT_EQ(confidence1.rows(), confidence1.cols()); \ |
| 61 | ASSERT_EQ(confidence2.rows(), confidence2.cols()); \ |
| 62 | for (size_t i = 0; i < confidence1.rows(); i++) { \ |
| 63 | EXPECT_GT(confidence1(i, i), confidence2(i, i)); \ |
| 64 | } \ |
| 65 | } |
| 66 | |
| 67 | namespace { |
| 68 | ceres::examples::Pose2d MakePose(double x, double y, double yaw_radians) { |
| 69 | return ceres::examples::Pose2d{x, y, yaw_radians}; |
| 70 | } |
| 71 | |
| 72 | bool TargetIsInView(TargetMapper::TargetPose target_detection) { |
| 73 | // And check if it is within the fov of the robot / |
| 74 | // camera, assuming camera is pointing in the |
| 75 | // positive x-direction of the robot |
| 76 | double angle_to_target = |
| 77 | atan2(target_detection.pose.y, target_detection.pose.x); |
| 78 | |
| 79 | // Simulated camera field of view, in radians |
| 80 | constexpr double kCameraFov = M_PI_2; |
| 81 | if (fabs(angle_to_target) <= kCameraFov / 2.0) { |
| 82 | VLOG(2) << "Found target in view, based on T = " << target_detection.pose.x |
| 83 | << ", " << target_detection.pose.y << " with angle " |
| 84 | << angle_to_target; |
| 85 | return true; |
| 86 | } else { |
| 87 | return false; |
| 88 | } |
| 89 | } |
| 90 | |
| 91 | aos::distributed_clock::time_point TimeInMs(size_t ms) { |
| 92 | return aos::distributed_clock::time_point(std::chrono::milliseconds(ms)); |
| 93 | } |
| 94 | |
| 95 | } // namespace |
| 96 | |
| 97 | TEST(DataAdapterTest, Interpolation) { |
| 98 | std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses = { |
| 99 | {TimeInMs(0), ceres::examples::Pose2d{1.0, 2.0, 0.0}}, |
| 100 | {TimeInMs(5), ceres::examples::Pose2d{1.0, 2.0, 0.0}}, |
| 101 | {TimeInMs(10), ceres::examples::Pose2d{3.0, 1.0, M_PI_2}}, |
| 102 | {TimeInMs(15), ceres::examples::Pose2d{5.0, -2.0, -M_PI}}, |
| 103 | {TimeInMs(20), ceres::examples::Pose2d{5.0, -2.0, -M_PI}}, |
| 104 | {TimeInMs(25), ceres::examples::Pose2d{10.0, -32.0, M_PI_2}}, |
| 105 | {TimeInMs(30), ceres::examples::Pose2d{-15.0, 12.0, 0.0}}, |
| 106 | {TimeInMs(35), ceres::examples::Pose2d{-15.0, 12.0, 0.0}}}; |
| 107 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
| 108 | {{TimeInMs(5), |
| 109 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{5.0, -4.0, 0.0}), |
| 110 | 0}, |
| 111 | {TimeInMs(9), |
| 112 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{5.0, -4.0, 0.0}), |
| 113 | 1}, |
| 114 | {TimeInMs(9), |
| 115 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{5.0, -4.0, 0.0}), |
| 116 | 2}, |
| 117 | {TimeInMs(15), |
| 118 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{5.0, -4.0, 0.0}), |
| 119 | 0}, |
| 120 | {TimeInMs(16), |
| 121 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{5.0, -4.0, 0.0}), |
| 122 | 2}, |
| 123 | {TimeInMs(27), |
| 124 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{5.0, -4.0, 0.0}), |
| 125 | 1}}; |
| 126 | auto [target_constraints, robot_delta_poses] = |
| 127 | DataAdapter::MatchTargetDetections(timestamped_robot_poses, |
| 128 | timestamped_target_detections); |
| 129 | |
| 130 | // Check that target constraints got inserted in the |
| 131 | // correct spots |
| 132 | EXPECT_EQ(target_constraints.size(), |
| 133 | timestamped_target_detections.size() - 1); |
| 134 | for (auto it = target_constraints.begin(); it < target_constraints.end(); |
| 135 | it++) { |
| 136 | auto timestamped_it = timestamped_target_detections.begin() + |
| 137 | (it - target_constraints.begin()); |
| 138 | EXPECT_EQ(it->id_begin, timestamped_it->id); |
| 139 | EXPECT_EQ(it->id_end, (timestamped_it + 1)->id); |
| 140 | } |
| 141 | |
| 142 | // Check that poses were interpolated correctly. |
| 143 | // Keep track of the computed robot pose by adding the delta poses |
| 144 | auto computed_robot_pose = timestamped_robot_poses[1].pose; |
| 145 | |
| 146 | computed_robot_pose = |
| 147 | PoseUtils::ComputeOffsetPose(computed_robot_pose, robot_delta_poses[0]); |
| 148 | EXPECT_POSE_IN_RANGE(computed_robot_pose, timestamped_robot_poses[1].pose, |
| 149 | timestamped_robot_poses[2].pose); |
| 150 | |
| 151 | computed_robot_pose = |
| 152 | PoseUtils::ComputeOffsetPose(computed_robot_pose, robot_delta_poses[1]); |
| 153 | EXPECT_POSE_IN_RANGE(computed_robot_pose, timestamped_robot_poses[1].pose, |
| 154 | timestamped_robot_poses[2].pose); |
| 155 | EXPECT_POSE_EQ(robot_delta_poses[1], MakePose(0.0, 0.0, 0.0)); |
| 156 | |
| 157 | computed_robot_pose = |
| 158 | PoseUtils::ComputeOffsetPose(computed_robot_pose, robot_delta_poses[2]); |
| 159 | EXPECT_POSE_EQ(computed_robot_pose, timestamped_robot_poses[3].pose); |
| 160 | |
| 161 | computed_robot_pose = |
| 162 | PoseUtils::ComputeOffsetPose(computed_robot_pose, robot_delta_poses[3]); |
| 163 | EXPECT_POSE_EQ(computed_robot_pose, timestamped_robot_poses[4].pose); |
| 164 | |
| 165 | computed_robot_pose = |
| 166 | PoseUtils::ComputeOffsetPose(computed_robot_pose, robot_delta_poses[4]); |
| 167 | EXPECT_POSE_IN_RANGE(computed_robot_pose, timestamped_robot_poses[5].pose, |
| 168 | timestamped_robot_poses[6].pose); |
| 169 | |
| 170 | // Check the confidence matrices. Don't check the actual values |
| 171 | // in case the constants change, just check the confidence of contraints |
| 172 | // relative to each other, as constraints over longer time periods should have |
| 173 | // lower confidence. |
| 174 | const auto confidence_0ms = |
| 175 | DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(0)); |
| 176 | const auto confidence_1ms = |
| 177 | DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(1)); |
| 178 | const auto confidence_4ms = |
| 179 | DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(4)); |
| 180 | const auto confidence_6ms = |
| 181 | DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(6)); |
| 182 | const auto confidence_11ms = |
| 183 | DataAdapter::ComputeConfidence(TimeInMs(0), TimeInMs(11)); |
| 184 | |
| 185 | // Check relative magnitude of different confidences. |
| 186 | // Confidences for 0-5ms, 5-10ms, and 10-15ms periods are equal |
| 187 | // because they fit within one control loop iteration. |
| 188 | EXPECT_EQ(confidence_0ms, confidence_1ms); |
| 189 | EXPECT_EQ(confidence_1ms, confidence_4ms); |
| 190 | EXPECT_CONFIDENCE_GT(confidence_4ms, confidence_6ms); |
| 191 | EXPECT_CONFIDENCE_GT(confidence_6ms, confidence_11ms); |
| 192 | |
| 193 | // Check that confidences (information) of actual constraints are correct |
| 194 | EXPECT_EQ(target_constraints[0].information, confidence_4ms); |
| 195 | EXPECT_EQ(target_constraints[1].information, confidence_0ms); |
| 196 | EXPECT_EQ(target_constraints[2].information, confidence_6ms); |
| 197 | EXPECT_EQ(target_constraints[3].information, confidence_1ms); |
| 198 | EXPECT_EQ(target_constraints[4].information, confidence_11ms); |
| 199 | } |
| 200 | |
| 201 | TEST(TargetMapperTest, TwoTargetsOneConstraint) { |
| 202 | std::map<TargetMapper::TargetId, ceres::examples::Pose2d> target_poses; |
| 203 | target_poses[0] = ceres::examples::Pose2d{5.0, 0.0, M_PI}; |
| 204 | target_poses[1] = ceres::examples::Pose2d{-5.0, 0.0, 0.0}; |
| 205 | |
| 206 | std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses = { |
| 207 | {TimeInMs(5), ceres::examples::Pose2d{2.0, 0.0, 0.0}}, |
| 208 | {TimeInMs(10), ceres::examples::Pose2d{-1.0, 0.0, 0.0}}, |
| 209 | {TimeInMs(15), ceres::examples::Pose2d{-1.0, 0.0, 0.0}}}; |
| 210 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
| 211 | {{TimeInMs(5), |
| 212 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{3.0, 0.0, M_PI}), |
| 213 | 0}, |
| 214 | {TimeInMs(10), |
| 215 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{-4.0, 0.0, 0.0}), |
| 216 | 1}}; |
| 217 | auto target_constraints = |
| 218 | DataAdapter::MatchTargetDetections(timestamped_robot_poses, |
| 219 | timestamped_target_detections) |
| 220 | .first; |
| 221 | |
| 222 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame^] | 223 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 224 | |
| 225 | ASSERT_EQ(mapper.target_poses().size(), 2); |
| 226 | EXPECT_POSE_NEAR(mapper.target_poses()[0], MakePose(5.0, 0.0, M_PI)); |
| 227 | EXPECT_POSE_NEAR(mapper.target_poses()[1], MakePose(-5.0, 0.0, 0.0)); |
| 228 | } |
| 229 | |
| 230 | TEST(TargetMapperTest, TwoTargetsTwoConstraints) { |
| 231 | std::map<TargetMapper::TargetId, ceres::examples::Pose2d> target_poses; |
| 232 | target_poses[0] = ceres::examples::Pose2d{5.0, 0.0, M_PI}; |
| 233 | target_poses[1] = ceres::examples::Pose2d{-5.0, 0.0, -M_PI_2}; |
| 234 | |
| 235 | std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses = { |
| 236 | {TimeInMs(5), ceres::examples::Pose2d{-1.0, 0.0, 0.0}}, |
| 237 | {TimeInMs(10), ceres::examples::Pose2d{3.0, 0.0, 0.0}}, |
| 238 | {TimeInMs(15), ceres::examples::Pose2d{4.0, 0.0, 0.0}}, |
| 239 | {TimeInMs(20), ceres::examples::Pose2d{-1.0, 0.0, 0.0}}}; |
| 240 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
| 241 | {{TimeInMs(5), |
| 242 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{6.0, 0.0, M_PI}), |
| 243 | 0}, |
| 244 | {TimeInMs(10), |
| 245 | PoseUtils::Pose2dToAffine3d( |
| 246 | ceres::examples::Pose2d{-8.0, 0.0, -M_PI_2}), |
| 247 | 1}, |
| 248 | {TimeInMs(15), |
| 249 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{1.0, 0.0, M_PI}), |
| 250 | 0}}; |
| 251 | auto target_constraints = |
| 252 | DataAdapter::MatchTargetDetections(timestamped_robot_poses, |
| 253 | timestamped_target_detections) |
| 254 | .first; |
| 255 | |
| 256 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame^] | 257 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 258 | |
| 259 | ASSERT_EQ(mapper.target_poses().size(), 2); |
| 260 | EXPECT_POSE_NEAR(mapper.target_poses()[0], MakePose(5.0, 0.0, M_PI)); |
| 261 | EXPECT_POSE_NEAR(mapper.target_poses()[1], MakePose(-5.0, 0.0, -M_PI_2)); |
| 262 | } |
| 263 | |
| 264 | TEST(TargetMapperTest, TwoTargetsOneNoisyConstraint) { |
| 265 | std::map<TargetMapper::TargetId, ceres::examples::Pose2d> target_poses; |
| 266 | target_poses[0] = ceres::examples::Pose2d{5.0, 0.0, M_PI}; |
| 267 | target_poses[1] = ceres::examples::Pose2d{-5.0, 0.0, 0.0}; |
| 268 | |
| 269 | std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses = { |
| 270 | {TimeInMs(5), ceres::examples::Pose2d{1.99, 0.0, 0.0}}, |
| 271 | {TimeInMs(10), ceres::examples::Pose2d{-1.0, 0.0, 0.0}}, |
| 272 | {TimeInMs(15), ceres::examples::Pose2d{-1.01, -0.01, 0.004}}}; |
| 273 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
| 274 | {{TimeInMs(5), |
| 275 | PoseUtils::Pose2dToAffine3d( |
| 276 | ceres::examples::Pose2d{3.01, 0.001, M_PI - 0.001}), |
| 277 | 0}, |
| 278 | {TimeInMs(10), |
| 279 | PoseUtils::Pose2dToAffine3d(ceres::examples::Pose2d{-4.01, 0.0, 0.0}), |
| 280 | 1}}; |
| 281 | |
| 282 | auto target_constraints = |
| 283 | DataAdapter::MatchTargetDetections(timestamped_robot_poses, |
| 284 | timestamped_target_detections) |
| 285 | .first; |
| 286 | |
| 287 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame^] | 288 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 289 | |
| 290 | ASSERT_EQ(mapper.target_poses().size(), 2); |
| 291 | EXPECT_POSE_NEAR(mapper.target_poses()[0], MakePose(5.0, 0.0, M_PI)); |
| 292 | EXPECT_POSE_NEAR(mapper.target_poses()[1], MakePose(-5.0, 0.0, 0.0)); |
| 293 | } |
| 294 | |
| 295 | TEST(TargetMapperTest, MultiTargetCircleMotion) { |
| 296 | // Build set of target locations wrt global origin |
| 297 | // For simplicity, do this on a grid of the field |
| 298 | double field_half_length = 7.5; // half length of the field |
| 299 | double field_half_width = 5.0; // half width of the field |
| 300 | std::map<TargetMapper::TargetId, ceres::examples::Pose2d> target_poses; |
| 301 | std::vector<TargetMapper::TargetPose> actual_target_poses; |
| 302 | for (int i = 0; i < 3; i++) { |
| 303 | for (int j = 0; j < 3; j++) { |
| 304 | TargetMapper::TargetId target_id = i * 3 + j; |
| 305 | TargetMapper::TargetPose target_pose{ |
| 306 | target_id, ceres::examples::Pose2d{field_half_length * (1 - i), |
| 307 | field_half_width * (1 - j), 0.0}}; |
| 308 | actual_target_poses.emplace_back(target_pose); |
| 309 | target_poses[target_id] = target_pose.pose; |
| 310 | VLOG(2) << "VERTEX_SE2 " << target_id << " " << target_pose.pose.x << " " |
| 311 | << target_pose.pose.y << " " << target_pose.pose.yaw_radians; |
| 312 | } |
| 313 | } |
| 314 | |
| 315 | // Now, create a bunch of robot poses and target |
| 316 | // observations |
| 317 | size_t dt = 1; |
| 318 | |
| 319 | std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses; |
| 320 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 321 | |
| 322 | constexpr size_t kTotalSteps = 100; |
| 323 | for (size_t step_count = 0; step_count < kTotalSteps; step_count++) { |
| 324 | size_t t = dt * step_count; |
| 325 | // Circle clockwise around the center of the field |
| 326 | double robot_theta = t; |
| 327 | double robot_x = (field_half_length / 2.0) * cos(robot_theta); |
| 328 | double robot_y = (-field_half_width / 2.0) * sin(robot_theta); |
| 329 | |
| 330 | ceres::examples::Pose2d robot_pose{robot_x, robot_y, robot_theta}; |
| 331 | for (TargetMapper::TargetPose target_pose : actual_target_poses) { |
| 332 | TargetMapper::TargetPose target_detection = { |
| 333 | .id = target_pose.id, |
| 334 | .pose = PoseUtils::ComputeRelativePose(robot_pose, target_pose.pose)}; |
| 335 | if (TargetIsInView(target_detection)) { |
| 336 | // Define random generator with Gaussian |
| 337 | // distribution |
| 338 | const double mean = 0.0; |
| 339 | const double stddev = 1.0; |
| 340 | // Can play with this to see how it impacts |
| 341 | // randomness |
| 342 | constexpr double kNoiseScale = 0.01; |
| 343 | std::default_random_engine generator(aos::testing::RandomSeed()); |
| 344 | std::normal_distribution<double> dist(mean, stddev); |
| 345 | |
| 346 | target_detection.pose.x += dist(generator) * kNoiseScale; |
| 347 | target_detection.pose.y += dist(generator) * kNoiseScale; |
| 348 | robot_pose.x += dist(generator) * kNoiseScale; |
| 349 | robot_pose.y += dist(generator) * kNoiseScale; |
| 350 | |
| 351 | auto time_point = |
| 352 | aos::distributed_clock::time_point(std::chrono::milliseconds(t)); |
| 353 | timestamped_robot_poses.emplace_back(DataAdapter::TimestampedPose{ |
| 354 | .time = time_point, .pose = robot_pose}); |
| 355 | timestamped_target_detections.emplace_back( |
| 356 | DataAdapter::TimestampedDetection{ |
| 357 | .time = time_point, |
| 358 | .H_robot_target = |
| 359 | PoseUtils::Pose2dToAffine3d(target_detection.pose), |
| 360 | .id = target_detection.id}); |
| 361 | } |
| 362 | } |
| 363 | } |
| 364 | |
| 365 | { |
| 366 | // Add in a robot pose after all target poses |
| 367 | auto final_robot_pose = |
| 368 | timestamped_robot_poses[timestamped_robot_poses.size() - 1]; |
| 369 | timestamped_robot_poses.emplace_back(DataAdapter::TimestampedPose{ |
| 370 | .time = final_robot_pose.time + std::chrono::milliseconds(dt), |
| 371 | .pose = final_robot_pose.pose}); |
| 372 | } |
| 373 | |
| 374 | auto target_constraints = |
| 375 | DataAdapter::MatchTargetDetections(timestamped_robot_poses, |
| 376 | timestamped_target_detections) |
| 377 | .first; |
| 378 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame^] | 379 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 380 | |
| 381 | for (auto [target_pose_id, mapper_target_pose] : mapper.target_poses()) { |
| 382 | TargetMapper::TargetPose actual_target_pose = |
| 383 | TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id) |
| 384 | .value(); |
| 385 | EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose); |
| 386 | } |
| 387 | |
| 388 | // |
| 389 | // See what happens when we don't start with the |
| 390 | // correct values |
| 391 | // |
| 392 | for (auto [target_id, target_pose] : target_poses) { |
| 393 | // Skip first pose, since that needs to be correct |
| 394 | // and is fixed in the solver |
| 395 | if (target_id != 0) { |
| 396 | ceres::examples::Pose2d bad_pose{0.0, 0.0, M_PI / 2.0}; |
| 397 | target_poses[target_id] = bad_pose; |
| 398 | } |
| 399 | } |
| 400 | |
| 401 | frc971::vision::TargetMapper mapper_bad_poses(target_poses, |
| 402 | target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame^] | 403 | mapper_bad_poses.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 404 | |
| 405 | for (auto [target_pose_id, mapper_target_pose] : |
| 406 | mapper_bad_poses.target_poses()) { |
| 407 | TargetMapper::TargetPose actual_target_pose = |
| 408 | TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id) |
| 409 | .value(); |
| 410 | EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose); |
| 411 | } |
| 412 | } |
| 413 | |
| 414 | } // namespace frc971::vision |