blob: 8c6d37d3efc22810b6d91fc63c50d0649b61a9c8 [file] [log] [blame]
Milind Upadhyay7c205222022-11-16 18:20:58 -08001#include "frc971/vision/target_mapper.h"
2
3#include <random>
4
Philipp Schrader790cb542023-07-05 21:06:52 -07005#include "glog/logging.h"
6#include "gtest/gtest.h"
7
Milind Upadhyay7c205222022-11-16 18:20:58 -08008#include "aos/events/simulated_event_loop.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08009#include "aos/testing/path.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080010#include "aos/testing/random_seed.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -080011#include "aos/util/math.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080012
milind-u8f4e43e2023-04-09 17:11:19 -070013DECLARE_int32(min_target_id);
14DECLARE_int32(max_target_id);
15
Milind Upadhyay7c205222022-11-16 18:20:58 -080016namespace frc971::vision {
17
18namespace {
19constexpr double kToleranceMeters = 0.05;
20constexpr double kToleranceRadians = 0.05;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080021// Conversions between euler angles and quaternion result in slightly-off
22// doubles
23constexpr double kOrientationEqTolerance = 1e-10;
24constexpr std::chrono::milliseconds kMaxDt = std::chrono::milliseconds(3);
Milind Upadhyay05652cb2022-12-07 20:51:51 -080025constexpr std::string_view kFieldName = "test";
Milind Upadhyay7c205222022-11-16 18:20:58 -080026} // namespace
27
Milind Upadhyayc5beba12022-12-17 17:41:20 -080028// Angles normalized by aos::math::NormalizeAngle()
29#define EXPECT_NORMALIZED_ANGLES_NEAR(theta1, theta2, tolerance) \
30 { \
31 double delta = std::abs(aos::math::DiffAngle(theta1, theta2)); \
32 /* Have to check delta - 2pi for the case that one angle is very */ \
33 /* close to -pi, and the other is very close to +pi */ \
34 EXPECT_TRUE(delta < tolerance || std::abs(aos::math::DiffAngle( \
35 delta, 2.0 * M_PI)) < tolerance); \
Milind Upadhyay7c205222022-11-16 18:20:58 -080036 }
37
Milind Upadhyayc5beba12022-12-17 17:41:20 -080038#define EXPECT_POSE_NEAR(pose1, pose2) \
39 { \
40 for (size_t i = 0; i < 3; i++) { \
41 EXPECT_NEAR(pose1.p(i), pose2.p(i), kToleranceMeters); \
42 } \
43 auto rpy_1 = PoseUtils::QuaternionToEulerAngles(pose1.q); \
44 auto rpy_2 = PoseUtils::QuaternionToEulerAngles(pose2.q); \
45 for (size_t i = 0; i < 3; i++) { \
46 SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \
47 rpy_1(i), i, rpy_2(i))); \
48 EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), kToleranceRadians) \
49 } \
50 }
Milind Upadhyay7c205222022-11-16 18:20:58 -080051
Milind Upadhyayc5beba12022-12-17 17:41:20 -080052#define EXPECT_POSE_EQ(pose1, pose2) \
53 EXPECT_EQ(pose1.p, pose2.p); \
54 EXPECT_EQ(pose1.q, pose2.q);
Milind Upadhyay7c205222022-11-16 18:20:58 -080055
Milind Upadhyayc5beba12022-12-17 17:41:20 -080056#define EXPECT_QUATERNION_NEAR(q1, q2) \
57 EXPECT_NEAR(q1.x(), q2.x(), kOrientationEqTolerance) << q1 << " != " << q2; \
58 EXPECT_NEAR(q1.y(), q2.y(), kOrientationEqTolerance) << q1 << " != " << q2; \
59 EXPECT_NEAR(q1.z(), q2.z(), kOrientationEqTolerance) << q1 << " != " << q2; \
60 EXPECT_NEAR(q1.w(), q2.w(), kOrientationEqTolerance) << q1 << " != " << q2;
61
62// Expects same roll, pitch, and yaw values (not equivalent rotation)
63#define EXPECT_RPY_EQ(rpy_1, rpy_2) \
64 { \
65 for (size_t i = 0; i < 3; i++) { \
66 SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \
67 rpy_1(i), i, rpy_2(i))); \
68 EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), \
69 kOrientationEqTolerance) \
70 } \
71 }
72
73#define EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw) \
74 { \
75 auto rpy = Eigen::Vector3d(roll, pitch, yaw); \
76 auto converted_rpy = PoseUtils::QuaternionToEulerAngles( \
77 PoseUtils::EulerAnglesToQuaternion(rpy)); \
78 EXPECT_RPY_EQ(converted_rpy, rpy); \
79 }
Milind Upadhyay7c205222022-11-16 18:20:58 -080080
81// Both confidence matrixes should have the same dimensions and be square
82#define EXPECT_CONFIDENCE_GT(confidence1, confidence2) \
83 { \
84 ASSERT_EQ(confidence1.rows(), confidence2.rows()); \
85 ASSERT_EQ(confidence1.rows(), confidence1.cols()); \
86 ASSERT_EQ(confidence2.rows(), confidence2.cols()); \
87 for (size_t i = 0; i < confidence1.rows(); i++) { \
88 EXPECT_GT(confidence1(i, i), confidence2(i, i)); \
89 } \
90 }
91
92namespace {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080093ceres::examples::Pose3d Make2dPose(double x, double y, double yaw_radians) {
94 return ceres::examples::Pose3d{Eigen::Vector3d(x, y, 0.0),
95 PoseUtils::EulerAnglesToQuaternion(
96 Eigen::Vector3d(0.0, 0.0, yaw_radians))};
Milind Upadhyay7c205222022-11-16 18:20:58 -080097}
98
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080099// Assumes camera and robot origin are the same
100DataAdapter::TimestampedDetection MakeTimestampedDetection(
101 aos::distributed_clock::time_point time, Eigen::Affine3d H_robot_target,
milind-ud62f80a2023-03-04 16:37:09 -0800102 TargetMapper::TargetId id, double distortion_factor = 0.001) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800103 auto target_pose = PoseUtils::Affine3dToPose3d(H_robot_target);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800104 return DataAdapter::TimestampedDetection{
milind-ud62f80a2023-03-04 16:37:09 -0800105 .time = time,
106 .H_robot_target = H_robot_target,
107 .distance_from_camera = target_pose.p.norm(),
108 .distortion_factor = distortion_factor,
109 .id = id};
110}
111
112DataAdapter::TimestampedDetection MakeTimestampedDetectionForConfidence(
113 aos::distributed_clock::time_point time, TargetMapper::TargetId id,
114 double distance_from_camera, double distortion_factor) {
115 auto target_pose = ceres::examples::Pose3d{
116 .p = Eigen::Vector3d(distance_from_camera, 0.0, 0.0),
117 .q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0)};
118 return DataAdapter::TimestampedDetection{
119 .time = time,
120 .H_robot_target = PoseUtils::Pose3dToAffine3d(target_pose),
121 .distance_from_camera = target_pose.p.norm(),
122 .distortion_factor = distortion_factor,
123 .id = id};
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800124}
125
Milind Upadhyay7c205222022-11-16 18:20:58 -0800126bool TargetIsInView(TargetMapper::TargetPose target_detection) {
127 // And check if it is within the fov of the robot /
128 // camera, assuming camera is pointing in the
129 // positive x-direction of the robot
130 double angle_to_target =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800131 atan2(target_detection.pose.p(1), target_detection.pose.p(0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800132
133 // Simulated camera field of view, in radians
134 constexpr double kCameraFov = M_PI_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800135 if (std::abs(angle_to_target) <= kCameraFov / 2.0) {
136 VLOG(2) << "Found target in view, based on T = "
137 << target_detection.pose.p(0) << ", " << target_detection.pose.p(1)
138 << " with angle " << angle_to_target;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800139 return true;
140 } else {
141 return false;
142 }
143}
144
145aos::distributed_clock::time_point TimeInMs(size_t ms) {
146 return aos::distributed_clock::time_point(std::chrono::milliseconds(ms));
147}
148
149} // namespace
150
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800151TEST(PoseUtilsTest, EulerAnglesAndQuaternionConversions) {
152 // Make sure that the conversions are consistent back and forth.
153 // These angles shouldn't get changed to a different, equivalent roll pitch
154 // yaw.
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);
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, -M_PI_2);
159 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, 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, 0.0);
162 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, M_PI_4);
163 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(M_PI_4, -M_PI_4, M_PI_4);
164 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(-M_PI_2, -M_PI_4, M_PI_4);
165
166 // Now, do a sweep of roll, pitch, and yaws in the normalized
167 // range.
168 // - roll: (-pi/2, pi/2)
169 // - pitch: (-pi/2, pi/2)
170 // - yaw: [-pi, pi)
171 constexpr double kThetaMaxRoll = M_PI_2 - kToleranceRadians;
172 constexpr double kThetaMaxPitch = M_PI_2 - kToleranceRadians;
173 constexpr double kThetaMaxYaw = M_PI;
174 constexpr double kDeltaTheta = M_PI / 16;
175
176 for (double roll = -kThetaMaxRoll; roll < kThetaMaxRoll;
177 roll += kDeltaTheta) {
178 for (double pitch = -kThetaMaxPitch; pitch < kThetaMaxPitch;
179 pitch += kDeltaTheta) {
180 for (double yaw = -kThetaMaxYaw; yaw < kThetaMaxYaw; yaw += kDeltaTheta) {
181 SCOPED_TRACE(
182 absl::StrFormat("roll: %f, pitch: %f, yaw: %f", roll, pitch, yaw));
183 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw);
184 }
185 }
186 }
187}
188
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800189TEST(DataAdapterTest, ComputeConfidence) {
190 // Check the confidence matrices. Don't check the actual values
191 // in case the constants change, just check that the confidence of contraints
192 // decreases as time period or distances from camera increase.
milind-ud62f80a2023-03-04 16:37:09 -0800193
194 constexpr size_t kIdStart = 0;
195 constexpr size_t kIdEnd = 1;
196
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800197 {
198 // Vary time period
199 constexpr double kDistanceStart = 0.5;
200 constexpr double kDistanceEnd = 2.0;
milind-ud62f80a2023-03-04 16:37:09 -0800201 constexpr double kDistortionFactor = 0.001;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800202
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800203 TargetMapper::ConfidenceMatrix last_confidence =
204 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800205 for (size_t dt = 0; dt < 15; dt++) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800206 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800207 DataAdapter::ComputeConfidence(
208 MakeTimestampedDetectionForConfidence(
209 TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
210 MakeTimestampedDetectionForConfidence(
211 TimeInMs(dt), kIdEnd, kDistanceEnd, kDistortionFactor));
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800212
213 if (dt != 0) {
214 // Confidence only decreases every 5ms (control loop period)
215 if (dt % 5 == 0) {
216 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
217 } else {
218 EXPECT_EQ(last_confidence, confidence);
219 }
220 }
221 last_confidence = confidence;
222 }
223 }
224
225 {
226 // Vary distance at start
227 constexpr int kDt = 3;
228 constexpr double kDistanceEnd = 1.5;
milind-ud62f80a2023-03-04 16:37:09 -0800229 constexpr double kDistortionFactor = 0.001;
230
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800231 TargetMapper::ConfidenceMatrix last_confidence =
232 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800233 for (double distance_start = 0.0; distance_start < 3.0;
234 distance_start += 0.5) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800235 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800236 DataAdapter::ComputeConfidence(
237 MakeTimestampedDetectionForConfidence(
238 TimeInMs(0), kIdStart, distance_start, kDistortionFactor),
239 MakeTimestampedDetectionForConfidence(
240 TimeInMs(kDt), kIdEnd, kDistanceEnd, kDistortionFactor));
241
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800242 if (distance_start != 0.0) {
243 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
244 }
245 last_confidence = confidence;
246 }
247 }
248
249 {
250 // Vary distance at end
251 constexpr int kDt = 2;
252 constexpr double kDistanceStart = 2.5;
milind-ud62f80a2023-03-04 16:37:09 -0800253 constexpr double kDistortionFactor = 0.001;
254
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800255 TargetMapper::ConfidenceMatrix last_confidence =
256 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800257 for (double distance_end = 0.0; distance_end < 3.0; distance_end += 0.5) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800258 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800259 DataAdapter::ComputeConfidence(
260 MakeTimestampedDetectionForConfidence(
261 TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
262 MakeTimestampedDetectionForConfidence(
263 TimeInMs(kDt), kIdEnd, distance_end, kDistortionFactor));
264
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800265 if (distance_end != 0.0) {
266 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
267 }
268 last_confidence = confidence;
269 }
270 }
milind-ud62f80a2023-03-04 16:37:09 -0800271
272 {
273 // Vary distortion factor
274 constexpr int kDt = 2;
275 constexpr double kDistanceStart = 2.5;
276 constexpr double kDistanceEnd = 1.5;
277
278 TargetMapper::ConfidenceMatrix last_confidence =
279 TargetMapper::ConfidenceMatrix::Zero();
280 for (double distortion_factor = 0.0; distortion_factor <= 1.0;
281 distortion_factor += 0.01) {
282 TargetMapper::ConfidenceMatrix confidence =
283 DataAdapter::ComputeConfidence(
284 MakeTimestampedDetectionForConfidence(
285 TimeInMs(0), kIdStart, kDistanceStart, distortion_factor),
286 MakeTimestampedDetectionForConfidence(
287 TimeInMs(kDt), kIdEnd, kDistanceEnd, distortion_factor));
288
289 if (distortion_factor != 0.0) {
290 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
291 }
292 last_confidence = confidence;
293 }
294 }
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800295}
296
Milind Upadhyayec493912022-12-18 21:33:15 -0800297TEST(DataAdapterTest, MatchTargetDetections) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800298 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800299 {MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800300 TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -5.0, 0.0)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800301 2),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800302 MakeTimestampedDetection(
303 TimeInMs(6),
304 PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -4.0, M_PI)), 0),
305 MakeTimestampedDetection(
306 TimeInMs(10),
307 PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, -3.0, M_PI)), 1),
308 MakeTimestampedDetection(
309 TimeInMs(13),
310 PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -7.0, M_PI_2)), 2),
311 MakeTimestampedDetection(
312 TimeInMs(14),
313 PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -4.0, M_PI_2)), 2)};
Milind Upadhyayec493912022-12-18 21:33:15 -0800314
Milind Upadhyayec493912022-12-18 21:33:15 -0800315 auto target_constraints =
316 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
317
318 // The constraint between the detection at 6ms and the one at 10 ms is skipped
319 // because dt > kMaxDt.
320 // Also, the constraint between the last two detections is skipped because
321 // they are the same target
322 EXPECT_EQ(target_constraints.size(),
323 timestamped_target_detections.size() - 3);
324
325 // Between 5ms and 6ms detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800326 EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(0), 0.0);
327 EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(1), 1.0);
328 EXPECT_QUATERNION_NEAR(
329 target_constraints[0].t_be.q,
330 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, M_PI)));
Milind Upadhyayec493912022-12-18 21:33:15 -0800331 EXPECT_EQ(target_constraints[0].id_begin, 2);
332 EXPECT_EQ(target_constraints[0].id_end, 0);
333
334 // Between 10ms and 13ms detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800335 EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(0), -1.0);
336 EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(1), 4.0);
337 EXPECT_QUATERNION_NEAR(
338 target_constraints[1].t_be.q,
339 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, -M_PI_2)));
Milind Upadhyayec493912022-12-18 21:33:15 -0800340 EXPECT_EQ(target_constraints[1].id_begin, 1);
341 EXPECT_EQ(target_constraints[1].id_end, 2);
342}
343
Milind Upadhyay7c205222022-11-16 18:20:58 -0800344TEST(TargetMapperTest, TwoTargetsOneConstraint) {
milind-u8f4e43e2023-04-09 17:11:19 -0700345 FLAGS_min_target_id = 0;
346 FLAGS_max_target_id = 1;
347
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800348 ceres::examples::MapOfPoses target_poses;
349 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
350 target_poses[1] = Make2dPose(-5.0, 0.0, 0.0);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800351
Milind Upadhyay7c205222022-11-16 18:20:58 -0800352 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800353 {MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800354 TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, 0.0, M_PI)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800355 0),
356 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800357 TimeInMs(6), PoseUtils::Pose3dToAffine3d(Make2dPose(-7.0, 0.0, 0.0)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800358 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800359 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800360 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800361
362 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800363 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800364
365 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800366 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
367 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800368}
369
370TEST(TargetMapperTest, TwoTargetsTwoConstraints) {
milind-u8f4e43e2023-04-09 17:11:19 -0700371 FLAGS_min_target_id = 0;
372 FLAGS_max_target_id = 1;
373
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800374 ceres::examples::MapOfPoses target_poses;
375 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
376 target_poses[1] = Make2dPose(-5.0, 0.0, -M_PI_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800377
Milind Upadhyay7c205222022-11-16 18:20:58 -0800378 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800379 {MakeTimestampedDetection(
380 TimeInMs(5),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800381 PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 0.0, M_PI_2)), 0),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800382 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800383 TimeInMs(7),
384 PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 10.0, -M_PI)), 1),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800385 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800386 TimeInMs(12),
387 PoseUtils::Pose3dToAffine3d(Make2dPose(1.0, 0.0, M_PI)), 0),
388 MakeTimestampedDetection(
389 TimeInMs(13),
390 PoseUtils::Pose3dToAffine3d(Make2dPose(-9.0, 0.0, -M_PI_2)), 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800391 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800392 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800393
394 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800395 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800396
397 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800398 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
399 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, -M_PI_2));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800400}
401
402TEST(TargetMapperTest, TwoTargetsOneNoisyConstraint) {
milind-u8f4e43e2023-04-09 17:11:19 -0700403 FLAGS_min_target_id = 0;
404 FLAGS_max_target_id = 1;
405
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800406 ceres::examples::MapOfPoses target_poses;
407 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
408 target_poses[1] = Make2dPose(-5.0, 0.0, 0.0);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800409
Milind Upadhyay7c205222022-11-16 18:20:58 -0800410 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800411 {MakeTimestampedDetection(
412 TimeInMs(5),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800413 PoseUtils::Pose3dToAffine3d(Make2dPose(3.01, 0.001, M_PI - 0.001)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800414 0),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800415 MakeTimestampedDetection(
416 TimeInMs(7),
417 PoseUtils::Pose3dToAffine3d(Make2dPose(-7.01, 0.0, 0.0)), 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800418
419 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800420 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800421
422 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800423 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800424
425 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800426 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
427 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800428}
429
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800430class ChargedUpTargetMapperTest : public ::testing::Test {
431 public:
432 ChargedUpTargetMapperTest() : generator_(aos::testing::RandomSeed()) {}
433
434 // Generates noisy target detection if target in camera FOV
435 std::optional<DataAdapter::TimestampedDetection> MaybeGenerateNoisyDetection(
436 const ceres::examples::Pose3d &robot_pose,
437 const TargetMapper::TargetPose &target_pose, size_t t,
438 bool force_in_view = false) {
439 TargetMapper::TargetPose target_detection = {
440 .id = target_pose.id,
441 .pose = PoseUtils::ComputeRelativePose(robot_pose, target_pose.pose)};
442 if (force_in_view || TargetIsInView(target_detection)) {
443 // Define random generator with Gaussian
444 // distribution
445 constexpr double kMean = 0.0;
446 constexpr double kStdDev = 1.0;
447 // Can play with this to see how it impacts
448 // randomness
449 constexpr double kNoiseScalePosition = 0.01;
450 constexpr double kNoiseScaleOrientation = 0.0005;
451 std::normal_distribution<double> dist(kMean, kStdDev);
452
453 target_detection.pose.p(0) += dist(generator_) * kNoiseScalePosition;
454 target_detection.pose.p(1) += dist(generator_) * kNoiseScalePosition;
455 target_detection.pose.p(2) += dist(generator_) * kNoiseScalePosition;
456
457 target_detection.pose.q.w() += dist(generator_) * kNoiseScaleOrientation;
458 target_detection.pose.q.x() += dist(generator_) * kNoiseScaleOrientation;
459 target_detection.pose.q.y() += dist(generator_) * kNoiseScaleOrientation;
460 target_detection.pose.q.z() += dist(generator_) * kNoiseScaleOrientation;
461
milind-ud62f80a2023-03-04 16:37:09 -0800462 // Get most distortion factors close to zero, but have a few outliers
463 const std::vector<double> kDistortionFactorIntervals = {0.0, 0.01, 1.0};
464 const std::vector<double> kDistortionFactorWeights = {0.9, 0.1};
465 std::piecewise_constant_distribution<double> distortion_factor_dist(
466 kDistortionFactorIntervals.begin(), kDistortionFactorIntervals.end(),
467 kDistortionFactorWeights.begin());
468 double distortion_factor = distortion_factor_dist(generator_);
469
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800470 auto time_point = TimeInMs(t);
471 return MakeTimestampedDetection(
472 time_point, PoseUtils::Pose3dToAffine3d(target_detection.pose),
milind-ud62f80a2023-03-04 16:37:09 -0800473 target_detection.id, distortion_factor);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800474 }
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800475
476 return std::nullopt;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800477 }
478
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800479 private:
480 std::default_random_engine generator_;
481};
482
483// Drive in a circle around the 2023 field, and add a bit of randomness to 3d
milind-u401de982023-04-14 17:32:03 -0700484// pose detections.
485// TODO(milind): use valgrind to debug why this test passes, but then segfaults
486// when freeing memory. For some reason this segfault occurs only in this test,
487// but when running the test with gdb it doesn't occur...
488TEST_F(ChargedUpTargetMapperTest, DISABLED_FieldCircleMotion) {
489 FLAGS_min_target_id = 1;
490 FLAGS_max_target_id = 8;
491
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800492 // Read target map
493 auto target_map_fbs = aos::JsonFileToFlatbuffer<TargetMap>(
494 aos::testing::ArtifactPath("frc971/vision/target_map.json"));
495
496 std::vector<TargetMapper::TargetPose> actual_target_poses;
497 ceres::examples::MapOfPoses target_poses;
milind-u3f5f83c2023-01-29 15:23:51 -0800498 for (const auto *target_pose_fbs : *target_map_fbs.message().target_poses()) {
499 const TargetMapper::TargetPose target_pose =
500 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800501 actual_target_poses.emplace_back(target_pose);
502 target_poses[target_pose.id] = target_pose.pose;
503 }
504
505 double kFieldHalfLength = 16.54 / 2.0; // half length of the field
506 double kFieldHalfWidth = 8.02 / 2.0; // half width of the field
507
Milind Upadhyay7c205222022-11-16 18:20:58 -0800508 // Now, create a bunch of robot poses and target
509 // observations
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800510 constexpr size_t kDt = 5;
511 constexpr double kRobotZ = 1.0;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800512
Milind Upadhyay7c205222022-11-16 18:20:58 -0800513 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
514
515 constexpr size_t kTotalSteps = 100;
516 for (size_t step_count = 0; step_count < kTotalSteps; step_count++) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800517 size_t t = kDt * step_count;
518
Milind Upadhyay7c205222022-11-16 18:20:58 -0800519 // Circle clockwise around the center of the field
520 double robot_theta = t;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800521
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800522 constexpr double kRadiusScalar = 0.5;
523 double robot_x = (kRadiusScalar * kFieldHalfLength) * cos(robot_theta);
524 double robot_y = (kRadiusScalar * -kFieldHalfWidth) * sin(robot_theta);
525
526 auto robot_pose =
527 ceres::examples::Pose3d{.p = Eigen::Vector3d(robot_x, robot_y, kRobotZ),
528 .q = PoseUtils::EulerAnglesToQuaternion(
529 Eigen::Vector3d(robot_theta, 0.0, 0.0))};
530
Milind Upadhyay7c205222022-11-16 18:20:58 -0800531 for (TargetMapper::TargetPose target_pose : actual_target_poses) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800532 auto optional_detection =
533 MaybeGenerateNoisyDetection(robot_pose, target_pose, t);
534 if (optional_detection.has_value()) {
535 timestamped_target_detections.emplace_back(*optional_detection);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800536 }
537 }
538 }
539
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800540 // The above circular motion only captures targets 1-4, so add another
541 // detection with the camera looking at targets 5-8, and 4 at the same time to
542 // have a connection to the rest of the targets
Milind Upadhyay7c205222022-11-16 18:20:58 -0800543 {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800544 auto last_robot_pose =
545 ceres::examples::Pose3d{.p = Eigen::Vector3d(0.0, 0.0, kRobotZ),
546 .q = PoseUtils::EulerAnglesToQuaternion(
547 Eigen::Vector3d(0.0, 0.0, M_PI))};
548 for (size_t id = 4; id <= 8; id++) {
549 auto target_pose =
550 TargetMapper::GetTargetPoseById(actual_target_poses, id).value();
551 auto optional_detection = MaybeGenerateNoisyDetection(
552 last_robot_pose, target_pose, kTotalSteps * kDt, true);
553
554 ASSERT_TRUE(optional_detection.has_value())
555 << "Didn't detect target " << target_pose.id;
556 timestamped_target_detections.emplace_back(*optional_detection);
557 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800558 }
559
560 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800561 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800562 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800563 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800564
565 for (auto [target_pose_id, mapper_target_pose] : mapper.target_poses()) {
566 TargetMapper::TargetPose actual_target_pose =
567 TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id)
568 .value();
569 EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose);
570 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800571}
572
573} // namespace frc971::vision