C / C++ API Reference
IMU.IMU()
IMU::IMU(uint32_t device_id, Interface *interface)
Description
Construct a new IMU object.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t | device_id | Device Id for the IMU device |
Interface * | interface | CAN Interface object for the interface to which the IMU is connected |
IMU.IMU()
IMU::IMU(Interface *interface)
Description
Construct a new IMU object.
Parameters
| Datatype | Variable | Description |
|---|
Interface * | interface | Device Id for the IMU device |
IMU.clearDCD()
ret_status_t IMU::clearDCD()
Description
Clear Dynamic Calibration Data (DCD)
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.clearTare()
ret_status_t IMU::clearTare()
Description
Clear all tare offsets.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableAccelerometer()
ret_status_t IMU::disableAccelerometer()
Description
Disable Accelerometer Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableGravity()
ret_status_t IMU::disableGravity()
Description
Disable Gravity Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableGyro()
ret_status_t IMU::disableGyro()
Description
Disable Gyroscope Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableLinearAccelerometer()
ret_status_t IMU::disableLinearAccelerometer()
Description
Disable Linear Accelerometer Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableMagnetometer()
ret_status_t IMU::disableMagnetometer()
Description
Disable Magnetometer Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableRawAccelerometer()
ret_status_t IMU::disableRawAccelerometer()
Description
Disable Raw Accelerometer Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableRawGyro()
ret_status_t IMU::disableRawGyro()
Description
Disable Raw Gyroscope Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableRawMagnetometer()
ret_status_t IMU::disableRawMagnetometer()
Description
Disable Raw Magnetometer Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableRotationVector()
ret_status_t IMU::disableRotationVector()
Description
Disable Rotation Vector Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.disableUncalibratedGyro()
ret_status_t IMU::disableUncalibratedGyro()
Description
Disable Uncalibrated Gyroscope Data.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableAccelerometer()
ret_status_t IMU::enableAccelerometer(uint16_t report_interval)
Description
Enable Accelerometer Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableGravity()
ret_status_t IMU::enableGravity(uint16_t report_interval)
Description
Enable Gravity Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableGyro()
ret_status_t IMU::enableGyro(uint16_t report_interval)
Description
Enable Gyroscope Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableLinearAccelerometer()
ret_status_t IMU::enableLinearAccelerometer(uint16_t report_interval)
Description
Enable Linear Accelerometer Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableMagnetometer()
ret_status_t IMU::enableMagnetometer(uint16_t report_interval)
Description
Enable Magnetometer Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableRawAccelerometer()
ret_status_t IMU::enableRawAccelerometer(uint16_t report_interval)
Description
Enable Raw Accelerometer Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableRawGyro()
ret_status_t IMU::enableRawGyro(uint16_t report_interval)
Description
Enable Raw Gyroscope Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableRawMagnetometer()
ret_status_t IMU::enableRawMagnetometer(uint16_t report_interval)
Description
Enable Raw Magnetometer Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableRotationVector()
ret_status_t IMU::enableRotationVector(uint16_t report_interval)
Description
Enable Rotation Vector Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enableUncalibratedGyro()
ret_status_t IMU::enableUncalibratedGyro(uint16_t report_interval)
Description
Enable Uncalibrated Gyroscope Data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
uint16_t | report_interval | Report interval in milliseconds |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.enterDFUMode()
ret_status_t IMU::enterDFUMode()
Description
Enter the Device Firmware Update (DFU) mode.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.eraseConfigurations()
ret_status_t IMU::eraseConfigurations()
Description
Erase the saved configurations from non-volatile memory.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.getAccelerometerData()
ret_status_t IMU::getAccelerometerData(float *x, float *y, float *z, uint8_t *accuracy)
Description
Retrieves the accelerometer data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the acceleration in x axis (m/s²) is to be stored. |
float * | y | Pointer to the variable where the acceleration in y axis (m/s²) is to be stored. |
float * | z | Pointer to the variable where the acceleration in z axis (m/s²) is to be stored. |
uint8_t * | accuracy | Pointer to the variable where the accuracy of the acceleration data is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getCalibrationStatus()
ret_status_t IMU::getCalibrationStatus(bool *isCalibrated)
Description
Get the current calibration status.
Parameters
| Datatype | Variable | Description |
|---|
bool * | isCalibrated | Pointer to the variable where calibration completion status is to be stored |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.getEulerAngles()
ret_status_t IMU::getEulerAngles(float *yaw, float *pitch, float *roll)
Description
Retrieves the Euler angles from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | yaw | Pointer to the variable where the yaw angle (degrees) is to be stored. |
float * | pitch | Pointer to the variable where the pitch angle (degrees) is to be stored. |
float * | roll | Pointer to the variable where the roll angle (degrees) is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getFirmwareCommit()
ret_status_t IMU::getFirmwareCommit(std::string *commit)
Description
Get the firmware commit hash of the NIMU device.
Parameters
| Datatype | Variable | Description |
|---|
std::string * | commit | Pointer to the string where the commit hash is to be saved |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.getFirmwareVersion()
ret_status_t IMU::getFirmwareVersion(uint8_t *major, uint8_t *minor, uint16_t *revision)
Description
Get the firmware version of the NIMU device.
Parameters
| Datatype | Variable | Description |
|---|
uint8_t * | major | Pointer to the variable where the major version is to be saved |
uint8_t * | minor | Pointer to the variable where the minor version is to be saved |
uint16_t * | revision | Pointer to the variable where the revision number is to be saved |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.getGravityData()
ret_status_t IMU::getGravityData(float *x, float *y, float *z)
Description
Retrieves the gravity data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the gravity in x axis (g) is to be stored. |
float * | y | Pointer to the variable where the gravity in y axis (g) is to be stored. |
float * | z | Pointer to the variable where the gravity in z axis (g) is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getGyroData()
ret_status_t IMU::getGyroData(float *x, float *y, float *z, uint8_t *accuracy)
Description
Retrieves the gyroscope data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the gyro value in x axis (radians per second) is to be stored. |
float * | y | Pointer to the variable where the gyro value in y axis (radians per second) is to be stored. |
float * | z | Pointer to the variable where the gyro value in z axis (radians per second) is to be stored. |
uint8_t * | accuracy | Pointer to the variable where the accuracy of the gyro data is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getHardwareVersion()
ret_status_t IMU::getHardwareVersion(uint8_t *tag, uint8_t *major, uint8_t *minor, uint8_t *variant)
Description
Get the hardware version of the NIMU device.
Parameters
| Datatype | Variable | Description |
|---|
uint8_t * | tag | Pointer to the variable where the hardware tag is to be saved |
uint8_t * | major | Pointer to the variable where the major version is to be saved |
uint8_t * | minor | Pointer to the variable where the minor version is to be saved |
uint8_t * | variant | Pointer to the variable where the variant is to be saved |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.getLinearAccelerometerData()
ret_status_t IMU::getLinearAccelerometerData(float *x, float *y, float *z, uint8_t *accuracy)
Description
Retrieves the linear accelerometer data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the linear acceleration in x axis (m/s²) is to be stored. |
float * | y | Pointer to the variable where the linear acceleration in y axis (m/s²) is to be stored. |
float * | z | Pointer to the variable where the linear acceleration in z axis (m/s²) is to be stored. |
uint8_t * | accuracy | Pointer to the variable where the accuracy of the linear acceleration data is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getMagnetometerData()
ret_status_t IMU::getMagnetometerData(float *x, float *y, float *z, uint8_t *accuracy)
Description
Retrieves the magnetometer data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the magnetometer value in x axis (uTesla) is to be stored. |
float * | y | Pointer to the variable where the magnetometer value in y axis (uTesla) is to be stored. |
float * | z | Pointer to the variable where the magnetometer value in z axis (uTesla) is to be stored. |
uint8_t * | accuracy | Pointer to the variable where the accuracy of the magnetometer data is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getNodeId()
ret_status_t IMU::getNodeId(uint32_t *node_id)
Description
Get current CAN Node ID of the NIMU.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t * | node_id | Pointer to the variable to which the current CAN Node ID of the NIMU is to be saved. |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.getRawAccelerometerData()
ret_status_t IMU::getRawAccelerometerData(int16_t *x, int16_t *y, int16_t *z)
Description
Retrieves the raw accelerometer data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
int16_t * | x | Pointer to the variable where the raw accelerometer value in x axis is to be stored. |
int16_t * | y | Pointer to the variable where the raw accelerometer value in y axis is to be stored. |
int16_t * | z | Pointer to the variable where the raw accelerometer value in z axis is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getRawGyroData()
ret_status_t IMU::getRawGyroData(int16_t *x, int16_t *y, int16_t *z)
Description
Retrieves the raw gyroscope data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
int16_t * | x | Pointer to the variable where the raw gyro value in x axis is to be stored. |
int16_t * | y | Pointer to the variable where the raw gyro value in y axis is to be stored. |
int16_t * | z | Pointer to the variable where the raw gyro value in z axis is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getRawMagnetometerData()
ret_status_t IMU::getRawMagnetometerData(int16_t *x, int16_t *y, int16_t *z)
Description
Retrieves the raw magnetometer data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
int16_t * | x | Pointer to the variable where the raw magnetometer value in x axis is to be stored. |
int16_t * | y | Pointer to the variable where the raw magnetometer value in y axis is to be stored. |
int16_t * | z | Pointer to the variable where the raw magnetometer value in z axis is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getRotationVectorAccuracy()
ret_status_t IMU::getRotationVectorAccuracy(float *quat_rad_accuracy, uint8_t *quat_accuracy)
Description
Retrieves the rotation vector accuracy data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | quat_rad_accuracy | Pointer to the variable where the estimated accuracy of the quaternion in radians is to be stored. |
uint8_t * | quat_accuracy | Pointer to the variable where the estimated accuracy of the quaternion is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getRotationVectorData()
ret_status_t IMU::getRotationVectorData(float *quat_i, float *quat_j, float *quat_k, float *quat_real)
Description
Retrieves the rotation vector data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | quat_i | Pointer to the variable where the i component of the quaternion is to be stored. |
float * | quat_j | Pointer to the variable where the j component of the quaternion is to be stored. |
float * | quat_k | Pointer to the variable where the k component of the quaternion is to be stored. |
float * | quat_real | Pointer to the variable where the real component of the quaternion is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getUncalibratedGyroBiasData()
ret_status_t IMU::getUncalibratedGyroBiasData(float *x, float *y, float *z)
Description
Retrieves the uncalibrated gyroscope bias data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the uncalibrated gyro bias in x axis (radians per second) is to be stored. |
float * | y | Pointer to the variable where the uncalibrated gyro bias in y axis (radians per second) is to be stored. |
float * | z | Pointer to the variable where the uncalibrated gyro bias in z axis (radians per second) is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.getUncalibratedGyroData()
ret_status_t IMU::getUncalibratedGyroData(float *x, float *y, float *z)
Description
Retrieves the uncalibrated gyroscope data from the IMU.
Parameters
| Datatype | Variable | Description |
|---|
float * | x | Pointer to the variable where the uncalibrated gyro value in x axis (radians per second) is to be stored. |
float * | y | Pointer to the variable where the uncalibrated gyro value in y axis (radians per second) is to be stored. |
float * | z | Pointer to the variable where the uncalibrated gyro value in z axis (radians per second) is to be stored. |
Returns
| Datatype | Description |
|---|
ret_status_t | Status of the operation. |
IMU.isConnected()
Description
Check if the device is still connected or not.
Returns
| Datatype | Description |
|---|
bool | true |
IMU.rebootNIMU()
ret_status_t IMU::rebootNIMU()
Description
Reboot the NIMU device.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.saveCalibration()
ret_status_t IMU::saveCalibration()
Description
Save calibration data to non-volatile memory.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.saveConfigurations()
ret_status_t IMU::saveConfigurations()
Description
Save the current configurations to non-volatile memory.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.setNodeId()
ret_status_t IMU::setNodeId(uint32_t id)
Description
Set the node id for the NIMU.
Parameters
| Datatype | Variable | Description |
|---|
uint32_t | id | CAN Node ID of the NIMU |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.setOrientation()
ret_status_t IMU::setOrientation(float i, float j, float k, float real)
Description
Set the sensor orientation using a quaternion.
Parameters
| Datatype | Variable | Description |
|---|
float | i | The i component of the quaternion |
float | j | The j component of the quaternion |
float | k | The k component of the quaternion |
float | real | The real component of the quaternion |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.setOutputLogStream()
void IMU::setOutputLogStream(std::ostream *out)
Description
Set the Output Log Stream object.
Parameters
| Datatype | Variable | Description |
|---|
std::ostream * | out | Output log stream object |
IMU.startCalibration()
ret_status_t IMU::startCalibration(bool accel, bool gyro, bool mag, bool planarAccel)
Description
Start calibration and configure it.
Parameters
| Datatype | Variable | Description |
|---|
bool | accel | Enable accelerometer calibration |
bool | gyro | Enable gyroscope calibration |
bool | mag | Enable magnetometer calibration |
bool | planarAccel | Enable planar accelerometer calibration |
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.stopCalibration()
ret_status_t IMU::stopCalibration()
Description
Stop the ongoing calibration process.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.tareAll()
ret_status_t IMU::tareAll()
Description
Apply tare to all axes of the IMU.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.tareYaw()
ret_status_t IMU::tareYaw()
Description
Apply tare to the Z-axis.
Returns
| Datatype | Description |
|---|
ret_status_t | Return Status |
IMU.~IMU()
Description
Destroy the IMU object.
Python API Reference
IMU.__init__()
__init__(id: int = -1, interface: USBInterface = None)
Description
IMU class constructor.
Parameters
| Datatype | Variable | Description |
|---|
int | id | CAN Node ID of the IMU device |
USBInterface | interface | Initialised CANInterface or USBInterface object |
IMU.clearDCD()
Description
Clear Dynamic Calibration Data (DCD)
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.clearTare()
Description
Clear all tare offsets.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableAccelerometer()
disableAccelerometer() -> int
Description
Disable accelerometer data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableGravity()
Description
Disable gravity data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableGyro()
Description
Disable gyroscope data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableLinearAccelerometer()
disableLinearAccelerometer() -> int
Description
Disable linear accelerometer data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableMagnetometer()
disableMagnetometer() -> int
Description
Disable magnetometer data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableRawAccelerometer()
disableRawAccelerometer() -> int
Description
Disable raw accelerometer data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableRawGyro()
Description
Disable raw gyroscope data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableRawMagnetometer()
disableRawMagnetometer() -> int
Description
Disable raw magnetometer data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableRotationVector()
disableRotationVector() -> int
Description
Disable rotation vector data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.disableUncalibratedGyro()
disableUncalibratedGyro() -> int
Description
Disable uncalibrated gyroscope data.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableAccelerometer()
enableAccelerometer(time_interval: int) -> int
Description
Enable accelerometer data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableGravity()
enableGravity(time_interval: int) -> int
Description
Enable gravity data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableGyro()
enableGyro(time_interval: int) -> int
Description
Enable gyroscope data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableLinearAccelerometer()
enableLinearAccelerometer(time_interval: int) -> int
Description
Enable linear accelerometer data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableMagnetometer()
enableMagnetometer(time_interval: int) -> int
Description
Enable magnetometer data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableRawAccelerometer()
enableRawAccelerometer(time_interval: int) -> int
Description
Enable raw accelerometer data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableRawGyro()
enableRawGyro(time_interval: int) -> int
Description
Enable raw gyroscope data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableRawMagnetometer()
enableRawMagnetometer(time_interval: int) -> int
Description
Enable raw magnetometer data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableRotationVector()
enableRotationVector(time_interval: int) -> int
Description
Enable rotation vector data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enableUncalibratedGyro()
enableUncalibratedGyro(time_interval: int) -> int
Description
Enable uncalibrated gyroscope data and configure it.
Parameters
| Datatype | Variable | Description |
|---|
int | time_interval | interval in milliseconds |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.enterDFUMode()
Description
Enter Device Firmware Update Mode.
Returns
| Datatype | Description |
|---|
int | Return Status. |
IMU.eraseConfigurations()
eraseConfigurations() -> int
Description
Erase the saved configurations from non-volatile memory.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.getAccelerometerData()
getAccelerometerData() -> 'tuple[float, float, float, int]'
Description
Retrieve the accelerometer data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float,int]' | Tuple containing acceleration values (x, y, z) in m/s² and accuracy |
IMU.getCalibrationStatus()
getCalibrationStatus() -> 'tuple[int, bool]'
Description
Get the current calibration status.
Returns
| Datatype | Description |
|---|
'tuple[int,bool]' | Tuple containing return status and calibration completion status |
IMU.getEulerAngles()
getEulerAngles() -> 'tuple[float, float, float]'
Description
Retrieve the Euler angles from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float]' | Tuple containing Euler angles (yaw, pitch, roll) in degrees |
IMU.getFirmwareCommit()
getFirmwareCommit() -> 'tuple[int, str]'
Description
Get the IMU firmware's commit hash.
Returns
| Datatype | Description |
|---|
'tuple[int,str]' | Tuple containing return status and the commit hash string. |
IMU.getFirmwareVersion()
getFirmwareVersion() -> 'tuple[int, int, int, int]'
Description
Get the IMU firmware's major, minor and revision information.
Returns
| Datatype | Description |
|---|
'tuple[int,int,int,int]' | Tuple containing return status, major, minor and revision information. |
IMU.getGravityData()
getGravityData() -> 'tuple[float, float, float]'
Description
Retrieve the gravity data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float]' | Tuple containing gravity values (x, y, z) in g |
IMU.getGyroData()
getGyroData() -> 'tuple[float, float, float, int]'
Description
Retrieve the gyroscope data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float,int]' | Tuple containing gyro values (x, y, z) in radians per second and accuracy |
IMU.getHardwareVersion()
getHardwareVersion() -> 'tuple[int, int, int, int, int]'
Description
Get the IMU hardware's current tag, major, minor and variant information.
Returns
| Datatype | Description |
|---|
'tuple[int,int,int,int,int]' | Tuple containing return status, tag, major, minor and variant information. |
IMU.getLinearAccelerometerData()
getLinearAccelerometerData() -> 'tuple[float, float, float, int]'
Description
Retrieve the linear accelerometer data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float,int]' | Tuple containing linear acceleration values (x, y, z) in m/s² and accuracy |
IMU.getMagnetometerData()
getMagnetometerData() -> 'tuple[float, float, float, int]'
Description
Retrieve the magnetometer data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float,int]' | Tuple containing magnetometer values (x, y, z) in uTesla and accuracy |
IMU.getNodeId()
getNodeId() -> 'tuple[int, int]'
Description
Get current Node ID of the NIMU.
Returns
| Datatype | Description |
|---|
'tuple[int,int]' | Tuple containing return status and the current Node ID. |
IMU.getRawAccelerometerData()
getRawAccelerometerData() -> 'tuple[int, int, int]'
Description
Retrieve the raw accelerometer data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[int,int,int]' | Tuple containing raw accelerometer values (x, y, z) |
IMU.getRawGyroData()
getRawGyroData() -> 'tuple[int, int, int]'
Description
Retrieve the raw gyroscope data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[int,int,int]' | Tuple containing raw gyro values (x, y, z) |
IMU.getRawMagnetometerData()
getRawMagnetometerData() -> 'tuple[int, int, int]'
Description
Retrieve the raw magnetometer data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[int,int,int]' | Tuple containing raw magnetometer values (x, y, z) |
IMU.getRotationVectorAccuracy()
getRotationVectorAccuracy() -> 'tuple[float, int]'
Description
Retrieve the rotation vector accuracy data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,int]' | Tuple containing (quat_rad_accuracy, quat_accuracy) rotation vector accuracy |
IMU.getRotationVectorData()
getRotationVectorData() -> 'tuple[float, float, float, float]'
Description
Retrieve the rotation vector data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float,float]' | Tuple containing (quat_i, quat_j, quat_k, quat_real) quaternion components |
IMU.getUncalibratedGyroBiasData()
getUncalibratedGyroBiasData() -> 'tuple[float, float, float]'
Description
Retrieve the uncalibrated gyroscope bias data from the IMU getEncoderRawData.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float]' | Tuple containing uncalibrated gyro bias values (x, y, z) in radians per second |
IMU.getUncalibratedGyroData()
getUncalibratedGyroData() -> 'tuple[float, float, float]'
Description
Retrieve the uncalibrated gyroscope data from the IMU.
Returns
| Datatype | Description |
|---|
'tuple[float,float,float]' | Tuple containing uncalibrated gyro values (x, y, z) in radians per second |
IMU.rebootNIMU()
Description
Reboot the NIMU device.
Returns
| Datatype | Description |
|---|
int | Return Status. |
IMU.saveCalibration()
Description
Save calibration data to non-volatile memory.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.saveConfigurations()
saveConfigurations() -> int
Description
Save the current configurations to non-volatile memory.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.setNodeId()
setNodeId(id: int) -> int
Description
Set the node id for the NIMU.
Parameters
| Datatype | Variable | Description |
|---|
int | id | Device ID of the NIMU |
Returns
| Datatype | Description |
|---|
int | Return Status |
IMU.setOrientation()
setOrientation(i: float, j: float, k: float, real: float) -> int
Description
Set the sensor orientation using a quaternion.
Parameters
| Datatype | Variable | Description |
|---|
float | i | The i component of the quaternion |
float | j | The j component of the quaternion |
float | k | The k component of the quaternion |
float | real | The real component of the quaternion |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.startCalibration()
startCalibration(accel: bool, gyro: bool, mag: bool, planarAccel: bool) -> int
Description
Start calibration process and configure it.
Parameters
| Datatype | Variable | Description |
|---|
bool | accel | Enable accelerometer calibration |
bool | gyro | Enable gyroscope calibration |
bool | mag | Enable magnetometer calibration |
bool | planarAccel | Enable planar accelerometer calibration |
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.stopCalibration()
Description
Stop the ongoing calibration process.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.tareAll()
Description
Apply tare to all axes of the IMU.
Returns
| Datatype | Description |
|---|
int | Return status |
IMU.tareYaw()
Description
Apply tare to the Z-axis (yaw)
Returns
| Datatype | Description |
|---|
int | Return status |