Class ImuInterface
Defined in File imu_interface.hpp
Inheritance Relationships
Derived Types
public tap::communication::sensors::imu::bmi088::final_mockable
(Class final_mockable)public tap::communication::sensors::imu::mpu6500::final_mockable
(Class final_mockable)
Class Documentation
-
class ImuInterface
An interface for interacting with a 6 axis IMU.
Subclassed by tap::communication::sensors::imu::bmi088::final_mockable, tap::communication::sensors::imu::mpu6500::final_mockable
Public Types
-
enum class ImuState
Possible IMU states for an IMU.
Values:
-
enumerator IMU_NOT_CONNECTED
Indicates the IMU’s init function was not called or initialization failed, so data from this class will be undefined.
-
enumerator IMU_NOT_CALIBRATED
Indicates the IMU is connected and reading data, but calibration offsets have not been computed.
-
enumerator IMU_CALIBRATING
Indicates the IMU is in the process of computing calibration offsets. Data read when the IMU is in this state is undefined.
-
enumerator IMU_CALIBRATED
Indicates the IMU is connected and calibration offsets have been computed.
-
enumerator IMU_NOT_CONNECTED
Public Functions
-
inline virtual const char *getName() const = 0
-
inline virtual float getAx() = 0
Returns the linear acceleration in the x direction, in \(\frac{\mbox{m}}{\mbox{second}^2}\).
-
inline virtual float getAy() = 0
Returns the linear acceleration in the y direction, in \(\frac{\mbox{m}}{\mbox{second}^2}\).
-
inline virtual float getAz() = 0
Returns the linear acceleration in the z direction, in \(\frac{\mbox{m}}{\mbox{second}^2}\).
-
inline virtual float getGx() = 0
Returns the gyroscope reading (rotational speed) in the x direction, in \(\frac{\mbox{degrees}}{\mbox{second}}\).
-
inline virtual float getGy() = 0
Returns the gyroscope reading (rotational speed) in the y direction, in \(\frac{\mbox{degrees}}{\mbox{second}}\).
-
inline virtual float getGz() = 0
Returns the gyroscope reading (rotational speed) in the z direction, in \(\frac{\mbox{degrees}}{\mbox{second}}\).
-
inline virtual float getTemp() = 0
Returns the temperature of the imu in degrees C.
-
inline virtual float getYaw() = 0
Returns yaw angle. in degrees.
-
inline virtual float getPitch() = 0
Returns pitch angle in degrees.
-
inline virtual float getRoll() = 0
Returns roll angle in degrees.
-
enum class ImuState