Overview

ROS driver for all of Microstrain's current G and C series products.

The interface makes use of MSCL (Microstrain Communication Library) from Microstrain to communicate with the device. Includes the following applications:

Supported Devices

3DM-GQ7

3DM-GX5-45

3DM-GX5-25

3DM-GX5-15

  Show EOL distros: 

ROS Nodes

microstrain_inertial_driver

ROS node that advertises IMU/GPS data, and exposes services to interact with the device.

Published Topics

imu/data (sensor_msgs/Imu)
  • Raw IMU data. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, and 3DM-GX5-15
gps_corr (microstrain_inertial_msgs/GPSCorrelationTimestampStamped) mag (sensor_msgs/MagneticField) gnss1/fix (sensor_msgs/NavSatFix)
  • Provides GPS fix information for GNSS1 receiver. Available for 3DM-GQ7 and 3DM-GX5-45. TODO NED/ENU
gnss1/odom (nav_msgs/Odometry)
  • Provides odometry from the GNSS1 receiver. Available for 3DM-GQ7 and 3DM-GX5-45. TODO NED/ENU. TODO LAT/LON and ECEF
gnss1/time_ref (sensor_msgs/TimeReference)
  • Provides a time reference based on the GNSS1 receiver. Available for 3DM-GQ7 and 3DM-GX5-45.
gnss1/aiding_status (microstrain_inertial_msgs/GNSSAidingStatus) gnss2/fix (sensor_msgs/NavSatFix)
  • Provides GPS fix information for GNSS2 receiver. Available for 3DM-GQ7. TODO NED/ENU
gnss2/odom (nav_msgs/Odometry)
  • Provides odometry from the GNSS2 receiver. Available for 3DM-GQ7. TODO NED/ENU. TODO LAT/LON and ECEF
gnss2/time_ref (sensor_msgs/TimeReference)
  • Provides a time reference based on the GNSS2 receiver. Available for 3DM-GQ7.
gnss2/aiding_status (microstrain_inertial_msgs/GNSSAidingStatus) rtk/status (microstrain_inertial_msgs/RTKStatus)
  • Provides status information of a 3DM-RTK if connected to a 3DM-GQ7. Available for 3DM-GQ7.
nav/status (microstrain_inertial_msgs/FilterStatus)
  • Provides status of Extended Kalman Filter running on the device. More information on the specific values can be found in the GQ7 User Manual. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, and 3DM-GX5-15.
nav/odom (nav_msgs/Odometry)
  • Provides odometry based on the output of the EKF running on the device. Available for 3DM-GQ7, and 3DM-GX5-45. TODO ENU/NED. TODO LAT/LON ECEF
nav/heading (microstrain_inertial_msgs/FilterHeading)
  • Provides the heading based on the output of the EKF running on the device. Available for 3DM-GQ7, 3DM-GX5-45, and 3DM-GX5-25.
nav/heading_state (microstrain_inertial_msgs/FilterHeadingState)
  • Provides heading state of the EKF running on the device. Available for 3DM-GQ7, 3DM-GX5-45, and 3DM-GX5-25
nav/filtered_imu/data (sensor_msgs/Imu)
  • Provides filtered IMU data based on the output of the EKF running on the device. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, and 3DM-GX5-15.
nav/dual_antenna_status (microstrain_inertial_msgs/GNSSDualAntennaStatus)
  • Provides additional status information about the Dual Antenna Solution if used. Available for 3DM-GQ7.
nav/relative_pos/odom (nav_msgs/Odometry)
  • Provides odometry based on the output of the EKF running on the device. Available for 3DM-GQ7, and 3DM-GX5-45. TODO ENU/NED. TODO LAT/LON ECEF TODO Relative config

Services

get_basic_status (std_srvs/Trigger)
  • Prints basic device info to the screen. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, and 3DM-GX5-15.
get_diagnostic_report (std_srvs/Trigger)
  • Prints a more comprehensive list of device info to the screen. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, and 3DM-GX5-15.
device_report (std_srvs/Trigger)
  • Prints a different variety of device info to the screen. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, and 3DM-GX5-15.
set_tare_orientation (microstrain_inertial_msgs/SetTareOrientation)
  • Tares the orientation of the device. Available for 3DM-GQ7, 3DM-GX5-45, and 3DM-GX5-25.
set_complementary_filter (microstrain_inertial_msgs/SetComplementtaryFilter)
  • TODO
get_complementary_filter (microstrain_inertial_msgs/GetcomplementaryFilter)
  • TODO
set_sensor2vehicle_rotation (microstrain_inertial_msgs/SetSensor2VehicleRotation)
  • Sets the rotation of the sensor in relation to the vehicle frame. Available for TODO
get_sensor2vehicle_rotation (microstrain_inertial_msgs/GetSensor2VehicleRotation)
  • Gets the ration of the sensor in relation to the vehicle frame. Available for TODO
set_sensor2vehicle_offset (microstrain_inertial_msgs/SetSensor2VehicleOffset)
  • Sets the translation of the sensor in relation to the vehicle frame. Available for TODO
get_sensor2vehicle_offset (microstrain_inertial_msgs/GetSensor2VehicleOffset)
  • Gets the translation of the sensor in relation to the vehicle frame. Available for TODO
get_sensor2vehicle_transformation (microstrain_inertial_msgs/GetSensor2VehicleTransformation)
  • Gets the translation and rotation of the sensor in relation to the vehicle frame. Available for TODO
set_accel_bias (microstrain_inertial_msgs/SetAccelBias)
  • Sets a specified acceleration bias to the sensor. Available for TODO
get_accel_bias (microstrain_inertial_msgs/GetAccelBias)
  • Gets the acceleration bias set on the sensor. Available for TODO
set_gyro_bias (microstrain_inertial_msgs/SetGyroBias)
  • Sets a specified gyro bias to the sensor. Available for TODO
get_gyro_bias (microstrain_inertial_msgs/GetGyroBias)
  • Gets the gyro bias set on the sensor. Available for TODO
gyro_bias_capture (std_srvs/Trigger)
  • Captures gyro bias data for 10 seconds and updates the bias settings on the device. Available for TODO
set_hard_iron_values (microstrain_inertial_msgs/SetHardIronValues)
  • TODO
get_hard_iron_values (microstrain_inertial_msgs/GetHardIronValues)
  • TODO
set_soft_iron_matrix (microstrain_inertial_msgs/SetSoftIronMatrix)
  • TODO
get_soft_iron_matrix (microstrain_inertial_msgs/GetSoftIronMatrix)
  • TODO
set_coning_sculling_comp (microstrain_inertial_msgs/SetConingScullingComp)
  • TODO
get_coning_sculling_comp (microstrain_inertial_msgs/GetConingScullingComp)
  • TODO
reset_kf (std_srvs/Empty)
  • Restarts the Extended Kalman Filter running on the device. Available for 3DM-GQ7, 3DM-GX5-45, 3DM-GX5-25, 3DM-GX5-15.
set_estimation_control_flags (microstrain_inertial_msgs/SetEstimationControlFlags)
  • TODO
get_estimation_control_flags (microstrain_inertial_msgs/GetEstimationControlFlags)
  • TODO
init_filter_heading (microstrain_inertial_msgs/InitFilterHeading)
  • TODO
set_heading_source (microstrain_inertial_msgs/SetHeadingSource)
  • TODO
get_heading_source (microstrain_inertial_msgs/GetHeadingSource)
  • TODO
commanded_vel_zupt (std_srvs/Trigger)
  • TODO
commanded_ang_rate_zupt (std_srvs/Trigger)
  • TODO
set_accel_noise (microstrain_inertial_msgs/SetAccelNoise)
  • Sets a specified acceleration noise to the sensor. Available for TODO
get_accel_noise (microstrain_inertial_msgs/GetAccelNoise)
  • Gets the acceleration noise set on the sensor. Available for TODO
set_gyro_noise (microstrain_inertial_msgs/SetGyroNoise)
  • Sets a specified gyro noise to the sensor. Available for TODO
get_gyro_noise (microstrain_inertial_msgs/GetGyroNoise)
  • Gets the gyro noise set on the sensor. Available for TODO
set_mag_noise (microstrain_inertial_msgs/SetMagNoise)
  • Sets a specified magnetometer noise to the sensor. Available for TODO
get_mag_noise (microstrain_inertial_msgs/GetMagNoise)
  • Gets the magnetometer noise set on the sensor. Available for TODO
set_accel_bias_model (microstrain_inertial_msgs/SetAccelBiasModel)
  • TODO
get_accel_bias_model (microstrain_inertial_msgs/GetAccelBiasModel)
  • TODO
set_gyro_bias_model (microstrain_inertial_msgs/SetGyroBiasModel)
  • TODO
get_gyro_bias_model (microstrain_inertial_msgs/GetGyroBiasModel)
  • TODO
set_mag_adaptive_vals (microstrain_inertial_msgs/SetMagAdaptiveVals)
  • TODO
get_mag_adaptive_vals (microstrain_inertial_msgs/GetMagAdaptiveVals)
  • TODO
set_mag_dip_adaptive_vals (microstrain_inertial_msgs/SetMagDipAdaptiveVals)
  • TODO
get_mag_dip_adaptive_vals (microstrain_inertial_msgs/GetMagDipAdaptiveVals)
  • TODO
set_gravity_adaptive_vals (microstrain_inertial_msgs/SetGravityAdaptiveVals)
  • TODO
get_gravity_adaptive_vals (microstrain_inertial_msgs/GetGravityAdaptiveVals)
  • TODO
set_zero_angle_update_threshold (microstrain_inertial_msgs/SetZeroAngleUpdateThreshold)
  • TODO
get_zero_angle_update_threshold (microstrain_inertial_msgs/GetZeroAngleUpdateThreshold)
  • TODO
set_zero_velocity_update_threshold (microstrain_inertial_msgs/SetZeroVelocityUpdateThreshold)
  • TODO
get_zero_velocity_update_threshold (microstrain_inertial_msgs/GetZeroVelocityUpdateThreshold)
  • TODO
set_reference_position (microstrain_inertial_msgs/SetReferencePosition)
  • TODO
get_reference_position (microstrain_inertial_msgs/GetReferencePosition)
  • TODO
set_dynamics_mode (microstrain_inertial_msgs/SetDynamicsMode)
  • TODO
get_dynamics_mode (microstrain_inertial_msgs/GetDynamicsMode)
  • TODO
device_settings (microstrain_inertial_msgs/DeviceSettings)
  • TODO
external_heading (microstrain_inertial_msgs/ExternalHeadingUpdate)
  • TODO
set_relative_position_reference (microstrain_inertial_msgs/SetRelativePositionReference)
  • TODO
set_filter_speed_lever_arm (microstrain_inertial_msgs/SetFilterSpeedLeverArm)
  • TODO

Parameters

port (string, default: /dev/ttyACM0)
  • Serial port used to communicate with the device.
aux_port (string, default: /dev/ttyACM1)
  • Serial port used to send RTCM corrections to the device and receive NMEA messages from the device. Currently only supported by the 3DM-GQ7
baudrate (int)
  • Baud rate to use when opening the serial devices used by this node. Note that the same baudrate will be used for both the main port and the aux port.
poll_rate_hz (float, default: 1.0)
  • Rate that the node will poll the port in HZ
poll_max_tries (int, default: 60)
  • Maximum number of tries to check if the port exists before exiting with an error. If set to -1, the node will poll forever until the device exists.
device_setup (bool, default: true)
  • Controls if the driver should setup and configure the device. If set to false, the driver will not do ANY configuration of the device.
save_settings (bool, default: false)
  • Controls if the settings configured by the driver will be saved to the devices' non-volatile memory which will persist through power cycles.
raw_file_enable (bool, default: false)
  • Controls if the driver creates a raw binary file containing all requested channels from the device. The file will be named <Model Number>_<Serial Number>_<Year>_<Month>_<Day>_<Hour>_<Minute>_<Sec>.bin
raw_file_include_support_data (bool, default: false)
  • Controls whether the driver will add additional factory support channels to the binary file produced. Useful when requesting support from the manufacturer, but this increases bandwidth usage considerably, so use with caution.
raw_file_directory (string, default: /home/your_name)
  • The directory to store the raw data file. Should not have a trailing /
imu_frame_id (string, default: sensor)
  • Frame ID to use with the IMU data.
gnss1_frame_id (string, default: gnss1_wgs84_ned)
  • Frame ID to use with the GNSS1 data.
gnss2_frame_id (string, default: gnss2_wgs84_ned)
  • Frame ID to use with the GNSS2 data.
filter_frame_id (string, default: sensor_wgs84_ned)
  • Frame ID to use with the filter data. The node will also produce a transform between this and filter_child_frame_id when publish_relative_position is set to true
filter_child_frame_id (string, default: sensor)
  • Child frame ID used with filter data. The node will also produce a transform between the filter_frame_id and this frame when publish_relative_position is set to true
nmea_frame_id (string, default: nmea)
  • Frame ID to use with the NMEA data.
use_enu_frame (bool, default: false)
  • Controls if the driver outputs data with respect to the ENU frame.
use_device_timestamp (bool, default: false)
  • Controls if the driver uses the device generated timestamp (if available) for timestamping messages as well as providing a TimeReference message.
publish_imu (bool, default: true)
  • Controls whether the driver will publish IMU data. If device_setup is set to true, this will also enable the channels required to receive IMU data.
imu_data_rate (float, default: 10)
  • Rate in hertz that the device will produce IMU data. Up to TODO
imu_orientation_cov (array, default: [0.01,0,0,0,0.01,0,0,0,0.01])
  • 3x3 matrix that contains the static IMU covariance values for orientation
imu_linear_cov (array, default: [0.01,0,0,0,0.01,0,0,0,0.01])
  • 3x3 matrix that contains the static IMU linear values for linear velocity
imu_angular_cov (array, default: [0.01,0,0,0,0.01,0,0,0,0.01])
  • 3x3 matrix that contains the static IMU covariance values for angular velocity
publish_gps_corr (bool, default: false)
  • Controls if the driver will publish GPS time of week. Useful if you need to provide external information synced to GPS time of week.
publish_gnss1 (bool, default: true)
  • Controls whether the node will publish data from GNSS antenna 1. If device_setup is set to true, this will also enable the channels required to receive GNSS1 data.
gnss1_data_rate (float, default: 2)
  • Rate in hertz that the device will produce GNSS1 data. Up to TODO
gnss1_antenna_offset (array, default: [0.0,-0.7,-1.0])
  • Antenna 1 lever arm offset vector in meters. For GQ7 this is in the vehicle frame with respect to IMU origin. For all other models this is in the IMU frame with respect to IMU origin
publish_gnss2 (bool, default: true)
  • Controls whether the node will publish data from GNSS antenna 2. If device_setup is set to true, this will also enable the channels required to receive GNSS2 data.
gnss2_data_rate (float, default: 2)
  • Rate in hertz that the device will produce GNSS2 data. Up to TODO
gnss2_antenna_offset (array, default: [0.0,-0.7,-1.0])
  • Antenna 2 lever arm offset vector in meters. This is in the vehicle frame with respect to IMU origin.
rtk_dongle_enable (bool, default: false)
  • Whether to enable the RTK dongle interface.
subscribe_rtcm (bool, default: false)
  • Whether to subscribe to RTCM corrections and provide them to the filter
rtcm_topic (string)
  • The topic to subscribe to when receiving RTCM corrections from the ROS network.
publish_nmea (bool, default: false)
  • Whether to publish NMEA messages received from the GQ7 aux port.
publish_filter (bool, default: true)
  • Controls whether the node will publish data from the EKF running on the device. If device_setup is set to true, this will also enable the channels required to receive filter data
filter_data_rate (bool, default: 10)
  • Rate in hertz at which the device will produce filter data. Up to TODO
filter_sensor2vehicle_frame_selector (int, default: 0)
  • Selects the method that the sensor2vehicle frame translation will be passed into the device. 0 = None, 1 = Euler Angles, 2 = Matrix, 3 = Quaternion.
filter_sensor2vehicle_frame_transformation_euler (array, default: [0.0,0.0,0.0])
  • Euler transform between the sensor frame and vehicle frame
filter_sensor2vehicle_frame_transformation_matrix (array, default: [1.0,0.0,0.0,0.0,1.0,0.0,0.0,0.0,1.0])
  • Matrix transform between the sensor frame and vehicle frame
filter_sensor2vehicle_frame_transformation_quaternion (array, default: [0.0,0.0,0.0,1.0])
  • Quaternion transform between the sensor frame and vehicle frame
filter_reset_after_config (bool, default: true)
  • Controls if the Kalman filter is reset after the settings are configured.
filter_auto_init (bool, default: true)
  • Controls if the Kalman filter will auto-init or require manual initialization
filter_declination_source (int, default: 2)
  • Declination source. 1 = None, 2 = Magnetic Label, 3 = Manual
filter_declination (double, default: 0.23)
  • Manual declination source. Used if filter_declination_source is set to 3
filter_heading_source (int, default: 1)
  • Heading source. 0 = None, 1 = Magnetic, 2 = GNSS Velocity
filter_dynamics_mode (int, default: 1)
  • Dynamics mode. 1 = Portable, 2 = Automotive, 3 = Airborne (<2Gs), 4 = Airborne High G (<4Gs)
filter_velocity_zupt (bool, default: true)
  • Controls whether the node will subscribe to a topic that will receive boolean messages to either enable or disable velocity ZUPT messages being sent to the device on an interval.
filter_velocity_zupt_topic (string, default: /moving_vel)
  • Topic that we will listen to for velocity ZUPT start and stop commands.
filter_angular_zupt (bool, default: true)
  • Controls whether the node will subscribe to a topic that will receive boolean messages to either enable or disable angular ZUPT messages being sent to the device on an interval.
filter_angular_zupt_topic (string, default: /moving_ang)
  • Topic that we will listen to for angular ZUPT start and stop commands.
filter_adaptive_level (int, default: 2)
  • Adaptive filter settings. 0 = Off, 1 = Conservative, 2 = Moderate, 3 = Aggressive
filter_adaptive_time_limit_ms (int, default: 15000)
  • Max duration of measurement rejection prior to recovery in milliseconds.
filter_enable_gnss_pos_vel_aiding (bool, default: true)
  • Controls whether the filter uses GNSS position and velocity as an aiding measurement.
filter_enable_gnss_heading_aiding (bool, default: true)
  • Controls whether the filter uses GNSS heading as an aiding meas3rement.
filter_enable_altimeter_aiding (bool, default: false)
  • Controls whether the filter uses altimeter data as an aiding measurement.
filter_enable_odometer_aiding (bool, default: false)
  • Controls whether the filter uses odometer data as an aiding measurement.
filter_enable_magnetometer_aiding (bool, default: false)
  • Controls whether the filter uses magnetometer data as an aiding measurement.
filter_enable_external_heading_aiding (bool, default: false)
  • Controls whether the filter uses external heading as an aiding measurement.
filter_enable_external_gps_time_update (bool, default: false)
  • Controls whether the node should listen for external GPS time from the ROS network.
filter_external_gps_time_topic (string, default: /external_gps_time)
  • The topic that the node will listen to for external GPS time.
gps_leap_seconds (int, default: 18)
  • Current number of GPS leap seconds
filter_external_speed_topic (string, default: /external_speed)
  • The topic that the node will listen to for external speed measurements. Only enabled if filter_enable_odometer_aiding is true. Not available when hardware odometer is enabled.
enable_hardware_odometer (bool, default: false)
  • Controls whether the GQ7 will be configured to accept odometer data through the GPIO pins.
odometer_scaling (float, default: 0.0)
  • Odometer scaling used with the hardware odometer
odometer_uncertainty (float, default: 0.0)
  • Odometer uncertainty used with the hardware odometer
gpio1_feature (int, default: 0)
  • TODO
gpio1_behavior (int, default: 0)
  • TODO
gpio1_pin_mode (int, default: 0)
  • TODO
gpio2_feature (int, default: 0)
  • TODO
gpio2_behavior (int, default: 0)
  • TODO
gpio2_pin_mode (int, default: 0)
  • TODO
gpio3_feature (int, default: 0)
  • TODO
gpio3_behavior (int, default: 0)
  • TODO
gpio3_pin_mode (int, default: 0)
  • TODO
gpio4_feature (int, default: 0)
  • TODO
gpio4_behavior (int, default: 0)
  • TODO
gpio4_pin_mode (int, default: 0)
  • TODO
gpio_config (bool, default: false)
  • Controls whether the driver should configure the GPIO pins
filter_init_condition_src (int, default: 0)
  • Init Condition Source. 0 = Auto, 1 = Manual Heading, 2 = Manual Attitude, 3 = Manual
filter_auto_heading_alignment_selector (int, default: 1)
  • Bit field that controls auto heading alignment. Bit 0 is for Dual-antenna GNSS. Bit 1 is for GNSS kinematic. Bit 2 is for Magnetometer
filter_init_reference_frame (int, default: 2)
  • Reference Frame. 1 = WGS84 ECEF, 2 = WGS84 LLH
filter_init_position (array, default: [0.0,0.0,0.0])
  • TODO
filter_init_velocity (array, default: [0.0,0.0,0.0])
  • TODO
filter_init_attitude (array, default: [0.0,0.0,0.0])
  • TODO
publish_relative_position (bool, default: false)
  • TODO
filter_relative_position_frame (int, default: 2)
  • TODO
filter_relative_position_ref (array, default: [0,0,0.01])
  • TODO
filter_speed_lever_arm (array, default: [0.0,0.0,0.0])
  • TODO
filter_enable_wheeled_vehicle_constraint (bool, default: false)
  • TODO
filter_enable_vertical_gyro_constraint (bool, default: False)
  • TODO
filter_pps_source (int, default: 1)
  • TODO
filter_enable_gnss_antenna_cal (bool, default: false)
  • TODO
filter_gnss_antenna_cal_max_offset (float, default: 0.1)
  • TODO

Wiki: microstrain_inertial_driver/devices/archive (last edited 2022-01-19 15:54:59 by IanMoore)