WPILibC++ 2024.3.2
ADIS16470_IMU.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5/*----------------------------------------------------------------------------*/
6/* Copyright (c) 2016-2020 Analog Devices Inc. All Rights Reserved. */
7/* Open Source Software - may be modified and shared by FRC teams. The code */
8/* must be accompanied by the FIRST BSD license file in the root directory of */
9/* the project. */
10/* */
11/* Juan Chong - frcsupport@analog.com */
12/*----------------------------------------------------------------------------*/
13
14#pragma once
15
16#include <stdint.h>
17
18#include <atomic>
19#include <thread>
20
21#include <hal/SimDevice.h>
22#include <units/acceleration.h>
23#include <units/angle.h>
26#include <wpi/mutex.h>
29
30#include "frc/DigitalInput.h"
31#include "frc/DigitalOutput.h"
32#include "frc/SPI.h"
33
34namespace frc {
35/**
36 * Use DMA SPI to read rate and acceleration data from the ADIS16470 IMU and
37 * return the robot's heading relative to a starting position and instant
38 * measurements
39 *
40 * The ADIS16470 gyro angle outputs track the robot's heading based on the
41 * starting position. As the robot rotates the new heading is computed by
42 * integrating the rate of rotation returned by the IMU. When the class is
43 * instantiated, a short calibration routine is performed where the IMU samples
44 * the gyros while at rest to determine the initial offset. This is subtracted
45 * from each sample to determine the heading.
46 *
47 * This class is for the ADIS16470 IMU connected via the primary SPI port
48 * available on the RoboRIO.
49 */
50
52 public wpi::SendableHelper<ADIS16470_IMU> {
53 public:
54 /**
55 * ADIS16470 calibration times.
56 */
57 enum class CalibrationTime {
58 /// 32 ms calibration time.
59 _32ms = 0,
60 /// 64 ms calibration time.
61 _64ms = 1,
62 /// 128 ms calibration time.
63 _128ms = 2,
64 /// 256 ms calibration time.
65 _256ms = 3,
66 /// 512 ms calibration time.
67 _512ms = 4,
68 /// 1 s calibration time.
69 _1s = 5,
70 /// 2 s calibration time.
71 _2s = 6,
72 /// 4 s calibration time.
73 _4s = 7,
74 /// 8 s calibration time.
75 _8s = 8,
76 /// 16 s calibration time.
77 _16s = 9,
78 /// 32 s calibration time.
79 _32s = 10,
80 /// 64 s calibration time.
81 _64s = 11
82 };
83
84 /**
85 * IMU axes.
86 *
87 * kX, kY, and kZ refer to the IMU's X, Y, and Z axes respectively. kYaw,
88 * kPitch, and kRoll are configured by the user to refer to an X, Y, or Z
89 * axis.
90 */
91 enum IMUAxis {
92 /// The IMU's X axis.
94 /// The IMU's Y axis.
96 /// The IMU's Z axis.
98 /// The user-configured yaw axis.
100 /// The user-configured pitch axis.
102 /// The user-configured roll axis.
103 kRoll
104 };
105
106 /**
107 * Creates a new ADIS16740 IMU object.
108 *
109 * The default setup is the onboard SPI port with a calibration time of 4
110 * seconds. Yaw, pitch, and roll are kZ, kX, and kY respectively.
111 */
113
114 /**
115 * Creates a new ADIS16740 IMU object.
116 *
117 * The default setup is the onboard SPI port with a calibration time of 4
118 * seconds.
119 *
120 * <b><i>Input axes limited to kX, kY and kZ. Specifying kYaw, kPitch,or kRoll
121 * will result in an error.</i></b>
122 *
123 * @param yaw_axis The axis that measures the yaw
124 * @param pitch_axis The axis that measures the pitch
125 * @param roll_axis The axis that measures the roll
126 */
127 ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis, IMUAxis roll_axis);
128
129 /**
130 * Creates a new ADIS16740 IMU object.
131 *
132 * <b><i>Input axes limited to kX, kY and kZ. Specifying kYaw, kPitch, or
133 * kRoll will result in an error.</i></b>
134 *
135 * @param yaw_axis The axis that measures the yaw
136 * @param pitch_axis The axis that measures the pitch
137 * @param roll_axis The axis that measures the roll
138 * @param port The SPI Port the gyro is plugged into
139 * @param cal_time Calibration time
140 */
141 explicit ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis,
142 IMUAxis roll_axis, frc::SPI::Port port,
143 CalibrationTime cal_time);
144
145 ~ADIS16470_IMU() override;
146
149
150 /**
151 * Configures the decimation rate of the IMU.
152 *
153 * @param decimationRate The new decimation value.
154 * @return 0 if success, 1 if no change, 2 if error.
155 */
156 int ConfigDecRate(uint16_t decimationRate);
157
158 /**
159 * @brief Switches the active SPI port to standard SPI mode, writes the
160 * command to activate the new null configuration, and re-enables auto SPI.
161 */
162 void Calibrate();
163
164 /**
165 * @brief Switches the active SPI port to standard SPI mode, writes a new
166 * value to the NULL_CNFG register in the IMU, and re-enables auto SPI.
167 */
169
170 /**
171 * Reset the gyro.
172 *
173 * Resets the gyro accumulations to a heading of zero. This can be used if
174 * there is significant drift in the gyro and it needs to be recalibrated
175 * after running.
176 */
177 void Reset();
178
179 /**
180 * Allow the designated gyro angle to be set to a given value. This may happen
181 * with unread values in the buffer, it is suggested that the IMU is not
182 * moving when this method is run.
183 *
184 * @param axis IMUAxis that will be changed
185 * @param angle The new angle (CCW positive)
186 */
187 void SetGyroAngle(IMUAxis axis, units::degree_t angle);
188
189 /**
190 * Allow the gyro angle X to be set to a given value. This may happen with
191 * unread values in the buffer, it is suggested that the IMU is not moving
192 * when this method is run.
193 *
194 * @param angle The new angle (CCW positive)
195 */
196 void SetGyroAngleX(units::degree_t angle);
197
198 /**
199 * Allow the gyro angle Y to be set to a given value. This may happen with
200 * unread values in the buffer, it is suggested that the IMU is not moving
201 * when this method is run.
202 *
203 * @param angle The new angle (CCW positive)
204 */
205 void SetGyroAngleY(units::degree_t angle);
206
207 /**
208 * Allow the gyro angle Z to be set to a given value. This may happen with
209 * unread values in the buffer, it is suggested that the IMU is not moving
210 * when this method is run.
211 *
212 * @param angle The new angle (CCW positive)
213 */
214 void SetGyroAngleZ(units::degree_t angle);
215
216 /**
217 * Returns the axis angle (CCW positive).
218 *
219 * @param axis The IMUAxis whose angle to return. Defaults to user configured
220 * Yaw.
221 * @return The axis angle (CCW positive).
222 */
223 units::degree_t GetAngle(IMUAxis axis = IMUAxis::kYaw) const;
224
225 /**
226 * Returns the axis angular rate (CCW positive).
227 *
228 * @param axis The IMUAxis whose rate to return. Defaults to user configured
229 * Yaw.
230 * @return Axis angular rate (CCW positive).
231 */
232 units::degrees_per_second_t GetRate(IMUAxis axis = IMUAxis::kYaw) const;
233
234 /**
235 * Returns the acceleration in the X axis.
236 */
237 units::meters_per_second_squared_t GetAccelX() const;
238
239 /**
240 * Returns the acceleration in the Y axis.
241 */
242 units::meters_per_second_squared_t GetAccelY() const;
243
244 /**
245 * Returns the acceleration in the Z axis.
246 */
247 units::meters_per_second_squared_t GetAccelZ() const;
248
249 /**
250 * Returns the X-axis complementary angle.
251 */
252 units::degree_t GetXComplementaryAngle() const;
253
254 /**
255 * Returns the Y-axis complementary angle.
256 */
257 units::degree_t GetYComplementaryAngle() const;
258
259 /**
260 * Returns the X-axis filtered acceleration angle.
261 */
262 units::degree_t GetXFilteredAccelAngle() const;
263
264 /**
265 * Returns the Y-axis filtered acceleration angle.
266 */
267 units::degree_t GetYFilteredAccelAngle() const;
268
269 /**
270 * Returns which axis, kX, kY, or kZ, is set to the yaw axis.
271 *
272 * @return IMUAxis Yaw Axis
273 */
275
276 /**
277 * Returns which axis, kX, kY, or kZ, is set to the pitch axis.
278 *
279 * @return IMUAxis Pitch Axis
280 */
282
283 /**
284 * Returns which axis, kX, kY, or kZ, is set to the roll axis.
285 *
286 * @return IMUAxis Roll Axis
287 */
289
290 /**
291 * Checks the connection status of the IMU.
292 *
293 * @return True if the IMU is connected, false otherwise.
294 */
295 bool IsConnected() const;
296
300
301 /**
302 * Gets the SPI port number.
303 *
304 * @return The SPI port number.
305 */
306 int GetPort() const;
307
308 void InitSendable(wpi::SendableBuilder& builder) override;
309
310 private:
311 // Register Map Declaration
312 static constexpr uint8_t FLASH_CNT = 0x00; // Flash memory write count
313 static constexpr uint8_t DIAG_STAT =
314 0x02; // Diagnostic and operational status
315 static constexpr uint8_t X_GYRO_LOW =
316 0x04; // X-axis gyroscope output, lower word
317 static constexpr uint8_t X_GYRO_OUT =
318 0x06; // X-axis gyroscope output, upper word
319 static constexpr uint8_t Y_GYRO_LOW =
320 0x08; // Y-axis gyroscope output, lower word
321 static constexpr uint8_t Y_GYRO_OUT =
322 0x0A; // Y-axis gyroscope output, upper word
323 static constexpr uint8_t Z_GYRO_LOW =
324 0x0C; // Z-axis gyroscope output, lower word
325 static constexpr uint8_t Z_GYRO_OUT =
326 0x0E; // Z-axis gyroscope output, upper word
327 static constexpr uint8_t X_ACCL_LOW =
328 0x10; // X-axis accelerometer output, lower word
329 static constexpr uint8_t X_ACCL_OUT =
330 0x12; // X-axis accelerometer output, upper word
331 static constexpr uint8_t Y_ACCL_LOW =
332 0x14; // Y-axis accelerometer output, lower word
333 static constexpr uint8_t Y_ACCL_OUT =
334 0x16; // Y-axis accelerometer output, upper word
335 static constexpr uint8_t Z_ACCL_LOW =
336 0x18; // Z-axis accelerometer output, lower word
337 static constexpr uint8_t Z_ACCL_OUT =
338 0x1A; // Z-axis accelerometer output, upper word
339 static constexpr uint8_t TEMP_OUT =
340 0x1C; // Temperature output (internal, not calibrated)
341 static constexpr uint8_t TIME_STAMP = 0x1E; // PPS mode time stamp
342 static constexpr uint8_t X_DELTANG_LOW =
343 0x24; // X-axis delta angle output, lower word
344 static constexpr uint8_t X_DELTANG_OUT =
345 0x26; // X-axis delta angle output, upper word
346 static constexpr uint8_t Y_DELTANG_LOW =
347 0x28; // Y-axis delta angle output, lower word
348 static constexpr uint8_t Y_DELTANG_OUT =
349 0x2A; // Y-axis delta angle output, upper word
350 static constexpr uint8_t Z_DELTANG_LOW =
351 0x2C; // Z-axis delta angle output, lower word
352 static constexpr uint8_t Z_DELTANG_OUT =
353 0x2E; // Z-axis delta angle output, upper word
354 static constexpr uint8_t X_DELTVEL_LOW =
355 0x30; // X-axis delta velocity output, lower word
356 static constexpr uint8_t X_DELTVEL_OUT =
357 0x32; // X-axis delta velocity output, upper word
358 static constexpr uint8_t Y_DELTVEL_LOW =
359 0x34; // Y-axis delta velocity output, lower word
360 static constexpr uint8_t Y_DELTVEL_OUT =
361 0x36; // Y-axis delta velocity output, upper word
362 static constexpr uint8_t Z_DELTVEL_LOW =
363 0x38; // Z-axis delta velocity output, lower word
364 static constexpr uint8_t Z_DELTVEL_OUT =
365 0x3A; // Z-axis delta velocity output, upper word
366 static constexpr uint8_t XG_BIAS_LOW =
367 0x40; // X-axis gyroscope bias offset correction, lower word
368 static constexpr uint8_t XG_BIAS_HIGH =
369 0x42; // X-axis gyroscope bias offset correction, upper word
370 static constexpr uint8_t YG_BIAS_LOW =
371 0x44; // Y-axis gyroscope bias offset correction, lower word
372 static constexpr uint8_t YG_BIAS_HIGH =
373 0x46; // Y-axis gyroscope bias offset correction, upper word
374 static constexpr uint8_t ZG_BIAS_LOW =
375 0x48; // Z-axis gyroscope bias offset correction, lower word
376 static constexpr uint8_t ZG_BIAS_HIGH =
377 0x4A; // Z-axis gyroscope bias offset correction, upper word
378 static constexpr uint8_t XA_BIAS_LOW =
379 0x4C; // X-axis accelerometer bias offset correction, lower word
380 static constexpr uint8_t XA_BIAS_HIGH =
381 0x4E; // X-axis accelerometer bias offset correction, upper word
382 static constexpr uint8_t YA_BIAS_LOW =
383 0x50; // Y-axis accelerometer bias offset correction, lower word
384 static constexpr uint8_t YA_BIAS_HIGH =
385 0x52; // Y-axis accelerometer bias offset correction, upper word
386 static constexpr uint8_t ZA_BIAS_LOW =
387 0x54; // Z-axis accelerometer bias offset correction, lower word
388 static constexpr uint8_t ZA_BIAS_HIGH =
389 0x56; // Z-axis accelerometer bias offset correction, upper word
390 static constexpr uint8_t FILT_CTRL = 0x5C; // Filter control
391 static constexpr uint8_t MSC_CTRL = 0x60; // Miscellaneous control
392 static constexpr uint8_t UP_SCALE = 0x62; // Clock scale factor, PPS mode
393 static constexpr uint8_t DEC_RATE =
394 0x64; // Decimation rate control (output data rate)
395 static constexpr uint8_t NULL_CNFG = 0x66; // Auto-null configuration control
396 static constexpr uint8_t GLOB_CMD = 0x68; // Global commands
397 static constexpr uint8_t FIRM_REV = 0x6C; // Firmware revision
398 static constexpr uint8_t FIRM_DM =
399 0x6E; // Firmware revision date, month and day
400 static constexpr uint8_t FIRM_Y = 0x70; // Firmware revision date, year
401 static constexpr uint8_t PROD_ID = 0x72; // Product identification
402 static constexpr uint8_t SERIAL_NUM =
403 0x74; // Serial number (relative to assembly lot)
404 static constexpr uint8_t USER_SCR1 = 0x76; // User scratch register 1
405 static constexpr uint8_t USER_SCR2 = 0x78; // User scratch register 2
406 static constexpr uint8_t USER_SCR3 = 0x7A; // User scratch register 3
407 static constexpr uint8_t FLSHCNT_LOW =
408 0x7C; // Flash update count, lower word
409 static constexpr uint8_t FLSHCNT_HIGH =
410 0x7E; // Flash update count, upper word
411
412 // Auto SPI Data Packet to read all thrre gyro axes.
413 static constexpr uint8_t m_autospi_allangle_packet[24] = {
414 X_DELTANG_OUT, FLASH_CNT, X_DELTANG_LOW, FLASH_CNT, Y_DELTANG_OUT,
415 FLASH_CNT, Y_DELTANG_LOW, FLASH_CNT, Z_DELTANG_OUT, FLASH_CNT,
416 Z_DELTANG_LOW, FLASH_CNT, X_GYRO_OUT, FLASH_CNT, Y_GYRO_OUT,
417 FLASH_CNT, Z_GYRO_OUT, FLASH_CNT, X_ACCL_OUT, FLASH_CNT,
418 Y_ACCL_OUT, FLASH_CNT, Z_ACCL_OUT, FLASH_CNT};
419
420 static constexpr double delta_angle_sf = 2160.0 / 2147483648.0;
421 static constexpr double rad_to_deg = 57.2957795;
422 static constexpr double deg_to_rad = 0.0174532;
423 static constexpr double grav = 9.81;
424
425 /** @brief Resources **/
426 DigitalInput* m_reset_in = nullptr;
427 DigitalOutput* m_status_led = nullptr;
428
429 /**
430 * @brief Switches to standard SPI operation. Primarily used when exiting auto
431 * SPI mode.
432 *
433 * @return A boolean indicating the success or failure of setting up the SPI
434 * peripheral in standard SPI mode.
435 */
436 bool SwitchToStandardSPI();
437
438 /**
439 * @brief Switches to auto SPI operation. Primarily used when exiting standard
440 * SPI mode.
441 *
442 * @return A boolean indicating the success or failure of setting up the SPI
443 * peripheral in auto SPI mode.
444 */
445 bool SwitchToAutoSPI();
446
447 /**
448 * @brief Reads the contents of a specified register location over SPI.
449 *
450 * @param reg An unsigned, 8-bit register location.
451 *
452 * @return An unsigned, 16-bit number representing the contents of the
453 * requested register location.
454 */
455 uint16_t ReadRegister(uint8_t reg);
456
457 /**
458 * @brief Writes an unsigned, 16-bit value to two adjacent, 8-bit register
459 * locations over SPI.
460 *
461 * @param reg An unsigned, 8-bit register location.
462 *
463 * @param val An unsigned, 16-bit value to be written to the specified
464 * register location.
465 */
466 void WriteRegister(uint8_t reg, uint16_t val);
467
468 /**
469 * @brief Main acquisition loop. Typically called asynchronously and
470 * free-wheels while the robot code is active.
471 */
472 void Acquire();
473
474 void Close();
475
476 // Integrated gyro angles.
477 double m_integ_angle_x = 0.0;
478 double m_integ_angle_y = 0.0;
479 double m_integ_angle_z = 0.0;
480
481 // Instant raw outputs
482 double m_gyro_rate_x = 0.0;
483 double m_gyro_rate_y = 0.0;
484 double m_gyro_rate_z = 0.0;
485 double m_accel_x = 0.0;
486 double m_accel_y = 0.0;
487 double m_accel_z = 0.0;
488
489 // Complementary filter variables
490 double m_tau = 1.0;
491 double m_dt, m_alpha = 0.0;
492 double m_compAngleX, m_compAngleY, m_accelAngleX, m_accelAngleY = 0.0;
493
494 // Complementary filter functions
495 double FormatFastConverge(double compAngle, double accAngle);
496
497 double FormatRange0to2PI(double compAngle);
498
499 double FormatAccelRange(double accelAngle, double accelZ);
500
501 double CompFilterProcess(double compAngle, double accelAngle, double omega);
502
503 // State and resource variables
504 std::atomic<bool> m_thread_active = false;
505 std::atomic<bool> m_first_run = true;
506 std::atomic<bool> m_thread_idle = false;
507 bool m_auto_configured = false;
508 SPI::Port m_spi_port;
509 uint16_t m_calibration_time = 0;
510 SPI* m_spi = nullptr;
511 DigitalInput* m_auto_interrupt = nullptr;
512 double m_scaled_sample_rate = 2500.0; // Default sample rate setting
513 bool m_connected{false};
514
515 std::thread m_acquire_task;
516
517 hal::SimDevice m_simDevice;
518 hal::SimBoolean m_simConnected;
519 hal::SimDouble m_simGyroAngleX;
520 hal::SimDouble m_simGyroAngleY;
521 hal::SimDouble m_simGyroAngleZ;
522 hal::SimDouble m_simGyroRateX;
523 hal::SimDouble m_simGyroRateY;
524 hal::SimDouble m_simGyroRateZ;
525 hal::SimDouble m_simAccelX;
526 hal::SimDouble m_simAccelY;
527 hal::SimDouble m_simAccelZ;
528
529 struct NonMovableMutexWrapper {
530 wpi::mutex mutex;
531 NonMovableMutexWrapper() = default;
532
533 NonMovableMutexWrapper(const NonMovableMutexWrapper&) = delete;
534 NonMovableMutexWrapper& operator=(const NonMovableMutexWrapper&) = delete;
535
536 NonMovableMutexWrapper(NonMovableMutexWrapper&&) {}
537 NonMovableMutexWrapper& operator=(NonMovableMutexWrapper&&) {
538 return *this;
539 }
540
541 void lock() { mutex.lock(); }
542
543 void unlock() { mutex.unlock(); }
544
545 bool try_lock() noexcept { return mutex.try_lock(); }
546 };
547
548 mutable NonMovableMutexWrapper m_mutex;
549};
550
551} // namespace frc
Use DMA SPI to read rate and acceleration data from the ADIS16470 IMU and return the robot's heading ...
Definition: ADIS16470_IMU.h:52
~ADIS16470_IMU() override
void SetGyroAngleX(units::degree_t angle)
Allow the gyro angle X to be set to a given value.
ADIS16470_IMU()
Creates a new ADIS16740 IMU object.
bool IsConnected() const
Checks the connection status of the IMU.
units::degree_t GetYFilteredAccelAngle() const
Returns the Y-axis filtered acceleration angle.
IMUAxis GetPitchAxis() const
Returns which axis, kX, kY, or kZ, is set to the pitch axis.
void SetGyroAngleZ(units::degree_t angle)
Allow the gyro angle Z to be set to a given value.
ADIS16470_IMU(ADIS16470_IMU &&other)
IMUAxis
IMU axes.
Definition: ADIS16470_IMU.h:91
@ kRoll
The user-configured roll axis.
Definition: ADIS16470_IMU.h:103
@ kX
The IMU's X axis.
Definition: ADIS16470_IMU.h:93
@ kYaw
The user-configured yaw axis.
Definition: ADIS16470_IMU.h:99
@ kZ
The IMU's Z axis.
Definition: ADIS16470_IMU.h:97
@ kPitch
The user-configured pitch axis.
Definition: ADIS16470_IMU.h:101
@ kY
The IMU's Y axis.
Definition: ADIS16470_IMU.h:95
IMUAxis m_roll_axis
Definition: ADIS16470_IMU.h:299
void Calibrate()
Switches the active SPI port to standard SPI mode, writes the command to activate the new null config...
CalibrationTime
ADIS16470 calibration times.
Definition: ADIS16470_IMU.h:57
ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis, IMUAxis roll_axis)
Creates a new ADIS16740 IMU object.
units::degree_t GetAngle(IMUAxis axis=IMUAxis::kYaw) const
Returns the axis angle (CCW positive).
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
void SetGyroAngleY(units::degree_t angle)
Allow the gyro angle Y to be set to a given value.
units::degree_t GetXFilteredAccelAngle() const
Returns the X-axis filtered acceleration angle.
int ConfigDecRate(uint16_t decimationRate)
Configures the decimation rate of the IMU.
IMUAxis GetRollAxis() const
Returns which axis, kX, kY, or kZ, is set to the roll axis.
ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis, IMUAxis roll_axis, frc::SPI::Port port, CalibrationTime cal_time)
Creates a new ADIS16740 IMU object.
units::degree_t GetYComplementaryAngle() const
Returns the Y-axis complementary angle.
int GetPort() const
Gets the SPI port number.
int ConfigCalTime(CalibrationTime new_cal_time)
Switches the active SPI port to standard SPI mode, writes a new value to the NULL_CNFG register in th...
IMUAxis m_yaw_axis
Definition: ADIS16470_IMU.h:297
IMUAxis GetYawAxis() const
Returns which axis, kX, kY, or kZ, is set to the yaw axis.
void Reset()
Reset the gyro.
units::meters_per_second_squared_t GetAccelX() const
Returns the acceleration in the X axis.
void SetGyroAngle(IMUAxis axis, units::degree_t angle)
Allow the designated gyro angle to be set to a given value.
units::meters_per_second_squared_t GetAccelY() const
Returns the acceleration in the Y axis.
ADIS16470_IMU & operator=(ADIS16470_IMU &&other)
units::degrees_per_second_t GetRate(IMUAxis axis=IMUAxis::kYaw) const
Returns the axis angular rate (CCW positive).
IMUAxis m_pitch_axis
Definition: ADIS16470_IMU.h:298
units::meters_per_second_squared_t GetAccelZ() const
Returns the acceleration in the Z axis.
units::degree_t GetXComplementaryAngle() const
Returns the X-axis complementary angle.
Class to read a digital input.
Definition: DigitalInput.h:27
Class to write to digital outputs.
Definition: DigitalOutput.h:25
SPI bus interface class.
Definition: SPI.h:26
Port
SPI port.
Definition: SPI.h:31
C++ wrapper around a HAL simulator boolean value handle.
Definition: SimDevice.h:608
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:642
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:533
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15
::std::mutex mutex
Definition: mutex.h:17