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" |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 6 | #include "aos/testing/path.h" |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 7 | #include "aos/testing/random_seed.h" |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 8 | #include "aos/util/math.h" |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 9 | #include "glog/logging.h" |
| 10 | #include "gtest/gtest.h" |
| 11 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 12 | DECLARE_int32(min_target_id); |
| 13 | DECLARE_int32(max_target_id); |
| 14 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 15 | namespace frc971::vision { |
| 16 | |
| 17 | namespace { |
| 18 | constexpr double kToleranceMeters = 0.05; |
| 19 | constexpr double kToleranceRadians = 0.05; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 20 | // Conversions between euler angles and quaternion result in slightly-off |
| 21 | // doubles |
| 22 | constexpr double kOrientationEqTolerance = 1e-10; |
| 23 | constexpr std::chrono::milliseconds kMaxDt = std::chrono::milliseconds(3); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 24 | constexpr std::string_view kFieldName = "test"; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 25 | } // namespace |
| 26 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 27 | // Angles normalized by aos::math::NormalizeAngle() |
| 28 | #define EXPECT_NORMALIZED_ANGLES_NEAR(theta1, theta2, tolerance) \ |
| 29 | { \ |
| 30 | double delta = std::abs(aos::math::DiffAngle(theta1, theta2)); \ |
| 31 | /* Have to check delta - 2pi for the case that one angle is very */ \ |
| 32 | /* close to -pi, and the other is very close to +pi */ \ |
| 33 | EXPECT_TRUE(delta < tolerance || std::abs(aos::math::DiffAngle( \ |
| 34 | delta, 2.0 * M_PI)) < tolerance); \ |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 35 | } |
| 36 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 37 | #define EXPECT_POSE_NEAR(pose1, pose2) \ |
| 38 | { \ |
| 39 | for (size_t i = 0; i < 3; i++) { \ |
| 40 | EXPECT_NEAR(pose1.p(i), pose2.p(i), kToleranceMeters); \ |
| 41 | } \ |
| 42 | auto rpy_1 = PoseUtils::QuaternionToEulerAngles(pose1.q); \ |
| 43 | auto rpy_2 = PoseUtils::QuaternionToEulerAngles(pose2.q); \ |
| 44 | for (size_t i = 0; i < 3; i++) { \ |
| 45 | SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \ |
| 46 | rpy_1(i), i, rpy_2(i))); \ |
| 47 | EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), kToleranceRadians) \ |
| 48 | } \ |
| 49 | } |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 50 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 51 | #define EXPECT_POSE_EQ(pose1, pose2) \ |
| 52 | EXPECT_EQ(pose1.p, pose2.p); \ |
| 53 | EXPECT_EQ(pose1.q, pose2.q); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 54 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 55 | #define EXPECT_QUATERNION_NEAR(q1, q2) \ |
| 56 | EXPECT_NEAR(q1.x(), q2.x(), kOrientationEqTolerance) << q1 << " != " << q2; \ |
| 57 | EXPECT_NEAR(q1.y(), q2.y(), kOrientationEqTolerance) << q1 << " != " << q2; \ |
| 58 | EXPECT_NEAR(q1.z(), q2.z(), kOrientationEqTolerance) << q1 << " != " << q2; \ |
| 59 | EXPECT_NEAR(q1.w(), q2.w(), kOrientationEqTolerance) << q1 << " != " << q2; |
| 60 | |
| 61 | // Expects same roll, pitch, and yaw values (not equivalent rotation) |
| 62 | #define EXPECT_RPY_EQ(rpy_1, rpy_2) \ |
| 63 | { \ |
| 64 | for (size_t i = 0; i < 3; i++) { \ |
| 65 | SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \ |
| 66 | rpy_1(i), i, rpy_2(i))); \ |
| 67 | EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), \ |
| 68 | kOrientationEqTolerance) \ |
| 69 | } \ |
| 70 | } |
| 71 | |
| 72 | #define EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw) \ |
| 73 | { \ |
| 74 | auto rpy = Eigen::Vector3d(roll, pitch, yaw); \ |
| 75 | auto converted_rpy = PoseUtils::QuaternionToEulerAngles( \ |
| 76 | PoseUtils::EulerAnglesToQuaternion(rpy)); \ |
| 77 | EXPECT_RPY_EQ(converted_rpy, rpy); \ |
| 78 | } |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 79 | |
| 80 | // Both confidence matrixes should have the same dimensions and be square |
| 81 | #define EXPECT_CONFIDENCE_GT(confidence1, confidence2) \ |
| 82 | { \ |
| 83 | ASSERT_EQ(confidence1.rows(), confidence2.rows()); \ |
| 84 | ASSERT_EQ(confidence1.rows(), confidence1.cols()); \ |
| 85 | ASSERT_EQ(confidence2.rows(), confidence2.cols()); \ |
| 86 | for (size_t i = 0; i < confidence1.rows(); i++) { \ |
| 87 | EXPECT_GT(confidence1(i, i), confidence2(i, i)); \ |
| 88 | } \ |
| 89 | } |
| 90 | |
| 91 | namespace { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 92 | ceres::examples::Pose3d Make2dPose(double x, double y, double yaw_radians) { |
| 93 | return ceres::examples::Pose3d{Eigen::Vector3d(x, y, 0.0), |
| 94 | PoseUtils::EulerAnglesToQuaternion( |
| 95 | Eigen::Vector3d(0.0, 0.0, yaw_radians))}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 96 | } |
| 97 | |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 98 | // Assumes camera and robot origin are the same |
| 99 | DataAdapter::TimestampedDetection MakeTimestampedDetection( |
| 100 | aos::distributed_clock::time_point time, Eigen::Affine3d H_robot_target, |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 101 | TargetMapper::TargetId id, double distortion_factor = 0.001) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 102 | auto target_pose = PoseUtils::Affine3dToPose3d(H_robot_target); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 103 | return DataAdapter::TimestampedDetection{ |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 104 | .time = time, |
| 105 | .H_robot_target = H_robot_target, |
| 106 | .distance_from_camera = target_pose.p.norm(), |
| 107 | .distortion_factor = distortion_factor, |
| 108 | .id = id}; |
| 109 | } |
| 110 | |
| 111 | DataAdapter::TimestampedDetection MakeTimestampedDetectionForConfidence( |
| 112 | aos::distributed_clock::time_point time, TargetMapper::TargetId id, |
| 113 | double distance_from_camera, double distortion_factor) { |
| 114 | auto target_pose = ceres::examples::Pose3d{ |
| 115 | .p = Eigen::Vector3d(distance_from_camera, 0.0, 0.0), |
| 116 | .q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0)}; |
| 117 | return DataAdapter::TimestampedDetection{ |
| 118 | .time = time, |
| 119 | .H_robot_target = PoseUtils::Pose3dToAffine3d(target_pose), |
| 120 | .distance_from_camera = target_pose.p.norm(), |
| 121 | .distortion_factor = distortion_factor, |
| 122 | .id = id}; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 123 | } |
| 124 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 125 | bool TargetIsInView(TargetMapper::TargetPose target_detection) { |
| 126 | // And check if it is within the fov of the robot / |
| 127 | // camera, assuming camera is pointing in the |
| 128 | // positive x-direction of the robot |
| 129 | double angle_to_target = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 130 | atan2(target_detection.pose.p(1), target_detection.pose.p(0)); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 131 | |
| 132 | // Simulated camera field of view, in radians |
| 133 | constexpr double kCameraFov = M_PI_2; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 134 | if (std::abs(angle_to_target) <= kCameraFov / 2.0) { |
| 135 | VLOG(2) << "Found target in view, based on T = " |
| 136 | << target_detection.pose.p(0) << ", " << target_detection.pose.p(1) |
| 137 | << " with angle " << angle_to_target; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 138 | return true; |
| 139 | } else { |
| 140 | return false; |
| 141 | } |
| 142 | } |
| 143 | |
| 144 | aos::distributed_clock::time_point TimeInMs(size_t ms) { |
| 145 | return aos::distributed_clock::time_point(std::chrono::milliseconds(ms)); |
| 146 | } |
| 147 | |
| 148 | } // namespace |
| 149 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 150 | TEST(PoseUtilsTest, EulerAnglesAndQuaternionConversions) { |
| 151 | // Make sure that the conversions are consistent back and forth. |
| 152 | // These angles shouldn't get changed to a different, equivalent roll pitch |
| 153 | // yaw. |
| 154 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, M_PI); |
| 155 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, -M_PI); |
| 156 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, M_PI_2); |
| 157 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, -M_PI_2); |
| 158 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, 0.0); |
| 159 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, M_PI_4, 0.0); |
| 160 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, 0.0); |
| 161 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, M_PI_4); |
| 162 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(M_PI_4, -M_PI_4, M_PI_4); |
| 163 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(-M_PI_2, -M_PI_4, M_PI_4); |
| 164 | |
| 165 | // Now, do a sweep of roll, pitch, and yaws in the normalized |
| 166 | // range. |
| 167 | // - roll: (-pi/2, pi/2) |
| 168 | // - pitch: (-pi/2, pi/2) |
| 169 | // - yaw: [-pi, pi) |
| 170 | constexpr double kThetaMaxRoll = M_PI_2 - kToleranceRadians; |
| 171 | constexpr double kThetaMaxPitch = M_PI_2 - kToleranceRadians; |
| 172 | constexpr double kThetaMaxYaw = M_PI; |
| 173 | constexpr double kDeltaTheta = M_PI / 16; |
| 174 | |
| 175 | for (double roll = -kThetaMaxRoll; roll < kThetaMaxRoll; |
| 176 | roll += kDeltaTheta) { |
| 177 | for (double pitch = -kThetaMaxPitch; pitch < kThetaMaxPitch; |
| 178 | pitch += kDeltaTheta) { |
| 179 | for (double yaw = -kThetaMaxYaw; yaw < kThetaMaxYaw; yaw += kDeltaTheta) { |
| 180 | SCOPED_TRACE( |
| 181 | absl::StrFormat("roll: %f, pitch: %f, yaw: %f", roll, pitch, yaw)); |
| 182 | EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw); |
| 183 | } |
| 184 | } |
| 185 | } |
| 186 | } |
| 187 | |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 188 | TEST(DataAdapterTest, ComputeConfidence) { |
| 189 | // Check the confidence matrices. Don't check the actual values |
| 190 | // in case the constants change, just check that the confidence of contraints |
| 191 | // decreases as time period or distances from camera increase. |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 192 | |
| 193 | constexpr size_t kIdStart = 0; |
| 194 | constexpr size_t kIdEnd = 1; |
| 195 | |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 196 | { |
| 197 | // Vary time period |
| 198 | constexpr double kDistanceStart = 0.5; |
| 199 | constexpr double kDistanceEnd = 2.0; |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 200 | constexpr double kDistortionFactor = 0.001; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 201 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 202 | TargetMapper::ConfidenceMatrix last_confidence = |
| 203 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 204 | for (size_t dt = 0; dt < 15; dt++) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 205 | TargetMapper::ConfidenceMatrix confidence = |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 206 | DataAdapter::ComputeConfidence( |
| 207 | MakeTimestampedDetectionForConfidence( |
| 208 | TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor), |
| 209 | MakeTimestampedDetectionForConfidence( |
| 210 | TimeInMs(dt), kIdEnd, kDistanceEnd, kDistortionFactor)); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 211 | |
| 212 | if (dt != 0) { |
| 213 | // Confidence only decreases every 5ms (control loop period) |
| 214 | if (dt % 5 == 0) { |
| 215 | EXPECT_CONFIDENCE_GT(last_confidence, confidence); |
| 216 | } else { |
| 217 | EXPECT_EQ(last_confidence, confidence); |
| 218 | } |
| 219 | } |
| 220 | last_confidence = confidence; |
| 221 | } |
| 222 | } |
| 223 | |
| 224 | { |
| 225 | // Vary distance at start |
| 226 | constexpr int kDt = 3; |
| 227 | constexpr double kDistanceEnd = 1.5; |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 228 | constexpr double kDistortionFactor = 0.001; |
| 229 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 230 | TargetMapper::ConfidenceMatrix last_confidence = |
| 231 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 232 | for (double distance_start = 0.0; distance_start < 3.0; |
| 233 | distance_start += 0.5) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 234 | TargetMapper::ConfidenceMatrix confidence = |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 235 | DataAdapter::ComputeConfidence( |
| 236 | MakeTimestampedDetectionForConfidence( |
| 237 | TimeInMs(0), kIdStart, distance_start, kDistortionFactor), |
| 238 | MakeTimestampedDetectionForConfidence( |
| 239 | TimeInMs(kDt), kIdEnd, kDistanceEnd, kDistortionFactor)); |
| 240 | |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 241 | if (distance_start != 0.0) { |
| 242 | EXPECT_CONFIDENCE_GT(last_confidence, confidence); |
| 243 | } |
| 244 | last_confidence = confidence; |
| 245 | } |
| 246 | } |
| 247 | |
| 248 | { |
| 249 | // Vary distance at end |
| 250 | constexpr int kDt = 2; |
| 251 | constexpr double kDistanceStart = 2.5; |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 252 | constexpr double kDistortionFactor = 0.001; |
| 253 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 254 | TargetMapper::ConfidenceMatrix last_confidence = |
| 255 | TargetMapper::ConfidenceMatrix::Zero(); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 256 | for (double distance_end = 0.0; distance_end < 3.0; distance_end += 0.5) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 257 | TargetMapper::ConfidenceMatrix confidence = |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 258 | DataAdapter::ComputeConfidence( |
| 259 | MakeTimestampedDetectionForConfidence( |
| 260 | TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor), |
| 261 | MakeTimestampedDetectionForConfidence( |
| 262 | TimeInMs(kDt), kIdEnd, distance_end, kDistortionFactor)); |
| 263 | |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 264 | if (distance_end != 0.0) { |
| 265 | EXPECT_CONFIDENCE_GT(last_confidence, confidence); |
| 266 | } |
| 267 | last_confidence = confidence; |
| 268 | } |
| 269 | } |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 270 | |
| 271 | { |
| 272 | // Vary distortion factor |
| 273 | constexpr int kDt = 2; |
| 274 | constexpr double kDistanceStart = 2.5; |
| 275 | constexpr double kDistanceEnd = 1.5; |
| 276 | |
| 277 | TargetMapper::ConfidenceMatrix last_confidence = |
| 278 | TargetMapper::ConfidenceMatrix::Zero(); |
| 279 | for (double distortion_factor = 0.0; distortion_factor <= 1.0; |
| 280 | distortion_factor += 0.01) { |
| 281 | TargetMapper::ConfidenceMatrix confidence = |
| 282 | DataAdapter::ComputeConfidence( |
| 283 | MakeTimestampedDetectionForConfidence( |
| 284 | TimeInMs(0), kIdStart, kDistanceStart, distortion_factor), |
| 285 | MakeTimestampedDetectionForConfidence( |
| 286 | TimeInMs(kDt), kIdEnd, kDistanceEnd, distortion_factor)); |
| 287 | |
| 288 | if (distortion_factor != 0.0) { |
| 289 | EXPECT_CONFIDENCE_GT(last_confidence, confidence); |
| 290 | } |
| 291 | last_confidence = confidence; |
| 292 | } |
| 293 | } |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 294 | } |
| 295 | |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 296 | TEST(DataAdapterTest, MatchTargetDetections) { |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 297 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 298 | {MakeTimestampedDetection( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 299 | TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -5.0, 0.0)), |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 300 | 2), |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 301 | MakeTimestampedDetection( |
| 302 | TimeInMs(6), |
| 303 | PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -4.0, M_PI)), 0), |
| 304 | MakeTimestampedDetection( |
| 305 | TimeInMs(10), |
| 306 | PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, -3.0, M_PI)), 1), |
| 307 | MakeTimestampedDetection( |
| 308 | TimeInMs(13), |
| 309 | PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -7.0, M_PI_2)), 2), |
| 310 | MakeTimestampedDetection( |
| 311 | TimeInMs(14), |
| 312 | PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -4.0, M_PI_2)), 2)}; |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 313 | |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 314 | auto target_constraints = |
| 315 | DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt); |
| 316 | |
| 317 | // The constraint between the detection at 6ms and the one at 10 ms is skipped |
| 318 | // because dt > kMaxDt. |
| 319 | // Also, the constraint between the last two detections is skipped because |
| 320 | // they are the same target |
| 321 | EXPECT_EQ(target_constraints.size(), |
| 322 | timestamped_target_detections.size() - 3); |
| 323 | |
| 324 | // Between 5ms and 6ms detections |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 325 | EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(0), 0.0); |
| 326 | EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(1), 1.0); |
| 327 | EXPECT_QUATERNION_NEAR( |
| 328 | target_constraints[0].t_be.q, |
| 329 | PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, M_PI))); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 330 | EXPECT_EQ(target_constraints[0].id_begin, 2); |
| 331 | EXPECT_EQ(target_constraints[0].id_end, 0); |
| 332 | |
| 333 | // Between 10ms and 13ms detections |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 334 | EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(0), -1.0); |
| 335 | EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(1), 4.0); |
| 336 | EXPECT_QUATERNION_NEAR( |
| 337 | target_constraints[1].t_be.q, |
| 338 | PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, -M_PI_2))); |
Milind Upadhyay | ec49391 | 2022-12-18 21:33:15 -0800 | [diff] [blame] | 339 | EXPECT_EQ(target_constraints[1].id_begin, 1); |
| 340 | EXPECT_EQ(target_constraints[1].id_end, 2); |
| 341 | } |
| 342 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 343 | TEST(TargetMapperTest, TwoTargetsOneConstraint) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 344 | FLAGS_min_target_id = 0; |
| 345 | FLAGS_max_target_id = 1; |
| 346 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 347 | ceres::examples::MapOfPoses target_poses; |
| 348 | target_poses[0] = Make2dPose(5.0, 0.0, M_PI); |
| 349 | target_poses[1] = Make2dPose(-5.0, 0.0, 0.0); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 350 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 351 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 352 | {MakeTimestampedDetection( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 353 | TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, 0.0, M_PI)), |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 354 | 0), |
| 355 | MakeTimestampedDetection( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 356 | TimeInMs(6), PoseUtils::Pose3dToAffine3d(Make2dPose(-7.0, 0.0, 0.0)), |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 357 | 1)}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 358 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 359 | DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 360 | |
| 361 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 362 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 363 | |
| 364 | ASSERT_EQ(mapper.target_poses().size(), 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 365 | EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI)); |
| 366 | EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0)); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 367 | } |
| 368 | |
| 369 | TEST(TargetMapperTest, TwoTargetsTwoConstraints) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 370 | FLAGS_min_target_id = 0; |
| 371 | FLAGS_max_target_id = 1; |
| 372 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 373 | ceres::examples::MapOfPoses target_poses; |
| 374 | target_poses[0] = Make2dPose(5.0, 0.0, M_PI); |
| 375 | target_poses[1] = Make2dPose(-5.0, 0.0, -M_PI_2); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 376 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 377 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 378 | {MakeTimestampedDetection( |
| 379 | TimeInMs(5), |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 380 | PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 0.0, M_PI_2)), 0), |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 381 | MakeTimestampedDetection( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 382 | TimeInMs(7), |
| 383 | PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 10.0, -M_PI)), 1), |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 384 | MakeTimestampedDetection( |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 385 | TimeInMs(12), |
| 386 | PoseUtils::Pose3dToAffine3d(Make2dPose(1.0, 0.0, M_PI)), 0), |
| 387 | MakeTimestampedDetection( |
| 388 | TimeInMs(13), |
| 389 | PoseUtils::Pose3dToAffine3d(Make2dPose(-9.0, 0.0, -M_PI_2)), 1)}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 390 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 391 | DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 392 | |
| 393 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 394 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 395 | |
| 396 | ASSERT_EQ(mapper.target_poses().size(), 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 397 | EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI)); |
| 398 | EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, -M_PI_2)); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 399 | } |
| 400 | |
| 401 | TEST(TargetMapperTest, TwoTargetsOneNoisyConstraint) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame^] | 402 | FLAGS_min_target_id = 0; |
| 403 | FLAGS_max_target_id = 1; |
| 404 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 405 | ceres::examples::MapOfPoses target_poses; |
| 406 | target_poses[0] = Make2dPose(5.0, 0.0, M_PI); |
| 407 | target_poses[1] = Make2dPose(-5.0, 0.0, 0.0); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 408 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 409 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections = |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 410 | {MakeTimestampedDetection( |
| 411 | TimeInMs(5), |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 412 | PoseUtils::Pose3dToAffine3d(Make2dPose(3.01, 0.001, M_PI - 0.001)), |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 413 | 0), |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 414 | MakeTimestampedDetection( |
| 415 | TimeInMs(7), |
| 416 | PoseUtils::Pose3dToAffine3d(Make2dPose(-7.01, 0.0, 0.0)), 1)}; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 417 | |
| 418 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 419 | DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 420 | |
| 421 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 422 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 423 | |
| 424 | ASSERT_EQ(mapper.target_poses().size(), 2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 425 | EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI)); |
| 426 | EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0)); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 427 | } |
| 428 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 429 | class ChargedUpTargetMapperTest : public ::testing::Test { |
| 430 | public: |
| 431 | ChargedUpTargetMapperTest() : generator_(aos::testing::RandomSeed()) {} |
| 432 | |
| 433 | // Generates noisy target detection if target in camera FOV |
| 434 | std::optional<DataAdapter::TimestampedDetection> MaybeGenerateNoisyDetection( |
| 435 | const ceres::examples::Pose3d &robot_pose, |
| 436 | const TargetMapper::TargetPose &target_pose, size_t t, |
| 437 | bool force_in_view = false) { |
| 438 | TargetMapper::TargetPose target_detection = { |
| 439 | .id = target_pose.id, |
| 440 | .pose = PoseUtils::ComputeRelativePose(robot_pose, target_pose.pose)}; |
| 441 | if (force_in_view || TargetIsInView(target_detection)) { |
| 442 | // Define random generator with Gaussian |
| 443 | // distribution |
| 444 | constexpr double kMean = 0.0; |
| 445 | constexpr double kStdDev = 1.0; |
| 446 | // Can play with this to see how it impacts |
| 447 | // randomness |
| 448 | constexpr double kNoiseScalePosition = 0.01; |
| 449 | constexpr double kNoiseScaleOrientation = 0.0005; |
| 450 | std::normal_distribution<double> dist(kMean, kStdDev); |
| 451 | |
| 452 | target_detection.pose.p(0) += dist(generator_) * kNoiseScalePosition; |
| 453 | target_detection.pose.p(1) += dist(generator_) * kNoiseScalePosition; |
| 454 | target_detection.pose.p(2) += dist(generator_) * kNoiseScalePosition; |
| 455 | |
| 456 | target_detection.pose.q.w() += dist(generator_) * kNoiseScaleOrientation; |
| 457 | target_detection.pose.q.x() += dist(generator_) * kNoiseScaleOrientation; |
| 458 | target_detection.pose.q.y() += dist(generator_) * kNoiseScaleOrientation; |
| 459 | target_detection.pose.q.z() += dist(generator_) * kNoiseScaleOrientation; |
| 460 | |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 461 | // Get most distortion factors close to zero, but have a few outliers |
| 462 | const std::vector<double> kDistortionFactorIntervals = {0.0, 0.01, 1.0}; |
| 463 | const std::vector<double> kDistortionFactorWeights = {0.9, 0.1}; |
| 464 | std::piecewise_constant_distribution<double> distortion_factor_dist( |
| 465 | kDistortionFactorIntervals.begin(), kDistortionFactorIntervals.end(), |
| 466 | kDistortionFactorWeights.begin()); |
| 467 | double distortion_factor = distortion_factor_dist(generator_); |
| 468 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 469 | auto time_point = TimeInMs(t); |
| 470 | return MakeTimestampedDetection( |
| 471 | time_point, PoseUtils::Pose3dToAffine3d(target_detection.pose), |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 472 | target_detection.id, distortion_factor); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 473 | } |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 474 | |
| 475 | return std::nullopt; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 476 | } |
| 477 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 478 | private: |
| 479 | std::default_random_engine generator_; |
| 480 | }; |
| 481 | |
| 482 | // Drive in a circle around the 2023 field, and add a bit of randomness to 3d |
| 483 | // pose detections |
| 484 | TEST_F(ChargedUpTargetMapperTest, FieldCircleMotion) { |
| 485 | // Read target map |
| 486 | auto target_map_fbs = aos::JsonFileToFlatbuffer<TargetMap>( |
| 487 | aos::testing::ArtifactPath("frc971/vision/target_map.json")); |
| 488 | |
| 489 | std::vector<TargetMapper::TargetPose> actual_target_poses; |
| 490 | ceres::examples::MapOfPoses target_poses; |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 491 | for (const auto *target_pose_fbs : *target_map_fbs.message().target_poses()) { |
| 492 | const TargetMapper::TargetPose target_pose = |
| 493 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 494 | actual_target_poses.emplace_back(target_pose); |
| 495 | target_poses[target_pose.id] = target_pose.pose; |
| 496 | } |
| 497 | |
| 498 | double kFieldHalfLength = 16.54 / 2.0; // half length of the field |
| 499 | double kFieldHalfWidth = 8.02 / 2.0; // half width of the field |
| 500 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 501 | // Now, create a bunch of robot poses and target |
| 502 | // observations |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 503 | constexpr size_t kDt = 5; |
| 504 | constexpr double kRobotZ = 1.0; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 505 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 506 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 507 | |
| 508 | constexpr size_t kTotalSteps = 100; |
| 509 | for (size_t step_count = 0; step_count < kTotalSteps; step_count++) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 510 | size_t t = kDt * step_count; |
| 511 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 512 | // Circle clockwise around the center of the field |
| 513 | double robot_theta = t; |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 514 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 515 | constexpr double kRadiusScalar = 0.5; |
| 516 | double robot_x = (kRadiusScalar * kFieldHalfLength) * cos(robot_theta); |
| 517 | double robot_y = (kRadiusScalar * -kFieldHalfWidth) * sin(robot_theta); |
| 518 | |
| 519 | auto robot_pose = |
| 520 | ceres::examples::Pose3d{.p = Eigen::Vector3d(robot_x, robot_y, kRobotZ), |
| 521 | .q = PoseUtils::EulerAnglesToQuaternion( |
| 522 | Eigen::Vector3d(robot_theta, 0.0, 0.0))}; |
| 523 | |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 524 | for (TargetMapper::TargetPose target_pose : actual_target_poses) { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 525 | auto optional_detection = |
| 526 | MaybeGenerateNoisyDetection(robot_pose, target_pose, t); |
| 527 | if (optional_detection.has_value()) { |
| 528 | timestamped_target_detections.emplace_back(*optional_detection); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 529 | } |
| 530 | } |
| 531 | } |
| 532 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 533 | // The above circular motion only captures targets 1-4, so add another |
| 534 | // detection with the camera looking at targets 5-8, and 4 at the same time to |
| 535 | // have a connection to the rest of the targets |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 536 | { |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 537 | auto last_robot_pose = |
| 538 | ceres::examples::Pose3d{.p = Eigen::Vector3d(0.0, 0.0, kRobotZ), |
| 539 | .q = PoseUtils::EulerAnglesToQuaternion( |
| 540 | Eigen::Vector3d(0.0, 0.0, M_PI))}; |
| 541 | for (size_t id = 4; id <= 8; id++) { |
| 542 | auto target_pose = |
| 543 | TargetMapper::GetTargetPoseById(actual_target_poses, id).value(); |
| 544 | auto optional_detection = MaybeGenerateNoisyDetection( |
| 545 | last_robot_pose, target_pose, kTotalSteps * kDt, true); |
| 546 | |
| 547 | ASSERT_TRUE(optional_detection.has_value()) |
| 548 | << "Didn't detect target " << target_pose.id; |
| 549 | timestamped_target_detections.emplace_back(*optional_detection); |
| 550 | } |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 551 | } |
| 552 | |
| 553 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 554 | DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 555 | frc971::vision::TargetMapper mapper(target_poses, target_constraints); |
Milind Upadhyay | 05652cb | 2022-12-07 20:51:51 -0800 | [diff] [blame] | 556 | mapper.Solve(kFieldName); |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 557 | |
| 558 | for (auto [target_pose_id, mapper_target_pose] : mapper.target_poses()) { |
| 559 | TargetMapper::TargetPose actual_target_pose = |
| 560 | TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id) |
| 561 | .value(); |
| 562 | EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose); |
| 563 | } |
Milind Upadhyay | 7c20522 | 2022-11-16 18:20:58 -0800 | [diff] [blame] | 564 | } |
| 565 | |
| 566 | } // namespace frc971::vision |