blob: d9a55f6d22dc0b92517cc9518f234dccca4e9e5a [file] [log] [blame]
James Kuszmaul1057ce82019-02-09 17:58:24 -08001#include "y2019/control_loops/drivetrain/localizer.h"
2
James Kuszmaul1057ce82019-02-09 17:58:24 -08003#include <queue>
James Kuszmaul651fc3f2019-05-15 21:14:25 -07004#include <random>
James Kuszmaul1057ce82019-02-09 17:58:24 -08005
6#include "aos/testing/random_seed.h"
7#include "aos/testing/test_shm.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -08008#include "frc971/control_loops/drivetrain/splinedrivetrain.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -07009#include "frc971/control_loops/drivetrain/trajectory.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -080010#include "gflags/gflags.h"
11#if defined(SUPPORT_PLOT)
12#include "third_party/matplotlib-cpp/matplotlibcpp.h"
13#endif
14#include "gtest/gtest.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -080015#include "y2019/constants.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -070016#include "y2019/control_loops/drivetrain/drivetrain_base.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -080017
18DEFINE_bool(plot, false, "If true, plot");
19
20namespace y2019 {
21namespace control_loops {
22namespace testing {
23
24using ::y2019::constants::Field;
25
26constexpr size_t kNumCameras = 4;
27constexpr size_t kNumTargetsPerFrame = 3;
28
29typedef TypedLocalizer<kNumCameras, Field::kNumTargets, Field::kNumObstacles,
James Kuszmaul651fc3f2019-05-15 21:14:25 -070030 kNumTargetsPerFrame, double>
31 TestLocalizer;
James Kuszmaul1057ce82019-02-09 17:58:24 -080032typedef typename TestLocalizer::Camera TestCamera;
33typedef typename TestCamera::Pose Pose;
34typedef typename TestCamera::LineSegment Obstacle;
35
36typedef TestLocalizer::StateIdx StateIdx;
37
38using ::frc971::control_loops::drivetrain::DrivetrainConfig;
39
40// When placing the cameras on the robot, set them all kCameraOffset out from
41// the center, to test that we really can handle cameras that aren't at the
42// center-of-mass.
43constexpr double kCameraOffset = 0.1;
44
45#if defined(SUPPORT_PLOT)
46// Plots a line from a vector of Pose's.
47void PlotPlotPts(const ::std::vector<Pose> &poses,
48 const ::std::map<::std::string, ::std::string> &kwargs) {
49 ::std::vector<double> x;
50 ::std::vector<double> y;
James Kuszmaul651fc3f2019-05-15 21:14:25 -070051 for (const Pose &p : poses) {
James Kuszmaul1057ce82019-02-09 17:58:24 -080052 x.push_back(p.abs_pos().x());
53 y.push_back(p.abs_pos().y());
54 }
55 matplotlibcpp::plot(x, y, kwargs);
56}
57#endif
58
59struct LocalizerTestParams {
60 // Control points for the spline to make the robot follow.
61 ::std::array<float, 6> control_pts_x;
62 ::std::array<float, 6> control_pts_y;
63 // The actual state to start the robot at. By setting voltage errors and the
64 // such you can introduce persistent disturbances.
65 TestLocalizer::State true_start_state;
66 // The initial state of the estimator.
67 TestLocalizer::State known_start_state;
68 // Whether or not to add Gaussian noise to the sensors and cameras.
69 bool noisify;
70 // Whether or not to add unmodelled disturbances.
71 bool disturb;
72 // The tolerances for the estimator and for the trajectory following at
73 // the end of the spline:
74 double estimate_tolerance;
75 double goal_tolerance;
76};
77
78class ParameterizedLocalizerTest
79 : public ::testing::TestWithParam<LocalizerTestParams> {
80 public:
81 ::aos::testing::TestSharedMemory shm_;
82
83 // Set up three targets in a row, at (-1, 0), (0, 0), and (1, 0).
84 // Make the right-most target (1, 0) be facing away from the camera, and give
85 // the middle target some skew.
86 // Place one camera facing forward, the other facing backward, and set the
87 // robot at (0, -5) with the cameras each 0.1m from the center.
88 // Place one obstacle in a place where it can block the left-most target (-1,
89 // 0).
90 ParameterizedLocalizerTest()
91 : field_(),
92 targets_(field_.targets()),
93 modeled_obstacles_(field_.obstacles()),
94 true_obstacles_(field_.obstacles()),
95 dt_config_(drivetrain::GetDrivetrainConfig()),
96 // Pull the noise for the encoders/gyros from the R matrix:
97 encoder_noise_(::std::sqrt(
98 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R(
99 0, 0))),
100 gyro_noise_(::std::sqrt(
101 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R(
102 2, 2))),
103 // As per the comments in localizer.h, we set the field of view and
104 // noise parameters on the robot_cameras_ so that they see a bit more
105 // than the true_cameras_. The robot_cameras_ are what is passed to the
106 // localizer and used to generate "expected" targets. The true_cameras_
107 // are what we actually use to generate targets to pass to the
108 // localizer.
109 robot_cameras_{
110 {TestCamera({&robot_pose_, {0.0, kCameraOffset, 0.0}, M_PI_2},
111 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
112 modeled_obstacles_),
113 TestCamera({&robot_pose_, {kCameraOffset, 0.0, 0.0}, 0.0},
114 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
115 modeled_obstacles_),
116 TestCamera({&robot_pose_, {-kCameraOffset, 0.0, 0.0}, M_PI},
117 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
118 modeled_obstacles_),
119 TestCamera({&robot_pose_, {0.0, -kCameraOffset, 0.0}, -M_PI_2},
120 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
121 modeled_obstacles_)}},
122 true_cameras_{
123 {TestCamera({&true_robot_pose_, {0.0, kCameraOffset, 0.0}, M_PI_2},
124 M_PI_2 * 0.9, true_noise_parameters_, targets_,
125 true_obstacles_),
126 TestCamera({&true_robot_pose_, {kCameraOffset, 0.0, 0.0}, 0.0},
127 M_PI_2 * 0.9, true_noise_parameters_, targets_,
128 true_obstacles_),
129 TestCamera({&true_robot_pose_, {-kCameraOffset, 0.0, 0.0}, M_PI},
130 M_PI_2 * 0.9, true_noise_parameters_, targets_,
131 true_obstacles_),
132 TestCamera(
133 {&true_robot_pose_, {-0.0, -kCameraOffset, 0.0}, -M_PI_2},
134 M_PI_2 * 0.9, true_noise_parameters_, targets_,
135 true_obstacles_)}},
136 localizer_(dt_config_, &robot_pose_),
137 spline_drivetrain_(dt_config_) {
138 // We use the default P() for initialization.
139 localizer_.ResetInitialState(t0_, GetParam().known_start_state,
140 localizer_.P());
141 }
142
143 void SetUp() {
Alex Perrycb7da4b2019-08-28 19:35:56 -0700144 flatbuffers::DetachedBuffer goal_buffer;
145 {
146 flatbuffers::FlatBufferBuilder fbb;
147
148 flatbuffers::Offset<flatbuffers::Vector<float>> spline_x_offset =
149 fbb.CreateVector<float>(GetParam().control_pts_x.begin(),
150 GetParam().control_pts_x.size());
151
152 flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset =
153 fbb.CreateVector<float>(GetParam().control_pts_y.begin(),
154 GetParam().control_pts_y.size());
155
156 frc971::MultiSpline::Builder multispline_builder(fbb);
157
158 multispline_builder.add_spline_count(1);
159 multispline_builder.add_spline_x(spline_x_offset);
160 multispline_builder.add_spline_y(spline_y_offset);
161
162 flatbuffers::Offset<frc971::MultiSpline> multispline_offset =
163 multispline_builder.Finish();
164
165 frc971::control_loops::drivetrain::SplineGoal::Builder spline_builder(
166 fbb);
167
168 spline_builder.add_spline_idx(1);
169 spline_builder.add_spline(multispline_offset);
170
171 flatbuffers::Offset<frc971::control_loops::drivetrain::SplineGoal>
172 spline_offset = spline_builder.Finish();
173
174 frc971::control_loops::drivetrain::Goal::Builder goal_builder(fbb);
175
176 goal_builder.add_spline(spline_offset);
177 goal_builder.add_controller_type(
178 frc971::control_loops::drivetrain::ControllerType_SPLINE_FOLLOWER);
179 goal_builder.add_spline_handle(1);
180
181 fbb.Finish(goal_builder.Finish());
182
183 goal_buffer = fbb.Release();
184 }
185 aos::FlatbufferDetachedBuffer<frc971::control_loops::drivetrain::Goal> goal(
186 std::move(goal_buffer));
187
188 spline_drivetrain_.SetGoal(&goal.message());
Alex Perrycc3ee4c2019-02-09 21:20:41 -0800189
190 // Let the spline drivetrain compute the spline.
Alex Perrycb7da4b2019-08-28 19:35:56 -0700191 while (true) {
Alex Perrycc3ee4c2019-02-09 21:20:41 -0800192 ::std::this_thread::sleep_for(::std::chrono::milliseconds(5));
Alex Perrycb7da4b2019-08-28 19:35:56 -0700193
194 flatbuffers::FlatBufferBuilder fbb;
195
196 flatbuffers::Offset<frc971::control_loops::drivetrain::TrajectoryLogging>
197 trajectory_logging_offset =
198 spline_drivetrain_.MakeTrajectoryLogging(&fbb);
199
200 ::frc971::control_loops::drivetrain::Status::Builder status_builder(fbb);
201 status_builder.add_trajectory_logging(trajectory_logging_offset);
202 spline_drivetrain_.PopulateStatus(&status_builder);
203 fbb.Finish(status_builder.Finish());
204 aos::FlatbufferDetachedBuffer<::frc971::control_loops::drivetrain::Status>
205 status(fbb.Release());
206
207 if (status.message().trajectory_logging()->planning_state() ==
208 ::frc971::control_loops::drivetrain::PlanningState_PLANNED) {
209 break;
210 }
211 }
212 spline_drivetrain_.SetGoal(&goal.message());
James Kuszmaul1057ce82019-02-09 17:58:24 -0800213 }
214
215 void TearDown() {
216 printf("Each iteration of the simulation took on average %f seconds.\n",
217 avg_time_.count());
218#if defined(SUPPORT_PLOT)
219 if (FLAGS_plot) {
220 matplotlibcpp::figure();
221 matplotlibcpp::plot(simulation_t_, simulation_vl_, {{"label", "Vl"}});
222 matplotlibcpp::plot(simulation_t_, simulation_vr_, {{"label", "Vr"}});
223 matplotlibcpp::legend();
224
225 matplotlibcpp::figure();
226 matplotlibcpp::plot(spline_x_, spline_y_, {{"label", "spline"}});
227 matplotlibcpp::plot(simulation_x_, simulation_y_, {{"label", "robot"}});
228 matplotlibcpp::plot(estimated_x_, estimated_y_,
229 {{"label", "estimation"}});
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700230 for (const Target &target : targets_) {
James Kuszmaul1057ce82019-02-09 17:58:24 -0800231 PlotPlotPts(target.PlotPoints(), {{"c", "g"}});
232 }
233 for (const Obstacle &obstacle : true_obstacles_) {
234 PlotPlotPts(obstacle.PlotPoints(), {{"c", "k"}});
235 }
236 // Go through and plot true/expected camera targets for a few select
237 // time-steps.
238 ::std::vector<const char *> colors{"m", "y", "c"};
239 int jj = 0;
240 for (size_t ii = 0; ii < simulation_x_.size(); ii += 400) {
241 *true_robot_pose_.mutable_pos() << simulation_x_[ii], simulation_y_[ii],
242 0.0;
243 true_robot_pose_.set_theta(simulation_theta_[ii]);
244 for (const TestCamera &camera : true_cameras_) {
245 for (const auto &plot_pts : camera.PlotPoints()) {
246 PlotPlotPts(plot_pts, {{"c", colors[jj]}});
247 }
248 }
249 for (const TestCamera &camera : robot_cameras_) {
250 *robot_pose_.mutable_pos() << estimated_x_[ii], estimated_y_[ii], 0.0;
251 robot_pose_.set_theta(estimated_theta_[ii]);
252 const auto &all_plot_pts = camera.PlotPoints();
253 *robot_pose_.mutable_pos() = true_robot_pose_.rel_pos();
254 robot_pose_.set_theta(true_robot_pose_.rel_theta());
255 for (const auto &plot_pts : all_plot_pts) {
256 PlotPlotPts(plot_pts, {{"c", colors[jj]}, {"ls", "--"}});
257 }
258 }
259 jj = (jj + 1) % colors.size();
260 }
261 matplotlibcpp::legend();
262
263 matplotlibcpp::figure();
264 matplotlibcpp::plot(
265 simulation_t_, spline_x_,
266 {{"label", "spline x"}, {"c", "g"}, {"ls", ""}, {"marker", "o"}});
267 matplotlibcpp::plot(simulation_t_, simulation_x_,
268 {{"label", "simulated x"}, {"c", "g"}});
269 matplotlibcpp::plot(simulation_t_, estimated_x_,
270 {{"label", "estimated x"}, {"c", "g"}, {"ls", "--"}});
271
272 matplotlibcpp::plot(
273 simulation_t_, spline_y_,
274 {{"label", "spline y"}, {"c", "b"}, {"ls", ""}, {"marker", "o"}});
275 matplotlibcpp::plot(simulation_t_, simulation_y_,
276 {{"label", "simulated y"}, {"c", "b"}});
277 matplotlibcpp::plot(simulation_t_, estimated_y_,
278 {{"label", "estimated y"}, {"c", "b"}, {"ls", "--"}});
279
280 matplotlibcpp::plot(simulation_t_, simulation_theta_,
281 {{"label", "simulated theta"}, {"c", "r"}});
282 matplotlibcpp::plot(
283 simulation_t_, estimated_theta_,
284 {{"label", "estimated theta"}, {"c", "r"}, {"ls", "--"}});
285 matplotlibcpp::legend();
286
287 matplotlibcpp::show();
288 }
289#endif
290 }
291
292 protected:
293 // Returns a random number with a gaussian distribution with a mean of zero
294 // and a standard deviation of std, if noisify = true.
295 // If noisify is false, then returns 0.0.
296 double Normal(double std) {
297 if (GetParam().noisify) {
298 return normal_(gen_) * std;
299 }
300 return 0.0;
301 }
302 // Adds random noise to the given target view.
303 void Noisify(TestCamera::TargetView *view) {
304 view->reading.heading += Normal(view->noise.heading);
305 view->reading.distance += Normal(view->noise.distance);
306 view->reading.height += Normal(view->noise.height);
307 view->reading.skew += Normal(view->noise.skew);
308 }
309 // The differential equation for the dynamics of the system.
310 TestLocalizer::State DiffEq(const TestLocalizer::State &X,
311 const TestLocalizer::Input &U) {
312 return localizer_.DiffEq(X, U);
313 }
314
315 Field field_;
316 ::std::array<Target, Field::kNumTargets> targets_;
317 // The obstacles that are passed to the camera objects for the localizer.
318 ::std::array<Obstacle, Field::kNumObstacles> modeled_obstacles_;
319 // The obstacles that are used for actually simulating the cameras.
320 ::std::array<Obstacle, Field::kNumObstacles> true_obstacles_;
321
322 DrivetrainConfig<double> dt_config_;
323
324 // Noise information for the actual simulated cameras (true_*) and the
325 // parameters that the localizer should use for modelling the cameras. Note
326 // how the max_viewable_distance is larger for the localizer, so that if
327 // there is any error in the estimation, it still thinks that it can see
328 // any targets that might actually be in range.
329 TestCamera::NoiseParameters true_noise_parameters_ = {
330 .max_viewable_distance = 10.0,
331 .heading_noise = 0.02,
332 .nominal_distance_noise = 0.06,
333 .nominal_skew_noise = 0.1,
334 .nominal_height_noise = 0.01};
335 TestCamera::NoiseParameters robot_noise_parameters_ = {
336 .max_viewable_distance = 11.0,
337 .heading_noise = 0.02,
338 .nominal_distance_noise = 0.06,
339 .nominal_skew_noise = 0.1,
340 .nominal_height_noise = 0.01};
341
342 // Standard deviations of the noise for the encoders/gyro.
343 double encoder_noise_, gyro_noise_;
344
345 Pose robot_pose_;
346 ::std::array<TestCamera, 4> robot_cameras_;
347 Pose true_robot_pose_;
348 ::std::array<TestCamera, 4> true_cameras_;
349
350 TestLocalizer localizer_;
351
352 ::frc971::control_loops::drivetrain::SplineDrivetrain spline_drivetrain_;
353
354 // All the data we want to end up plotting.
355 ::std::vector<double> simulation_t_;
356
357 ::std::vector<double> spline_x_;
358 ::std::vector<double> spline_y_;
359 ::std::vector<double> estimated_x_;
360 ::std::vector<double> estimated_y_;
361 ::std::vector<double> estimated_theta_;
362 ::std::vector<double> simulation_x_;
363 ::std::vector<double> simulation_y_;
364 ::std::vector<double> simulation_theta_;
365
366 ::std::vector<double> simulation_vl_;
367 ::std::vector<double> simulation_vr_;
368
369 // Simulation start time
370 ::aos::monotonic_clock::time_point t0_;
371
372 // Average duration of each iteration; used for debugging and getting a
373 // sanity-check on what performance looks like--uses a real system clock.
374 ::std::chrono::duration<double> avg_time_;
375
376 ::std::mt19937 gen_{static_cast<uint32_t>(::aos::testing::RandomSeed())};
377 ::std::normal_distribution<> normal_;
378};
379
James Kuszmaul6f941b72019-03-08 18:12:25 -0800380using ::std::chrono::milliseconds;
381
James Kuszmaul1057ce82019-02-09 17:58:24 -0800382// Tests that, when we attempt to follow a spline and use the localizer to
383// perform the state estimation, we end up roughly where we should and that
384// the localizer has a valid position estimate.
385TEST_P(ParameterizedLocalizerTest, SplineTest) {
386 // state stores the true state of the robot throughout the simulation.
387 TestLocalizer::State state = GetParam().true_start_state;
388
389 ::aos::monotonic_clock::time_point t = t0_;
390
391 // The period with which we should take frames from the cameras. Currently,
392 // we just trigger all the cameras at once, rather than offsetting them or
393 // anything.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700394 const int camera_period = 5; // cycles
James Kuszmaul6f941b72019-03-08 18:12:25 -0800395 // The amount of time to delay the camera images from when they are taken, for
396 // each camera.
397 const ::std::array<milliseconds, 4> camera_latencies{
398 {milliseconds(45), milliseconds(50), milliseconds(55),
399 milliseconds(100)}};
James Kuszmaul1057ce82019-02-09 17:58:24 -0800400
James Kuszmaul6f941b72019-03-08 18:12:25 -0800401 // A queue of camera frames for each camera so that we can add a time delay to
402 // the data coming from the cameras.
403 ::std::array<
404 ::std::queue<::std::tuple<
405 ::aos::monotonic_clock::time_point, const TestCamera *,
406 ::aos::SizedArray<TestCamera::TargetView, kNumTargetsPerFrame>>>,
407 4>
408 camera_queues;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800409
410 // Start time, for debugging.
411 const auto begin = ::std::chrono::steady_clock::now();
412
413 size_t i;
414 for (i = 0; !spline_drivetrain_.IsAtEnd(); ++i) {
415 // Get the current state estimate into a matrix that works for the
416 // trajectory code.
417 ::Eigen::Matrix<double, 5, 1> known_state;
418 TestLocalizer::State X_hat = localizer_.X_hat();
419 known_state << X_hat(StateIdx::kX, 0), X_hat(StateIdx::kY, 0),
420 X_hat(StateIdx::kTheta, 0), X_hat(StateIdx::kLeftVelocity, 0),
421 X_hat(StateIdx::kRightVelocity, 0);
422
423 spline_drivetrain_.Update(true, known_state);
424
Alex Perrycb7da4b2019-08-28 19:35:56 -0700425 ::frc971::control_loops::drivetrain::OutputT output;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800426 output.left_voltage = 0;
427 output.right_voltage = 0;
428 spline_drivetrain_.SetOutput(&output);
429 TestLocalizer::Input U(output.left_voltage, output.right_voltage);
430
431 const ::Eigen::Matrix<double, 5, 1> goal_state =
432 spline_drivetrain_.CurrentGoalState();
433 simulation_t_.push_back(
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700434 ::aos::time::DurationInSeconds(t.time_since_epoch()));
James Kuszmaul1057ce82019-02-09 17:58:24 -0800435 spline_x_.push_back(goal_state(0, 0));
436 spline_y_.push_back(goal_state(1, 0));
437 simulation_x_.push_back(state(StateIdx::kX, 0));
438 simulation_y_.push_back(state(StateIdx::kY, 0));
439 simulation_theta_.push_back(state(StateIdx::kTheta, 0));
440 estimated_x_.push_back(known_state(0, 0));
441 estimated_y_.push_back(known_state(1, 0));
442 estimated_theta_.push_back(known_state(StateIdx::kTheta, 0));
443
444 simulation_vl_.push_back(U(0));
445 simulation_vr_.push_back(U(1));
446 U(0, 0) = ::std::max(::std::min(U(0, 0), 12.0), -12.0);
447 U(1, 0) = ::std::max(::std::min(U(1, 0), 12.0), -12.0);
448
449 state = ::frc971::control_loops::RungeKuttaU(
James Kuszmaul074429e2019-03-23 16:01:49 -0700450 [this](const ::Eigen::Matrix<double, 10, 1> &X,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800451 const ::Eigen::Matrix<double, 2, 1> &U) { return DiffEq(X, U); },
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700452 state, U, ::aos::time::DurationInSeconds(dt_config_.dt));
James Kuszmaul1057ce82019-02-09 17:58:24 -0800453
454 // Add arbitrary disturbances at some arbitrary interval. The main points of
455 // interest here are that we (a) stop adding disturbances at the very end of
456 // the trajectory, to allow us to actually converge to the goal, and (b)
457 // scale disturbances by the corruent velocity.
James Kuszmaulc73bb222019-04-07 12:15:35 -0700458 if (GetParam().disturb && i % 75 == 0) {
James Kuszmaul1057ce82019-02-09 17:58:24 -0800459 // Scale the disturbance so that when we have near-zero velocity we don't
460 // have much disturbance.
461 double disturbance_scale = ::std::min(
462 1.0, ::std::sqrt(::std::pow(state(StateIdx::kLeftVelocity, 0), 2) +
463 ::std::pow(state(StateIdx::kRightVelocity, 0), 2)) /
464 3.0);
465 TestLocalizer::State disturbance;
James Kuszmaul074429e2019-03-23 16:01:49 -0700466 disturbance << 0.02, 0.02, 0.001, 0.03, 0.02, 0.0, 0.0, 0.0, 0.0, 0.0;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800467 disturbance *= disturbance_scale;
468 state += disturbance;
469 }
470
471 t += dt_config_.dt;
472 *true_robot_pose_.mutable_pos() << state(StateIdx::kX, 0),
473 state(StateIdx::kY, 0), 0.0;
474 true_robot_pose_.set_theta(state(StateIdx::kTheta, 0));
475 const double left_enc = state(StateIdx::kLeftEncoder, 0);
476 const double right_enc = state(StateIdx::kRightEncoder, 0);
477
478 const double gyro = (state(StateIdx::kRightVelocity, 0) -
479 state(StateIdx::kLeftVelocity, 0)) /
480 dt_config_.robot_radius / 2.0;
481
482 localizer_.UpdateEncodersAndGyro(left_enc + Normal(encoder_noise_),
483 right_enc + Normal(encoder_noise_),
484 gyro + Normal(gyro_noise_), U, t);
485
James Kuszmaul6f941b72019-03-08 18:12:25 -0800486 for (size_t cam_idx = 0; cam_idx < camera_queues.size(); ++cam_idx) {
487 auto &camera_queue = camera_queues[cam_idx];
488 // Clear out the camera frames that we are ready to pass to the localizer.
489 while (!camera_queue.empty() && ::std::get<0>(camera_queue.front()) <
490 t - camera_latencies[cam_idx]) {
491 const auto tuple = camera_queue.front();
492 camera_queue.pop();
493 ::aos::monotonic_clock::time_point t_obs = ::std::get<0>(tuple);
494 const TestCamera *camera = ::std::get<1>(tuple);
495 ::aos::SizedArray<TestCamera::TargetView, kNumTargetsPerFrame> views =
496 ::std::get<2>(tuple);
497 localizer_.UpdateTargets(*camera, views, t_obs);
498 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800499
James Kuszmaul6f941b72019-03-08 18:12:25 -0800500 // Actually take all the images and store them in the queue.
501 if (i % camera_period == 0) {
502 for (size_t jj = 0; jj < true_cameras_.size(); ++jj) {
503 const auto target_views = true_cameras_[jj].target_views();
504 ::aos::SizedArray<TestCamera::TargetView, kNumTargetsPerFrame>
505 pass_views;
506 for (size_t ii = 0;
507 ii < ::std::min(kNumTargetsPerFrame, target_views.size());
508 ++ii) {
509 TestCamera::TargetView view = target_views[ii];
510 Noisify(&view);
511 pass_views.push_back(view);
512 }
513 camera_queue.emplace(t, &robot_cameras_[jj], pass_views);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800514 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800515 }
516 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800517 }
518
519 const auto end = ::std::chrono::steady_clock::now();
520 avg_time_ = (end - begin) / i;
521 TestLocalizer::State estimate_err = state - localizer_.X_hat();
522 EXPECT_LT(estimate_err.template topRows<7>().norm(),
523 GetParam().estimate_tolerance);
524 // Check that none of the states that we actually care about (x/y/theta, and
525 // wheel positions/speeds) are too far off, individually:
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700526 EXPECT_LT(estimate_err.template topRows<3>().cwiseAbs().maxCoeff(),
James Kuszmaul1057ce82019-02-09 17:58:24 -0800527 GetParam().estimate_tolerance / 3.0)
528 << "Estimate error: " << estimate_err.transpose();
529 Eigen::Matrix<double, 5, 1> final_trajectory_state;
530 final_trajectory_state << state(StateIdx::kX, 0), state(StateIdx::kY, 0),
531 state(StateIdx::kTheta, 0), state(StateIdx::kLeftVelocity, 0),
532 state(StateIdx::kRightVelocity, 0);
533 const Eigen::Matrix<double, 5, 1> final_trajectory_state_err =
534 final_trajectory_state - spline_drivetrain_.CurrentGoalState();
535 EXPECT_LT(final_trajectory_state_err.norm(), GetParam().goal_tolerance)
536 << "Goal error: " << final_trajectory_state_err.transpose();
537}
538
539INSTANTIATE_TEST_CASE_P(
540 LocalizerTest, ParameterizedLocalizerTest,
541 ::testing::Values(
542 // Checks a "perfect" scenario, where we should track perfectly.
543 LocalizerTestParams({
544 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
545 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700546 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
547 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800548 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700549 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
550 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800551 .finished(),
552 /*noisify=*/false,
553 /*disturb=*/false,
554 /*estimate_tolerance=*/1e-5,
555 /*goal_tolerance=*/2e-2,
556 }),
557 // Checks "perfect" estimation, but start off the spline and check
558 // that we can still follow it.
559 LocalizerTestParams({
560 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
561 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700562 (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
563 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800564 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700565 (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
566 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800567 .finished(),
568 /*noisify=*/false,
569 /*disturb=*/false,
570 /*estimate_tolerance=*/1e-5,
571 /*goal_tolerance=*/2e-2,
572 }),
573 // Repeats perfect scenario, but add sensor noise.
574 LocalizerTestParams({
575 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
576 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700577 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
578 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800579 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700580 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
581 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800582 .finished(),
583 /*noisify=*/true,
584 /*disturb=*/false,
585 /*estimate_tolerance=*/0.2,
James Kuszmaula5632fe2019-03-23 20:28:33 -0700586 /*goal_tolerance=*/0.4,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800587 }),
588 // Repeats perfect scenario, but add initial estimator error.
589 LocalizerTestParams({
590 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
591 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700592 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
593 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800594 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700595 (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0,
596 0.0, 0.0, 0.0)
597 .finished(),
598 /*noisify=*/false,
599 /*disturb=*/false,
600 /*estimate_tolerance=*/1e-4,
601 /*goal_tolerance=*/2e-2,
602 }),
603 // Repeats perfect scenario, but add voltage + angular errors:
604 LocalizerTestParams({
605 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
606 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
607 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0,
608 0.5, 0.02)
609 .finished(),
610 (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0,
611 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800612 .finished(),
613 /*noisify=*/false,
614 /*disturb=*/false,
615 /*estimate_tolerance=*/1e-4,
616 /*goal_tolerance=*/2e-2,
617 }),
618 // Add disturbances while we are driving:
619 LocalizerTestParams({
620 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
621 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700622 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
623 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800624 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700625 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
626 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800627 .finished(),
628 /*noisify=*/false,
629 /*disturb=*/true,
James Kuszmaulc73bb222019-04-07 12:15:35 -0700630 /*estimate_tolerance=*/2.5e-2,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800631 /*goal_tolerance=*/0.15,
632 }),
633 // Add noise and some initial error in addition:
634 LocalizerTestParams({
635 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
636 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700637 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
638 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800639 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700640 (TestLocalizer::State() << 0.1, -5.1, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0,
641 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800642 .finished(),
643 /*noisify=*/true,
644 /*disturb=*/true,
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700645 /*estimate_tolerance=*/0.2,
James Kuszmaul074429e2019-03-23 16:01:49 -0700646 /*goal_tolerance=*/0.5,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800647 }),
648 // Try another spline, just in case the one I was using is special for
649 // some reason; this path will also go straight up to a target, to
650 // better simulate what might happen when trying to score:
651 LocalizerTestParams({
652 /*control_pts_x=*/{{0.5, 3.5, 4.0, 8.0, 11.0, 10.2}},
653 /*control_pts_y=*/{{1.0, 1.0, -3.0, -2.0, -3.5, -3.65}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700654 (TestLocalizer::State() << 0.6, 1.01, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
655 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800656 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700657 (TestLocalizer::State() << 0.5, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
658 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800659 .finished(),
660 /*noisify=*/true,
661 /*disturb=*/false,
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700662 // TODO(james): Improve tests so that we aren't constantly
663 // readjusting the tolerances up.
James Kuszmaulc40c26e2019-03-24 16:26:43 -0700664 /*estimate_tolerance=*/0.3,
James Kuszmaul074429e2019-03-23 16:01:49 -0700665 /*goal_tolerance=*/0.7,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800666 })));
667
668} // namespace testing
669} // namespace control_loops
670} // namespace y2019