blob: 28f023590711e71a0783781663270cb02053f17c [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
Philipp Schrader790cb542023-07-05 21:06:52 -07006#include "gflags/gflags.h"
7
James Kuszmaul1057ce82019-02-09 17:58:24 -08008#include "aos/testing/random_seed.h"
9#include "aos/testing/test_shm.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -080010#include "frc971/control_loops/drivetrain/splinedrivetrain.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -070011#include "frc971/control_loops/drivetrain/trajectory.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -080012#if defined(SUPPORT_PLOT)
13#include "third_party/matplotlib-cpp/matplotlibcpp.h"
14#endif
15#include "gtest/gtest.h"
Philipp Schrader790cb542023-07-05 21:06:52 -070016
James Kuszmaul1057ce82019-02-09 17:58:24 -080017#include "y2019/constants.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -070018#include "y2019/control_loops/drivetrain/drivetrain_base.h"
James Kuszmaul1057ce82019-02-09 17:58:24 -080019
20DEFINE_bool(plot, false, "If true, plot");
21
22namespace y2019 {
23namespace control_loops {
24namespace testing {
25
26using ::y2019::constants::Field;
27
28constexpr size_t kNumCameras = 4;
29constexpr size_t kNumTargetsPerFrame = 3;
30
31typedef TypedLocalizer<kNumCameras, Field::kNumTargets, Field::kNumObstacles,
James Kuszmaul651fc3f2019-05-15 21:14:25 -070032 kNumTargetsPerFrame, double>
33 TestLocalizer;
James Kuszmaul1057ce82019-02-09 17:58:24 -080034typedef typename TestLocalizer::Camera TestCamera;
James Kuszmaulf4ede202020-02-14 08:47:40 -080035typedef typename TestLocalizer::Target Target;
James Kuszmaul1057ce82019-02-09 17:58:24 -080036typedef typename TestCamera::Pose Pose;
37typedef typename TestCamera::LineSegment Obstacle;
38
39typedef TestLocalizer::StateIdx StateIdx;
40
41using ::frc971::control_loops::drivetrain::DrivetrainConfig;
42
43// When placing the cameras on the robot, set them all kCameraOffset out from
44// the center, to test that we really can handle cameras that aren't at the
45// center-of-mass.
46constexpr double kCameraOffset = 0.1;
47
48#if defined(SUPPORT_PLOT)
49// Plots a line from a vector of Pose's.
50void PlotPlotPts(const ::std::vector<Pose> &poses,
51 const ::std::map<::std::string, ::std::string> &kwargs) {
52 ::std::vector<double> x;
53 ::std::vector<double> y;
James Kuszmaul651fc3f2019-05-15 21:14:25 -070054 for (const Pose &p : poses) {
James Kuszmaul1057ce82019-02-09 17:58:24 -080055 x.push_back(p.abs_pos().x());
56 y.push_back(p.abs_pos().y());
57 }
58 matplotlibcpp::plot(x, y, kwargs);
59}
60#endif
61
62struct LocalizerTestParams {
63 // Control points for the spline to make the robot follow.
64 ::std::array<float, 6> control_pts_x;
65 ::std::array<float, 6> control_pts_y;
66 // The actual state to start the robot at. By setting voltage errors and the
67 // such you can introduce persistent disturbances.
68 TestLocalizer::State true_start_state;
69 // The initial state of the estimator.
70 TestLocalizer::State known_start_state;
71 // Whether or not to add Gaussian noise to the sensors and cameras.
72 bool noisify;
73 // Whether or not to add unmodelled disturbances.
74 bool disturb;
75 // The tolerances for the estimator and for the trajectory following at
76 // the end of the spline:
77 double estimate_tolerance;
78 double goal_tolerance;
79};
80
81class ParameterizedLocalizerTest
82 : public ::testing::TestWithParam<LocalizerTestParams> {
83 public:
84 ::aos::testing::TestSharedMemory shm_;
85
86 // Set up three targets in a row, at (-1, 0), (0, 0), and (1, 0).
87 // Make the right-most target (1, 0) be facing away from the camera, and give
88 // the middle target some skew.
89 // Place one camera facing forward, the other facing backward, and set the
90 // robot at (0, -5) with the cameras each 0.1m from the center.
91 // Place one obstacle in a place where it can block the left-most target (-1,
92 // 0).
93 ParameterizedLocalizerTest()
94 : field_(),
95 targets_(field_.targets()),
96 modeled_obstacles_(field_.obstacles()),
97 true_obstacles_(field_.obstacles()),
98 dt_config_(drivetrain::GetDrivetrainConfig()),
99 // Pull the noise for the encoders/gyros from the R matrix:
100 encoder_noise_(::std::sqrt(
101 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R(
102 0, 0))),
103 gyro_noise_(::std::sqrt(
104 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R(
105 2, 2))),
106 // As per the comments in localizer.h, we set the field of view and
107 // noise parameters on the robot_cameras_ so that they see a bit more
108 // than the true_cameras_. The robot_cameras_ are what is passed to the
109 // localizer and used to generate "expected" targets. The true_cameras_
110 // are what we actually use to generate targets to pass to the
111 // localizer.
112 robot_cameras_{
113 {TestCamera({&robot_pose_, {0.0, kCameraOffset, 0.0}, M_PI_2},
114 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
115 modeled_obstacles_),
116 TestCamera({&robot_pose_, {kCameraOffset, 0.0, 0.0}, 0.0},
117 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
118 modeled_obstacles_),
119 TestCamera({&robot_pose_, {-kCameraOffset, 0.0, 0.0}, M_PI},
120 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
121 modeled_obstacles_),
122 TestCamera({&robot_pose_, {0.0, -kCameraOffset, 0.0}, -M_PI_2},
123 M_PI_2 * 1.1, robot_noise_parameters_, targets_,
124 modeled_obstacles_)}},
125 true_cameras_{
126 {TestCamera({&true_robot_pose_, {0.0, kCameraOffset, 0.0}, M_PI_2},
127 M_PI_2 * 0.9, true_noise_parameters_, targets_,
128 true_obstacles_),
129 TestCamera({&true_robot_pose_, {kCameraOffset, 0.0, 0.0}, 0.0},
130 M_PI_2 * 0.9, true_noise_parameters_, targets_,
131 true_obstacles_),
132 TestCamera({&true_robot_pose_, {-kCameraOffset, 0.0, 0.0}, M_PI},
133 M_PI_2 * 0.9, true_noise_parameters_, targets_,
134 true_obstacles_),
135 TestCamera(
136 {&true_robot_pose_, {-0.0, -kCameraOffset, 0.0}, -M_PI_2},
137 M_PI_2 * 0.9, true_noise_parameters_, targets_,
138 true_obstacles_)}},
139 localizer_(dt_config_, &robot_pose_),
140 spline_drivetrain_(dt_config_) {
141 // We use the default P() for initialization.
142 localizer_.ResetInitialState(t0_, GetParam().known_start_state,
143 localizer_.P());
144 }
145
146 void SetUp() {
Alex Perrycb7da4b2019-08-28 19:35:56 -0700147 {
148 flatbuffers::FlatBufferBuilder fbb;
Alex Perrycb7da4b2019-08-28 19:35:56 -0700149 flatbuffers::Offset<flatbuffers::Vector<float>> spline_x_offset =
150 fbb.CreateVector<float>(GetParam().control_pts_x.begin(),
151 GetParam().control_pts_x.size());
152
153 flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset =
154 fbb.CreateVector<float>(GetParam().control_pts_y.begin(),
155 GetParam().control_pts_y.size());
156
157 frc971::MultiSpline::Builder multispline_builder(fbb);
158
159 multispline_builder.add_spline_count(1);
160 multispline_builder.add_spline_x(spline_x_offset);
161 multispline_builder.add_spline_y(spline_y_offset);
162
163 flatbuffers::Offset<frc971::MultiSpline> multispline_offset =
164 multispline_builder.Finish();
165
166 frc971::control_loops::drivetrain::SplineGoal::Builder spline_builder(
167 fbb);
168
169 spline_builder.add_spline_idx(1);
170 spline_builder.add_spline(multispline_offset);
171
James Kuszmaul75a18c52021-03-10 22:02:07 -0800172 fbb.Finish(spline_builder.Finish());
173 aos::FlatbufferDetachedBuffer<
174 frc971::control_loops::drivetrain::SplineGoal>
175 spline_goal_buffer(fbb.Release());
176
177 frc971::control_loops::drivetrain::Trajectory trajectory(
178 spline_goal_buffer.message(), dt_config_);
179 trajectory.Plan();
180
181 flatbuffers::FlatBufferBuilder traj_fbb;
182
183 traj_fbb.Finish(trajectory.Serialize(&traj_fbb));
184
185 trajectory_ = std::make_unique<aos::FlatbufferDetachedBuffer<
186 frc971::control_loops::drivetrain::fb::Trajectory>>(
187 traj_fbb.Release());
188 spline_drivetrain_.AddTrajectory(&trajectory_->message());
189 }
190
191 flatbuffers::DetachedBuffer goal_buffer;
192 {
193 flatbuffers::FlatBufferBuilder fbb;
Alex Perrycb7da4b2019-08-28 19:35:56 -0700194
195 frc971::control_loops::drivetrain::Goal::Builder goal_builder(fbb);
196
Alex Perrycb7da4b2019-08-28 19:35:56 -0700197 goal_builder.add_controller_type(
Austin Schuh872723c2019-12-25 14:38:09 -0800198 frc971::control_loops::drivetrain::ControllerType::SPLINE_FOLLOWER);
Alex Perrycb7da4b2019-08-28 19:35:56 -0700199 goal_builder.add_spline_handle(1);
200
201 fbb.Finish(goal_builder.Finish());
202
203 goal_buffer = fbb.Release();
204 }
205 aos::FlatbufferDetachedBuffer<frc971::control_loops::drivetrain::Goal> goal(
206 std::move(goal_buffer));
207
Alex Perrycb7da4b2019-08-28 19:35:56 -0700208 spline_drivetrain_.SetGoal(&goal.message());
James Kuszmaul1057ce82019-02-09 17:58:24 -0800209 }
210
211 void TearDown() {
212 printf("Each iteration of the simulation took on average %f seconds.\n",
213 avg_time_.count());
214#if defined(SUPPORT_PLOT)
215 if (FLAGS_plot) {
216 matplotlibcpp::figure();
217 matplotlibcpp::plot(simulation_t_, simulation_vl_, {{"label", "Vl"}});
218 matplotlibcpp::plot(simulation_t_, simulation_vr_, {{"label", "Vr"}});
219 matplotlibcpp::legend();
220
221 matplotlibcpp::figure();
222 matplotlibcpp::plot(spline_x_, spline_y_, {{"label", "spline"}});
223 matplotlibcpp::plot(simulation_x_, simulation_y_, {{"label", "robot"}});
224 matplotlibcpp::plot(estimated_x_, estimated_y_,
225 {{"label", "estimation"}});
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700226 for (const Target &target : targets_) {
James Kuszmaul1057ce82019-02-09 17:58:24 -0800227 PlotPlotPts(target.PlotPoints(), {{"c", "g"}});
228 }
229 for (const Obstacle &obstacle : true_obstacles_) {
230 PlotPlotPts(obstacle.PlotPoints(), {{"c", "k"}});
231 }
232 // Go through and plot true/expected camera targets for a few select
233 // time-steps.
234 ::std::vector<const char *> colors{"m", "y", "c"};
235 int jj = 0;
236 for (size_t ii = 0; ii < simulation_x_.size(); ii += 400) {
237 *true_robot_pose_.mutable_pos() << simulation_x_[ii], simulation_y_[ii],
238 0.0;
239 true_robot_pose_.set_theta(simulation_theta_[ii]);
240 for (const TestCamera &camera : true_cameras_) {
241 for (const auto &plot_pts : camera.PlotPoints()) {
242 PlotPlotPts(plot_pts, {{"c", colors[jj]}});
243 }
244 }
245 for (const TestCamera &camera : robot_cameras_) {
246 *robot_pose_.mutable_pos() << estimated_x_[ii], estimated_y_[ii], 0.0;
247 robot_pose_.set_theta(estimated_theta_[ii]);
248 const auto &all_plot_pts = camera.PlotPoints();
249 *robot_pose_.mutable_pos() = true_robot_pose_.rel_pos();
250 robot_pose_.set_theta(true_robot_pose_.rel_theta());
251 for (const auto &plot_pts : all_plot_pts) {
252 PlotPlotPts(plot_pts, {{"c", colors[jj]}, {"ls", "--"}});
253 }
254 }
255 jj = (jj + 1) % colors.size();
256 }
257 matplotlibcpp::legend();
258
259 matplotlibcpp::figure();
260 matplotlibcpp::plot(
261 simulation_t_, spline_x_,
262 {{"label", "spline x"}, {"c", "g"}, {"ls", ""}, {"marker", "o"}});
263 matplotlibcpp::plot(simulation_t_, simulation_x_,
264 {{"label", "simulated x"}, {"c", "g"}});
265 matplotlibcpp::plot(simulation_t_, estimated_x_,
266 {{"label", "estimated x"}, {"c", "g"}, {"ls", "--"}});
267
268 matplotlibcpp::plot(
269 simulation_t_, spline_y_,
270 {{"label", "spline y"}, {"c", "b"}, {"ls", ""}, {"marker", "o"}});
271 matplotlibcpp::plot(simulation_t_, simulation_y_,
272 {{"label", "simulated y"}, {"c", "b"}});
273 matplotlibcpp::plot(simulation_t_, estimated_y_,
274 {{"label", "estimated y"}, {"c", "b"}, {"ls", "--"}});
275
276 matplotlibcpp::plot(simulation_t_, simulation_theta_,
277 {{"label", "simulated theta"}, {"c", "r"}});
278 matplotlibcpp::plot(
279 simulation_t_, estimated_theta_,
280 {{"label", "estimated theta"}, {"c", "r"}, {"ls", "--"}});
281 matplotlibcpp::legend();
282
283 matplotlibcpp::show();
284 }
285#endif
286 }
287
288 protected:
289 // Returns a random number with a gaussian distribution with a mean of zero
290 // and a standard deviation of std, if noisify = true.
291 // If noisify is false, then returns 0.0.
292 double Normal(double std) {
293 if (GetParam().noisify) {
294 return normal_(gen_) * std;
295 }
296 return 0.0;
297 }
298 // Adds random noise to the given target view.
299 void Noisify(TestCamera::TargetView *view) {
300 view->reading.heading += Normal(view->noise.heading);
301 view->reading.distance += Normal(view->noise.distance);
302 view->reading.height += Normal(view->noise.height);
303 view->reading.skew += Normal(view->noise.skew);
304 }
305 // The differential equation for the dynamics of the system.
306 TestLocalizer::State DiffEq(const TestLocalizer::State &X,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800307 const Eigen::Vector2d &voltage) {
308 TestLocalizer::Input U;
309 U.setZero();
310 U(0) = voltage(0);
311 U(1) = voltage(1);
312 return localizer_.DiffEq(X, U, true);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800313 }
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
James Kuszmaul75a18c52021-03-10 22:02:07 -0800352 std::unique_ptr<aos::FlatbufferDetachedBuffer<
353 frc971::control_loops::drivetrain::fb::Trajectory>>
354 trajectory_;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800355 ::frc971::control_loops::drivetrain::SplineDrivetrain spline_drivetrain_;
356
357 // All the data we want to end up plotting.
358 ::std::vector<double> simulation_t_;
359
360 ::std::vector<double> spline_x_;
361 ::std::vector<double> spline_y_;
362 ::std::vector<double> estimated_x_;
363 ::std::vector<double> estimated_y_;
364 ::std::vector<double> estimated_theta_;
365 ::std::vector<double> simulation_x_;
366 ::std::vector<double> simulation_y_;
367 ::std::vector<double> simulation_theta_;
368
369 ::std::vector<double> simulation_vl_;
370 ::std::vector<double> simulation_vr_;
371
372 // Simulation start time
373 ::aos::monotonic_clock::time_point t0_;
374
375 // Average duration of each iteration; used for debugging and getting a
376 // sanity-check on what performance looks like--uses a real system clock.
377 ::std::chrono::duration<double> avg_time_;
378
379 ::std::mt19937 gen_{static_cast<uint32_t>(::aos::testing::RandomSeed())};
380 ::std::normal_distribution<> normal_;
381};
382
James Kuszmaul6f941b72019-03-08 18:12:25 -0800383using ::std::chrono::milliseconds;
384
James Kuszmaul1057ce82019-02-09 17:58:24 -0800385// Tests that, when we attempt to follow a spline and use the localizer to
386// perform the state estimation, we end up roughly where we should and that
387// the localizer has a valid position estimate.
388TEST_P(ParameterizedLocalizerTest, SplineTest) {
389 // state stores the true state of the robot throughout the simulation.
390 TestLocalizer::State state = GetParam().true_start_state;
391
392 ::aos::monotonic_clock::time_point t = t0_;
393
394 // The period with which we should take frames from the cameras. Currently,
395 // we just trigger all the cameras at once, rather than offsetting them or
396 // anything.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700397 const int camera_period = 5; // cycles
James Kuszmaul6f941b72019-03-08 18:12:25 -0800398 // The amount of time to delay the camera images from when they are taken, for
399 // each camera.
400 const ::std::array<milliseconds, 4> camera_latencies{
401 {milliseconds(45), milliseconds(50), milliseconds(55),
402 milliseconds(100)}};
James Kuszmaul1057ce82019-02-09 17:58:24 -0800403
James Kuszmaul6f941b72019-03-08 18:12:25 -0800404 // A queue of camera frames for each camera so that we can add a time delay to
405 // the data coming from the cameras.
406 ::std::array<
407 ::std::queue<::std::tuple<
408 ::aos::monotonic_clock::time_point, const TestCamera *,
409 ::aos::SizedArray<TestCamera::TargetView, kNumTargetsPerFrame>>>,
410 4>
411 camera_queues;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800412
413 // Start time, for debugging.
414 const auto begin = ::std::chrono::steady_clock::now();
415
416 size_t i;
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700417 // Run the feedback-controller slightly past the nominal end-time. This both
418 // exercises the code to see what happens when we are trying to stand still,
419 // and gives the control loops time to stabilize.
420 aos::monotonic_clock::duration extra_time = std::chrono::seconds(2);
421 for (i = 0;
422 !spline_drivetrain_.IsAtEnd() || extra_time > std::chrono::seconds(0);
423 ++i) {
424 if (spline_drivetrain_.IsAtEnd()) {
425 extra_time -= dt_config_.dt;
426 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800427 // Get the current state estimate into a matrix that works for the
428 // trajectory code.
429 ::Eigen::Matrix<double, 5, 1> known_state;
430 TestLocalizer::State X_hat = localizer_.X_hat();
431 known_state << X_hat(StateIdx::kX, 0), X_hat(StateIdx::kY, 0),
432 X_hat(StateIdx::kTheta, 0), X_hat(StateIdx::kLeftVelocity, 0),
433 X_hat(StateIdx::kRightVelocity, 0);
434
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700435 Eigen::Vector2d voltage_error(X_hat(StateIdx::kLeftVoltageError),
436 X_hat(StateIdx::kRightVoltageError));
437 spline_drivetrain_.Update(true, known_state, voltage_error);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800438
Alex Perrycb7da4b2019-08-28 19:35:56 -0700439 ::frc971::control_loops::drivetrain::OutputT output;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800440 output.left_voltage = 0;
441 output.right_voltage = 0;
442 spline_drivetrain_.SetOutput(&output);
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800443 Eigen::Vector2d U(output.left_voltage, output.right_voltage);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800444
445 const ::Eigen::Matrix<double, 5, 1> goal_state =
446 spline_drivetrain_.CurrentGoalState();
447 simulation_t_.push_back(
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700448 ::aos::time::DurationInSeconds(t.time_since_epoch()));
James Kuszmaul1057ce82019-02-09 17:58:24 -0800449 spline_x_.push_back(goal_state(0, 0));
450 spline_y_.push_back(goal_state(1, 0));
451 simulation_x_.push_back(state(StateIdx::kX, 0));
452 simulation_y_.push_back(state(StateIdx::kY, 0));
453 simulation_theta_.push_back(state(StateIdx::kTheta, 0));
454 estimated_x_.push_back(known_state(0, 0));
455 estimated_y_.push_back(known_state(1, 0));
456 estimated_theta_.push_back(known_state(StateIdx::kTheta, 0));
457
458 simulation_vl_.push_back(U(0));
459 simulation_vr_.push_back(U(1));
460 U(0, 0) = ::std::max(::std::min(U(0, 0), 12.0), -12.0);
461 U(1, 0) = ::std::max(::std::min(U(1, 0), 12.0), -12.0);
462
463 state = ::frc971::control_loops::RungeKuttaU(
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800464 [this](const ::Eigen::Matrix<double, 12, 1> &X,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800465 const ::Eigen::Matrix<double, 2, 1> &U) { return DiffEq(X, U); },
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700466 state, U, ::aos::time::DurationInSeconds(dt_config_.dt));
James Kuszmaul1057ce82019-02-09 17:58:24 -0800467
468 // Add arbitrary disturbances at some arbitrary interval. The main points of
469 // interest here are that we (a) stop adding disturbances at the very end of
470 // the trajectory, to allow us to actually converge to the goal, and (b)
471 // scale disturbances by the corruent velocity.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800472 // TODO(james): Figure out how to persist good accelerometer values through
473 // the disturbances.
James Kuszmaulc73bb222019-04-07 12:15:35 -0700474 if (GetParam().disturb && i % 75 == 0) {
James Kuszmaul1057ce82019-02-09 17:58:24 -0800475 // Scale the disturbance so that when we have near-zero velocity we don't
476 // have much disturbance.
477 double disturbance_scale = ::std::min(
478 1.0, ::std::sqrt(::std::pow(state(StateIdx::kLeftVelocity, 0), 2) +
479 ::std::pow(state(StateIdx::kRightVelocity, 0), 2)) /
480 3.0);
481 TestLocalizer::State disturbance;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800482 disturbance << 0.02, 0.02, 0.001, 0.03, 0.02, 0.0, 0.0, 0.0, 0.0, 0.0,
483 0.0, 0.0;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800484 disturbance *= disturbance_scale;
485 state += disturbance;
486 }
487
488 t += dt_config_.dt;
489 *true_robot_pose_.mutable_pos() << state(StateIdx::kX, 0),
490 state(StateIdx::kY, 0), 0.0;
491 true_robot_pose_.set_theta(state(StateIdx::kTheta, 0));
492 const double left_enc = state(StateIdx::kLeftEncoder, 0);
493 const double right_enc = state(StateIdx::kRightEncoder, 0);
494
Philipp Schrader790cb542023-07-05 21:06:52 -0700495 const double gyro =
496 (state(StateIdx::kRightVelocity) - state(StateIdx::kLeftVelocity)) /
497 dt_config_.robot_radius / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800498 const TestLocalizer::State xdot = DiffEq(state, U);
499 const Eigen::Vector3d accel(
500 localizer_.CalcLongitudinalVelocity(xdot) -
501 gyro * state(StateIdx::kLateralVelocity),
502 gyro * localizer_.CalcLongitudinalVelocity(state), 1.0);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800503
504 localizer_.UpdateEncodersAndGyro(left_enc + Normal(encoder_noise_),
505 right_enc + Normal(encoder_noise_),
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800506 gyro + Normal(gyro_noise_), U, accel, t);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800507
James Kuszmaul6f941b72019-03-08 18:12:25 -0800508 for (size_t cam_idx = 0; cam_idx < camera_queues.size(); ++cam_idx) {
509 auto &camera_queue = camera_queues[cam_idx];
510 // Clear out the camera frames that we are ready to pass to the localizer.
511 while (!camera_queue.empty() && ::std::get<0>(camera_queue.front()) <
512 t - camera_latencies[cam_idx]) {
513 const auto tuple = camera_queue.front();
514 camera_queue.pop();
515 ::aos::monotonic_clock::time_point t_obs = ::std::get<0>(tuple);
516 const TestCamera *camera = ::std::get<1>(tuple);
517 ::aos::SizedArray<TestCamera::TargetView, kNumTargetsPerFrame> views =
518 ::std::get<2>(tuple);
519 localizer_.UpdateTargets(*camera, views, t_obs);
520 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800521
James Kuszmaul6f941b72019-03-08 18:12:25 -0800522 // Actually take all the images and store them in the queue.
523 if (i % camera_period == 0) {
524 for (size_t jj = 0; jj < true_cameras_.size(); ++jj) {
525 const auto target_views = true_cameras_[jj].target_views();
526 ::aos::SizedArray<TestCamera::TargetView, kNumTargetsPerFrame>
527 pass_views;
528 for (size_t ii = 0;
529 ii < ::std::min(kNumTargetsPerFrame, target_views.size());
530 ++ii) {
531 TestCamera::TargetView view = target_views[ii];
532 Noisify(&view);
533 pass_views.push_back(view);
534 }
535 camera_queue.emplace(t, &robot_cameras_[jj], pass_views);
James Kuszmaul1057ce82019-02-09 17:58:24 -0800536 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800537 }
538 }
James Kuszmaul1057ce82019-02-09 17:58:24 -0800539 }
540
541 const auto end = ::std::chrono::steady_clock::now();
542 avg_time_ = (end - begin) / i;
543 TestLocalizer::State estimate_err = state - localizer_.X_hat();
544 EXPECT_LT(estimate_err.template topRows<7>().norm(),
545 GetParam().estimate_tolerance);
546 // Check that none of the states that we actually care about (x/y/theta, and
547 // wheel positions/speeds) are too far off, individually:
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700548 EXPECT_LT(estimate_err.template topRows<3>().cwiseAbs().maxCoeff(),
James Kuszmaul1057ce82019-02-09 17:58:24 -0800549 GetParam().estimate_tolerance / 3.0)
550 << "Estimate error: " << estimate_err.transpose();
551 Eigen::Matrix<double, 5, 1> final_trajectory_state;
552 final_trajectory_state << state(StateIdx::kX, 0), state(StateIdx::kY, 0),
553 state(StateIdx::kTheta, 0), state(StateIdx::kLeftVelocity, 0),
554 state(StateIdx::kRightVelocity, 0);
555 const Eigen::Matrix<double, 5, 1> final_trajectory_state_err =
556 final_trajectory_state - spline_drivetrain_.CurrentGoalState();
557 EXPECT_LT(final_trajectory_state_err.norm(), GetParam().goal_tolerance)
558 << "Goal error: " << final_trajectory_state_err.transpose();
559}
560
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700561// NOTE: Following the 2019 season, we stopped maintaining this as rigorously.
562// This means that changes to either the base HybridEKF class or the spline
563// controller can cause us to violate the tolerances specified here. We
564// currently just up the tolerances whenever they cause issues, so long as
565// things don't appear to be unstable (since these tests do do a test of the
566// full localizer + spline system, we should pay attention if there is actual
567// instability rather than just poor tolerances).
James Kuszmaulf4bf9fe2021-05-10 22:58:24 -0700568INSTANTIATE_TEST_SUITE_P(
James Kuszmaul1057ce82019-02-09 17:58:24 -0800569 LocalizerTest, ParameterizedLocalizerTest,
570 ::testing::Values(
571 // Checks a "perfect" scenario, where we should track perfectly.
572 LocalizerTestParams({
573 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
574 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700575 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800576 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800577 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700578 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800579 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800580 .finished(),
581 /*noisify=*/false,
582 /*disturb=*/false,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800583 /*estimate_tolerance=*/1e-2,
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700584 /*goal_tolerance=*/0.2,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800585 }),
586 // Checks "perfect" estimation, but start off the spline and check
587 // that we can still follow it.
588 LocalizerTestParams({
589 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
590 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700591 (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800592 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800593 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700594 (TestLocalizer::State() << 0.0, -4.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800595 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800596 .finished(),
597 /*noisify=*/false,
598 /*disturb=*/false,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800599 /*estimate_tolerance=*/1e-2,
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700600 /*goal_tolerance=*/0.4,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800601 }),
602 // Repeats perfect scenario, but add sensor noise.
603 LocalizerTestParams({
604 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
605 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700606 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800607 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800608 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700609 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800610 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800611 .finished(),
612 /*noisify=*/true,
613 /*disturb=*/false,
James Kuszmaulea314d92019-02-18 19:45:06 -0800614 /*estimate_tolerance=*/0.4,
James Kuszmaul07b40442020-03-08 22:20:21 -0700615 /*goal_tolerance=*/0.8,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800616 }),
617 // Repeats perfect scenario, but add initial estimator error.
618 LocalizerTestParams({
619 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
620 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700621 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800622 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800623 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700624 (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800625 0.0, 0.0, 0.0, 0.0, 0.0)
James Kuszmaul074429e2019-03-23 16:01:49 -0700626 .finished(),
627 /*noisify=*/false,
628 /*disturb=*/false,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800629 /*estimate_tolerance=*/1e-2,
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700630 /*goal_tolerance=*/0.2,
James Kuszmaul074429e2019-03-23 16:01:49 -0700631 }),
632 // Repeats perfect scenario, but add voltage + angular errors:
633 LocalizerTestParams({
634 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
635 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700636 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5,
637 0.25, 0.02, 0.0, 0.0)
James Kuszmaul074429e2019-03-23 16:01:49 -0700638 .finished(),
639 (TestLocalizer::State() << 0.1, -5.1, -0.01, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800640 0.0, 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800641 .finished(),
642 /*noisify=*/false,
643 /*disturb=*/false,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800644 /*estimate_tolerance=*/1e-2,
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700645 /*goal_tolerance=*/0.3,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800646 }),
647 // Add disturbances while we are driving:
648 LocalizerTestParams({
649 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
650 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700651 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800652 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800653 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700654 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800655 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800656 .finished(),
657 /*noisify=*/false,
658 /*disturb=*/true,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800659 /*estimate_tolerance=*/4e-2,
James Kuszmaulaa2499d2020-06-02 21:31:19 -0700660 /*goal_tolerance=*/0.25,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800661 }),
662 // Add noise and some initial error in addition:
663 LocalizerTestParams({
664 /*control_pts_x=*/{{0.0, 3.0, 3.0, 0.0, 1.0, 1.0}},
665 /*control_pts_y=*/{{-5.0, -5.0, 2.0, 2.0, 2.0, 3.0}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700666 (TestLocalizer::State() << 0.0, -5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800667 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800668 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700669 (TestLocalizer::State() << 0.1, -5.1, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800670 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800671 .finished(),
672 /*noisify=*/true,
673 /*disturb=*/true,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800674 /*estimate_tolerance=*/0.5,
675 /*goal_tolerance=*/1.0,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800676 }),
677 // Try another spline, just in case the one I was using is special for
678 // some reason; this path will also go straight up to a target, to
679 // better simulate what might happen when trying to score:
680 LocalizerTestParams({
681 /*control_pts_x=*/{{0.5, 3.5, 4.0, 8.0, 11.0, 10.2}},
682 /*control_pts_y=*/{{1.0, 1.0, -3.0, -2.0, -3.5, -3.65}},
James Kuszmaul074429e2019-03-23 16:01:49 -0700683 (TestLocalizer::State() << 0.6, 1.01, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800684 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800685 .finished(),
James Kuszmaul074429e2019-03-23 16:01:49 -0700686 (TestLocalizer::State() << 0.5, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800687 0.0, 0.0, 0.0, 0.0)
James Kuszmaul1057ce82019-02-09 17:58:24 -0800688 .finished(),
689 /*noisify=*/true,
690 /*disturb=*/false,
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700691 // TODO(james): Improve tests so that we aren't constantly
692 // readjusting the tolerances up.
James Kuszmaulc40c26e2019-03-24 16:26:43 -0700693 /*estimate_tolerance=*/0.3,
James Kuszmaul074429e2019-03-23 16:01:49 -0700694 /*goal_tolerance=*/0.7,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800695 })));
696
697} // namespace testing
698} // namespace control_loops
699} // namespace y2019