blob: 58df8691b6e0d276fc8a206481ad0cad16d50836 [file] [log] [blame]
James Kuszmaul51fa1ae2022-02-26 00:49:57 -08001#include "y2022/localizer/localizer.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08002
James Kuszmaul8c4f6592022-02-26 15:49:30 -08003#include "aos/events/logging/log_writer.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08004#include "aos/events/simulated_event_loop.h"
5#include "gtest/gtest.h"
6#include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
James Kuszmaul8c4f6592022-02-26 15:49:30 -08007#include "frc971/control_loops/pose.h"
8#include "y2022/vision/target_estimate_generated.h"
9#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
10#include "y2022/control_loops/drivetrain/drivetrain_base.h"
11
12DEFINE_string(output_folder, "",
13 "If set, logs all channels to the provided logfile.");
James Kuszmaul29c59522022-02-12 16:44:26 -080014
15namespace frc971::controls::testing {
16typedef ModelBasedLocalizer::ModelState ModelState;
17typedef ModelBasedLocalizer::AccelState AccelState;
18typedef ModelBasedLocalizer::ModelInput ModelInput;
19typedef ModelBasedLocalizer::AccelInput AccelInput;
James Kuszmaul8c4f6592022-02-26 15:49:30 -080020
21using frc971::vision::calibration::CameraCalibrationT;
22using frc971::vision::calibration::TransformationMatrixT;
23using frc971::control_loops::drivetrain::DrivetrainConfig;
24using frc971::control_loops::drivetrain::LocalizerControl;
25using frc971::control_loops::Pose;
26using y2022::vision::TargetEstimate;
27using y2022::vision::TargetEstimateT;
28
James Kuszmaul29c59522022-02-12 16:44:26 -080029namespace {
30constexpr size_t kX = ModelBasedLocalizer::kX;
31constexpr size_t kY = ModelBasedLocalizer::kY;
32constexpr size_t kTheta = ModelBasedLocalizer::kTheta;
33constexpr size_t kVelocityX = ModelBasedLocalizer::kVelocityX;
34constexpr size_t kVelocityY = ModelBasedLocalizer::kVelocityY;
35constexpr size_t kAccelX = ModelBasedLocalizer::kAccelX;
36constexpr size_t kAccelY = ModelBasedLocalizer::kAccelY;
37constexpr size_t kThetaRate = ModelBasedLocalizer::kThetaRate;
38constexpr size_t kLeftEncoder = ModelBasedLocalizer::kLeftEncoder;
39constexpr size_t kLeftVelocity = ModelBasedLocalizer::kLeftVelocity;
40constexpr size_t kLeftVoltageError = ModelBasedLocalizer::kLeftVoltageError;
41constexpr size_t kRightEncoder = ModelBasedLocalizer::kRightEncoder;
42constexpr size_t kRightVelocity = ModelBasedLocalizer::kRightVelocity;
43constexpr size_t kRightVoltageError = ModelBasedLocalizer::kRightVoltageError;
44constexpr size_t kLeftVoltage = ModelBasedLocalizer::kLeftVoltage;
45constexpr size_t kRightVoltage = ModelBasedLocalizer::kRightVoltage;
James Kuszmaul8c4f6592022-02-26 15:49:30 -080046
47Eigen::Matrix<double, 4, 4> TurretRobotTransformation() {
48 Eigen::Matrix<double, 4, 4> H;
49 H.setIdentity();
50 H.block<3, 1>(0, 3) << 1, 1.1, 0.9;
51 return H;
52}
53
54// Provides the location of the camera on the turret.
55Eigen::Matrix<double, 4, 4> CameraTurretTransformation() {
56 Eigen::Matrix<double, 4, 4> H;
57 H.setIdentity();
58 H.block<3, 1>(0, 3) << 0.1, 0, 0;
59 H.block<3, 3>(0, 0) << 0, 0, 1, -1, 0, 0, 0, -1, 0;
60
61 // Introduce a bit of pitch to make sure that we're exercising all the code.
62 H.block<3, 3>(0, 0) =
63 Eigen::AngleAxis<double>(0.1, Eigen::Vector3d::UnitY()) *
64 H.block<3, 3>(0, 0);
65 return H;
66}
67
68// Copies an Eigen matrix into a row-major vector of the data.
69std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H) {
70 std::vector<float> data;
71 for (int row = 0; row < 4; ++row) {
72 for (int col = 0; col < 4; ++col) {
73 data.push_back(H(row, col));
74 }
75 }
76 return data;
77}
78
79DrivetrainConfig<double> GetTest2022DrivetrainConfig() {
80 DrivetrainConfig<double> config =
81 y2022::control_loops::drivetrain::GetDrivetrainConfig();
82 config.is_simulated = true;
83 return config;
84}
James Kuszmaul29c59522022-02-12 16:44:26 -080085}
86
87class LocalizerTest : public ::testing::Test {
88 protected:
89 LocalizerTest()
90 : dt_config_(
James Kuszmaul8c4f6592022-02-26 15:49:30 -080091 GetTest2022DrivetrainConfig()),
James Kuszmaul5ed29dd2022-02-13 18:32:06 -080092 localizer_(dt_config_) {
93 localizer_.set_longitudinal_offset(0.0);
94 }
James Kuszmaul29c59522022-02-12 16:44:26 -080095 ModelState CallDiffModel(const ModelState &state, const ModelInput &U) {
96 return localizer_.DiffModel(state, U);
97 }
98
99 AccelState CallDiffAccel(const AccelState &state, const AccelInput &U) {
100 return localizer_.DiffAccel(state, U);
101 }
102
103 const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
104 ModelBasedLocalizer localizer_;
105
106};
107
108TEST_F(LocalizerTest, AccelIntegrationTest) {
109 AccelState state;
110 state.setZero();
111 AccelInput input;
112 input.setZero();
113
114 EXPECT_EQ(0.0, CallDiffAccel(state, input).norm());
115 // Non-zero x/y/theta states should still result in a zero derivative.
116 state(kX) = 1.0;
117 state(kY) = 1.0;
118 state(kTheta) = 1.0;
119 EXPECT_EQ(0.0, CallDiffAccel(state, input).norm());
120
121 state.setZero();
122 state(kVelocityX) = 1.0;
123 state(kVelocityY) = 2.0;
124 EXPECT_EQ((AccelState() << 1.0, 2.0, 0.0, 0.0, 0.0).finished(),
125 CallDiffAccel(state, input));
126 // Derivatives should be independent of theta.
127 state(kTheta) = M_PI / 2.0;
128 EXPECT_EQ((AccelState() << 1.0, 2.0, 0.0, 0.0, 0.0).finished(),
129 CallDiffAccel(state, input));
130
131 state.setZero();
132 input(kAccelX) = 1.0;
133 input(kAccelY) = 2.0;
134 input(kThetaRate) = 3.0;
135 EXPECT_EQ((AccelState() << 0.0, 0.0, 3.0, 1.0, 2.0).finished(),
136 CallDiffAccel(state, input));
137 state(kTheta) = M_PI / 2.0;
138 EXPECT_EQ((AccelState() << 0.0, 0.0, 3.0, 1.0, 2.0).finished(),
139 CallDiffAccel(state, input));
140}
141
142TEST_F(LocalizerTest, ModelIntegrationTest) {
143 ModelState state;
144 state.setZero();
145 ModelInput input;
146 input.setZero();
147 ModelState diff;
148
149 EXPECT_EQ(0.0, CallDiffModel(state, input).norm());
150 // Non-zero x/y/theta/encoder states should still result in a zero derivative.
151 state(kX) = 1.0;
152 state(kY) = 1.0;
153 state(kTheta) = 1.0;
154 state(kLeftEncoder) = 1.0;
155 state(kRightEncoder) = 1.0;
156 EXPECT_EQ(0.0, CallDiffModel(state, input).norm());
157
158 state.setZero();
159 state(kLeftVelocity) = 1.0;
160 state(kRightVelocity) = 1.0;
161 diff = CallDiffModel(state, input);
162 const ModelState mask_velocities =
163 (ModelState() << 1.0, 1.0, 1.0, 1.0, 0.0, 1.0, 1.0, 0.0, 1.0).finished();
164 EXPECT_EQ(
165 (ModelState() << 1.0, 0.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0).finished(),
166 diff.cwiseProduct(mask_velocities));
167 EXPECT_EQ(diff(kLeftVelocity), diff(kRightVelocity));
168 EXPECT_GT(0.0, diff(kLeftVelocity));
169 state(kTheta) = M_PI / 2.0;
170 diff = CallDiffModel(state, input);
171 EXPECT_NEAR(0.0,
172 ((ModelState() << 0.0, 1.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, 0.0)
173 .finished() -
174 diff.cwiseProduct(mask_velocities))
175 .norm(),
176 1e-12);
177 EXPECT_EQ(diff(kLeftVelocity), diff(kRightVelocity));
178 EXPECT_GT(0.0, diff(kLeftVelocity));
179
180 state.setZero();
181 state(kLeftVelocity) = -1.0;
182 state(kRightVelocity) = 1.0;
183 diff = CallDiffModel(state, input);
184 EXPECT_EQ((ModelState() << 0.0, 0.0, 1.0 / dt_config_.robot_radius, -1.0, 0.0,
185 0.0, 1.0, 0.0, 0.0)
186 .finished(),
187 diff.cwiseProduct(mask_velocities));
188 EXPECT_EQ(-diff(kLeftVelocity), diff(kRightVelocity));
189 EXPECT_LT(0.0, diff(kLeftVelocity));
190
191 state.setZero();
192 input(kLeftVoltage) = 5.0;
193 input(kRightVoltage) = 6.0;
194 diff = CallDiffModel(state, input);
195 EXPECT_EQ(0, diff(kX));
196 EXPECT_EQ(0, diff(kY));
197 EXPECT_EQ(0, diff(kTheta));
198 EXPECT_EQ(0, diff(kLeftEncoder));
199 EXPECT_EQ(0, diff(kRightEncoder));
200 EXPECT_EQ(0, diff(kLeftVoltageError));
201 EXPECT_EQ(0, diff(kRightVoltageError));
202 EXPECT_LT(0, diff(kLeftVelocity));
203 EXPECT_LT(0, diff(kRightVelocity));
204 EXPECT_LT(diff(kLeftVelocity), diff(kRightVelocity));
205
206 state.setZero();
207 state(kLeftVoltageError) = -1.0;
208 state(kRightVoltageError) = -2.0;
209 input(kLeftVoltage) = 1.0;
210 input(kRightVoltage) = 2.0;
211 EXPECT_EQ(ModelState::Zero(), CallDiffModel(state, input));
212}
213
214// Test that the HandleReset does indeed reset the state of the localizer.
215TEST_F(LocalizerTest, LocalizerReset) {
216 aos::monotonic_clock::time_point t = aos::monotonic_clock::epoch();
217 localizer_.HandleReset(t, {1.0, 2.0, 3.0});
218 EXPECT_EQ((Eigen::Vector3d{1.0, 2.0, 3.0}), localizer_.xytheta());
219 localizer_.HandleReset(t, {4.0, 5.0, 6.0});
220 EXPECT_EQ((Eigen::Vector3d{4.0, 5.0, 6.0}), localizer_.xytheta());
221}
222
223// Test that if we are moving only by accelerometer readings (and just assuming
224// zero voltage/encoders) that we initially don't believe it but then latch into
225// following the accelerometer.
226// Note: this test is somewhat sensitive to the exact tuning values used for the
227// filter.
228TEST_F(LocalizerTest, AccelOnly) {
229 const aos::monotonic_clock::time_point start = aos::monotonic_clock::epoch();
230 const std::chrono::microseconds kDt{500};
231 aos::monotonic_clock::time_point t = start - std::chrono::milliseconds(1000);
232 Eigen::Vector3d gyro{0.0, 0.0, 0.0};
233 const Eigen::Vector2d encoders{0.0, 0.0};
234 const Eigen::Vector2d voltages{0.0, 0.0};
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800235 Eigen::Vector3d accel{5.0, 2.0, 9.80665};
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800236 Eigen::Vector3d accel_gs = dt_config_.imu_transform.inverse() * accel / 9.80665;
James Kuszmaul29c59522022-02-12 16:44:26 -0800237 while (t < start) {
238 // Spin to fill up the buffer.
239 localizer_.HandleImu(t, gyro, Eigen::Vector3d::UnitZ(), encoders, voltages);
240 t += kDt;
241 }
242 while (t < start + std::chrono::milliseconds(100)) {
243 localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
244 EXPECT_EQ(Eigen::Vector3d::Zero(), localizer_.xytheta());
245 t += kDt;
246 }
247 while (t < start + std::chrono::milliseconds(500)) {
248 // Too lazy to hard-code when the transition happens.
249 localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
250 t += kDt;
251 }
252 while (t < start + std::chrono::milliseconds(1000)) {
253 SCOPED_TRACE(t);
254 localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
255 const Eigen::Vector3d xytheta = localizer_.xytheta();
256 t += kDt;
257 EXPECT_NEAR(
258 0.5 * accel(0) * std::pow(aos::time::DurationInSeconds(t - start), 2),
259 xytheta(0), 1e-4);
260 EXPECT_NEAR(
261 0.5 * accel(1) * std::pow(aos::time::DurationInSeconds(t - start), 2),
262 xytheta(1), 1e-4);
263 EXPECT_EQ(0.0, xytheta(2));
264 }
265
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800266 ASSERT_NEAR(accel(0), localizer_.accel_state()(kVelocityX), 1e-10);
267 ASSERT_NEAR(accel(1), localizer_.accel_state()(kVelocityY), 1e-10);
James Kuszmaul29c59522022-02-12 16:44:26 -0800268
269 // Start going in a cirlce, and confirm that we
270 // handle things correctly. We rotate the accelerometer readings by 90 degrees
271 // and then leave them constant, which should make it look like we are going
272 // around in a circle.
273 accel = Eigen::Vector3d{-accel(1), accel(0), 9.80665};
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800274 accel_gs = dt_config_.imu_transform.inverse() * accel / 9.80665;
James Kuszmaul29c59522022-02-12 16:44:26 -0800275 // v^2 / r = a
276 // w * r = v
277 // v^2 / v * w = a
278 // w = a / v
279 const double omega = accel.topRows<2>().norm() /
280 std::hypot(localizer_.accel_state()(kVelocityX),
281 localizer_.accel_state()(kVelocityY));
282 gyro << 0.0, 0.0, omega;
283 // Due to the magic of math, omega works out to be 1.0 after having run at the
284 // acceleration for one second.
285 ASSERT_NEAR(1.0, omega, 1e-10);
286 // Yes, we could save some operations here, but let's be at least somewhat
287 // clear about what we're doing...
288 const double radius = accel.topRows<2>().norm() / (omega * omega);
289 const Eigen::Vector2d center = localizer_.xytheta().topRows<2>() +
290 accel.topRows<2>().normalized() * radius;
291 const double initial_theta = std::atan2(-accel(1), -accel(0));
292
293 std::chrono::microseconds one_revolution_time(
294 static_cast<int>(2 * M_PI / omega * 1e6));
295
296 aos::monotonic_clock::time_point circle_start = t;
297
298 while (t < circle_start + one_revolution_time) {
299 SCOPED_TRACE(t);
300 localizer_.HandleImu(t, gyro, accel_gs, encoders, voltages);
301 t += kDt;
302 const double t_circle = aos::time::DurationInSeconds(t - circle_start);
303 ASSERT_NEAR(t_circle * omega, localizer_.xytheta()(2), 1e-5);
304 const double theta_circle = t_circle * omega + initial_theta;
305 const Eigen::Vector2d offset =
306 radius *
307 Eigen::Vector2d{std::cos(theta_circle), std::sin(theta_circle)};
308 const Eigen::Vector2d expected = center + offset;
309 const Eigen::Vector2d estimated = localizer_.xytheta().topRows<2>();
310 const Eigen::Vector2d implied_offset = estimated - center;
311 const double implied_theta =
312 std::atan2(implied_offset.y(), implied_offset.x());
313 VLOG(1) << "center: " << center.transpose() << " radius " << radius
314 << "\nlocalizer " << localizer_.xytheta().transpose()
315 << " t_circle " << t_circle << " omega " << omega << " theta "
316 << theta_circle << "\noffset " << offset.transpose()
317 << "\nexpected " << expected.transpose() << "\nimplied offset "
318 << implied_offset << " implied_theta " << implied_theta << "\nvel "
319 << localizer_.accel_state()(kVelocityX) << ", "
320 << localizer_.accel_state()(kVelocityY);
321 ASSERT_NEAR(0.0, (expected - localizer_.xytheta().topRows<2>()).norm(),
322 1e-2);
323 }
324
325 // Set accelerometer back to zero and confirm that we recover (the
326 // implementation decays the accelerometer speeds to zero when still, so
327 // should recover).
328 while (t <
329 circle_start + one_revolution_time + std::chrono::milliseconds(3000)) {
330 localizer_.HandleImu(t, Eigen::Vector3d::Zero(), Eigen::Vector3d::UnitZ(),
331 encoders, voltages);
332 t += kDt;
333 }
334 const Eigen::Vector3d final_pos = localizer_.xytheta();
335 localizer_.HandleImu(t, Eigen::Vector3d::Zero(), Eigen::Vector3d::UnitZ(),
336 encoders, voltages);
337 ASSERT_NEAR(0.0, (final_pos - localizer_.xytheta()).norm(), 1e-10);
338}
339
340using control_loops::drivetrain::Output;
341
342class EventLoopLocalizerTest : public ::testing::Test {
343 protected:
344 EventLoopLocalizerTest()
Austin Schuhc5fa6d92022-02-25 14:36:28 -0800345 : configuration_(aos::configuration::ReadConfig("y2022/aos_config.json")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800346 event_loop_factory_(&configuration_.message()),
347 roborio_node_(
348 aos::configuration::GetNode(&configuration_.message(), "roborio")),
349 imu_node_(
350 aos::configuration::GetNode(&configuration_.message(), "imu")),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800351 camera_node_(
352 aos::configuration::GetNode(&configuration_.message(), "pi1")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800353 dt_config_(
354 control_loops::drivetrain::testing::GetTestDrivetrainConfig()),
355 localizer_event_loop_(
356 event_loop_factory_.MakeEventLoop("localizer", imu_node_)),
357 localizer_(localizer_event_loop_.get(), dt_config_),
358 drivetrain_plant_event_loop_(event_loop_factory_.MakeEventLoop(
359 "drivetrain_plant", roborio_node_)),
360 drivetrain_plant_imu_event_loop_(
361 event_loop_factory_.MakeEventLoop("drivetrain_plant", imu_node_)),
362 drivetrain_plant_(drivetrain_plant_event_loop_.get(),
363 drivetrain_plant_imu_event_loop_.get(), dt_config_,
364 std::chrono::microseconds(500)),
365 roborio_test_event_loop_(
366 event_loop_factory_.MakeEventLoop("test", roborio_node_)),
367 imu_test_event_loop_(
368 event_loop_factory_.MakeEventLoop("test", imu_node_)),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800369 camera_test_event_loop_(
370 event_loop_factory_.MakeEventLoop("test", camera_node_)),
James Kuszmaul29c59522022-02-12 16:44:26 -0800371 logger_test_event_loop_(
372 event_loop_factory_.GetNodeEventLoopFactory("logger")
373 ->MakeEventLoop("test")),
374 output_sender_(
375 roborio_test_event_loop_->MakeSender<Output>("/drivetrain")),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800376 turret_sender_(
377 roborio_test_event_loop_
378 ->MakeSender<y2022::control_loops::superstructure::Status>(
379 "/superstructure")),
380 target_sender_(
381 camera_test_event_loop_->MakeSender<y2022::vision::TargetEstimate>(
382 "/camera")),
383 control_sender_(roborio_test_event_loop_->MakeSender<LocalizerControl>(
384 "/drivetrain")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800385 output_fetcher_(roborio_test_event_loop_->MakeFetcher<LocalizerOutput>(
386 "/localizer")),
387 status_fetcher_(
388 imu_test_event_loop_->MakeFetcher<LocalizerStatus>("/localizer")) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800389 localizer_.localizer()->set_longitudinal_offset(0.0);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800390 {
391 aos::TimerHandler *timer = roborio_test_event_loop_->AddTimer([this]() {
392 {
393 auto builder = output_sender_.MakeBuilder();
394 auto output_builder = builder.MakeBuilder<Output>();
395 output_builder.add_left_voltage(output_voltages_(0));
396 output_builder.add_right_voltage(output_voltages_(1));
397 builder.CheckOk(builder.Send(output_builder.Finish()));
398 }
399 {
400 auto builder = turret_sender_.MakeBuilder();
401 auto turret_builder =
402 builder
403 .MakeBuilder<frc971::control_loops::
404 PotAndAbsoluteEncoderProfiledJointStatus>();
405 turret_builder.add_position(turret_position_);
406 turret_builder.add_velocity(turret_velocity_);
407 const auto turret_offset = turret_builder.Finish();
408 auto status_builder =
409 builder
410 .MakeBuilder<y2022::control_loops::superstructure::Status>();
411 status_builder.add_turret(turret_offset);
412 builder.CheckOk(builder.Send(status_builder.Finish()));
413 }
414 });
415 roborio_test_event_loop_->OnRun([timer, this]() {
416 timer->Setup(roborio_test_event_loop_->monotonic_now(),
417 std::chrono::milliseconds(5));
418 });
419 }
420 {
421 aos::TimerHandler *timer = camera_test_event_loop_->AddTimer([this]() {
422 if (!send_targets_) {
423 return;
424 }
425 const frc971::control_loops::Pose robot_pose(
426 {drivetrain_plant_.GetPosition().x(),
427 drivetrain_plant_.GetPosition().y(), 0.0},
428 drivetrain_plant_.state()(2, 0));
429 const Eigen::Matrix<double, 4, 4> H_turret_camera =
430 frc971::control_loops::TransformationMatrixForYaw(
431 turret_position_) *
432 CameraTurretTransformation();
433
434 const Eigen::Matrix<double, 4, 4> H_field_camera =
435 robot_pose.AsTransformationMatrix() * TurretRobotTransformation() *
436 H_turret_camera;
437 const Eigen::Matrix<double, 4, 4> target_transform =
438 Eigen::Matrix<double, 4, 4>::Identity();
439 const Eigen::Matrix<double, 4, 4> H_camera_target =
440 H_field_camera.inverse() * target_transform;
441 const Eigen::Matrix<double, 4, 4> H_target_camera =
442 H_camera_target.inverse();
443
444 std::unique_ptr<y2022::vision::TargetEstimateT> estimate(
445 new y2022::vision::TargetEstimateT());
446 estimate->distance = H_target_camera.block<2, 1>(0, 3).norm();
447 estimate->angle_to_target =
448 std::atan2(-H_camera_target(0, 3), H_camera_target(2, 3));
449 estimate->camera_calibration.reset(new CameraCalibrationT());
450 {
451 estimate->camera_calibration->fixed_extrinsics.reset(
452 new TransformationMatrixT());
453 TransformationMatrixT *H_robot_turret =
454 estimate->camera_calibration->fixed_extrinsics.get();
455 H_robot_turret->data = MatrixToVector(TurretRobotTransformation());
456 }
457
458 estimate->camera_calibration->turret_extrinsics.reset(
459 new TransformationMatrixT());
460 estimate->camera_calibration->turret_extrinsics->data =
461 MatrixToVector(CameraTurretTransformation());
462
463 auto builder = target_sender_.MakeBuilder();
464 builder.CheckOk(
465 builder.Send(TargetEstimate::Pack(*builder.fbb(), estimate.get())));
466 });
467 camera_test_event_loop_->OnRun([timer, this]() {
468 timer->Setup(camera_test_event_loop_->monotonic_now(),
469 std::chrono::milliseconds(50));
470 });
471 }
472
473 localizer_control_send_timer_ =
474 roborio_test_event_loop_->AddTimer([this]() {
475 auto builder = control_sender_.MakeBuilder();
476 auto control_builder = builder.MakeBuilder<LocalizerControl>();
477 control_builder.add_x(localizer_control_x_);
478 control_builder.add_y(localizer_control_y_);
479 control_builder.add_theta(localizer_control_theta_);
480 control_builder.add_theta_uncertainty(0.01);
481 control_builder.add_keep_current_theta(false);
482 builder.CheckOk(builder.Send(control_builder.Finish()));
483 });
484
James Kuszmaul29c59522022-02-12 16:44:26 -0800485 // Get things zeroed.
486 event_loop_factory_.RunFor(std::chrono::seconds(10));
487 CHECK(status_fetcher_.Fetch());
488 CHECK(status_fetcher_->zeroed());
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800489
490 if (!FLAGS_output_folder.empty()) {
491 logger_event_loop_ =
492 event_loop_factory_.MakeEventLoop("logger", imu_node_);
493 logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
494 logger_->StartLoggingOnRun(FLAGS_output_folder);
495 }
496 }
497
498 void SendLocalizerControl(double x, double y, double theta) {
499 localizer_control_x_ = x;
500 localizer_control_y_ = y;
501 localizer_control_theta_ = theta;
502 localizer_control_send_timer_->Setup(
503 roborio_test_event_loop_->monotonic_now());
504 }
505 ::testing::AssertionResult IsNear(double expected, double actual,
506 double epsilon) {
507 if (std::abs(expected - actual) < epsilon) {
508 return ::testing::AssertionSuccess();
509 } else {
510 return ::testing::AssertionFailure()
511 << "Expected " << expected << " but got " << actual
512 << " with a max difference of " << epsilon
513 << " and an actual difference of " << std::abs(expected - actual);
514 }
515 }
516 ::testing::AssertionResult VerifyEstimatorAccurate(double eps) {
517 const Eigen::Matrix<double, 5, 1> true_state = drivetrain_plant_.state();
518 ::testing::AssertionResult result(true);
519 status_fetcher_.Fetch();
520 if (!(result = IsNear(status_fetcher_->model_based()->x(), true_state(0),
521 eps))) {
522 return result;
523 }
524 if (!(result = IsNear(status_fetcher_->model_based()->y(), true_state(1),
525 eps))) {
526 return result;
527 }
528 if (!(result = IsNear(status_fetcher_->model_based()->theta(),
529 true_state(2), eps))) {
530 return result;
531 }
532 return result;
James Kuszmaul29c59522022-02-12 16:44:26 -0800533 }
534
535 aos::FlatbufferDetachedBuffer<aos::Configuration> configuration_;
536 aos::SimulatedEventLoopFactory event_loop_factory_;
537 const aos::Node *const roborio_node_;
538 const aos::Node *const imu_node_;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800539 const aos::Node *const camera_node_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800540 const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
541 std::unique_ptr<aos::EventLoop> localizer_event_loop_;
542 EventLoopLocalizer localizer_;
543
544 std::unique_ptr<aos::EventLoop> drivetrain_plant_event_loop_;
545 std::unique_ptr<aos::EventLoop> drivetrain_plant_imu_event_loop_;
546 control_loops::drivetrain::testing::DrivetrainSimulation drivetrain_plant_;
547
548 std::unique_ptr<aos::EventLoop> roborio_test_event_loop_;
549 std::unique_ptr<aos::EventLoop> imu_test_event_loop_;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800550 std::unique_ptr<aos::EventLoop> camera_test_event_loop_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800551 std::unique_ptr<aos::EventLoop> logger_test_event_loop_;
552
553 aos::Sender<Output> output_sender_;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800554 aos::Sender<y2022::control_loops::superstructure::Status> turret_sender_;
555 aos::Sender<y2022::vision::TargetEstimate> target_sender_;
556 aos::Sender<LocalizerControl> control_sender_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800557 aos::Fetcher<LocalizerOutput> output_fetcher_;
558 aos::Fetcher<LocalizerStatus> status_fetcher_;
559
560 Eigen::Vector2d output_voltages_ = Eigen::Vector2d::Zero();
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800561
562 aos::TimerHandler *localizer_control_send_timer_;
563
564 bool send_targets_ = false;
565 double turret_position_ = 0.0;
566 double turret_velocity_ = 0.0;
567
568 double localizer_control_x_ = 0.0;
569 double localizer_control_y_ = 0.0;
570 double localizer_control_theta_ = 0.0;
571
572 std::unique_ptr<aos::EventLoop> logger_event_loop_;
573 std::unique_ptr<aos::logger::Logger> logger_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800574};
575
576TEST_F(EventLoopLocalizerTest, Nominal) {
577 output_voltages_ << 1.0, 1.0;
578 event_loop_factory_.RunFor(std::chrono::seconds(2));
579 drivetrain_plant_.set_accel_sin_magnitude(0.01);
580 CHECK(output_fetcher_.Fetch());
581 CHECK(status_fetcher_.Fetch());
582 // The two can be different because they may've been sent at different times.
583 ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-6);
584 ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-6);
585 ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
586 1e-6);
587 ASSERT_LT(0.1, output_fetcher_->x());
588 ASSERT_NEAR(0.0, output_fetcher_->y(), 1e-10);
589 ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-10);
590 ASSERT_TRUE(status_fetcher_->has_model_based());
591 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
592 ASSERT_LT(0.1, status_fetcher_->model_based()->accel_state()->velocity_x());
593 ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_y(),
594 1e-10);
595 ASSERT_NEAR(
596 0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
597 1e-1);
598 ASSERT_NEAR(
599 0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
600 1e-1);
601}
602
603TEST_F(EventLoopLocalizerTest, Reverse) {
604 output_voltages_ << -4.0, -4.0;
605 drivetrain_plant_.set_accel_sin_magnitude(0.01);
606 event_loop_factory_.RunFor(std::chrono::seconds(2));
607 CHECK(output_fetcher_.Fetch());
608 CHECK(status_fetcher_.Fetch());
609 // The two can be different because they may've been sent at different times.
610 ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-6);
611 ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-6);
612 ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
613 1e-6);
614 ASSERT_GT(-0.1, output_fetcher_->x());
615 ASSERT_NEAR(0.0, output_fetcher_->y(), 1e-10);
616 ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-10);
617 ASSERT_TRUE(status_fetcher_->has_model_based());
618 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
619 ASSERT_GT(-0.1, status_fetcher_->model_based()->accel_state()->velocity_x());
620 ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_y(),
621 1e-10);
622 ASSERT_NEAR(
623 0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
624 1e-1);
625 ASSERT_NEAR(
626 0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
627 1e-1);
628}
629
630TEST_F(EventLoopLocalizerTest, SpinInPlace) {
631 output_voltages_ << 4.0, -4.0;
632 event_loop_factory_.RunFor(std::chrono::seconds(2));
633 CHECK(output_fetcher_.Fetch());
634 CHECK(status_fetcher_.Fetch());
635 // The two can be different because they may've been sent at different times.
636 ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-6);
637 ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-6);
638 ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
639 1e-1);
640 ASSERT_NEAR(0.0, output_fetcher_->x(), 1e-10);
641 ASSERT_NEAR(0.0, output_fetcher_->y(), 1e-10);
642 ASSERT_LT(0.1, std::abs(output_fetcher_->theta()));
643 ASSERT_TRUE(status_fetcher_->has_model_based());
644 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
645 ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_x(),
646 1e-10);
647 ASSERT_NEAR(0.0, status_fetcher_->model_based()->accel_state()->velocity_y(),
648 1e-10);
649 ASSERT_NEAR(-status_fetcher_->model_based()->model_state()->left_velocity(),
650 status_fetcher_->model_based()->model_state()->right_velocity(),
651 1e-3);
652 ASSERT_NEAR(
653 0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
654 1e-1);
655 ASSERT_NEAR(
656 0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
657 1e-1);
658 ASSERT_NEAR(0.0, status_fetcher_->model_based()->residual(), 1e-3);
659}
660
661TEST_F(EventLoopLocalizerTest, Curve) {
662 output_voltages_ << 2.0, 4.0;
663 event_loop_factory_.RunFor(std::chrono::seconds(2));
664 CHECK(output_fetcher_.Fetch());
665 CHECK(status_fetcher_.Fetch());
666 // The two can be different because they may've been sent at different times.
667 ASSERT_NEAR(output_fetcher_->x(), status_fetcher_->model_based()->x(), 1e-2);
668 ASSERT_NEAR(output_fetcher_->y(), status_fetcher_->model_based()->y(), 1e-2);
669 ASSERT_NEAR(output_fetcher_->theta(), status_fetcher_->model_based()->theta(),
670 1e-1);
671 ASSERT_LT(0.1, output_fetcher_->x());
672 ASSERT_LT(0.1, output_fetcher_->y());
673 ASSERT_LT(0.1, std::abs(output_fetcher_->theta()));
674 ASSERT_TRUE(status_fetcher_->has_model_based());
675 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
676 ASSERT_LT(0.0, status_fetcher_->model_based()->accel_state()->velocity_x());
677 ASSERT_LT(0.0, status_fetcher_->model_based()->accel_state()->velocity_y());
678 ASSERT_NEAR(
679 0.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
680 1e-1);
681 ASSERT_NEAR(
682 0.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
683 1e-1);
684 ASSERT_NEAR(0.0, status_fetcher_->model_based()->residual(), 1e-1)
685 << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
686}
687
688// Tests that small amounts of voltage error are handled by the model-based
689// half of the localizer.
690TEST_F(EventLoopLocalizerTest, VoltageError) {
691 output_voltages_ << 0.0, 0.0;
692 drivetrain_plant_.set_left_voltage_offset(2.0);
693 drivetrain_plant_.set_right_voltage_offset(2.0);
694 drivetrain_plant_.set_accel_sin_magnitude(0.01);
695
696 event_loop_factory_.RunFor(std::chrono::seconds(2));
697 CHECK(output_fetcher_.Fetch());
698 CHECK(status_fetcher_.Fetch());
699 // Should still be using the model, but have a non-trivial residual.
700 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800701 ASSERT_LT(0.02, status_fetcher_->model_based()->residual())
James Kuszmaul29c59522022-02-12 16:44:26 -0800702 << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
703
704 // Afer running for a while, voltage error terms should converge and result in
705 // low residuals.
706 event_loop_factory_.RunFor(std::chrono::seconds(10));
707 CHECK(output_fetcher_.Fetch());
708 CHECK(status_fetcher_.Fetch());
709 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
710 ASSERT_NEAR(
711 2.0, status_fetcher_->model_based()->model_state()->left_voltage_error(),
712 0.1)
713 << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
714 ASSERT_NEAR(
715 2.0, status_fetcher_->model_based()->model_state()->right_voltage_error(),
716 0.1)
717 << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800718 ASSERT_GT(0.02, status_fetcher_->model_based()->residual())
James Kuszmaul29c59522022-02-12 16:44:26 -0800719 << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
720}
721
722// Tests that large amounts of voltage error force us into the
723// acceleration-based localizer.
724TEST_F(EventLoopLocalizerTest, HighVoltageError) {
725 output_voltages_ << 0.0, 0.0;
726 drivetrain_plant_.set_left_voltage_offset(200.0);
727 drivetrain_plant_.set_right_voltage_offset(200.0);
728 drivetrain_plant_.set_accel_sin_magnitude(0.01);
729
730 event_loop_factory_.RunFor(std::chrono::seconds(2));
731 CHECK(output_fetcher_.Fetch());
732 CHECK(status_fetcher_.Fetch());
733 // Should still be using the model, but have a non-trivial residual.
734 ASSERT_FALSE(status_fetcher_->model_based()->using_model());
735 ASSERT_LT(0.1, status_fetcher_->model_based()->residual())
736 << aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
737 ASSERT_NEAR(drivetrain_plant_.state()(0),
738 status_fetcher_->model_based()->x(), 1.0);
739 ASSERT_NEAR(drivetrain_plant_.state()(1),
740 status_fetcher_->model_based()->y(), 1e-6);
741}
742
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800743// Tests that image corrections in the nominal case (no errors) causes no
744// issues.
745TEST_F(EventLoopLocalizerTest, NominalImageCorrections) {
746 output_voltages_ << 3.0, 2.0;
747 drivetrain_plant_.set_accel_sin_magnitude(0.01);
748 send_targets_ = true;
749
750 event_loop_factory_.RunFor(std::chrono::seconds(4));
751 CHECK(status_fetcher_.Fetch());
752 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
753 EXPECT_TRUE(VerifyEstimatorAccurate(1e-1));
754 ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
755 ASSERT_LT(10,
756 status_fetcher_->model_based()->statistics()->total_candidates());
757 ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
758 status_fetcher_->model_based()->statistics()->total_accepted());
759}
760
761// Tests that image corrections when there is an error at the start results
762// in us actually getting corrected over time.
763TEST_F(EventLoopLocalizerTest, ImageCorrections) {
764 output_voltages_ << 0.0, 0.0;
765 drivetrain_plant_.mutable_state()->x() = 2.0;
766 drivetrain_plant_.mutable_state()->y() = 2.0;
767 SendLocalizerControl(5.0, 3.0, 0.0);
768 event_loop_factory_.RunFor(std::chrono::seconds(4));
769 CHECK(output_fetcher_.Fetch());
770 ASSERT_NEAR(5.0, output_fetcher_->x(), 1e-5);
771 ASSERT_NEAR(3.0, output_fetcher_->y(), 1e-5);
772 ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-5);
773
774 send_targets_ = true;
775
776 event_loop_factory_.RunFor(std::chrono::seconds(4));
777 CHECK(status_fetcher_.Fetch());
778 ASSERT_TRUE(status_fetcher_->model_based()->using_model());
779 EXPECT_TRUE(VerifyEstimatorAccurate(1e-1));
780 ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
781 ASSERT_LT(10,
782 status_fetcher_->model_based()->statistics()->total_candidates());
783 ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
784 status_fetcher_->model_based()->statistics()->total_accepted());
785}
786
787// Tests that image corrections when we are in accel mode works.
788TEST_F(EventLoopLocalizerTest, ImageCorrectionsInAccel) {
789 output_voltages_ << 0.0, 0.0;
790 drivetrain_plant_.set_left_voltage_offset(200.0);
791 drivetrain_plant_.set_right_voltage_offset(200.0);
792 drivetrain_plant_.set_accel_sin_magnitude(0.01);
793 drivetrain_plant_.mutable_state()->x() = 2.0;
794 drivetrain_plant_.mutable_state()->y() = 2.0;
795 SendLocalizerControl(5.0, 3.0, 0.0);
796 event_loop_factory_.RunFor(std::chrono::seconds(1));
797 CHECK(output_fetcher_.Fetch());
798 CHECK(status_fetcher_.Fetch());
799 ASSERT_FALSE(status_fetcher_->model_based()->using_model());
800 EXPECT_FALSE(VerifyEstimatorAccurate(0.5));
801
802 send_targets_ = true;
803
804 event_loop_factory_.RunFor(std::chrono::seconds(4));
805 CHECK(status_fetcher_.Fetch());
806 ASSERT_FALSE(status_fetcher_->model_based()->using_model());
807 EXPECT_TRUE(VerifyEstimatorAccurate(0.5));
808 // y should be noticeably more accurate than x, since we are just driving
809 // straight.
810 ASSERT_NEAR(drivetrain_plant_.state()(1), status_fetcher_->model_based()->y(), 0.1);
811 ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
812 ASSERT_LT(10,
813 status_fetcher_->model_based()->statistics()->total_candidates());
814 ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
815 status_fetcher_->model_based()->statistics()->total_accepted());
816}
817
James Kuszmaul29c59522022-02-12 16:44:26 -0800818} // namespace frc91::controls::testing