Skip to main content
Firmware Version 0.1

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 connected to the IMU

IMU.getNodeId()

ret_status_t IMU::getNodeId(uint32_t *node_id)
Description

Get current CAN Node ID of 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.setNodeId()

ret_status_t IMU::setNodeId(uint32_t id)
Description

Set the node id for the IMU.

Parameters
DatatypeVariableDescription
uint32_tidCAN Node ID of the IMU
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.disableRotationVector()

ret_status_t IMU::disableRotationVector()
Description

Disable rotation vector data.

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.disableRawAccelerometer()

ret_status_t IMU::disableRawAccelerometer()
Description

Disable raw accelerometer data.

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.disableRawGyro()

ret_status_t IMU::disableRawGyro()
Description

Disable raw gyroscope data.

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.disableRawMagnetometer()

ret_status_t IMU::disableRawMagnetometer()
Description

Disable raw magnetometer data.

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.disableLinearAccelerometer()

ret_status_t IMU::disableLinearAccelerometer()
Description

Disable linear accelerometer 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.disableAccelerometer()

ret_status_t IMU::disableAccelerometer()
Description

Disable accelerometer data.

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.disableGyro()

ret_status_t IMU::disableGyro()
Description

Disable gyroscope data.

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.disableMagnetometer()

ret_status_t IMU::disableMagnetometer()
Description

Disable magnetometer data.

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.disableUncalibratedGyro()

ret_status_t IMU::disableUncalibratedGyro()
Description

Disable uncalibrated gyroscope data.

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.disableGravity()

ret_status_t IMU::disableGravity()
Description

Disable gravity data.

Returns
DatatypeDescription
ret_status_tReturn Status

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_ii component of the quaternion
float*quat_jj component of the quaternion
float*quat_kk component of the quaternion
float*quat_realreal component of the quaternion
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*xraw accelerometer value in x axis
int16_t*yraw accelerometer value in y axis
int16_t*zraw accelerometer value in z axis
Returns
DatatypeDescription
ret_status_tReturn Status

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*xraw gyro value in x axis
int16_t*yraw gyro value in y axis
int16_t*zraw gyro value in z axis
Returns
DatatypeDescription
ret_status_tReturn Status

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*xraw magnetometer value in x axis
int16_t*yraw magnetometer value in y axis
int16_t*zraw magnetometer value in z axis
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*xlinear acceleration in x axis (m/s²)
float*ylinear acceleration in y axis (m/s²)
float*zlinear acceleration in z axis (m/s²)
uint8_t*accuracyaccuracy of the linear acceleration data
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*xacceleration in x axis (m/s²)
float*yacceleration in y axis (m/s²)
float*zacceleration in z axis (m/s²)
uint8_t*accuracyaccuracy of the acceleration data
Returns
DatatypeDescription
ret_status_tReturn Status

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*xgyro value in x axis (radians per second)
float*ygyro value in y axis (radians per second)
float*zgyro value in z axis (radians per second)
uint8_t*accuracyaccuracy of the gyro data
Returns
DatatypeDescription
ret_status_tReturn Status

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*xmagnetometer value in x axis (uTesla)
float*ymagnetometer value in y axis (uTesla)
float*zmagnetometer value in z axis (uTesla)
uint8_t*accuracyaccuracy of the magnetometer data
Returns
DatatypeDescription
ret_status_tReturn Status

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*xuncalibrated gyro value in x axis (radians per second)
float*yuncalibrated gyro value in y axis (radians per second)
float*zuncalibrated gyro value in z axis (radians per second)
Returns
DatatypeDescription
ret_status_tReturn Status

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*xuncalibrated gyro bias in x axis (radians per second)
float*yuncalibrated gyro bias in y axis (radians per second)
float*zuncalibrated gyro bias in z axis (radians per second)
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*yawyaw angle (degrees)
float*pitchpitch angle (degrees)
float*rollroll angle (degrees)
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*xgravity in x axis (g)
float*ygravity in y axis (g)
float*zgravity in z axis (g)
Returns
DatatypeDescription
ret_status_tReturn Status

IMU.isConnected()

bool IMU::isConnected()
Description

Check if the device is still connected.

Returns
DatatypeDescription
booltrue if connected, false otherwise

Python API Reference

IMU.__init__()

__init__(id: int, interface: USBInterface) 
Description

IMU class constructor.

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

IMU.getNodeId()

getNodeId() ->  'tuple[int, int]'
Description

Get current CAN Node ID of the IMU.

Returns
DatatypeDescription
'tuple[int,int]'Tuple containing return status and the current CAN Node ID.

IMU.setNodeId()

setNodeId(id: int) -> int
Description

Set the node id for the IMU.

Parameters
DatatypeVariableDescription
intidCAN Device ID of the IMU
Returns
DatatypeDescription
intReturn Status

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 quaternion components (quat_i, quat_j, quat_k, quat_real).

IMU.getRawAccelerometerData

getRawAccelerometerData() ->  'tuple[int16_t, int16_t, int16_t]'
Description

Retrieve the raw accelerometer data from the IMU.

Returns
DatatypeDescription
'tuple[int16_t, int16_t, int16_t]'Raw accelerometer values (x, y, z).

IMU.getRawGyroData

getRawGyroData() ->  'tuple[int16_t, int16_t, int16_t]'
Description

Retrieve the raw gyroscope data from the IMU.

Returns
DatatypeDescription
'tuple[int16_t, int16_t, int16_t]'Raw gyroscope values (x, y, z).

IMU.getRawMagnetometerData

getRawMagnetometerData() ->  'tuple[int16_t, int16_t, int16_t]'
Description

Retrieve the raw magnetometer data from the IMU.

Returns
DatatypeDescription
'tuple[int16_t, int16_t, int16_t]'Raw magnetometer values (x, y, z).

IMU.getLinearAccelerometerData

getLinearAccelerometerData() ->  'tuple[float, float, float, uint8_t]'
Description

Retrieve the linear accelerometer data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float, uint8_t]'Linear acceleration values (x, y, z) in m/s² and accuracy.

IMU.getAccelerometerData

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

Retrieve the accelerometer data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float, uint8_t]'Acceleration values (x, y, z) in m/s² and accuracy.

IMU.getGyroData

getGyroData() ->  'tuple[float, float, float, uint8_t]'
Description

Retrieve the gyroscope data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float, uint8_t]'Gyroscope values (x, y, z) in radians per second and accuracy.

IMU.getMagnetometerData

getMagnetometerData() ->  'tuple[float, float, float, uint8_t]'
Description

Retrieve the magnetometer data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float, uint8_t]'Magnetometer values (x, y, z) in µT and accuracy.

IMU.getUncalibratedGyroData

getUncalibratedGyroData() ->  'tuple[float, float, float]'
Description

Retrieve the uncalibrated gyroscope data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float]'Uncalibrated gyroscope values (x, y, z) in radians per second.

IMU.getUncalibratedGyroBiasData

getUncalibratedGyroBiasData() ->  'tuple[float, float, float]'
Description

Retrieve the uncalibrated gyroscope bias data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float]'Uncalibrated gyroscope bias values (x, y, z) in radians per second.

IMU.getEulerAngles

getEulerAngles() ->  'tuple[float, float, float]'
Description

Retrieve the Euler angles from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float]'Euler angles (yaw, pitch, roll) in degrees.

IMU.getGravityData

getGravityData() ->  'tuple[float, float, float]'
Description

Retrieve the gravity data from the IMU.

Returns
DatatypeDescription
'tuple[float, float, float]'Gravity vector values (x, y, z) in g.

IMU.enableRotationVector

enableRotationVector(time_interval: int) -> int
Description

Enable Quaternion rotation vector data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableRotationVector

disableRotationVector() -> int
Description

Disable Quaternion rotation vector data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableRawAccelerometer

enableRawAccelerometer(time_interval: int) -> int
Description

Enable Raw accelerometer data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableRawAccelerometer

disableRawAccelerometer() -> int
Description

Disable Raw accelerometer data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableRawGyro

enableRawGyro(time_interval: int) -> int
Description

Enable Raw gyroscope data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableRawGyro

disableRawGyro() -> int
Description

Disable Raw gyroscope data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableRawMagnetometer

enableRawMagnetometer(time_interval: int) -> int
Description

Enable Raw magnetometer data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableRawMagnetometer

disableRawMagnetometer() -> int
Description

Disable Raw magnetometer data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableLinearAccelerometer

enableLinearAccelerometer(time_interval: int) -> int
Description

Enable Linear accelerometer data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableLinearAccelerometer

disableLinearAccelerometer() -> int
Description

Disable Linear accelerometer data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableAccelerometer

enableAccelerometer(time_interval: int) -> int
Description

Enable Calibrated accelerometer data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableAccelerometer

disableAccelerometer() -> int
Description

Disable Calibrated accelerometer data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableGyro

enableGyro(time_interval: int) -> int
Description

Enable Calibrated gyroscope data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableGyro

disableGyro() -> int
Description

Disable Calibrated gyroscope data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableMagnetometer

enableMagnetometer(time_interval: int) -> int
Description

Enable Calibrated magnetometer data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableMagnetometer

disableMagnetometer() -> int
Description

Disable Calibrated magnetometer data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableUncalibratedGyro

enableUncalibratedGyro(time_interval: int) -> int
Description

Enable Uncalibrated gyroscope data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableUncalibratedGyro

disableUncalibratedGyro() -> int
Description

Disable Uncalibrated gyroscope data stream.

Returns
DatatypeDescription
intStatus code.

IMU.enableGravity

enableGravity(time_interval: int) -> int
Description

Enable Gravity sensor data and configure report interval.

Returns
DatatypeDescription
intStatus code.

IMU.disableGravity

disableGravity() -> int
Description

Disable Gravity sensor data stream.

Returns
DatatypeDescription
intStatus code.
  NMotionTM  is a sub-brand of Nawe Robotics
Copyright © 2025 Nawe Robotics Private Limited