285 static constexpr uint8_t FLASH_CNT = 0x00;
286 static constexpr uint8_t XGYRO_OUT = 0x04;
287 static constexpr uint8_t YGYRO_OUT = 0x06;
288 static constexpr uint8_t ZGYRO_OUT = 0x08;
289 static constexpr uint8_t XACCL_OUT = 0x0A;
290 static constexpr uint8_t YACCL_OUT = 0x0C;
291 static constexpr uint8_t ZACCL_OUT = 0x0E;
292 static constexpr uint8_t XMAGN_OUT = 0x10;
293 static constexpr uint8_t YMAGN_OUT = 0x12;
294 static constexpr uint8_t ZMAGN_OUT = 0x14;
295 static constexpr uint8_t BARO_OUT =
297 static constexpr uint8_t TEMP_OUT = 0x18;
298 static constexpr uint8_t XGYRO_OFF =
300 static constexpr uint8_t YGYRO_OFF =
302 static constexpr uint8_t ZGYRO_OFF =
304 static constexpr uint8_t XACCL_OFF =
306 static constexpr uint8_t YACCL_OFF =
308 static constexpr uint8_t ZACCL_OFF =
310 static constexpr uint8_t XMAGN_HIC =
312 static constexpr uint8_t YMAGN_HIC =
314 static constexpr uint8_t ZMAGN_HIC =
316 static constexpr uint8_t XMAGN_SIC =
318 static constexpr uint8_t YMAGN_SIC =
320 static constexpr uint8_t ZMAGN_SIC =
322 static constexpr uint8_t GPIO_CTRL = 0x32;
323 static constexpr uint8_t MSC_CTRL = 0x34;
324 static constexpr uint8_t SMPL_PRD =
326 static constexpr uint8_t SENS_AVG = 0x38;
327 static constexpr uint8_t SEQ_CNT = 0x3A;
328 static constexpr uint8_t DIAG_STAT = 0x3C;
329 static constexpr uint8_t GLOB_CMD = 0x3E;
330 static constexpr uint8_t ALM_MAG1 = 0x40;
331 static constexpr uint8_t ALM_MAG2 = 0x42;
332 static constexpr uint8_t ALM_SMPL1 = 0x44;
333 static constexpr uint8_t ALM_SMPL2 = 0x46;
334 static constexpr uint8_t ALM_CTRL = 0x48;
335 static constexpr uint8_t LOT_ID1 = 0x52;
336 static constexpr uint8_t LOT_ID2 = 0x54;
337 static constexpr uint8_t PROD_ID = 0x56;
338 static constexpr uint8_t SERIAL_NUM = 0x58;
341 static constexpr double rad_to_deg = 57.2957795;
342 static constexpr double deg_to_rad = 0.0174532;
343 static constexpr double grav = 9.81;
347 double gyro_rate_x = 0.0;
348 double gyro_rate_y = 0.0;
349 double gyro_rate_z = 0.0;
356 bool SwitchToStandardSPI();
358 bool SwitchToAutoSPI();
360 uint16_t ReadRegister(uint8_t reg);
362 void WriteRegister(uint8_t reg, uint16_t val);
372 double m_gyro_rate_x = 0.0;
373 double m_gyro_rate_y = 0.0;
374 double m_gyro_rate_z = 0.0;
375 double m_accel_x = 0.0;
376 double m_accel_y = 0.0;
377 double m_accel_z = 0.0;
378 double m_mag_x = 0.0;
379 double m_mag_y = 0.0;
380 double m_mag_z = 0.0;
386 double m_dt, m_alpha = 0.0;
387 double m_compAngleX, m_compAngleY, m_accelAngleX, m_accelAngleY = 0.0;
390 OffsetData* m_offset_buffer =
nullptr;
392 double m_gyro_rate_offset_x = 0.0;
393 double m_gyro_rate_offset_y = 0.0;
394 double m_gyro_rate_offset_z = 0.0;
397 void InitOffsetBuffer(
int size);
401 int m_accum_count = 0;
404 double m_integ_gyro_angle_x = 0.0;
405 double m_integ_gyro_angle_y = 0.0;
406 double m_integ_gyro_angle_z = 0.0;
409 double FormatFastConverge(
double compAngle,
double accAngle);
411 double FormatRange0to2PI(
double compAngle);
413 double FormatAccelRange(
double accelAngle,
double accelZ);
415 double CompFilterProcess(
double compAngle,
double accelAngle,
double omega);
418 std::atomic<bool> m_thread_active =
false;
419 std::atomic<bool> m_first_run =
true;
420 std::atomic<bool> m_thread_idle =
false;
421 std::atomic<bool> m_start_up_mode =
true;
423 bool m_auto_configured =
false;
426 SPI* m_spi =
nullptr;
427 DigitalInput* m_auto_interrupt =
nullptr;
428 bool m_connected{
false};
430 std::thread m_acquire_task;
444 struct NonMovableMutexWrapper {
446 NonMovableMutexWrapper() =
default;
448 NonMovableMutexWrapper(
const NonMovableMutexWrapper&) =
delete;
449 NonMovableMutexWrapper&
operator=(
const NonMovableMutexWrapper&) =
delete;
451 NonMovableMutexWrapper(NonMovableMutexWrapper&&) {}
452 NonMovableMutexWrapper&
operator=(NonMovableMutexWrapper&&) {
456 void lock() { mutex.lock(); }
458 void unlock() { mutex.unlock(); }
460 bool try_lock() noexcept {
return mutex.try_lock(); }
463 mutable NonMovableMutexWrapper m_mutex;
466 static constexpr uint16_t adiscrc[256] = {
467 0x0000, 0x17CE, 0x0FDF, 0x1811, 0x1FBE, 0x0870, 0x1061, 0x07AF, 0x1F3F,
468 0x08F1, 0x10E0, 0x072E, 0x0081, 0x174F, 0x0F5E, 0x1890, 0x1E3D, 0x09F3,
469 0x11E2, 0x062C, 0x0183, 0x164D, 0x0E5C, 0x1992, 0x0102, 0x16CC, 0x0EDD,
470 0x1913, 0x1EBC, 0x0972, 0x1163, 0x06AD, 0x1C39, 0x0BF7, 0x13E6, 0x0428,
471 0x0387, 0x1449, 0x0C58, 0x1B96, 0x0306, 0x14C8, 0x0CD9, 0x1B17, 0x1CB8,
472 0x0B76, 0x1367, 0x04A9, 0x0204, 0x15CA, 0x0DDB, 0x1A15, 0x1DBA, 0x0A74,
473 0x1265, 0x05AB, 0x1D3B, 0x0AF5, 0x12E4, 0x052A, 0x0285, 0x154B, 0x0D5A,
474 0x1A94, 0x1831, 0x0FFF, 0x17EE, 0x0020, 0x078F, 0x1041, 0x0850, 0x1F9E,
475 0x070E, 0x10C0, 0x08D1, 0x1F1F, 0x18B0, 0x0F7E, 0x176F, 0x00A1, 0x060C,
476 0x11C2, 0x09D3, 0x1E1D, 0x19B2, 0x0E7C, 0x166D, 0x01A3, 0x1933, 0x0EFD,
477 0x16EC, 0x0122, 0x068D, 0x1143, 0x0952, 0x1E9C, 0x0408, 0x13C6, 0x0BD7,
478 0x1C19, 0x1BB6, 0x0C78, 0x1469, 0x03A7, 0x1B37, 0x0CF9, 0x14E8, 0x0326,
479 0x0489, 0x1347, 0x0B56, 0x1C98, 0x1A35, 0x0DFB, 0x15EA, 0x0224, 0x058B,
480 0x1245, 0x0A54, 0x1D9A, 0x050A, 0x12C4, 0x0AD5, 0x1D1B, 0x1AB4, 0x0D7A,
481 0x156B, 0x02A5, 0x1021, 0x07EF, 0x1FFE, 0x0830, 0x0F9F, 0x1851, 0x0040,
482 0x178E, 0x0F1E, 0x18D0, 0x00C1, 0x170F, 0x10A0, 0x076E, 0x1F7F, 0x08B1,
483 0x0E1C, 0x19D2, 0x01C3, 0x160D, 0x11A2, 0x066C, 0x1E7D, 0x09B3, 0x1123,
484 0x06ED, 0x1EFC, 0x0932, 0x0E9D, 0x1953, 0x0142, 0x168C, 0x0C18, 0x1BD6,
485 0x03C7, 0x1409, 0x13A6, 0x0468, 0x1C79, 0x0BB7, 0x1327, 0x04E9, 0x1CF8,
486 0x0B36, 0x0C99, 0x1B57, 0x0346, 0x1488, 0x1225, 0x05EB, 0x1DFA, 0x0A34,
487 0x0D9B, 0x1A55, 0x0244, 0x158A, 0x0D1A, 0x1AD4, 0x02C5, 0x150B, 0x12A4,
488 0x056A, 0x1D7B, 0x0AB5, 0x0810, 0x1FDE, 0x07CF, 0x1001, 0x17AE, 0x0060,
489 0x1871, 0x0FBF, 0x172F, 0x00E1, 0x18F0, 0x0F3E, 0x0891, 0x1F5F, 0x074E,
490 0x1080, 0x162D, 0x01E3, 0x19F2, 0x0E3C, 0x0993, 0x1E5D, 0x064C, 0x1182,
491 0x0912, 0x1EDC, 0x06CD, 0x1103, 0x16AC, 0x0162, 0x1973, 0x0EBD, 0x1429,
492 0x03E7, 0x1BF6, 0x0C38, 0x0B97, 0x1C59, 0x0448, 0x1386, 0x0B16, 0x1CD8,
493 0x04C9, 0x1307, 0x14A8, 0x0366, 0x1B77, 0x0CB9, 0x0A14, 0x1DDA, 0x05CB,
494 0x1205, 0x15AA, 0x0264, 0x1A75, 0x0DBB, 0x152B, 0x02E5, 0x1AF4, 0x0D3A,
495 0x0A95, 0x1D5B, 0x054A, 0x1284};
Use DMA SPI to read rate, acceleration, and magnetometer data from the ADIS16448 IMU and return the r...
Definition: ADIS16448_IMU.h:55
int ConfigDecRate(uint16_t decimationRate)
Configures the decimation rate of the IMU.
units::tesla_t GetMagneticFieldZ() const
Returns the magnetic field strength in the Z axis.
units::meters_per_second_squared_t GetAccelZ() const
Returns the acceleration in the Z axis.
units::degree_t GetYFilteredAccelAngle() const
Returns the Y-axis filtered acceleration angle.
units::degree_t GetGyroAngleX() const
Returns the accumulated gyro angle in the X axis.
units::degree_t GetXFilteredAccelAngle() const
Returns the X-axis filtered acceleration angle.
units::degree_t GetYComplementaryAngle() const
Returns the complementary angle around the Y axis computed from accelerometer and gyro rate measureme...
units::celsius_t GetTemperature() const
Returns the temperature.
units::degree_t GetAngle() const
Returns the yaw axis angle in degrees (CCW positive).
units::tesla_t GetMagneticFieldY() const
Returns the magnetic field strength in the Y axis.
units::degree_t GetXComplementaryAngle() const
Returns the complementary angle around the X axis computed from accelerometer and gyro rate measureme...
int SetYawAxis(IMUAxis yaw_axis)
int ConfigCalTime(CalibrationTime new_cal_time)
Configures the calibration time used for the next calibrate.
ADIS16448_IMU(IMUAxis yaw_axis, SPI::Port port, CalibrationTime cal_time)
IMU constructor on the specified MXP port and orientation.
IMUAxis
IMU axes.
Definition: ADIS16448_IMU.h:90
@ kY
The IMU's Y axis.
Definition: ADIS16448_IMU.h:94
@ kX
The IMU's X axis.
Definition: ADIS16448_IMU.h:92
@ kZ
The IMU's Z axis.
Definition: ADIS16448_IMU.h:96
void Reset()
Reset the gyro.
CalibrationTime
ADIS16448 calibration times.
Definition: ADIS16448_IMU.h:60
units::pounds_per_square_inch_t GetBarometricPressure() const
Returns the barometric pressure.
ADIS16448_IMU & operator=(ADIS16448_IMU &&)
void Calibrate()
Initialize the IMU.
units::degrees_per_second_t GetGyroRateX() const
Returns the angular rate in the X axis.
~ADIS16448_IMU() override
units::degrees_per_second_t GetGyroRateY() const
Returns the angular rate in the Y axis.
units::degrees_per_second_t GetRate() const
Returns the yaw axis angular rate in degrees per second (CCW positive).
units::meters_per_second_squared_t GetAccelY() const
Returns the acceleration in the Y axis.
int GetPort() const
Get the SPI port number.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
units::degree_t GetGyroAngleY() const
Returns the accumulated gyro angle in the Y axis.
units::degree_t GetGyroAngleZ() const
Returns the accumulated gyro angle in the Z axis.
units::meters_per_second_squared_t GetAccelX() const
Returns the acceleration in the X axis.
IMUAxis GetYawAxis() const
ADIS16448_IMU(ADIS16448_IMU &&)
bool IsConnected() const
Checks the connection status of the IMU.
ADIS16448_IMU()
IMU constructor on onboard MXP CS0, Z-up orientation, and complementary AHRS computation.
units::tesla_t GetMagneticFieldX() const
Returns the magnetic field strength in the X axis.
units::degrees_per_second_t GetGyroRateZ() const
Returns the angular rate in the Z axis.
Class to write to digital outputs.
Definition: DigitalOutput.h:25
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