Skip to main content
Firmware Version 0.2

API Reference

Firmware Version:

C / C++ API Reference

IMU.IMU()

IMU::IMU(uint32_t device_id, Interface *interface)
Description

Construct a new IMU object.

Parameters
DatatypeVariableDescription
uint32_tdevice_idDevice Id for the IMU device
Interface *interfaceCAN Interface object for the interface to which the IMU is connected

IMU.IMU()

IMU::IMU(Interface *interface)
Description

Construct a new IMU object.

Parameters
DatatypeVariableDescription
Interface *interfaceDevice Id for the IMU device

IMU.clearDCD()

ret_status_t IMU::clearDCD()
Description

Clear Dynamic Calibration Data (DCD)

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.clearTare()

ret_status_t IMU::clearTare()
Description

Clear all tare offsets.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableAccelerometer()

ret_status_t IMU::disableAccelerometer()
Description

Disable Accelerometer Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableGravity()

ret_status_t IMU::disableGravity()
Description

Disable Gravity Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableGyro()

ret_status_t IMU::disableGyro()
Description

Disable Gyroscope Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableLinearAccelerometer()

ret_status_t IMU::disableLinearAccelerometer()
Description

Disable Linear Accelerometer Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableMagnetometer()

ret_status_t IMU::disableMagnetometer()
Description

Disable Magnetometer Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableRawAccelerometer()

ret_status_t IMU::disableRawAccelerometer()
Description

Disable Raw Accelerometer Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableRawGyro()

ret_status_t IMU::disableRawGyro()
Description

Disable Raw Gyroscope Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableRawMagnetometer()

ret_status_t IMU::disableRawMagnetometer()
Description

Disable Raw Magnetometer Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableRotationVector()

ret_status_t IMU::disableRotationVector()
Description

Disable Rotation Vector Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.disableUncalibratedGyro()

ret_status_t IMU::disableUncalibratedGyro()
Description

Disable Uncalibrated Gyroscope Data.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableAccelerometer()

ret_status_t IMU::enableAccelerometer(uint16_t report_interval)
Description

Enable Accelerometer Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableGravity()

ret_status_t IMU::enableGravity(uint16_t report_interval)
Description

Enable Gravity Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableGyro()

ret_status_t IMU::enableGyro(uint16_t report_interval)
Description

Enable Gyroscope Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableLinearAccelerometer()

ret_status_t IMU::enableLinearAccelerometer(uint16_t report_interval)
Description

Enable Linear Accelerometer Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableMagnetometer()

ret_status_t IMU::enableMagnetometer(uint16_t report_interval)
Description

Enable Magnetometer Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableRawAccelerometer()

ret_status_t IMU::enableRawAccelerometer(uint16_t report_interval)
Description

Enable Raw Accelerometer Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableRawGyro()

ret_status_t IMU::enableRawGyro(uint16_t report_interval)
Description

Enable Raw Gyroscope Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableRawMagnetometer()

ret_status_t IMU::enableRawMagnetometer(uint16_t report_interval)
Description

Enable Raw Magnetometer Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableRotationVector()

ret_status_t IMU::enableRotationVector(uint16_t report_interval)
Description

Enable Rotation Vector Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enableUncalibratedGyro()

ret_status_t IMU::enableUncalibratedGyro(uint16_t report_interval)
Description

Enable Uncalibrated Gyroscope Data and configure it.

Parameters
DatatypeVariableDescription
uint16_treport_intervalReport interval in milliseconds
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.enterDFUMode()

ret_status_t IMU::enterDFUMode()
Description

Enter the Device Firmware Update (DFU) mode.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.eraseConfigurations()

ret_status_t IMU::eraseConfigurations()
Description

Erase the saved configurations from non-volatile memory.

Returns
DatatypeDescription
ret_status_tReturn 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
DatatypeVariableDescription
float *xPointer to the variable where the acceleration in x axis (m/s²) is to be stored.
float *yPointer to the variable where the acceleration in y axis (m/s²) is to be stored.
float *zPointer to the variable where the acceleration in z axis (m/s²) is to be stored.
uint8_t *accuracyPointer to the variable where the accuracy of the acceleration data is to be stored.
Returns
DatatypeDescription
ret_status_tStatus of the operation.

IMU.getCalibrationStatus()

ret_status_t IMU::getCalibrationStatus(bool *isCalibrated)
Description

Get the current calibration status.

Parameters
DatatypeVariableDescription
bool *isCalibratedPointer to the variable where calibration completion status is to be stored
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.getEulerAngles()

ret_status_t IMU::getEulerAngles(float *yaw, float *pitch, float *roll)
Description

Retrieves the Euler angles from the IMU.

Parameters
DatatypeVariableDescription
float *yawPointer to the variable where the yaw angle (degrees) is to be stored.
float *pitchPointer to the variable where the pitch angle (degrees) is to be stored.
float *rollPointer to the variable where the roll angle (degrees) is to be stored.
Returns
DatatypeDescription
ret_status_tStatus of the operation.

IMU.getFirmwareCommit()

ret_status_t IMU::getFirmwareCommit(std::string *commit)
Description

Get the firmware commit hash of the NIMU device.

Parameters
DatatypeVariableDescription
std::string *commitPointer to the string where the commit hash is to be saved
Returns
DatatypeDescription
ret_status_tReturn 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
DatatypeVariableDescription
uint8_t *majorPointer to the variable where the major version is to be saved
uint8_t *minorPointer to the variable where the minor version is to be saved
uint16_t *revisionPointer to the variable where the revision number is to be saved
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.getGravityData()

ret_status_t IMU::getGravityData(float *x, float *y, float *z)
Description

Retrieves the gravity data from the IMU.

Parameters
DatatypeVariableDescription
float *xPointer to the variable where the gravity in x axis (g) is to be stored.
float *yPointer to the variable where the gravity in y axis (g) is to be stored.
float *zPointer to the variable where the gravity in z axis (g) is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
float *xPointer to the variable where the gyro value in x axis (radians per second) is to be stored.
float *yPointer to the variable where the gyro value in y axis (radians per second) is to be stored.
float *zPointer to the variable where the gyro value in z axis (radians per second) is to be stored.
uint8_t *accuracyPointer to the variable where the accuracy of the gyro data is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
uint8_t *tagPointer to the variable where the hardware tag is to be saved
uint8_t *majorPointer to the variable where the major version is to be saved
uint8_t *minorPointer to the variable where the minor version is to be saved
uint8_t *variantPointer to the variable where the variant is to be saved
Returns
DatatypeDescription
ret_status_tReturn 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
DatatypeVariableDescription
float *xPointer to the variable where the linear acceleration in x axis (m/s²) is to be stored.
float *yPointer to the variable where the linear acceleration in y axis (m/s²) is to be stored.
float *zPointer to the variable where the linear acceleration in z axis (m/s²) is to be stored.
uint8_t *accuracyPointer to the variable where the accuracy of the linear acceleration data is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
float *xPointer to the variable where the magnetometer value in x axis (uTesla) is to be stored.
float *yPointer to the variable where the magnetometer value in y axis (uTesla) is to be stored.
float *zPointer to the variable where the magnetometer value in z axis (uTesla) is to be stored.
uint8_t *accuracyPointer to the variable where the accuracy of the magnetometer data is to be stored.
Returns
DatatypeDescription
ret_status_tStatus of the operation.

IMU.getNodeId()

ret_status_t IMU::getNodeId(uint32_t *node_id)
Description

Get current CAN Node ID of the NIMU.

Parameters
DatatypeVariableDescription
uint32_t *node_idPointer to the variable to which the current CAN Node ID of the NIMU is to be saved.
Returns
DatatypeDescription
ret_status_tReturn 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
DatatypeVariableDescription
int16_t *xPointer to the variable where the raw accelerometer value in x axis is to be stored.
int16_t *yPointer to the variable where the raw accelerometer value in y axis is to be stored.
int16_t *zPointer to the variable where the raw accelerometer value in z axis is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
int16_t *xPointer to the variable where the raw gyro value in x axis is to be stored.
int16_t *yPointer to the variable where the raw gyro value in y axis is to be stored.
int16_t *zPointer to the variable where the raw gyro value in z axis is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
int16_t *xPointer to the variable where the raw magnetometer value in x axis is to be stored.
int16_t *yPointer to the variable where the raw magnetometer value in y axis is to be stored.
int16_t *zPointer to the variable where the raw magnetometer value in z axis is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
float *quat_rad_accuracyPointer to the variable where the estimated accuracy of the quaternion in radians is to be stored.
uint8_t *quat_accuracyPointer to the variable where the estimated accuracy of the quaternion is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
float *quat_iPointer to the variable where the i component of the quaternion is to be stored.
float *quat_jPointer to the variable where the j component of the quaternion is to be stored.
float *quat_kPointer to the variable where the k component of the quaternion is to be stored.
float *quat_realPointer to the variable where the real component of the quaternion is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
float *xPointer to the variable where the uncalibrated gyro bias in x axis (radians per second) is to be stored.
float *yPointer to the variable where the uncalibrated gyro bias in y axis (radians per second) is to be stored.
float *zPointer to the variable where the uncalibrated gyro bias in z axis (radians per second) is to be stored.
Returns
DatatypeDescription
ret_status_tStatus 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
DatatypeVariableDescription
float *xPointer to the variable where the uncalibrated gyro value in x axis (radians per second) is to be stored.
float *yPointer to the variable where the uncalibrated gyro value in y axis (radians per second) is to be stored.
float *zPointer to the variable where the uncalibrated gyro value in z axis (radians per second) is to be stored.
Returns
DatatypeDescription
ret_status_tStatus of the operation.

IMU.isConnected()

bool IMU::isConnected()
Description

Check if the device is still connected or not.

Returns
DatatypeDescription
booltrue

IMU.rebootNIMU()

ret_status_t IMU::rebootNIMU()
Description

Reboot the NIMU device.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.saveCalibration()

ret_status_t IMU::saveCalibration()
Description

Save calibration data to non-volatile memory.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.saveConfigurations()

ret_status_t IMU::saveConfigurations()
Description

Save the current configurations to non-volatile memory.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.setNodeId()

ret_status_t IMU::setNodeId(uint32_t id)
Description

Set the node id for the NIMU.

Parameters
DatatypeVariableDescription
uint32_tidCAN Node ID of the NIMU
Returns
DatatypeDescription
ret_status_tReturn 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
DatatypeVariableDescription
floatiThe i component of the quaternion
floatjThe j component of the quaternion
floatkThe k component of the quaternion
floatrealThe real component of the quaternion
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.setOutputLogStream()

void IMU::setOutputLogStream(std::ostream *out)
Description

Set the Output Log Stream object.

Parameters
DatatypeVariableDescription
std::ostream *outOutput 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
DatatypeVariableDescription
boolaccelEnable accelerometer calibration
boolgyroEnable gyroscope calibration
boolmagEnable magnetometer calibration
boolplanarAccelEnable planar accelerometer calibration
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.stopCalibration()

ret_status_t IMU::stopCalibration()
Description

Stop the ongoing calibration process.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.tareAll()

ret_status_t IMU::tareAll()
Description

Apply tare to all axes of the IMU.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.tareYaw()

ret_status_t IMU::tareYaw()
Description

Apply tare to the Z-axis.

Returns
DatatypeDescription
ret_status_tReturn Status

IMU.~IMU()

IMU::~IMU()
Description

Destroy the IMU object.

Python API Reference

IMU.__init__()

__init__(id: int = -1, interface: USBInterface = None) 
Description

IMU class constructor.

Parameters
DatatypeVariableDescription
intidCAN Node ID of the IMU device
USBInterfaceinterfaceInitialised CANInterface or USBInterface object

IMU.clearDCD()

clearDCD() -> int
Description

Clear Dynamic Calibration Data (DCD)

Returns
DatatypeDescription
intReturn status

IMU.clearTare()

clearTare() -> int
Description

Clear all tare offsets.

Returns
DatatypeDescription
intReturn status

IMU.disableAccelerometer()

disableAccelerometer() -> int
Description

Disable accelerometer data.

Returns
DatatypeDescription
intReturn status

IMU.disableGravity()

disableGravity() -> int
Description

Disable gravity data.

Returns
DatatypeDescription
intReturn status

IMU.disableGyro()

disableGyro() -> int
Description

Disable gyroscope data.

Returns
DatatypeDescription
intReturn status

IMU.disableLinearAccelerometer()

disableLinearAccelerometer() -> int
Description

Disable linear accelerometer data.

Returns
DatatypeDescription
intReturn status

IMU.disableMagnetometer()

disableMagnetometer() -> int
Description

Disable magnetometer data.

Returns
DatatypeDescription
intReturn status

IMU.disableRawAccelerometer()

disableRawAccelerometer() -> int
Description

Disable raw accelerometer data.

Returns
DatatypeDescription
intReturn status

IMU.disableRawGyro()

disableRawGyro() -> int
Description

Disable raw gyroscope data.

Returns
DatatypeDescription
intReturn status

IMU.disableRawMagnetometer()

disableRawMagnetometer() -> int
Description

Disable raw magnetometer data.

Returns
DatatypeDescription
intReturn status

IMU.disableRotationVector()

disableRotationVector() -> int
Description

Disable rotation vector data.

Returns
DatatypeDescription
intReturn status

IMU.disableUncalibratedGyro()

disableUncalibratedGyro() -> int
Description

Disable uncalibrated gyroscope data.

Returns
DatatypeDescription
intReturn status

IMU.enableAccelerometer()

enableAccelerometer(time_interval: int) -> int
Description

Enable accelerometer data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableGravity()

enableGravity(time_interval: int) -> int
Description

Enable gravity data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableGyro()

enableGyro(time_interval: int) -> int
Description

Enable gyroscope data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableLinearAccelerometer()

enableLinearAccelerometer(time_interval: int) -> int
Description

Enable linear accelerometer data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableMagnetometer()

enableMagnetometer(time_interval: int) -> int
Description

Enable magnetometer data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableRawAccelerometer()

enableRawAccelerometer(time_interval: int) -> int
Description

Enable raw accelerometer data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableRawGyro()

enableRawGyro(time_interval: int) -> int
Description

Enable raw gyroscope data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableRawMagnetometer()

enableRawMagnetometer(time_interval: int) -> int
Description

Enable raw magnetometer data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableRotationVector()

enableRotationVector(time_interval: int) -> int
Description

Enable rotation vector data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enableUncalibratedGyro()

enableUncalibratedGyro(time_interval: int) -> int
Description

Enable uncalibrated gyroscope data and configure it.

Parameters
DatatypeVariableDescription
inttime_intervalinterval in milliseconds
Returns
DatatypeDescription
intReturn status

IMU.enterDFUMode()

enterDFUMode() -> int
Description

Enter Device Firmware Update Mode.

Returns
DatatypeDescription
intReturn Status.

IMU.eraseConfigurations()

eraseConfigurations() -> int
Description

Erase the saved configurations from non-volatile memory.

Returns
DatatypeDescription
intReturn status

IMU.getAccelerometerData()

getAccelerometerData() ->  'tuple[float, float, float, int]'
Description

Retrieve the accelerometer data from the IMU.

Returns
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'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
DatatypeDescription
'tuple[float,float,float]'Tuple containing uncalibrated gyro values (x, y, z) in radians per second

IMU.rebootNIMU()

rebootNIMU() -> int
Description

Reboot the NIMU device.

Returns
DatatypeDescription
intReturn Status.

IMU.saveCalibration()

saveCalibration() -> int
Description

Save calibration data to non-volatile memory.

Returns
DatatypeDescription
intReturn status

IMU.saveConfigurations()

saveConfigurations() -> int
Description

Save the current configurations to non-volatile memory.

Returns
DatatypeDescription
intReturn status

IMU.setNodeId()

setNodeId(id: int) -> int
Description

Set the node id for the NIMU.

Parameters
DatatypeVariableDescription
intidDevice ID of the NIMU
Returns
DatatypeDescription
intReturn Status

IMU.setOrientation()

setOrientation(i: float, j: float, k: float, real: float) -> int
Description

Set the sensor orientation using a quaternion.

Parameters
DatatypeVariableDescription
floatiThe i component of the quaternion
floatjThe j component of the quaternion
floatkThe k component of the quaternion
floatrealThe real component of the quaternion
Returns
DatatypeDescription
intReturn status

IMU.startCalibration()

startCalibration(accel: bool, gyro: bool, mag: bool, planarAccel: bool) -> int
Description

Start calibration process and configure it.

Parameters
DatatypeVariableDescription
boolaccelEnable accelerometer calibration
boolgyroEnable gyroscope calibration
boolmagEnable magnetometer calibration
boolplanarAccelEnable planar accelerometer calibration
Returns
DatatypeDescription
intReturn status

IMU.stopCalibration()

stopCalibration() -> int
Description

Stop the ongoing calibration process.

Returns
DatatypeDescription
intReturn status

IMU.tareAll()

tareAll() -> int
Description

Apply tare to all axes of the IMU.

Returns
DatatypeDescription
intReturn status

IMU.tareYaw()

tareYaw() -> int
Description

Apply tare to the Z-axis (yaw)

Returns
DatatypeDescription
intReturn status
  NMotionTM  is a sub-brand of Nawe Robotics
Copyright © 2025 Nawe Robotics Private Limited