blob: cd7d18b89ceafe3fa95beb3346188a148458d1ce [file] [log] [blame]
Milind Upadhyay7c205222022-11-16 18:20:58 -08001#include "frc971/vision/target_mapper.h"
2
3#include <random>
4
5#include "aos/events/simulated_event_loop.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08006#include "aos/testing/path.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08007#include "aos/testing/random_seed.h"
Milind Upadhyayc5beba12022-12-17 17:41:20 -08008#include "aos/util/math.h"
Milind Upadhyay7c205222022-11-16 18:20:58 -08009#include "glog/logging.h"
10#include "gtest/gtest.h"
11
12namespace frc971::vision {
13
14namespace {
15constexpr double kToleranceMeters = 0.05;
16constexpr double kToleranceRadians = 0.05;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080017// Conversions between euler angles and quaternion result in slightly-off
18// doubles
19constexpr double kOrientationEqTolerance = 1e-10;
20constexpr std::chrono::milliseconds kMaxDt = std::chrono::milliseconds(3);
Milind Upadhyay05652cb2022-12-07 20:51:51 -080021constexpr std::string_view kFieldName = "test";
Milind Upadhyay7c205222022-11-16 18:20:58 -080022} // namespace
23
Milind Upadhyayc5beba12022-12-17 17:41:20 -080024// Angles normalized by aos::math::NormalizeAngle()
25#define EXPECT_NORMALIZED_ANGLES_NEAR(theta1, theta2, tolerance) \
26 { \
27 double delta = std::abs(aos::math::DiffAngle(theta1, theta2)); \
28 /* Have to check delta - 2pi for the case that one angle is very */ \
29 /* close to -pi, and the other is very close to +pi */ \
30 EXPECT_TRUE(delta < tolerance || std::abs(aos::math::DiffAngle( \
31 delta, 2.0 * M_PI)) < tolerance); \
Milind Upadhyay7c205222022-11-16 18:20:58 -080032 }
33
Milind Upadhyayc5beba12022-12-17 17:41:20 -080034#define EXPECT_POSE_NEAR(pose1, pose2) \
35 { \
36 for (size_t i = 0; i < 3; i++) { \
37 EXPECT_NEAR(pose1.p(i), pose2.p(i), kToleranceMeters); \
38 } \
39 auto rpy_1 = PoseUtils::QuaternionToEulerAngles(pose1.q); \
40 auto rpy_2 = PoseUtils::QuaternionToEulerAngles(pose2.q); \
41 for (size_t i = 0; i < 3; i++) { \
42 SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \
43 rpy_1(i), i, rpy_2(i))); \
44 EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), kToleranceRadians) \
45 } \
46 }
Milind Upadhyay7c205222022-11-16 18:20:58 -080047
Milind Upadhyayc5beba12022-12-17 17:41:20 -080048#define EXPECT_POSE_EQ(pose1, pose2) \
49 EXPECT_EQ(pose1.p, pose2.p); \
50 EXPECT_EQ(pose1.q, pose2.q);
Milind Upadhyay7c205222022-11-16 18:20:58 -080051
Milind Upadhyayc5beba12022-12-17 17:41:20 -080052#define EXPECT_QUATERNION_NEAR(q1, q2) \
53 EXPECT_NEAR(q1.x(), q2.x(), kOrientationEqTolerance) << q1 << " != " << q2; \
54 EXPECT_NEAR(q1.y(), q2.y(), kOrientationEqTolerance) << q1 << " != " << q2; \
55 EXPECT_NEAR(q1.z(), q2.z(), kOrientationEqTolerance) << q1 << " != " << q2; \
56 EXPECT_NEAR(q1.w(), q2.w(), kOrientationEqTolerance) << q1 << " != " << q2;
57
58// Expects same roll, pitch, and yaw values (not equivalent rotation)
59#define EXPECT_RPY_EQ(rpy_1, rpy_2) \
60 { \
61 for (size_t i = 0; i < 3; i++) { \
62 SCOPED_TRACE(absl::StrFormat("rpy_1(%d) = %f, rpy_2(%d) = %f", i, \
63 rpy_1(i), i, rpy_2(i))); \
64 EXPECT_NORMALIZED_ANGLES_NEAR(rpy_1(i), rpy_2(i), \
65 kOrientationEqTolerance) \
66 } \
67 }
68
69#define EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw) \
70 { \
71 auto rpy = Eigen::Vector3d(roll, pitch, yaw); \
72 auto converted_rpy = PoseUtils::QuaternionToEulerAngles( \
73 PoseUtils::EulerAnglesToQuaternion(rpy)); \
74 EXPECT_RPY_EQ(converted_rpy, rpy); \
75 }
Milind Upadhyay7c205222022-11-16 18:20:58 -080076
77// Both confidence matrixes should have the same dimensions and be square
78#define EXPECT_CONFIDENCE_GT(confidence1, confidence2) \
79 { \
80 ASSERT_EQ(confidence1.rows(), confidence2.rows()); \
81 ASSERT_EQ(confidence1.rows(), confidence1.cols()); \
82 ASSERT_EQ(confidence2.rows(), confidence2.cols()); \
83 for (size_t i = 0; i < confidence1.rows(); i++) { \
84 EXPECT_GT(confidence1(i, i), confidence2(i, i)); \
85 } \
86 }
87
88namespace {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080089ceres::examples::Pose3d Make2dPose(double x, double y, double yaw_radians) {
90 return ceres::examples::Pose3d{Eigen::Vector3d(x, y, 0.0),
91 PoseUtils::EulerAnglesToQuaternion(
92 Eigen::Vector3d(0.0, 0.0, yaw_radians))};
Milind Upadhyay7c205222022-11-16 18:20:58 -080093}
94
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080095// Assumes camera and robot origin are the same
96DataAdapter::TimestampedDetection MakeTimestampedDetection(
97 aos::distributed_clock::time_point time, Eigen::Affine3d H_robot_target,
milind-ud62f80a2023-03-04 16:37:09 -080098 TargetMapper::TargetId id, double distortion_factor = 0.001) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080099 auto target_pose = PoseUtils::Affine3dToPose3d(H_robot_target);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800100 return DataAdapter::TimestampedDetection{
milind-ud62f80a2023-03-04 16:37:09 -0800101 .time = time,
102 .H_robot_target = H_robot_target,
103 .distance_from_camera = target_pose.p.norm(),
104 .distortion_factor = distortion_factor,
105 .id = id};
106}
107
108DataAdapter::TimestampedDetection MakeTimestampedDetectionForConfidence(
109 aos::distributed_clock::time_point time, TargetMapper::TargetId id,
110 double distance_from_camera, double distortion_factor) {
111 auto target_pose = ceres::examples::Pose3d{
112 .p = Eigen::Vector3d(distance_from_camera, 0.0, 0.0),
113 .q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0)};
114 return DataAdapter::TimestampedDetection{
115 .time = time,
116 .H_robot_target = PoseUtils::Pose3dToAffine3d(target_pose),
117 .distance_from_camera = target_pose.p.norm(),
118 .distortion_factor = distortion_factor,
119 .id = id};
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800120}
121
Milind Upadhyay7c205222022-11-16 18:20:58 -0800122bool TargetIsInView(TargetMapper::TargetPose target_detection) {
123 // And check if it is within the fov of the robot /
124 // camera, assuming camera is pointing in the
125 // positive x-direction of the robot
126 double angle_to_target =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800127 atan2(target_detection.pose.p(1), target_detection.pose.p(0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800128
129 // Simulated camera field of view, in radians
130 constexpr double kCameraFov = M_PI_2;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800131 if (std::abs(angle_to_target) <= kCameraFov / 2.0) {
132 VLOG(2) << "Found target in view, based on T = "
133 << target_detection.pose.p(0) << ", " << target_detection.pose.p(1)
134 << " with angle " << angle_to_target;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800135 return true;
136 } else {
137 return false;
138 }
139}
140
141aos::distributed_clock::time_point TimeInMs(size_t ms) {
142 return aos::distributed_clock::time_point(std::chrono::milliseconds(ms));
143}
144
145} // namespace
146
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800147TEST(PoseUtilsTest, EulerAnglesAndQuaternionConversions) {
148 // Make sure that the conversions are consistent back and forth.
149 // These angles shouldn't get changed to a different, equivalent roll pitch
150 // yaw.
151 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, M_PI);
152 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, -M_PI);
153 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, M_PI_2);
154 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, -M_PI_2);
155 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, 0.0, 0.0);
156 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, M_PI_4, 0.0);
157 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, 0.0);
158 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(0.0, -M_PI_4, M_PI_4);
159 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(M_PI_4, -M_PI_4, M_PI_4);
160 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(-M_PI_2, -M_PI_4, M_PI_4);
161
162 // Now, do a sweep of roll, pitch, and yaws in the normalized
163 // range.
164 // - roll: (-pi/2, pi/2)
165 // - pitch: (-pi/2, pi/2)
166 // - yaw: [-pi, pi)
167 constexpr double kThetaMaxRoll = M_PI_2 - kToleranceRadians;
168 constexpr double kThetaMaxPitch = M_PI_2 - kToleranceRadians;
169 constexpr double kThetaMaxYaw = M_PI;
170 constexpr double kDeltaTheta = M_PI / 16;
171
172 for (double roll = -kThetaMaxRoll; roll < kThetaMaxRoll;
173 roll += kDeltaTheta) {
174 for (double pitch = -kThetaMaxPitch; pitch < kThetaMaxPitch;
175 pitch += kDeltaTheta) {
176 for (double yaw = -kThetaMaxYaw; yaw < kThetaMaxYaw; yaw += kDeltaTheta) {
177 SCOPED_TRACE(
178 absl::StrFormat("roll: %f, pitch: %f, yaw: %f", roll, pitch, yaw));
179 EXPECT_EULER_ANGLES_QUATERNION_BACK_AND_FORTH_EQ(roll, pitch, yaw);
180 }
181 }
182 }
183}
184
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800185TEST(DataAdapterTest, ComputeConfidence) {
186 // Check the confidence matrices. Don't check the actual values
187 // in case the constants change, just check that the confidence of contraints
188 // decreases as time period or distances from camera increase.
milind-ud62f80a2023-03-04 16:37:09 -0800189
190 constexpr size_t kIdStart = 0;
191 constexpr size_t kIdEnd = 1;
192
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800193 {
194 // Vary time period
195 constexpr double kDistanceStart = 0.5;
196 constexpr double kDistanceEnd = 2.0;
milind-ud62f80a2023-03-04 16:37:09 -0800197 constexpr double kDistortionFactor = 0.001;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800198
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800199 TargetMapper::ConfidenceMatrix last_confidence =
200 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800201 for (size_t dt = 0; dt < 15; dt++) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800202 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800203 DataAdapter::ComputeConfidence(
204 MakeTimestampedDetectionForConfidence(
205 TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
206 MakeTimestampedDetectionForConfidence(
207 TimeInMs(dt), kIdEnd, kDistanceEnd, kDistortionFactor));
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800208
209 if (dt != 0) {
210 // Confidence only decreases every 5ms (control loop period)
211 if (dt % 5 == 0) {
212 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
213 } else {
214 EXPECT_EQ(last_confidence, confidence);
215 }
216 }
217 last_confidence = confidence;
218 }
219 }
220
221 {
222 // Vary distance at start
223 constexpr int kDt = 3;
224 constexpr double kDistanceEnd = 1.5;
milind-ud62f80a2023-03-04 16:37:09 -0800225 constexpr double kDistortionFactor = 0.001;
226
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800227 TargetMapper::ConfidenceMatrix last_confidence =
228 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800229 for (double distance_start = 0.0; distance_start < 3.0;
230 distance_start += 0.5) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800231 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800232 DataAdapter::ComputeConfidence(
233 MakeTimestampedDetectionForConfidence(
234 TimeInMs(0), kIdStart, distance_start, kDistortionFactor),
235 MakeTimestampedDetectionForConfidence(
236 TimeInMs(kDt), kIdEnd, kDistanceEnd, kDistortionFactor));
237
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800238 if (distance_start != 0.0) {
239 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
240 }
241 last_confidence = confidence;
242 }
243 }
244
245 {
246 // Vary distance at end
247 constexpr int kDt = 2;
248 constexpr double kDistanceStart = 2.5;
milind-ud62f80a2023-03-04 16:37:09 -0800249 constexpr double kDistortionFactor = 0.001;
250
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800251 TargetMapper::ConfidenceMatrix last_confidence =
252 TargetMapper::ConfidenceMatrix::Zero();
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800253 for (double distance_end = 0.0; distance_end < 3.0; distance_end += 0.5) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800254 TargetMapper::ConfidenceMatrix confidence =
milind-ud62f80a2023-03-04 16:37:09 -0800255 DataAdapter::ComputeConfidence(
256 MakeTimestampedDetectionForConfidence(
257 TimeInMs(0), kIdStart, kDistanceStart, kDistortionFactor),
258 MakeTimestampedDetectionForConfidence(
259 TimeInMs(kDt), kIdEnd, distance_end, kDistortionFactor));
260
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800261 if (distance_end != 0.0) {
262 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
263 }
264 last_confidence = confidence;
265 }
266 }
milind-ud62f80a2023-03-04 16:37:09 -0800267
268 {
269 // Vary distortion factor
270 constexpr int kDt = 2;
271 constexpr double kDistanceStart = 2.5;
272 constexpr double kDistanceEnd = 1.5;
273
274 TargetMapper::ConfidenceMatrix last_confidence =
275 TargetMapper::ConfidenceMatrix::Zero();
276 for (double distortion_factor = 0.0; distortion_factor <= 1.0;
277 distortion_factor += 0.01) {
278 TargetMapper::ConfidenceMatrix confidence =
279 DataAdapter::ComputeConfidence(
280 MakeTimestampedDetectionForConfidence(
281 TimeInMs(0), kIdStart, kDistanceStart, distortion_factor),
282 MakeTimestampedDetectionForConfidence(
283 TimeInMs(kDt), kIdEnd, kDistanceEnd, distortion_factor));
284
285 if (distortion_factor != 0.0) {
286 EXPECT_CONFIDENCE_GT(last_confidence, confidence);
287 }
288 last_confidence = confidence;
289 }
290 }
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800291}
292
Milind Upadhyayec493912022-12-18 21:33:15 -0800293TEST(DataAdapterTest, MatchTargetDetections) {
Milind Upadhyayec493912022-12-18 21:33:15 -0800294 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800295 {MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800296 TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -5.0, 0.0)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800297 2),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800298 MakeTimestampedDetection(
299 TimeInMs(6),
300 PoseUtils::Pose3dToAffine3d(Make2dPose(5.0, -4.0, M_PI)), 0),
301 MakeTimestampedDetection(
302 TimeInMs(10),
303 PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, -3.0, M_PI)), 1),
304 MakeTimestampedDetection(
305 TimeInMs(13),
306 PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -7.0, M_PI_2)), 2),
307 MakeTimestampedDetection(
308 TimeInMs(14),
309 PoseUtils::Pose3dToAffine3d(Make2dPose(4.0, -4.0, M_PI_2)), 2)};
Milind Upadhyayec493912022-12-18 21:33:15 -0800310
Milind Upadhyayec493912022-12-18 21:33:15 -0800311 auto target_constraints =
312 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
313
314 // The constraint between the detection at 6ms and the one at 10 ms is skipped
315 // because dt > kMaxDt.
316 // Also, the constraint between the last two detections is skipped because
317 // they are the same target
318 EXPECT_EQ(target_constraints.size(),
319 timestamped_target_detections.size() - 3);
320
321 // Between 5ms and 6ms detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800322 EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(0), 0.0);
323 EXPECT_DOUBLE_EQ(target_constraints[0].t_be.p(1), 1.0);
324 EXPECT_QUATERNION_NEAR(
325 target_constraints[0].t_be.q,
326 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, M_PI)));
Milind Upadhyayec493912022-12-18 21:33:15 -0800327 EXPECT_EQ(target_constraints[0].id_begin, 2);
328 EXPECT_EQ(target_constraints[0].id_end, 0);
329
330 // Between 10ms and 13ms detections
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800331 EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(0), -1.0);
332 EXPECT_DOUBLE_EQ(target_constraints[1].t_be.p(1), 4.0);
333 EXPECT_QUATERNION_NEAR(
334 target_constraints[1].t_be.q,
335 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d(0.0, 0.0, -M_PI_2)));
Milind Upadhyayec493912022-12-18 21:33:15 -0800336 EXPECT_EQ(target_constraints[1].id_begin, 1);
337 EXPECT_EQ(target_constraints[1].id_end, 2);
338}
339
Milind Upadhyay7c205222022-11-16 18:20:58 -0800340TEST(TargetMapperTest, TwoTargetsOneConstraint) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800341 ceres::examples::MapOfPoses target_poses;
342 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
343 target_poses[1] = Make2dPose(-5.0, 0.0, 0.0);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800344
Milind Upadhyay7c205222022-11-16 18:20:58 -0800345 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800346 {MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800347 TimeInMs(5), PoseUtils::Pose3dToAffine3d(Make2dPose(3.0, 0.0, M_PI)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800348 0),
349 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800350 TimeInMs(6), PoseUtils::Pose3dToAffine3d(Make2dPose(-7.0, 0.0, 0.0)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800351 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800352 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800353 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800354
355 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800356 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800357
358 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800359 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
360 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800361}
362
363TEST(TargetMapperTest, TwoTargetsTwoConstraints) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800364 ceres::examples::MapOfPoses target_poses;
365 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
366 target_poses[1] = Make2dPose(-5.0, 0.0, -M_PI_2);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800367
Milind Upadhyay7c205222022-11-16 18:20:58 -0800368 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800369 {MakeTimestampedDetection(
370 TimeInMs(5),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800371 PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 0.0, M_PI_2)), 0),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800372 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800373 TimeInMs(7),
374 PoseUtils::Pose3dToAffine3d(Make2dPose(6.0, 10.0, -M_PI)), 1),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800375 MakeTimestampedDetection(
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800376 TimeInMs(12),
377 PoseUtils::Pose3dToAffine3d(Make2dPose(1.0, 0.0, M_PI)), 0),
378 MakeTimestampedDetection(
379 TimeInMs(13),
380 PoseUtils::Pose3dToAffine3d(Make2dPose(-9.0, 0.0, -M_PI_2)), 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800381 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800382 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800383
384 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800385 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800386
387 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800388 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
389 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, -M_PI_2));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800390}
391
392TEST(TargetMapperTest, TwoTargetsOneNoisyConstraint) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800393 ceres::examples::MapOfPoses target_poses;
394 target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
395 target_poses[1] = Make2dPose(-5.0, 0.0, 0.0);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800396
Milind Upadhyay7c205222022-11-16 18:20:58 -0800397 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections =
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800398 {MakeTimestampedDetection(
399 TimeInMs(5),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800400 PoseUtils::Pose3dToAffine3d(Make2dPose(3.01, 0.001, M_PI - 0.001)),
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800401 0),
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800402 MakeTimestampedDetection(
403 TimeInMs(7),
404 PoseUtils::Pose3dToAffine3d(Make2dPose(-7.01, 0.0, 0.0)), 1)};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800405
406 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800407 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800408
409 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800410 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800411
412 ASSERT_EQ(mapper.target_poses().size(), 2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800413 EXPECT_POSE_NEAR(mapper.target_poses()[0], Make2dPose(5.0, 0.0, M_PI));
414 EXPECT_POSE_NEAR(mapper.target_poses()[1], Make2dPose(-5.0, 0.0, 0.0));
Milind Upadhyay7c205222022-11-16 18:20:58 -0800415}
416
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800417class ChargedUpTargetMapperTest : public ::testing::Test {
418 public:
419 ChargedUpTargetMapperTest() : generator_(aos::testing::RandomSeed()) {}
420
421 // Generates noisy target detection if target in camera FOV
422 std::optional<DataAdapter::TimestampedDetection> MaybeGenerateNoisyDetection(
423 const ceres::examples::Pose3d &robot_pose,
424 const TargetMapper::TargetPose &target_pose, size_t t,
425 bool force_in_view = false) {
426 TargetMapper::TargetPose target_detection = {
427 .id = target_pose.id,
428 .pose = PoseUtils::ComputeRelativePose(robot_pose, target_pose.pose)};
429 if (force_in_view || TargetIsInView(target_detection)) {
430 // Define random generator with Gaussian
431 // distribution
432 constexpr double kMean = 0.0;
433 constexpr double kStdDev = 1.0;
434 // Can play with this to see how it impacts
435 // randomness
436 constexpr double kNoiseScalePosition = 0.01;
437 constexpr double kNoiseScaleOrientation = 0.0005;
438 std::normal_distribution<double> dist(kMean, kStdDev);
439
440 target_detection.pose.p(0) += dist(generator_) * kNoiseScalePosition;
441 target_detection.pose.p(1) += dist(generator_) * kNoiseScalePosition;
442 target_detection.pose.p(2) += dist(generator_) * kNoiseScalePosition;
443
444 target_detection.pose.q.w() += dist(generator_) * kNoiseScaleOrientation;
445 target_detection.pose.q.x() += dist(generator_) * kNoiseScaleOrientation;
446 target_detection.pose.q.y() += dist(generator_) * kNoiseScaleOrientation;
447 target_detection.pose.q.z() += dist(generator_) * kNoiseScaleOrientation;
448
milind-ud62f80a2023-03-04 16:37:09 -0800449 // Get most distortion factors close to zero, but have a few outliers
450 const std::vector<double> kDistortionFactorIntervals = {0.0, 0.01, 1.0};
451 const std::vector<double> kDistortionFactorWeights = {0.9, 0.1};
452 std::piecewise_constant_distribution<double> distortion_factor_dist(
453 kDistortionFactorIntervals.begin(), kDistortionFactorIntervals.end(),
454 kDistortionFactorWeights.begin());
455 double distortion_factor = distortion_factor_dist(generator_);
456
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800457 auto time_point = TimeInMs(t);
458 return MakeTimestampedDetection(
459 time_point, PoseUtils::Pose3dToAffine3d(target_detection.pose),
milind-ud62f80a2023-03-04 16:37:09 -0800460 target_detection.id, distortion_factor);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800461 }
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800462
463 return std::nullopt;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800464 }
465
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800466 private:
467 std::default_random_engine generator_;
468};
469
470// Drive in a circle around the 2023 field, and add a bit of randomness to 3d
471// pose detections
472TEST_F(ChargedUpTargetMapperTest, FieldCircleMotion) {
473 // Read target map
474 auto target_map_fbs = aos::JsonFileToFlatbuffer<TargetMap>(
475 aos::testing::ArtifactPath("frc971/vision/target_map.json"));
476
477 std::vector<TargetMapper::TargetPose> actual_target_poses;
478 ceres::examples::MapOfPoses target_poses;
milind-u3f5f83c2023-01-29 15:23:51 -0800479 for (const auto *target_pose_fbs : *target_map_fbs.message().target_poses()) {
480 const TargetMapper::TargetPose target_pose =
481 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800482 actual_target_poses.emplace_back(target_pose);
483 target_poses[target_pose.id] = target_pose.pose;
484 }
485
486 double kFieldHalfLength = 16.54 / 2.0; // half length of the field
487 double kFieldHalfWidth = 8.02 / 2.0; // half width of the field
488
Milind Upadhyay7c205222022-11-16 18:20:58 -0800489 // Now, create a bunch of robot poses and target
490 // observations
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800491 constexpr size_t kDt = 5;
492 constexpr double kRobotZ = 1.0;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800493
Milind Upadhyay7c205222022-11-16 18:20:58 -0800494 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
495
496 constexpr size_t kTotalSteps = 100;
497 for (size_t step_count = 0; step_count < kTotalSteps; step_count++) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800498 size_t t = kDt * step_count;
499
Milind Upadhyay7c205222022-11-16 18:20:58 -0800500 // Circle clockwise around the center of the field
501 double robot_theta = t;
Milind Upadhyay7c205222022-11-16 18:20:58 -0800502
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800503 constexpr double kRadiusScalar = 0.5;
504 double robot_x = (kRadiusScalar * kFieldHalfLength) * cos(robot_theta);
505 double robot_y = (kRadiusScalar * -kFieldHalfWidth) * sin(robot_theta);
506
507 auto robot_pose =
508 ceres::examples::Pose3d{.p = Eigen::Vector3d(robot_x, robot_y, kRobotZ),
509 .q = PoseUtils::EulerAnglesToQuaternion(
510 Eigen::Vector3d(robot_theta, 0.0, 0.0))};
511
Milind Upadhyay7c205222022-11-16 18:20:58 -0800512 for (TargetMapper::TargetPose target_pose : actual_target_poses) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800513 auto optional_detection =
514 MaybeGenerateNoisyDetection(robot_pose, target_pose, t);
515 if (optional_detection.has_value()) {
516 timestamped_target_detections.emplace_back(*optional_detection);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800517 }
518 }
519 }
520
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800521 // The above circular motion only captures targets 1-4, so add another
522 // detection with the camera looking at targets 5-8, and 4 at the same time to
523 // have a connection to the rest of the targets
Milind Upadhyay7c205222022-11-16 18:20:58 -0800524 {
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800525 auto last_robot_pose =
526 ceres::examples::Pose3d{.p = Eigen::Vector3d(0.0, 0.0, kRobotZ),
527 .q = PoseUtils::EulerAnglesToQuaternion(
528 Eigen::Vector3d(0.0, 0.0, M_PI))};
529 for (size_t id = 4; id <= 8; id++) {
530 auto target_pose =
531 TargetMapper::GetTargetPoseById(actual_target_poses, id).value();
532 auto optional_detection = MaybeGenerateNoisyDetection(
533 last_robot_pose, target_pose, kTotalSteps * kDt, true);
534
535 ASSERT_TRUE(optional_detection.has_value())
536 << "Didn't detect target " << target_pose.id;
537 timestamped_target_detections.emplace_back(*optional_detection);
538 }
Milind Upadhyay7c205222022-11-16 18:20:58 -0800539 }
540
541 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800542 DataAdapter::MatchTargetDetections(timestamped_target_detections, kMaxDt);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800543 frc971::vision::TargetMapper mapper(target_poses, target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800544 mapper.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800545
546 for (auto [target_pose_id, mapper_target_pose] : mapper.target_poses()) {
547 TargetMapper::TargetPose actual_target_pose =
548 TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id)
549 .value();
550 EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose);
551 }
552
553 //
554 // See what happens when we don't start with the
555 // correct values
556 //
557 for (auto [target_id, target_pose] : target_poses) {
558 // Skip first pose, since that needs to be correct
559 // and is fixed in the solver
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800560 if (target_id != 1) {
561 ceres::examples::Pose3d bad_pose{
562 Eigen::Vector3d::Zero(),
563 PoseUtils::EulerAnglesToQuaternion(Eigen::Vector3d::Zero())};
Milind Upadhyay7c205222022-11-16 18:20:58 -0800564 target_poses[target_id] = bad_pose;
565 }
566 }
567
568 frc971::vision::TargetMapper mapper_bad_poses(target_poses,
569 target_constraints);
Milind Upadhyay05652cb2022-12-07 20:51:51 -0800570 mapper_bad_poses.Solve(kFieldName);
Milind Upadhyay7c205222022-11-16 18:20:58 -0800571
572 for (auto [target_pose_id, mapper_target_pose] :
573 mapper_bad_poses.target_poses()) {
574 TargetMapper::TargetPose actual_target_pose =
575 TargetMapper::GetTargetPoseById(actual_target_poses, target_pose_id)
576 .value();
577 EXPECT_POSE_NEAR(mapper_target_pose, actual_target_pose.pose);
578 }
579}
580
581} // namespace frc971::vision