Skip to main content
Version: ROS 2 Humble

Inertial Measurment Units

Inertial measurement units are sensors that publish messages of the type sensor_msgs/Imu. These messages contain orientation, angular velocity, and/or linear acceleration depending on the device.

Microstrain IMU

imu:
- model: microstrain_imu
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
microstrain_inertial_driver:
imu_frame_id: imu_0_link
port: /dev/microstrain_main
use_enu_frame: true

Package and Setup

The MicroStrain GX devices use the microstain_inertial ROS 2 package. The driver is open source, maintained by MicroStrain, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system launches the microstrain_inertial driver, see the MicroStrain GX launch file and the default parameter file in clearpath_sensors.

Device Path

The port ROS parameter must be set to the device path of the MicroStrain device. The microstrain_inertial package installs its UDEV rule, which will add the /dev/microstrain_main device.

CHRobotics UM6

imu:
- model: chrobotics_um6
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
um6_driver:
port: /dev/clearpath/imu
frame_id: imu_0_link
tf_ned_to_enu: true

Package and Setup

The CHRobotics UM6 IMU uses the umx_driver ROS 2 package. The driver is open source, maintained by the ROS community, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system launches the umx_driver, see the CHRobotics UM6 launch file and the default parameter file in clearpath_sensors.

Device Path

The port ROS parameter must be set to the device path of the CHRobotics UM6. To simplify this process, use the /dev/clearpath/imu path. This path is only available when the Clearpath robot UDEV rules are installed. These are installed alongside the clearpath_robot package. If the IMU is connected, but the /dev/clearpath/imu device is not, check the file /lib/udev/rules.d/60-ros-humble-clearpath-robot.rules exists.

Redshift UM7

imu:
- model: redshift_um7
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
um7_driver:
port: /dev/clearpath/imu
frame_id: imu_0_link
tf_ned_to_enu: true

Package and Setup

The RedShift UM7 IMU uses the umx_driver ROS 2 package. The driver is open source, maintained by the ROS community, and hosted on GitHub.

For more specifics on the way Clearpath's configuration system launches the umx_driver, see the RedShift UM7 launch file and the default parameter file in clearpath_sensors.

Device Path

The port ROS parameter must be set to the device path of the RedShift UM7. To simplify this process, use the /dev/clearpath/imu path. This path is only available when the Clearpath robot UDEV rules are installed. These are installed alongside the clearpath_robot package. If the IMU is connected, but the /dev/clearpath/imu device is not, check the file /lib/udev/rules.d/60-ros-humble-clearpath-robot.rules exists.