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