| Topic Name | Message Type | Type | Description |
|---|---|---|---|
| /filtered_ahrs | sensor_msgs/Imu | Publisher | AHRS optimized acc/gyro/quaternion |
| /filtered_imu | sensor_msgs/Imu | Publisher | High dynamic acc/gyro/quaternion |
| /linear_accel | geometry_msgs/msg/AccelStamped | Publisher | Gravity compensated acceleration |
| /magnetometer | sensor_msgs/MagneticField | Publisher | Measured magnetic field |
| /status | diagnostic_msgs/DiagnosticStatus | Publisher | Device status |
| /feedback | std_msgs/msg/Float32MultiArray | Publisher | Sensor IO loops |
| /temperature | sensor_msgs/msg/Temperature | Publisher | Sensor temperature |
| /pose | geometry_msgs/msg/PoseStamped | Publisher | 3D position (estimation) |
| /twist | geometry_msgs/msg/TwistStamped | Publisher | 3D velocity (estimation) |
| /tf | tf2_msgs/msg/TFMessage | Publisher | TF |
filtered_AHRS: Provides improved quaternion calculations (roll, pitch, yaw) and is more robust against drift and vibrations. It operates efficiently at up to 100 Hz.
filtered_IMU: Optimized for higher sample rates, up to 2000 Hz, focusing on minimizing latency and improving accelerometer and gyroscope accuracy.
filtered_IMU.filtered_AHRS.| Topic Name | Message Type | Type | Description |
|---|---|---|---|
| /ahrs | sensor_msgs/Imu | Publisher | AHRS optimized acc/gyro/quaternion |
| /mpu | sensor_msgs/Imu | Publisher | High dynamic acc/gyro/quaternion |
| /acceleration | geometry_msgs/msg/AccelStamped | Publisher | Gravity compensated acceleration |
| /magneticfield | sensor_msgs/MagneticField | Publisher | Measured magnetic field |
| /status | diagnostic_msgs/DiagnosticStatus | Publisher | Device status |
| /feedback | std_msgs/msg/Float32MultiArray | Publisher | Sensor IO loops |
| /temperature | sensor_msgs/msg/Temperature | Publisher | Sensor temperature |
| /pose | geometry_msgs/msg/PoseStamped | Publisher | 3D position (estimation) |
| /velocity | geometry_msgs/msg/TwistStamped | Publisher | 3D velocity (estimation) |
| /tf | tf2_msgs/msg/TFMessage | Publisher | TF |
AHRS: Provides improved quaternion calculations (roll, pitch, yaw) and is more robust against drift and vibrations. It operates efficiently at up to 100 Hz.
MPU: Optimized for higher sample rates, up to 2000 Hz, focusing on minimizing latency and improving accelerometer and gyroscope accuracy.
Summary:
MPU.AHRS.IMU Mode
| Topic Name | Message Type | Type | Description |
|---|---|---|---|
| .../imu | sensor_msgs/msg/Imu | Publisher | High dynamic acc/gyro/quaternion |
| ../magneticfield | sensor_msgs/MagneticField | Publisher | Measured magnetic field |
| .../status | diagnostic_msgs/msg/DiagnosticStatus | Publisher | Device status |
| .../temperature | sensor_msgs/msg/Temperature | Publisher | Sensor temperature |
| ../tf | tf2_msgs/msg/TFMessage | Publisher | TF |
AHRS Mode
| Topic Name | Message Type | Type | Description |
|---|---|---|---|
| .../imu | sensor_msgs/msg/Imu | Publisher | AHRS optimized acc/gyro/quaternion |
| .../acceleration | geometry_msgs/msg/AccelStamped | Publisher | Gravity compensated acceleration |
| .../status | diagnostic_msgs/msg/DiagnosticStatus | Publisher | Device status |
| .../temperature | sensor_msgs/msg/Temperature | Publisher | Sensor temperature |
| .../velocity | geometry_msgs/msg/TwistStamped | Publisher | 3D velocity (estimation) |
| ../tf | tf2_msgs/msg/TFMessage | Publisher | TF |
| Service Name | Service Type | Description |
|---|---|---|
| /setBias | std_srvs/srv/Trigger | Calibrating the sensor's bias offset values |
| /setZeroQuaternion | std_srvs/srv/Trigger | Resetting the sensor's rotation axis |
| /reboot | std_srvs/srv/Trigger | Reboot sensor |
| /restartDCMServices | std_srvs/srv/Trigger | Restart DCM services |
| /standby | std_srvs/srv/SetBool | Set sensor in standby mode |
By calling the setBias service or triggering it from the GUI, the sensor will collect bias values to minimize the zero offset. During this process, please ensure that the sensor remains completely stable and is not moving. It is also important to call the service when the sensor is placed in the correct Orientation:the Olive logo facing up and the four screw holes facing down.

The device allows certain parameters to be changed at runtime. To get an overview of all changeable parameters use
ros2 param list
To change a parameter use this command below or the GUI rqt
ros2 param set /dcm_imu <parameter> <new_value>
| Name | Description | Type | Default Value | Range / Options |
|---|---|---|---|---|
| operation_mode | Change sensor operation mode: AHRS-, AHRS, AHRS+. | string | AHRS- | AHRS- | AHRS | AHRS+ |
| enable_tf_publisher | Publish a dedicated tf with respect to filtered IMU data. | bool | true | - |
| enable_fusion_publisher | Activate the fusion data publisher. | bool | true | - |
| enable_linear_acc_publisher | Activate the linear gravity-compensated accelerometer publisher. | bool | true | - |
| enable_startup_zero_quaternion | Reset quaternion on system startup. | bool | true | - |
| enable_ahrs_publisher | Activate the filtered AHRS data publisher. | bool | true | - |
| ahrs_publish_rate | Publish rate for filtered AHRS data. | int | 100 | [0, 100] Hz |
| enable_temperature_publisher | Activate the temperature data publisher. | bool | true | - |
| enable_twist_publisher | Activate the twist (velocity) data publisher. | bool | true | - |
| imu_acc_cutoff_frequency | IMU accelerometer cutoff frequency (0 disables). | double | 100.0 | [0, 500] Hz |
| imu_acc_ema_gain | EMA gain for IMU accelerometer (0 disables). | double | 0.9 | [0, 1] |
| imu_gyro_cutoff_frequency | IMU gyroscope cutoff frequency (0 disables). | double | 100.0 | [0, 500] Hz |
| imu_gyro_ema_gain | EMA gain for IMU gyroscope (0 disables). | double | 0.9 | [0, 1] |
| ahrs_acc_cutoff_frequency | AHRS accelerometer cutoff frequency (0 disables). | double | 100.0 | [0, 500] Hz |
| ahrs_acc_ema_gain | EMA gain for AHRS accelerometer (0 disables). | double | 0.5 | [0, 1] |
| ahrs_gyro_cutoff_frequency | AHRS gyroscope cutoff frequency (0 disables). | double | 100.0 | [0, 500] Hz |
| ahrs_gyro_ema_gain | EMA gain for AHRS gyroscope (0 disables). | double | 0.5 | [0, 1] |
| ahrs_mag_cutoff_frequency | AHRS magnetometer cutoff frequency (0 disables). | double | 100.0 | [0, 500] Hz |
| ahrs_mag_ema_gain | EMA gain for AHRS magnetometer (0 disables). | double | 0.5 | [0, 1] |
| fusion_gain | Fusion gain for sensor data fusion. | double | 0.1 | [0, 1] |
| fusion_publish_rate | Publish rate of fusion data. | int | 500 | [0, 1000] Hz |
| gyro_zero_cutoff_threshold | Gyro zero cutoff threshold (0 disables). | double | 0.005 | [0, 1] |
| linear_acc_zero_cutoff_threshold | Linear acceleration zero cutoff threshold (0 disables). | double | 0.2 | [0, 1] |
| topic_publisher_qos | QoS type for all topic publishers. | string | reliable | besteffort | reliable |
Detailed Parameter Descriptions
| Parameter | Description |
|---|---|
operation_mode |
Changes the internal sensor operation mode: AHRS+ (absolute orientation with fast magnetic calibration), AHRS (absolute orientation without fast calibration), AHRS- (relative orientation, magnetometer disabled). |
enable_tf_publisher |
Publishes a dedicated TF frame based on filtered IMU data for spatial orientation. |
enable_fusion_publisher |
Enables the fusion data publisher. |
enable_linear_acc_publisher |
Enables publishing of gravity-compensated linear acceleration data. |
enable_startup_zero_quaternion |
Resets quaternion values to zero at system startup. |
enable_ahrs_publisher |
Enables the filtered AHRS data publisher. |
ahrs_publish_rate |
Sets the publish rate of AHRS data. Range: [0, 100] Hz. |
enable_temperature_publisher |
Enables the temperature data publisher. |
enable_twist_publisher |
Enables the twist (angular and linear velocity) publisher. |
imu_acc_cutoff_frequency |
Cutoff frequency for IMU accelerometer filtering (0 disables). Range: [0, 500] Hz. |
imu_acc_ema_gain |
EMA gain for IMU accelerometer filtering (0 disables). Range: [0, 1]. |
imu_gyro_cutoff_frequency |
Cutoff frequency for IMU gyroscope filtering (0 disables). Range: [0, 500] Hz. |
imu_gyro_ema_gain |
EMA gain for IMU gyroscope filtering (0 disables). Range: [0, 1]. |
ahrs_acc_cutoff_frequency |
Cutoff frequency for AHRS accelerometer filtering (0 disables). Range: [0, 500] Hz. |
ahrs_acc_ema_gain |
EMA gain for AHRS accelerometer filtering (0 disables). Range: [0, 1]. |
ahrs_gyro_cutoff_frequency |
Cutoff frequency for AHRS gyroscope filtering (0 disables). Range: [0, 500] Hz. |
ahrs_gyro_ema_gain |
EMA gain for AHRS gyroscope filtering (0 disables). Range: [0, 1]. |
ahrs_mag_cutoff_frequency |
Cutoff frequency for AHRS magnetometer filtering (0 disables). Range: [0, 500] Hz. |
ahrs_mag_ema_gain |
EMA gain for AHRS magnetometer filtering (0 disables). Range: [0, 1]. |
fusion_gain |
Controls sensor fusion responsiveness (low = stable, high = responsive). Range: [0, 1]. |
fusion_publish_rate |
Sets the publish rate of fusion data. Range: [0, 1000] Hz. |
gyro_zero_cutoff_threshold |
Threshold below which gyro values are treated as zero (0 disables). Range: [0, 1]. |
linear_acc_zero_cutoff_threshold |
Threshold below which linear acceleration is treated as zero (0 disables). Range: [0, 1]. |
topic_publisher_qos |
QoS setting for publishers: reliable (guaranteed delivery) or besteffort (low latency, possible loss). |
| Name | Description | Type | Default Value | Range / Options |
|---|---|---|---|---|
| acc_cutoff_frequency | accelerometer cutoff frequency (0 disables). | double | 100.0 | 0 - 500Hz |
| acc_ema_gain | EMA gain for IMU accelerometer (0 disables). | double | 0.5 | 0 - 1 |
| enable_startup-zero_quaterntion | Enables to zero the Quaternions of the IMU at startup. | bool | true | true | false |
| enable_tf_publisher | Enable tf publisher. | bool | true | true | false |
| fusion_acc_ema_gain | EMA gain for fused accelerometer (0 disables). | double | 0.9 | 0 - 1 |
| fusion_gyro_ema_gain | EMA gain for fused gyroscope (0 disables). | double | 0.9 | 0 - 1 |
| gyro_cutoff_frequency | Gyroscope cutoff frequency (0 disables). | double | 100 | 0 - 500 Hz |
| gyro_ema_gain | EMA gain for gyroscope (0 disables). | double | 0.5 | 0 - 1 |
| gyro_zero_cutoff_threshold | Gyro zero cutoff threshold (0 disables). | double | 0.0025 | 0 - 1 |
| publish_rate | Publish rate of the IMU data | int | 100 | 0 - 1000 Hz |
| topic_publisher_qos | QoS type for all topic publishers. | string | reliable | reliable | besteffort |
| use_sim_time | Use ROS 2 Simulation Time | bool | false | true | false |
IMU Mode:
| Name | Description | Type | Default Value | Range / Options |
|---|---|---|---|---|
| fusion_gain | Fusion gain for sensor data fusion. | double | 0.1 | 0 - 1 |
| mag_cuttoff_frequency | Magnetometer cutoff frequency (0 disables). | double | 100 | 0 - 500 Hz |
| mag_ema_gain | EMA gain for magnetometer (0 disables). | double | 0.9 | 0 - 1 |
AHRS Mode:
| Name | Description | Type | Default Value | Range / Options |
|---|---|---|---|---|
| linear_acc_zero_cutoff_frequency | Gravity compensated linear acceleration cuttoff frequency | double | 0.25 | 0 - 1 |
Detailed Parameter Descriptions
| Parameter | Description |
|---|---|
acc_cutoff_frequency / gyro_cutoff_frequency / mag_cutoff_frequency |
Sets the cutoff frequency for the IMU accelerometer / gyroscope / magnetometer. A value of 0 disables the cutoff filter. Range: [0, 500] Hz. |
acc_ema_gain / gyro_ema_gain / mag_ema_gain |
Sets the exponential moving average (EMA) gain for the IMU accelerometer / gyroscope / magnetometer. A value of 0 disables EMA filtering. Range: [0, 1]. |
enable_startup_zero_quaternion |
Resets the quaternion values to zero on system startup for consistent initial conditions. |
enable_tf_publisher |
Publishes a dedicated TF frame based on the filtered IMU data for applications requiring precise spatial orientation. |
fusion_acc_ema_gain / fusion_gyro_ema_gain |
Sets the exponential moving average (EMA) gain for the fused accelerometer / gyroscope. A value of 0 disables EMA filtering. Range: [0, 1]. |
fusion_gain |
Adjusts the fusion gain used for combining sensor data. A smaller value gives slower, more stable fusion, while a larger value makes it more responsive. Range: [0, 1]. |
gyro_zero_cutoff_threshold / linear_acc_zero_cutoff_threshold |
Specifies a zero cutoff threshold for the gyroscope / linear acceleration output. Values below this threshold are treated as noise and set to zero. A value of 0 disables the threshold. Range: [0, 1]. |
publish_rate |
Sets the publish rate for fusion data in Hz. Range: [0, 1000]. |
topic_publisher_qos |
Defines the Quality of Service (QoS) setting for all topic publishers. Options: besteffort | reliable. reliable ensures delivery by retrying until acknowledged; besteffort prioritizes low latency and allows some data loss. |
Ensure consistency between your fusion rate, AHRS rate, and QoS settings depending on your application needs.
Any EMA Gain = 0 or Cutoff Frequency = 0 disables that specific filter.
From patch 2136 you can change the mode only from GUI
| Parameter | Type | Range Min | Range Max | Default | Description |
|---|---|---|---|---|---|
| frequency | int | 0 | 10 | 1 | System status publish rate |