WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
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 1
110 * second. 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 1
118 * second.
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 * Configures calibration time.
166 *
167 * @param new_cal_time New calibration time
168 * @return 0 if success, 1 if no change, 2 if error.
169 */
171
172 /**
173 * Reset the gyro.
174 *
175 * Resets the gyro accumulations to a heading of zero. This can be used if
176 * there is significant drift in the gyro and it needs to be recalibrated
177 * after running.
178 */
179 void Reset();
180
181 /**
182 * Allow the designated gyro angle to be set to a given value. This may happen
183 * with unread values in the buffer, it is suggested that the IMU is not
184 * moving when this method is run.
185 *
186 * @param axis IMUAxis that will be changed
187 * @param angle The new angle (CCW positive)
188 */
189 void SetGyroAngle(IMUAxis axis, units::degree_t angle);
190
191 /**
192 * Allow the gyro angle X to be set to a given value. This may happen with
193 * unread values in the buffer, it is suggested that the IMU is not moving
194 * when this method is run.
195 *
196 * @param angle The new angle (CCW positive)
197 */
198 void SetGyroAngleX(units::degree_t angle);
199
200 /**
201 * Allow the gyro angle Y to be set to a given value. This may happen with
202 * unread values in the buffer, it is suggested that the IMU is not moving
203 * when this method is run.
204 *
205 * @param angle The new angle (CCW positive)
206 */
207 void SetGyroAngleY(units::degree_t angle);
208
209 /**
210 * Allow the gyro angle Z to be set to a given value. This may happen with
211 * unread values in the buffer, it is suggested that the IMU is not moving
212 * when this method is run.
213 *
214 * @param angle The new angle (CCW positive)
215 */
216 void SetGyroAngleZ(units::degree_t angle);
217
218 /**
219 * Returns the axis angle (CCW positive).
220 *
221 * @param axis The IMUAxis whose angle to return. Defaults to user configured
222 * Yaw.
223 * @return The axis angle (CCW positive).
224 */
225 units::degree_t GetAngle(IMUAxis axis = IMUAxis::kYaw) const;
226
227 /**
228 * Returns the axis angular rate (CCW positive).
229 *
230 * @param axis The IMUAxis whose rate to return. Defaults to user configured
231 * Yaw.
232 * @return Axis angular rate (CCW positive).
233 */
234 units::degrees_per_second_t GetRate(IMUAxis axis = IMUAxis::kYaw) const;
235
236 /**
237 * Returns the acceleration in the X axis.
238 */
239 units::meters_per_second_squared_t GetAccelX() const;
240
241 /**
242 * Returns the acceleration in the Y axis.
243 */
244 units::meters_per_second_squared_t GetAccelY() const;
245
246 /**
247 * Returns the acceleration in the Z axis.
248 */
249 units::meters_per_second_squared_t GetAccelZ() const;
250
251 /**
252 * Returns the X-axis complementary angle.
253 */
254 units::degree_t GetXComplementaryAngle() const;
255
256 /**
257 * Returns the Y-axis complementary angle.
258 */
259 units::degree_t GetYComplementaryAngle() const;
260
261 /**
262 * Returns the X-axis filtered acceleration angle.
263 */
264 units::degree_t GetXFilteredAccelAngle() const;
265
266 /**
267 * Returns the Y-axis filtered acceleration angle.
268 */
269 units::degree_t GetYFilteredAccelAngle() const;
270
271 /**
272 * Returns which axis, kX, kY, or kZ, is set to the yaw axis.
273 *
274 * @return IMUAxis Yaw Axis
275 */
277
278 /**
279 * Returns which axis, kX, kY, or kZ, is set to the pitch axis.
280 *
281 * @return IMUAxis Pitch Axis
282 */
284
285 /**
286 * Returns which axis, kX, kY, or kZ, is set to the roll axis.
287 *
288 * @return IMUAxis Roll Axis
289 */
291
292 /**
293 * Checks the connection status of the IMU.
294 *
295 * @return True if the IMU is connected, false otherwise.
296 */
297 bool IsConnected() const;
298
302
303 /**
304 * Gets the SPI port number.
305 *
306 * @return The SPI port number.
307 */
308 int GetPort() const;
309
310 void InitSendable(wpi::SendableBuilder& builder) override;
311
312 private:
313 // Register Map Declaration
314 static constexpr uint8_t FLASH_CNT = 0x00; // Flash memory write count
315 static constexpr uint8_t DIAG_STAT =
316 0x02; // Diagnostic and operational status
317 static constexpr uint8_t X_GYRO_LOW =
318 0x04; // X-axis gyroscope output, lower word
319 static constexpr uint8_t X_GYRO_OUT =
320 0x06; // X-axis gyroscope output, upper word
321 static constexpr uint8_t Y_GYRO_LOW =
322 0x08; // Y-axis gyroscope output, lower word
323 static constexpr uint8_t Y_GYRO_OUT =
324 0x0A; // Y-axis gyroscope output, upper word
325 static constexpr uint8_t Z_GYRO_LOW =
326 0x0C; // Z-axis gyroscope output, lower word
327 static constexpr uint8_t Z_GYRO_OUT =
328 0x0E; // Z-axis gyroscope output, upper word
329 static constexpr uint8_t X_ACCL_LOW =
330 0x10; // X-axis accelerometer output, lower word
331 static constexpr uint8_t X_ACCL_OUT =
332 0x12; // X-axis accelerometer output, upper word
333 static constexpr uint8_t Y_ACCL_LOW =
334 0x14; // Y-axis accelerometer output, lower word
335 static constexpr uint8_t Y_ACCL_OUT =
336 0x16; // Y-axis accelerometer output, upper word
337 static constexpr uint8_t Z_ACCL_LOW =
338 0x18; // Z-axis accelerometer output, lower word
339 static constexpr uint8_t Z_ACCL_OUT =
340 0x1A; // Z-axis accelerometer output, upper word
341 static constexpr uint8_t TEMP_OUT =
342 0x1C; // Temperature output (internal, not calibrated)
343 static constexpr uint8_t TIME_STAMP = 0x1E; // PPS mode time stamp
344 static constexpr uint8_t X_DELTANG_LOW =
345 0x24; // X-axis delta angle output, lower word
346 static constexpr uint8_t X_DELTANG_OUT =
347 0x26; // X-axis delta angle output, upper word
348 static constexpr uint8_t Y_DELTANG_LOW =
349 0x28; // Y-axis delta angle output, lower word
350 static constexpr uint8_t Y_DELTANG_OUT =
351 0x2A; // Y-axis delta angle output, upper word
352 static constexpr uint8_t Z_DELTANG_LOW =
353 0x2C; // Z-axis delta angle output, lower word
354 static constexpr uint8_t Z_DELTANG_OUT =
355 0x2E; // Z-axis delta angle output, upper word
356 static constexpr uint8_t X_DELTVEL_LOW =
357 0x30; // X-axis delta velocity output, lower word
358 static constexpr uint8_t X_DELTVEL_OUT =
359 0x32; // X-axis delta velocity output, upper word
360 static constexpr uint8_t Y_DELTVEL_LOW =
361 0x34; // Y-axis delta velocity output, lower word
362 static constexpr uint8_t Y_DELTVEL_OUT =
363 0x36; // Y-axis delta velocity output, upper word
364 static constexpr uint8_t Z_DELTVEL_LOW =
365 0x38; // Z-axis delta velocity output, lower word
366 static constexpr uint8_t Z_DELTVEL_OUT =
367 0x3A; // Z-axis delta velocity output, upper word
368 static constexpr uint8_t XG_BIAS_LOW =
369 0x40; // X-axis gyroscope bias offset correction, lower word
370 static constexpr uint8_t XG_BIAS_HIGH =
371 0x42; // X-axis gyroscope bias offset correction, upper word
372 static constexpr uint8_t YG_BIAS_LOW =
373 0x44; // Y-axis gyroscope bias offset correction, lower word
374 static constexpr uint8_t YG_BIAS_HIGH =
375 0x46; // Y-axis gyroscope bias offset correction, upper word
376 static constexpr uint8_t ZG_BIAS_LOW =
377 0x48; // Z-axis gyroscope bias offset correction, lower word
378 static constexpr uint8_t ZG_BIAS_HIGH =
379 0x4A; // Z-axis gyroscope bias offset correction, upper word
380 static constexpr uint8_t XA_BIAS_LOW =
381 0x4C; // X-axis accelerometer bias offset correction, lower word
382 static constexpr uint8_t XA_BIAS_HIGH =
383 0x4E; // X-axis accelerometer bias offset correction, upper word
384 static constexpr uint8_t YA_BIAS_LOW =
385 0x50; // Y-axis accelerometer bias offset correction, lower word
386 static constexpr uint8_t YA_BIAS_HIGH =
387 0x52; // Y-axis accelerometer bias offset correction, upper word
388 static constexpr uint8_t ZA_BIAS_LOW =
389 0x54; // Z-axis accelerometer bias offset correction, lower word
390 static constexpr uint8_t ZA_BIAS_HIGH =
391 0x56; // Z-axis accelerometer bias offset correction, upper word
392 static constexpr uint8_t FILT_CTRL = 0x5C; // Filter control
393 static constexpr uint8_t MSC_CTRL = 0x60; // Miscellaneous control
394 static constexpr uint8_t UP_SCALE = 0x62; // Clock scale factor, PPS mode
395 static constexpr uint8_t DEC_RATE =
396 0x64; // Decimation rate control (output data rate)
397 static constexpr uint8_t NULL_CNFG = 0x66; // Auto-null configuration control
398 static constexpr uint8_t GLOB_CMD = 0x68; // Global commands
399 static constexpr uint8_t FIRM_REV = 0x6C; // Firmware revision
400 static constexpr uint8_t FIRM_DM =
401 0x6E; // Firmware revision date, month and day
402 static constexpr uint8_t FIRM_Y = 0x70; // Firmware revision date, year
403 static constexpr uint8_t PROD_ID = 0x72; // Product identification
404 static constexpr uint8_t SERIAL_NUM =
405 0x74; // Serial number (relative to assembly lot)
406 static constexpr uint8_t USER_SCR1 = 0x76; // User scratch register 1
407 static constexpr uint8_t USER_SCR2 = 0x78; // User scratch register 2
408 static constexpr uint8_t USER_SCR3 = 0x7A; // User scratch register 3
409 static constexpr uint8_t FLSHCNT_LOW =
410 0x7C; // Flash update count, lower word
411 static constexpr uint8_t FLSHCNT_HIGH =
412 0x7E; // Flash update count, upper word
413
414 // Auto SPI Data Packet to read all thrre gyro axes.
415 static constexpr uint8_t m_autospi_allangle_packet[24] = {
416 X_DELTANG_OUT, FLASH_CNT, X_DELTANG_LOW, FLASH_CNT, Y_DELTANG_OUT,
417 FLASH_CNT, Y_DELTANG_LOW, FLASH_CNT, Z_DELTANG_OUT, FLASH_CNT,
418 Z_DELTANG_LOW, FLASH_CNT, X_GYRO_OUT, FLASH_CNT, Y_GYRO_OUT,
419 FLASH_CNT, Z_GYRO_OUT, FLASH_CNT, X_ACCL_OUT, FLASH_CNT,
420 Y_ACCL_OUT, FLASH_CNT, Z_ACCL_OUT, FLASH_CNT};
421
422 static constexpr double delta_angle_sf = 2160.0 / 2147483648.0;
423 static constexpr double kRadToDeg = 57.2957795;
424 static constexpr double kDegToRad = 0.0174532;
425 static constexpr double kGrav = 9.81;
426
427 // Resources
428 DigitalInput* m_reset_in = nullptr;
429 DigitalOutput* m_status_led = nullptr;
430
431 /**
432 * @brief Switches to standard SPI operation. Primarily used when exiting auto
433 * SPI mode.
434 *
435 * @return A boolean indicating the success or failure of setting up the SPI
436 * peripheral in standard SPI mode.
437 */
438 bool SwitchToStandardSPI();
439
440 /**
441 * @brief Switches to auto SPI operation. Primarily used when exiting standard
442 * SPI mode.
443 *
444 * @return A boolean indicating the success or failure of setting up the SPI
445 * peripheral in auto SPI mode.
446 */
447 bool SwitchToAutoSPI();
448
449 /**
450 * @brief Reads the contents of a specified register location over SPI.
451 *
452 * @param reg An unsigned, 8-bit register location.
453 *
454 * @return An unsigned, 16-bit number representing the contents of the
455 * requested register location.
456 */
457 uint16_t ReadRegister(uint8_t reg);
458
459 /**
460 * @brief Writes an unsigned, 16-bit value to two adjacent, 8-bit register
461 * locations over SPI.
462 *
463 * @param reg An unsigned, 8-bit register location.
464 *
465 * @param val An unsigned, 16-bit value to be written to the specified
466 * register location.
467 */
468 void WriteRegister(uint8_t reg, uint16_t val);
469
470 /**
471 * @brief Main acquisition loop. Typically called asynchronously and
472 * free-wheels while the robot code is active.
473 */
474 void Acquire();
475
476 void Close();
477
478 // Integrated gyro angles.
479 double m_integ_angle_x = 0.0;
480 double m_integ_angle_y = 0.0;
481 double m_integ_angle_z = 0.0;
482
483 // Instant raw outputs
484 double m_gyro_rate_x = 0.0;
485 double m_gyro_rate_y = 0.0;
486 double m_gyro_rate_z = 0.0;
487 double m_accel_x = 0.0;
488 double m_accel_y = 0.0;
489 double m_accel_z = 0.0;
490
491 // Complementary filter variables
492 double m_dt, m_alpha = 0.0;
493 static constexpr double kTau = 1.0;
494 double m_compAngleX, m_compAngleY, m_accelAngleX, m_accelAngleY = 0.0;
495
496 // Complementary filter functions
497 double FormatFastConverge(double compAngle, double accAngle);
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:301
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
@ _512ms
512 ms calibration time.
@ _16s
16 s calibration time.
@ _32s
32 s calibration time.
@ _64ms
64 ms calibration time.
@ _128ms
128 ms calibration time.
@ _64s
64 s calibration time.
@ _32ms
32 ms calibration time.
@ _256ms
256 ms calibration time.
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)
Configures calibration time.
IMUAxis m_yaw_axis
Definition ADIS16470_IMU.h:299
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:300
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:28
Class to write to digital outputs.
Definition DigitalOutput.h:26
SPI bus interface class.
Definition SPI.h:27
Port
SPI port.
Definition SPI.h:32
C++ wrapper around a HAL simulator boolean value handle.
Definition SimDevice.h:611
A move-only C++ wrapper around a HAL simulator device handle.
Definition SimDevice.h:645
C++ wrapper around a HAL simulator double value handle.
Definition SimDevice.h:536
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:21
Interface for Sendable objects.
Definition Sendable.h:16
Definition CAN.h:11
::std::mutex mutex
Definition mutex.h:17