Wiki

Only released in EOL distros:  

Package Summary

The microstrain_3dm_gx5_45 package provides a driver for the LORD/Microstrain 3DM_GXx_45 GPS-aided IMU sensor.

Package Summary

The microstrain_3dm_gx5_45 package provides a driver for the LORD/Microstrain 3DM_GXx_45 GPS-aided IMU sensor.

Overview

Interface (driver) software, including ROS node, for Microstrain 3DM-GX5-45.

The interface makes use of the MIP SDK Version 1.1 from Microstrain to communicate with the device. Includes the following applications:

Supported Devices

ROS Nodes

microstrain_3dm_gx5_45

ROS node reports the GPS data, AHRS data and Nav Filter estimate

Published Topics

gps/fix (sensor_msgs/NavSatFix) imu/data (sensor_msgs/Imu) nav/odom (nav_msgs/Odometry) nav/status (std_msgs/Int16MultiArray)

Services

reset_kf (std_srvs/Empty)

Parameters

port (string, default: /dev/ttyACM0) baud_rate (int, default: 115200) device_setup (bool, default: true) readback_settings (bool, default: true) auto-init (bool, default: true) dynamics_mode (int, default: 1) declination_source (int, default: 2) gps_frame_id (string, default: wgs84) imu_frame_id (string, default: base_link) odom_frame_id (string, default: wgs84) odom_child_frame_id (string, default: base_link) publish_gps (bool, default: true) publish_imu (bool, default: true) publish_gps (bool, default: true) gps_rate (int, default: 1) imu_rate (int, default: 10) odom_rate (int, default: 10)

Update Rates

The rates are set as a target value in Hz. The device accepts a decimation value for each output; the packet rate is base_rate/decimation, where decimation is an integer. The program calculates the decimation to get close the the desired rate, based on polling the sensor for its base rate.

For the 3DM-GX4-45 and 3DM-GX5-45 devices tested the base rates were...

Odometry message information

Position covariance is populated with diagonals based on reported horizontal and vertical accuracy. The status.status field is the LLH position data "valid flag"-1. The valid flag mapping from the 3DM protocol is

Build Instructions

Building from source

DISTRO={hydro|indigo}
cd ~/catkin_ws
rosdep update
rosdep check --from-paths src/microstrain_3dm_gx5_45/ --rosdistro=$DISRO
rosdep install --from-paths src/microstrain_3dm_gx5_45/ --ignore-src --rosdistro=$DISTRO --simulate
rosdep install --from-paths src/microstrain_3dm_gx5_45/ --ignore-src --rosdistro=$DISTRO
catkin_make
source devel/setup.bash

Dev Notes

TODO

Launch File Examples

There are launch files in the /launch directory to illustrate use of the node.

Wiki: microstrain_3dm_gx5_45 (last edited 2017-04-14 02:01:12 by BrianBingham)