navX MXP C++ Class Library for RoboRIO
navX MXP Robotics Navigation Sensor
AHRS.h
1 /*
2  * AHRS.h
3  *
4  * Created on: Jul 30, 2015
5  * Author: Scott
6  */
7 
8 #ifndef SRC_AHRS_H_
9 #define SRC_AHRS_H_
10 
11 #include <wpi/sendable/Sendable.h>
12 #include <wpi/sendable/SendableHelper.h>
13 #include "frc/I2C.h"
14 #include "frc/SPI.h"
15 #include "frc/SerialPort.h"
16 #include "frc/Timer.h"
17 #include "frc/interfaces/Gyro.h"
18 #include "ITimestampedDataSubscriber.h"
19 #include "networktables/NetworkTableEntry.h"
20 #include <hal/SimDevice.h>
21 
22 class IIOProvider;
23 class ContinuousAngleTracker;
24 class InertialDataIntegrator;
25 class OffsetTracker;
26 class AHRSInternal;
27 
30 class AHRS : public frc::Gyro,
31  public wpi::Sendable,
32  public wpi::SendableHelper<AHRS> {
33 public:
34 
36  enum BoardAxis {
43  };
44 
46  struct BoardYawAxis
47  {
51  bool up;
52  };
53 
63  kRawData = 1
64  };
65 
66 private:
67  friend class AHRSInternal;
68  AHRSInternal * ahrs_internal;
69 
70  volatile float yaw;
71  volatile float pitch;
72  volatile float roll;
73  volatile float compass_heading;
74  volatile float world_linear_accel_x;
75  volatile float world_linear_accel_y;
76  volatile float world_linear_accel_z;
77  volatile float mpu_temp_c;
78  volatile float fused_heading;
79  volatile float altitude;
80  volatile float baro_pressure;
81  volatile bool is_moving;
82  volatile bool is_rotating;
83  volatile float baro_sensor_temp_c;
84  volatile bool altitude_valid;
85  volatile bool is_magnetometer_calibrated;
86  volatile bool magnetic_disturbance;
87  volatile float quaternionW;
88  volatile float quaternionX;
89  volatile float quaternionY;
90  volatile float quaternionZ;
91 
92  /* Integrated Data */
93  float velocity[3];
94  float displacement[3];
95 
96 
97  /* Raw Data */
98  volatile int16_t raw_gyro_x;
99  volatile int16_t raw_gyro_y;
100  volatile int16_t raw_gyro_z;
101  volatile int16_t raw_accel_x;
102  volatile int16_t raw_accel_y;
103  volatile int16_t raw_accel_z;
104  volatile int16_t cal_mag_x;
105  volatile int16_t cal_mag_y;
106  volatile int16_t cal_mag_z;
107 
108  /* Configuration/Status */
109  volatile uint8_t update_rate_hz;
110  volatile int16_t accel_fsr_g;
111  volatile int16_t gyro_fsr_dps;
112  volatile int16_t capability_flags;
113  volatile uint8_t op_status;
114  volatile int16_t sensor_status;
115  volatile uint8_t cal_status;
116  volatile uint8_t selftest_status;
117 
118  /* Board ID */
119  volatile uint8_t board_type;
120  volatile uint8_t hw_rev;
121  volatile uint8_t fw_ver_major;
122  volatile uint8_t fw_ver_minor;
123 
124  long last_sensor_timestamp;
125  double last_update_time;
126 
127  InertialDataIntegrator *integrator;
128  ContinuousAngleTracker *yaw_angle_tracker;
129  OffsetTracker * yaw_offset_tracker;
130  IIOProvider * io;
131 
132  std::thread * task;
133 
134  // Simulation
135  hal::SimDevice m_simDevice;
136 
137 #define MAX_NUM_CALLBACKS 3
138  ITimestampedDataSubscriber *callbacks[MAX_NUM_CALLBACKS];
139  void *callback_contexts[MAX_NUM_CALLBACKS];
140 
141  bool enable_boardlevel_yawreset;
142  double last_yawreset_request_timestamp;
143  double last_yawreset_while_calibrating_request_timestamp;
144  uint32_t successive_suppressed_yawreset_request_count;
145  bool disconnect_startupcalibration_recovery_pending;
146  bool logging_enabled;
147 
148 public:
149  AHRS(frc::SPI::Port spi_port_id);
150  AHRS(frc::I2C::Port i2c_port_id);
151  AHRS(frc::SerialPort::Port serial_port_id);
152 
153  AHRS(frc::SPI::Port spi_port_id, uint8_t update_rate_hz);
154  AHRS(frc::SPI::Port spi_port_id, uint32_t spi_bitrate, uint8_t update_rate_hz);
155 
156  AHRS(frc::I2C::Port i2c_port_id, uint8_t update_rate_hz);
157 
158  AHRS(frc::SerialPort::Port serial_port_id, AHRS::SerialDataType data_type, uint8_t update_rate_hz);
159 
160  float GetPitch();
161  float GetRoll();
162  float GetYaw();
163  float GetCompassHeading();
164  void ZeroYaw();
165  bool IsCalibrating();
166  bool IsConnected();
167  double GetByteCount();
168  double GetUpdateCount();
169  long GetLastSensorTimestamp();
170  float GetWorldLinearAccelX();
171  float GetWorldLinearAccelY();
172  float GetWorldLinearAccelZ();
173  bool IsMoving();
174  bool IsRotating();
175  float GetBarometricPressure();
176  float GetAltitude();
177  bool IsAltitudeValid();
178  float GetFusedHeading();
179  bool IsMagneticDisturbance();
181  float GetQuaternionW();
182  float GetQuaternionX();
183  float GetQuaternionY();
184  float GetQuaternionZ();
185  void ResetDisplacement();
186  void UpdateDisplacement( float accel_x_g, float accel_y_g,
187  int update_rate_hz, bool is_moving );
188  float GetVelocityX();
189  float GetVelocityY();
190  float GetVelocityZ();
191  float GetDisplacementX();
192  float GetDisplacementY();
193  float GetDisplacementZ();
194  double GetAngle() const override;
195  double GetRate() const override;
196  void SetAngleAdjustment(double angle);
197  double GetAngleAdjustment();
198  void Reset() override;
199  float GetRawGyroX();
200  float GetRawGyroY();
201  float GetRawGyroZ();
202  float GetRawAccelX();
203  float GetRawAccelY();
204  float GetRawAccelZ();
205  float GetRawMagX();
206  float GetRawMagY();
207  float GetRawMagZ();
208  float GetPressure();
209  float GetTempC();
211  std::string GetFirmwareVersion();
212 
213  bool RegisterCallback( ITimestampedDataSubscriber *callback, void *callback_context);
214  bool DeregisterCallback( ITimestampedDataSubscriber *callback );
215 
216  int GetActualUpdateRate();
218 
219  void EnableLogging(bool enable);
220  void EnableBoardlevelYawReset(bool enable);
222 
223  int16_t GetGyroFullScaleRangeDPS();
224  int16_t GetAccelFullScaleRangeG();
225 
227  void Calibrate() override;
228 
229 private:
230  void SPIInit( frc::SPI::Port spi_port_id, uint32_t bitrate, uint8_t update_rate_hz );
231  void I2CInit( frc::I2C::Port i2c_port_id, uint8_t update_rate_hz );
232  void SerialInit(frc::SerialPort::Port serial_port_id, AHRS::SerialDataType data_type, uint8_t update_rate_hz);
233  void commonInit( uint8_t update_rate_hz );
234  static int ThreadFunc(IIOProvider *io_provider);
235 
236  /* SendableBase implementation */
237  void InitSendable(wpi::SendableBuilder& builder) override;
238 
239  uint8_t GetActualUpdateRateInternal(uint8_t update_rate);
240 
241  nt::NetworkTableEntry m_valueEntry;
242 };
243 
244 #endif /* SRC_AHRS_H_ */
Class providing an "Attitude and Heading Reference System" (AHRS) interface to a navX-sensor.
Definition: AHRS.h:32
void EnableLogging(bool enable)
Enables or disables logging (via Console I/O) of AHRS library internal behaviors, including events su...
Definition: AHRS.cpp:1046
bool IsAltitudeValid()
Indicates whether the current altitude (and barometric pressure) data is valid.
Definition: AHRS.cpp:813
void UpdateDisplacement(float accel_x_g, float accel_y_g, int update_rate_hz, bool is_moving)
Each time new linear acceleration samples are received, this function should be invoked.
Definition: AHRS.cpp:958
void SetAngleAdjustment(double angle)
Sets an amount of angle to be automatically added before returning a angle from the getAngle() method...
Definition: AHRS.cpp:1298
float GetRawGyroZ()
Returns the current raw (unprocessed) Z-axis gyro rotation rate (in degrees/sec).
Definition: AHRS.cpp:1359
bool IsCalibrating()
Returns true if the sensor is currently performing automatic gyro/accelerometer calibration.
Definition: AHRS.cpp:641
double GetUpdateCount()
Returns the count of valid updates which have been received from the sensor.
Definition: AHRS.cpp:679
double GetByteCount()
Returns the count in bytes of data received from the sensor.
Definition: AHRS.cpp:669
float GetRawMagZ()
Returns the current raw (unprocessed) Z-axis magnetometer reading (in uTesla).
Definition: AHRS.cpp:1439
float GetVelocityY()
Returns the velocity (in meters/sec) of the Y axis [Experimental].
Definition: AHRS.cpp:983
SerialDataType
navX-Sensor support Serial Data types
Definition: AHRS.h:55
@ kProcessedData
(default): 6 and 9-axis processed data
Definition: AHRS.h:59
@ kRawData
unprocessed data from each individual sensor
Definition: AHRS.h:63
float GetDisplacementY()
Returns the displacement (in meters) of the Y axis since resetDisplacement() was last invoked [Experi...
Definition: AHRS.cpp:1023
float GetDisplacementZ()
Returns the displacement (in meters) of the Z axis since resetDisplacement() was last invoked [Experi...
Definition: AHRS.cpp:1037
float GetPressure()
Returns the current barometric pressure (in millibar) [navX Aero only].
Definition: AHRS.cpp:1450
float GetYaw()
Returns the current yaw value (in degrees, from -180 to 180) reported by the sensor.
Definition: AHRS.cpp:547
float GetFusedHeading()
Returns the "fused" (9-axis) heading.
Definition: AHRS.cpp:833
int GetActualUpdateRate()
Returns the navX-Model device's currently configured update rate.
Definition: AHRS.cpp:1598
bool IsMoving()
Indicates if the sensor is currently detecting motion, based upon the X and Y-axis world linear accel...
Definition: AHRS.cpp:752
float GetWorldLinearAccelZ()
Returns the current linear acceleration in the Z-axis (in G).
Definition: AHRS.cpp:739
float GetBarometricPressure()
Returns the current barometric pressure, based upon calibrated readings from the onboard pressure sen...
Definition: AHRS.cpp:781
void Calibrate() override
Gyro interface implementation.
Definition: AHRS.cpp:1629
float GetVelocityZ()
Returns the velocity (in meters/sec) of the Z axis [Experimental].
Definition: AHRS.cpp:995
float GetTempC()
Returns the current temperature (in degrees centigrade) reported by the sensor's gyro/accelerometer c...
Definition: AHRS.cpp:1465
bool DeregisterCallback(ITimestampedDataSubscriber *callback)
Deregisters a previously registered callback interface.
Definition: AHRS.cpp:1569
bool IsRotating()
Indicates if the sensor is currently detecting yaw rotation, based upon whether the change in yaw ove...
Definition: AHRS.cpp:768
bool IsConnected()
Indicates whether the sensor is currently connected to the host computer.
Definition: AHRS.cpp:655
float GetRawGyroY()
Returns the current raw (unprocessed) Y-axis gyro rotation rate (in degrees/sec).
Definition: AHRS.cpp:1347
float GetRawAccelZ()
Returns the current raw (unprocessed) Z-axis acceleration rate (in G).
Definition: AHRS.cpp:1398
float GetRoll()
Returns the current roll value (in degrees, from -180 to 180) reported by the sensor.
Definition: AHRS.cpp:533
float GetRawMagX()
Returns the current raw (unprocessed) X-axis magnetometer reading (in uTesla).
Definition: AHRS.cpp:1413
float GetRawMagY()
Returns the current raw (unprocessed) Y-axis magnetometer reading (in uTesla).
Definition: AHRS.cpp:1426
float GetPitch()
Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor.
Definition: AHRS.cpp:523
float GetQuaternionW()
Returns the imaginary portion (W) of the Orientation Quaternion which fully describes the current sen...
Definition: AHRS.cpp:882
float GetQuaternionX()
Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sen...
Definition: AHRS.cpp:897
BoardAxis
Enumeration of all board axes.
Definition: AHRS.h:36
@ kBoardAxisZ
Board Z (up/down) Axis.
Definition: AHRS.h:42
@ kBoardAxisX
Board X (left/right) Axis.
Definition: AHRS.h:38
@ kBoardAxisY
Board Y (forward/reverse) Axis.
Definition: AHRS.h:40
void EnableBoardlevelYawReset(bool enable)
Enables or disables board-level yaw zero (reset) requests.
Definition: AHRS.cpp:1066
long GetLastSensorTimestamp()
Returns the sensor timestamp corresponding to the last sample retrieved from the sensor.
Definition: AHRS.cpp:692
bool IsMagneticDisturbance()
Indicates whether the current magnetic field strength diverges from the calibrated value for the eart...
Definition: AHRS.cpp:847
float GetRawGyroX()
Returns the current raw (unprocessed) X-axis gyro rotation rate (in degrees/sec).
Definition: AHRS.cpp:1335
float GetDisplacementX()
Returns the displacement (in meters) of the X axis since resetDisplacement() was last invoked [Experi...
Definition: AHRS.cpp:1009
AHRS(frc::SPI::Port spi_port_id)
Constructs the AHRS class using SPI communication and the default update rate.
Definition: AHRS.cpp:484
float GetRawAccelX()
Returns the current raw (unprocessed) X-axis acceleration rate (in G).
Definition: AHRS.cpp:1372
void Reset() override
Reset the Yaw gyro.
Definition: AHRS.cpp:1321
int16_t GetAccelFullScaleRangeG()
Returns the sensor full scale range (in G) of the X, Y and X-axis accelerometers.
Definition: AHRS.cpp:1096
int GetRequestedUpdateRate()
Returns the currently requested update rate.
Definition: AHRS.cpp:1624
double GetRate() const override
Return the rate of rotation of the yaw (Z-axis) gyro, in degrees per second.
Definition: AHRS.cpp:1279
bool IsMagnetometerCalibrated()
Indicates whether the magnetometer has been calibrated.
Definition: AHRS.cpp:863
void ResetDisplacement()
Zeros the displacement integration variables.
Definition: AHRS.cpp:941
float GetRawAccelY()
Returns the current raw (unprocessed) Y-axis acceleration rate (in G).
Definition: AHRS.cpp:1385
float GetQuaternionY()
Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sen...
Definition: AHRS.cpp:915
AHRS::BoardYawAxis GetBoardYawAxis()
Returns information regarding which sensor board axis (X,Y or Z) and direction (up/down) is currently...
Definition: AHRS.cpp:1482
double GetAngle() const override
Returns the total accumulated yaw angle (Z Axis, in degrees) reported by the sensor.
Definition: AHRS.cpp:1267
void ZeroYaw()
Sets the user-specified yaw offset to the current yaw value reported by the sensor.
Definition: AHRS.cpp:588
double GetAngleAdjustment()
Returns the currently configured adjustment angle.
Definition: AHRS.cpp:1310
float GetWorldLinearAccelX()
Returns the current linear acceleration in the X-axis (in G).
Definition: AHRS.cpp:707
bool IsBoardlevelYawResetEnabled()
Returns true if Board-level yaw resets are enabled.
Definition: AHRS.cpp:1076
float GetWorldLinearAccelY()
Returns the current linear acceleration in the Y-axis (in G).
Definition: AHRS.cpp:723
bool RegisterCallback(ITimestampedDataSubscriber *callback, void *callback_context)
Registers a callback interface.
Definition: AHRS.cpp:1548
float GetVelocityX()
Returns the velocity (in meters/sec) of the X axis [Experimental].
Definition: AHRS.cpp:971
int16_t GetGyroFullScaleRangeDPS()
Returns the sensor full scale range (in degrees per second) of the X, Y and X-axis gyroscopes.
Definition: AHRS.cpp:1086
float GetQuaternionZ()
Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sen...
Definition: AHRS.cpp:933
float GetCompassHeading()
Returns the current tilt-compensated compass heading value (in degrees, from 0 to 360) reported by th...
Definition: AHRS.cpp:569
float GetAltitude()
Returns the current altitude, based upon calibrated readings from a barometric pressure sensor,...
Definition: AHRS.cpp:798
std::string GetFirmwareVersion()
Returns the version number of the firmware currently executing on the sensor.
Definition: AHRS.cpp:1518
Structure describing the current board orientation w/respect to the IMU axes of measurement.
Definition: AHRS.h:47
bool up
true if axis is pointing up (with respect to gravity); false if pointing down.
Definition: AHRS.h:51
BoardAxis board_axis
Identifies one of the board axes.
Definition: AHRS.h:49