314 static constexpr uint8_t FLASH_CNT = 0x00;
315 static constexpr uint8_t DIAG_STAT =
317 static constexpr uint8_t X_GYRO_LOW =
319 static constexpr uint8_t X_GYRO_OUT =
321 static constexpr uint8_t Y_GYRO_LOW =
323 static constexpr uint8_t Y_GYRO_OUT =
325 static constexpr uint8_t Z_GYRO_LOW =
327 static constexpr uint8_t Z_GYRO_OUT =
329 static constexpr uint8_t X_ACCL_LOW =
331 static constexpr uint8_t X_ACCL_OUT =
333 static constexpr uint8_t Y_ACCL_LOW =
335 static constexpr uint8_t Y_ACCL_OUT =
337 static constexpr uint8_t Z_ACCL_LOW =
339 static constexpr uint8_t Z_ACCL_OUT =
341 static constexpr uint8_t TEMP_OUT =
343 static constexpr uint8_t TIME_STAMP = 0x1E;
344 static constexpr uint8_t X_DELTANG_LOW =
346 static constexpr uint8_t X_DELTANG_OUT =
348 static constexpr uint8_t Y_DELTANG_LOW =
350 static constexpr uint8_t Y_DELTANG_OUT =
352 static constexpr uint8_t Z_DELTANG_LOW =
354 static constexpr uint8_t Z_DELTANG_OUT =
356 static constexpr uint8_t X_DELTVEL_LOW =
358 static constexpr uint8_t X_DELTVEL_OUT =
360 static constexpr uint8_t Y_DELTVEL_LOW =
362 static constexpr uint8_t Y_DELTVEL_OUT =
364 static constexpr uint8_t Z_DELTVEL_LOW =
366 static constexpr uint8_t Z_DELTVEL_OUT =
368 static constexpr uint8_t XG_BIAS_LOW =
370 static constexpr uint8_t XG_BIAS_HIGH =
372 static constexpr uint8_t YG_BIAS_LOW =
374 static constexpr uint8_t YG_BIAS_HIGH =
376 static constexpr uint8_t ZG_BIAS_LOW =
378 static constexpr uint8_t ZG_BIAS_HIGH =
380 static constexpr uint8_t XA_BIAS_LOW =
382 static constexpr uint8_t XA_BIAS_HIGH =
384 static constexpr uint8_t YA_BIAS_LOW =
386 static constexpr uint8_t YA_BIAS_HIGH =
388 static constexpr uint8_t ZA_BIAS_LOW =
390 static constexpr uint8_t ZA_BIAS_HIGH =
392 static constexpr uint8_t FILT_CTRL = 0x5C;
393 static constexpr uint8_t MSC_CTRL = 0x60;
394 static constexpr uint8_t UP_SCALE = 0x62;
395 static constexpr uint8_t DEC_RATE =
397 static constexpr uint8_t NULL_CNFG = 0x66;
398 static constexpr uint8_t GLOB_CMD = 0x68;
399 static constexpr uint8_t FIRM_REV = 0x6C;
400 static constexpr uint8_t FIRM_DM =
402 static constexpr uint8_t FIRM_Y = 0x70;
403 static constexpr uint8_t PROD_ID = 0x72;
404 static constexpr uint8_t SERIAL_NUM =
406 static constexpr uint8_t USER_SCR1 = 0x76;
407 static constexpr uint8_t USER_SCR2 = 0x78;
408 static constexpr uint8_t USER_SCR3 = 0x7A;
409 static constexpr uint8_t FLSHCNT_LOW =
411 static constexpr uint8_t FLSHCNT_HIGH =
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};
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;
438 bool SwitchToStandardSPI();
447 bool SwitchToAutoSPI();
457 uint16_t ReadRegister(uint8_t reg);
468 void WriteRegister(uint8_t reg, uint16_t val);
479 double m_integ_angle_x = 0.0;
480 double m_integ_angle_y = 0.0;
481 double m_integ_angle_z = 0.0;
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;
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;
497 double FormatFastConverge(
double compAngle,
double accAngle);
499 double FormatAccelRange(
double accelAngle,
double accelZ);
501 double CompFilterProcess(
double compAngle,
double accelAngle,
double omega);
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;
509 uint16_t m_calibration_time = 0;
510 SPI* m_spi =
nullptr;
512 double m_scaled_sample_rate = 2500.0;
513 bool m_connected{
false};
515 std::thread m_acquire_task;
529 struct NonMovableMutexWrapper {
531 NonMovableMutexWrapper() =
default;
533 NonMovableMutexWrapper(
const NonMovableMutexWrapper&) =
delete;
534 NonMovableMutexWrapper& operator=(
const NonMovableMutexWrapper&) =
delete;
536 NonMovableMutexWrapper(NonMovableMutexWrapper&&) {}
537 NonMovableMutexWrapper& operator=(NonMovableMutexWrapper&&) {
541 void lock() {
mutex.lock(); }
543 void unlock() {
mutex.unlock(); }
545 bool try_lock() noexcept {
return mutex.try_lock(); }
548 mutable NonMovableMutexWrapper m_mutex;
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.
@ _1s
1 s calibration time.
@ _16s
16 s calibration time.
@ _2s
2 s calibration time.
@ _8s
8 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.
@ _4s
4 s 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 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
::std::mutex mutex
Definition mutex.h:17