blob: 4e9db6fa9fbfc4db13f597f9ae5e67dec365a4d1 [file] [log] [blame]
Milind Upadhyay7c205222022-11-16 18:20:58 -08001#include "frc971/vision/target_mapper.h"
2
3#include <random>
4
Austin Schuh99f7c6a2024-06-25 22:07:44 -07005#include "absl/flags/declare.h"
6#include "absl/flags/flag.h"
7#include "absl/log/check.h"
8#include "absl/log/log.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07009#include "gtest/gtest.h"
10
Milind Upadhyay7c205222022-11-16 18:20:58 -080011#include "aos/events/simulated_event_loop.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -080012#include "aos/testing/path.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080013#include "aos/testing/random_seed.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -080014#include "aos/util/math.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -080015
Austin Schuh99f7c6a2024-06-25 22:07:44 -070016ABSL_DECLARE_FLAG(int32_t, min_target_id);
17ABSL_DECLARE_FLAG(int32_t, max_target_id);
milind-u8f4e43e2023-04-09 17:11:19 -070018
Milind Upadhyay7c205222022-11-16 18:20:58 -080019namespace frc971::vision {
20
21namespace {
22constexpr double kToleranceMeters = 0.05;
23constexpr double kToleranceRadians = 0.05;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080024// Conversions between euler angles and quaternion result in slightly-off
25// doubles
26constexpr double kOrientationEqTolerance = 1e-10;
27constexpr std::chrono::milliseconds kMaxDt = std::chrono::milliseconds(3);
Milind Upadhyay05652cb2022-12-07 20:51:51 -080028constexpr std::string_view kFieldName = "test";
Milind Upadhyay7c205222022-11-16 18:20:58 -080029} // namespace
30
Milind Upadhyayc5beba12022-12-17 17:41:20 -080031// Angles normalized by aos::math::NormalizeAngle()
32#define EXPECT_NORMALIZED_ANGLES_NEAR(theta1, theta2, tolerance) \
33 { \
34 double delta = std::abs(aos::math::DiffAngle(theta1, theta2)); \
35 /* Have to check delta - 2pi for the case that one angle is very */ \
36 /* close to -pi, and the other is very close to +pi */ \
37 EXPECT_TRUE(delta < tolerance || std::abs(aos::math::DiffAngle( \
38 delta, 2.0 * M_PI)) < tolerance); \
Milind Upadhyay7c205222022-11-16 18:20:58 -080039 }
40
Milind Upadhyayc5beba12022-12-17 17:41:20 -080041#define EXPECT_POSE_NEAR(pose1, pose2) \
42 { \
43 for (size_t i = 0; i < 3; i++) { \
44 EXPECT_NEAR(pose1.p(i), pose2.p(i), kToleranceMeters); \
45 } \
46 auto rpy_1 = PoseUtils::QuaternionToEulerAngles(pose1.q); \
47 auto rpy_2 = PoseUtils::QuaternionToEulerAngles(pose2.q); \
48 for (size_t i = 0; i < 3; i++) { \
49 SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \
50 rpy_1(i), i, rpy_2(i))); \
51 EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), kToleranceRadians) \
52 } \
53 }
Milind Upadhyay7c205222022-11-16 18:20:58 -080054
Milind Upadhyayc5beba12022-12-17 17:41:20 -080055#define EXPECT_POSE_EQ(pose1, pose2) \
56 EXPECT_EQ(pose1.p, pose2.p); \
57 EXPECT_EQ(pose1.q, pose2.q);
Milind Upadhyay7c205222022-11-16 18:20:58 -080058
Milind Upadhyayc5beba12022-12-17 17:41:20 -080059#define EXPECT_QUATERNION_NEAR(q1, q2) \
60 EXPECT_NEAR(q1.x(), q2.x(), kOrientationEqTolerance) << q1 << " != " << q2; \
61 EXPECT_NEAR(q1.y(), q2.y(), kOrientationEqTolerance) << q1 << " != " << q2; \
62 EXPECT_NEAR(q1.z(), q2.z(), kOrientationEqTolerance) << q1 << " != " << q2; \
63 EXPECT_NEAR(q1.w(), q2.w(), kOrientationEqTolerance) << q1 << " != " << q2;
64
65// Expects same roll, pitch, and yaw values (not equivalent rotation)
66#define EXPECT_RPY_EQ(rpy_1, rpy_2) \
67 { \
68 for (size_t i = 0; i < 3; i++) { \
69 SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \
70 rpy_1(i), i, rpy_2(i))); \
71 EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), \
72 kOrientationEqTolerance) \
73 } \
74 }
75
76#define EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw) \
77 { \
78 auto rpy = Eigen::Vector3d(roll, pitch, yaw); \
79 auto converted_rpy = PoseUtils::QuaternionToEulerAngles( \
80 PoseUtils::EulerAnglesToQuaternion(rpy)); \
81 EXPECT_RPY_EQ(converted_rpy, rpy); \
82 }
Milind Upadhyay7c205222022-11-16 18:20:58 -080083
84// Both confidence matrixes should have the same dimensions and be square
85#define EXPECT_CONFIDENCE_GT(confidence1, confidence2) \
86 { \
87 ASSERT_EQ(confidence1.rows(), confidence2.rows()); \
88 ASSERT_EQ(confidence1.rows(), confidence1.cols()); \
89 ASSERT_EQ(confidence2.rows(), confidence2.cols()); \
90 for (size_t i = 0; i < confidence1.rows(); i++) { \
91 EXPECT_GT(confidence1(i, i), confidence2(i, i)); \
92 } \
93 }
94
95namespace {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080096ceres::examples::Pose3d Make2dPose(double x, double y, double yaw_radians) {
97 return ceres::examples::Pose3d{Eigen::Vector3d(x, y, 0.0),
98 PoseUtils::EulerAnglesToQuaternion(
99 Eigen::Vector3d(0.0, 0.0, yaw_radians))};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800100}
101
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800102// Assumes camera and robot origin are the same
103DataAdapter::TimestampedDetection MakeTimestampedDetection(
104 aos::distributed_clock::time_point time, Eigen::Affine3d H_robot_target,
milind-ud62f80a2023-03-04 16:37:09 -0800105 TargetMapper::TargetId id, double distortion_factor = 0.001) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800106 auto target_pose = PoseUtils::Affine3dToPose3d(H_robot_target);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800107 return DataAdapter::TimestampedDetection{
milind-ud62f80a2023-03-04 16:37:09 -0800108 .time = time,
109 .H_robot_target = H_robot_target,
110 .distance_from_camera = target_pose.p.norm(),
111 .distortion_factor = distortion_factor,
112 .id = id};
113}
114
115DataAdapter::TimestampedDetection MakeTimestampedDetectionForConfidence(
116 aos::distributed_clock::time_point time, TargetMapper::TargetId id,
117 double distance_from_camera, double distortion_factor) {
118 auto target_pose = ceres::examples::Pose3d{
119 .p = Eigen::Vector3d(distance_from_camera, 0.0, 0.0),
120 .q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0)};
121 return DataAdapter::TimestampedDetection{
122 .time = time,
123 .H_robot_target = PoseUtils::Pose3dToAffine3d(target_pose),
124 .distance_from_camera = target_pose.p.norm(),
125 .distortion_factor = distortion_factor,
126 .id = id};
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800127}
128
Milind Upadhyay7c205222022-11-16 18:20:58 -0800129bool TargetIsInView(TargetMapper::TargetPose target_detection) {
130 // And check if it is within the fov of the robot /
131 // camera, assuming camera is pointing in the
132 // positive x-direction of the robot
133 double angle_to_target =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800134 atan2(target_detection.pose.p(1), target_detection.pose.p(0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800135
136 // Simulated camera field of view, in radians
137 constexpr double kCameraFov = M_PI_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800138 if (std::abs(angle_to_target) <= kCameraFov / 2.0) {
139 VLOG(2) << "Found target in view, based on T = "
140 << target_detection.pose.p(0) << ", " << target_detection.pose.p(1)
141 << " with angle " << angle_to_target;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800142 return true;
143 } else {
144 return false;
145 }
146}
147
148aos::distributed_clock::time_point TimeInMs(size_t ms) {
149 return aos::distributed_clock::time_point(std::chrono::milliseconds(ms));
150}
151
152} // namespace
153
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800154TEST(PoseUtilsTest, EulerAnglesAndQuaternionConversions) {
155 // Make sure that the conversions are consistent back and forth.
156 // These angles shouldn't get changed to a different, equivalent roll pitch
157 // yaw.
158 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, M_PI);
159 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, -M_PI);
160 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, M_PI_2);
161 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, -M_PI_2);
162 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, 0.0);
163 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, M_PI_4, 0.0);
164 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, 0.0);
165 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, M_PI_4);
166 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(M_PI_4, -M_PI_4, M_PI_4);
167 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(-M_PI_2, -M_PI_4, M_PI_4);
168
169 // Now, do a sweep of roll, pitch, and yaws in the normalized
170 // range.
171 // - roll: (-pi/2, pi/2)
172 // - pitch: (-pi/2, pi/2)
173 // - yaw: [-pi, pi)
174 constexpr double kThetaMaxRoll = M_PI_2 - kToleranceRadians;
175 constexpr double kThetaMaxPitch = M_PI_2 - kToleranceRadians;
176 constexpr double kThetaMaxYaw = M_PI;
177 constexpr double kDeltaTheta = M_PI / 16;
178
179 for (double roll = -kThetaMaxRoll; roll < kThetaMaxRoll;
180 roll += kDeltaTheta) {
181 for (double pitch = -kThetaMaxPitch; pitch < kThetaMaxPitch;
182 pitch += kDeltaTheta) {
183 for (double yaw = -kThetaMaxYaw; yaw < kThetaMaxYaw; yaw += kDeltaTheta) {
184 SCOPED_TRACE(
185 absl::StrFormat("roll: %f, pitch: %f, yaw: %f", roll, pitch, yaw));
186 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw);
187 }
188 }
189 }
190}
191
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800192TEST(DataAdapterTest, ComputeConfidence) {
193 // Check the confidence matrices. Don't check the actual values
194 // in case the constants change, just check that the confidence of contraints
195 // decreases as time period or distances from camera increase.
milind-ud62f80a2023-03-04 16:37:09 -0800196
197 constexpr size_t kIdStart = 0;
198 constexpr size_t kIdEnd = 1;
199
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800200 {
201 // Vary time period
202 constexpr double kDistanceStart = 0.5;
203 constexpr double kDistanceEnd = 2.0;
milind-ud62f80a2023-03-04 16:37:09 -0800204 constexpr double kDistortionFactor = 0.001;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800205
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800206 TargetMapper::ConfidenceMatrix last_confidence =
207 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800208 for (size_t dt = 0; dt < 15; dt++) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800209 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800210 DataAdapter::ComputeConfidence(
211 MakeTimestampedDetectionForConfidence(
212 TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
213 MakeTimestampedDetectionForConfidence(
214 TimeInMs(dt), kIdEnd, kDistanceEnd, kDistortionFactor));
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800215
216 if (dt != 0) {
217 // Confidence only decreases every 5ms (control loop period)
218 if (dt % 5 == 0) {
219 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
220 } else {
221 EXPECT_EQ(last_confidence, confidence);
222 }
223 }
224 last_confidence = confidence;
225 }
226 }
227
228 {
229 // Vary distance at start
230 constexpr int kDt = 3;
231 constexpr double kDistanceEnd = 1.5;
milind-ud62f80a2023-03-04 16:37:09 -0800232 constexpr double kDistortionFactor = 0.001;
233
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800234 TargetMapper::ConfidenceMatrix last_confidence =
235 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800236 for (double distance_start = 0.0; distance_start < 3.0;
237 distance_start += 0.5) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800238 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800239 DataAdapter::ComputeConfidence(
240 MakeTimestampedDetectionForConfidence(
241 TimeInMs(0), kIdStart, distance_start, kDistortionFactor),
242 MakeTimestampedDetectionForConfidence(
243 TimeInMs(kDt), kIdEnd, kDistanceEnd, kDistortionFactor));
244
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800245 if (distance_start != 0.0) {
246 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
247 }
248 last_confidence = confidence;
249 }
250 }
251
252 {
253 // Vary distance at end
254 constexpr int kDt = 2;
255 constexpr double kDistanceStart = 2.5;
milind-ud62f80a2023-03-04 16:37:09 -0800256 constexpr double kDistortionFactor = 0.001;
257
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800258 TargetMapper::ConfidenceMatrix last_confidence =
259 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800260 for (double distance_end = 0.0; distance_end < 3.0; distance_end += 0.5) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800261 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800262 DataAdapter::ComputeConfidence(
263 MakeTimestampedDetectionForConfidence(
264 TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
265 MakeTimestampedDetectionForConfidence(
266 TimeInMs(kDt), kIdEnd, distance_end, kDistortionFactor));
267
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800268 if (distance_end != 0.0) {
269 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
270 }
271 last_confidence = confidence;
272 }
273 }
milind-ud62f80a2023-03-04 16:37:09 -0800274
275 {
276 // Vary distortion factor
277 constexpr int kDt = 2;
278 constexpr double kDistanceStart = 2.5;
279 constexpr double kDistanceEnd = 1.5;
280
281 TargetMapper::ConfidenceMatrix last_confidence =
282 TargetMapper::ConfidenceMatrix::Zero();
283 for (double distortion_factor = 0.0; distortion_factor <= 1.0;
284 distortion_factor += 0.01) {
285 TargetMapper::ConfidenceMatrix confidence =
286 DataAdapter::ComputeConfidence(
287 MakeTimestampedDetectionForConfidence(
288 TimeInMs(0), kIdStart, kDistanceStart, distortion_factor),
289 MakeTimestampedDetectionForConfidence(
290 TimeInMs(kDt), kIdEnd, kDistanceEnd, distortion_factor));
291
292 if (distortion_factor != 0.0) {
293 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
294 }
295 last_confidence = confidence;
296 }
297 }
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800298}
299
Milind Upadhyayec493912022-12-18 21:33:15 -0800300TEST(DataAdapterTest, MatchTargetDetections) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800301 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800302 {MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800303 TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -5.0, 0.0)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800304 2),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800305 MakeTimestampedDetection(
306 TimeInMs(6),
307 PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -4.0, M_PI)), 0),
308 MakeTimestampedDetection(
309 TimeInMs(10),
310 PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, -3.0, M_PI)), 1),
311 MakeTimestampedDetection(
312 TimeInMs(13),
313 PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -7.0, M_PI_2)), 2),
314 MakeTimestampedDetection(
315 TimeInMs(14),
316 PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -4.0, M_PI_2)), 2)};
Milind Upadhyayec493912022-12-18 21:33:15 -0800317
Milind Upadhyayec493912022-12-18 21:33:15 -0800318 auto target_constraints =
319 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
320
321 // The constraint between the detection at 6ms and the one at 10 ms is skipped
322 // because dt > kMaxDt.
323 // Also, the constraint between the last two detections is skipped because
324 // they are the same target
325 EXPECT_EQ(target_constraints.size(),
326 timestamped_target_detections.size() - 3);
327
328 // Between 5ms and 6ms detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800329 EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(0), 0.0);
330 EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(1), 1.0);
331 EXPECT_QUATERNION_NEAR(
332 target_constraints[0].t_be.q,
333 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, M_PI)));
Milind Upadhyayec493912022-12-18 21:33:15 -0800334 EXPECT_EQ(target_constraints[0].id_begin, 2);
335 EXPECT_EQ(target_constraints[0].id_end, 0);
336
337 // Between 10ms and 13ms detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800338 EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(0), -1.0);
339 EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(1), 4.0);
340 EXPECT_QUATERNION_NEAR(
341 target_constraints[1].t_be.q,
342 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, -M_PI_2)));
Milind Upadhyayec493912022-12-18 21:33:15 -0800343 EXPECT_EQ(target_constraints[1].id_begin, 1);
344 EXPECT_EQ(target_constraints[1].id_end, 2);
345}
346
Milind Upadhyay7c205222022-11-16 18:20:58 -0800347TEST(TargetMapperTest, TwoTargetsOneConstraint) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700348 absl::SetFlag(&FLAGS_min_target_id, 0);
349 absl::SetFlag(&FLAGS_max_target_id, 1);
milind-u8f4e43e2023-04-09 17:11:19 -0700350
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800351 ceres::examples::MapOfPoses target_poses;
352 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
353 target_poses[1] = Make2dPose(-5.0, 0.0, 0.0);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800354
Milind Upadhyay7c205222022-11-16 18:20:58 -0800355 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800356 {MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800357 TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, 0.0, M_PI)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800358 0),
359 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800360 TimeInMs(6), PoseUtils::Pose3dToAffine3d(Make2dPose(-7.0, 0.0, 0.0)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800361 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800362 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800363 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800364
365 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800366 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800367
368 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800369 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
370 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800371}
372
373TEST(TargetMapperTest, TwoTargetsTwoConstraints) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700374 absl::SetFlag(&FLAGS_min_target_id, 0);
375 absl::SetFlag(&FLAGS_max_target_id, 1);
milind-u8f4e43e2023-04-09 17:11:19 -0700376
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800377 ceres::examples::MapOfPoses target_poses;
378 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
379 target_poses[1] = Make2dPose(-5.0, 0.0, -M_PI_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800380
Milind Upadhyay7c205222022-11-16 18:20:58 -0800381 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800382 {MakeTimestampedDetection(
383 TimeInMs(5),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800384 PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 0.0, M_PI_2)), 0),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800385 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800386 TimeInMs(7),
387 PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 10.0, -M_PI)), 1),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800388 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800389 TimeInMs(12),
390 PoseUtils::Pose3dToAffine3d(Make2dPose(1.0, 0.0, M_PI)), 0),
391 MakeTimestampedDetection(
392 TimeInMs(13),
393 PoseUtils::Pose3dToAffine3d(Make2dPose(-9.0, 0.0, -M_PI_2)), 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800394 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800395 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800396
397 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800398 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800399
400 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800401 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
402 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, -M_PI_2));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800403}
404
405TEST(TargetMapperTest, TwoTargetsOneNoisyConstraint) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700406 absl::SetFlag(&FLAGS_min_target_id, 0);
407 absl::SetFlag(&FLAGS_max_target_id, 1);
milind-u8f4e43e2023-04-09 17:11:19 -0700408
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800409 ceres::examples::MapOfPoses target_poses;
410 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
411 target_poses[1] = Make2dPose(-5.0, 0.0, 0.0);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800412
Milind Upadhyay7c205222022-11-16 18:20:58 -0800413 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800414 {MakeTimestampedDetection(
415 TimeInMs(5),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800416 PoseUtils::Pose3dToAffine3d(Make2dPose(3.01, 0.001, M_PI - 0.001)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800417 0),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800418 MakeTimestampedDetection(
419 TimeInMs(7),
420 PoseUtils::Pose3dToAffine3d(Make2dPose(-7.01, 0.0, 0.0)), 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800421
422 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800423 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800424
425 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800426 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800427
428 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800429 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
430 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800431}
432
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800433class ChargedUpTargetMapperTest : public ::testing::Test {
434 public:
435 ChargedUpTargetMapperTest() : generator_(aos::testing::RandomSeed()) {}
436
437 // Generates noisy target detection if target in camera FOV
438 std::optional<DataAdapter::TimestampedDetection> MaybeGenerateNoisyDetection(
439 const ceres::examples::Pose3d &robot_pose,
440 const TargetMapper::TargetPose &target_pose, size_t t,
441 bool force_in_view = false) {
442 TargetMapper::TargetPose target_detection = {
443 .id = target_pose.id,
444 .pose = PoseUtils::ComputeRelativePose(robot_pose, target_pose.pose)};
445 if (force_in_view || TargetIsInView(target_detection)) {
446 // Define random generator with Gaussian
447 // distribution
448 constexpr double kMean = 0.0;
449 constexpr double kStdDev = 1.0;
450 // Can play with this to see how it impacts
451 // randomness
452 constexpr double kNoiseScalePosition = 0.01;
453 constexpr double kNoiseScaleOrientation = 0.0005;
454 std::normal_distribution<double> dist(kMean, kStdDev);
455
456 target_detection.pose.p(0) += dist(generator_) * kNoiseScalePosition;
457 target_detection.pose.p(1) += dist(generator_) * kNoiseScalePosition;
458 target_detection.pose.p(2) += dist(generator_) * kNoiseScalePosition;
459
460 target_detection.pose.q.w() += dist(generator_) * kNoiseScaleOrientation;
461 target_detection.pose.q.x() += dist(generator_) * kNoiseScaleOrientation;
462 target_detection.pose.q.y() += dist(generator_) * kNoiseScaleOrientation;
463 target_detection.pose.q.z() += dist(generator_) * kNoiseScaleOrientation;
464
milind-ud62f80a2023-03-04 16:37:09 -0800465 // Get most distortion factors close to zero, but have a few outliers
466 const std::vector<double> kDistortionFactorIntervals = {0.0, 0.01, 1.0};
467 const std::vector<double> kDistortionFactorWeights = {0.9, 0.1};
468 std::piecewise_constant_distribution<double> distortion_factor_dist(
469 kDistortionFactorIntervals.begin(), kDistortionFactorIntervals.end(),
470 kDistortionFactorWeights.begin());
471 double distortion_factor = distortion_factor_dist(generator_);
472
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800473 auto time_point = TimeInMs(t);
474 return MakeTimestampedDetection(
475 time_point, PoseUtils::Pose3dToAffine3d(target_detection.pose),
milind-ud62f80a2023-03-04 16:37:09 -0800476 target_detection.id, distortion_factor);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800477 }
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800478
479 return std::nullopt;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800480 }
481
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800482 private:
483 std::default_random_engine generator_;
484};
485
486// Drive in a circle around the 2023 field, and add a bit of randomness to 3d
milind-u401de982023-04-14 17:32:03 -0700487// pose detections.
488// TODO(milind): use valgrind to debug why this test passes, but then segfaults
489// when freeing memory. For some reason this segfault occurs only in this test,
490// but when running the test with gdb it doesn't occur...
491TEST_F(ChargedUpTargetMapperTest, DISABLED_FieldCircleMotion) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700492 absl::SetFlag(&FLAGS_min_target_id, 1);
493 absl::SetFlag(&FLAGS_max_target_id, 8);
milind-u401de982023-04-14 17:32:03 -0700494
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800495 // Read target map
496 auto target_map_fbs = aos::JsonFileToFlatbuffer<TargetMap>(
497 aos::testing::ArtifactPath("frc971/vision/target_map.json"));
498
499 std::vector<TargetMapper::TargetPose> actual_target_poses;
500 ceres::examples::MapOfPoses target_poses;
milind-u3f5f83c2023-01-29 15:23:51 -0800501 for (const auto *target_pose_fbs : *target_map_fbs.message().target_poses()) {
502 const TargetMapper::TargetPose target_pose =
503 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800504 actual_target_poses.emplace_back(target_pose);
505 target_poses[target_pose.id] = target_pose.pose;
506 }
507
508 double kFieldHalfLength = 16.54 / 2.0; // half length of the field
509 double kFieldHalfWidth = 8.02 / 2.0; // half width of the field
510
Milind Upadhyay7c205222022-11-16 18:20:58 -0800511 // Now, create a bunch of robot poses and target
512 // observations
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800513 constexpr size_t kDt = 5;
514 constexpr double kRobotZ = 1.0;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800515
Milind Upadhyay7c205222022-11-16 18:20:58 -0800516 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
517
518 constexpr size_t kTotalSteps = 100;
519 for (size_t step_count = 0; step_count < kTotalSteps; step_count++) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800520 size_t t = kDt * step_count;
521
Milind Upadhyay7c205222022-11-16 18:20:58 -0800522 // Circle clockwise around the center of the field
523 double robot_theta = t;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800524
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800525 constexpr double kRadiusScalar = 0.5;
526 double robot_x = (kRadiusScalar * kFieldHalfLength) * cos(robot_theta);
527 double robot_y = (kRadiusScalar * -kFieldHalfWidth) * sin(robot_theta);
528
529 auto robot_pose =
530 ceres::examples::Pose3d{.p = Eigen::Vector3d(robot_x, robot_y, kRobotZ),
531 .q = PoseUtils::EulerAnglesToQuaternion(
532 Eigen::Vector3d(robot_theta, 0.0, 0.0))};
533
Milind Upadhyay7c205222022-11-16 18:20:58 -0800534 for (TargetMapper::TargetPose target_pose : actual_target_poses) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800535 auto optional_detection =
536 MaybeGenerateNoisyDetection(robot_pose, target_pose, t);
537 if (optional_detection.has_value()) {
538 timestamped_target_detections.emplace_back(*optional_detection);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800539 }
540 }
541 }
542
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800543 // The above circular motion only captures targets 1-4, so add another
544 // detection with the camera looking at targets 5-8, and 4 at the same time to
545 // have a connection to the rest of the targets
Milind Upadhyay7c205222022-11-16 18:20:58 -0800546 {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800547 auto last_robot_pose =
548 ceres::examples::Pose3d{.p = Eigen::Vector3d(0.0, 0.0, kRobotZ),
549 .q = PoseUtils::EulerAnglesToQuaternion(
550 Eigen::Vector3d(0.0, 0.0, M_PI))};
551 for (size_t id = 4; id <= 8; id++) {
552 auto target_pose =
553 TargetMapper::GetTargetPoseById(actual_target_poses, id).value();
554 auto optional_detection = MaybeGenerateNoisyDetection(
555 last_robot_pose, target_pose, kTotalSteps * kDt, true);
556
557 ASSERT_TRUE(optional_detection.has_value())
558 << "Didn't detect target " << target_pose.id;
559 timestamped_target_detections.emplace_back(*optional_detection);
560 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800561 }
562
563 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800564 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800565 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800566 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800567
568 for (auto [target_pose_id, mapper_target_pose] : mapper.target_poses()) {
569 TargetMapper::TargetPose actual_target_pose =
570 TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id)
571 .value();
572 EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose);
573 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800574}
575
576} // namespace frc971::vision