Show EOL distros: 

imu_drivers: microstrain_3dmgx2_imu

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

imu_drivers: microstrain_3dmgx2_imu

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

imu_drivers: microstrain_3dmgx2_imu

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

imu_drivers: microstrain_3dmgx2_imu

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

pr2: audio_common | camera1394 | hokuyo_node | joystick_drivers | linux_networking | microstrain_3dmgx2_imu | pr2_base | pr2_ethercat_drivers | pr2_navigation_apps | pr2_power_drivers | pr2_robot | prosilica_camera | sicktoolbox | sicktoolbox_wrapper | wge100_driver | wifi_ddwrt

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

pr2: audio_common | hokuyo_node | joystick_drivers | linux_networking | microstrain_3dmgx2_imu | pr2_apps | pr2_base | pr2_ethercat_drivers | pr2_navigation_apps | pr2_power_drivers | pr2_robot | prosilica_camera | wge100_driver | wifi_ddwrt

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

  • Maintainer status: maintained
  • Maintainer: Chad Rockey <chadrockey AT gmail DOT com>
  • Author: Jeremy Leibs, Blaise Gassend
  • License: LGPL
pr2: audio_common | joystick_drivers | linux_networking | microstrain_3dmgx2_imu | pr2_apps | pr2_base | pr2_ethercat_drivers | pr2_navigation_apps | pr2_power_drivers | pr2_robot | prosilica_camera | urg_node | wge100_driver | wifi_ddwrt

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

Package Summary

A driver for IMUs compatible the microstrain 3DM-GX2 and 3DM-GX3 protocol. Includes a heavily modified standalone driver pulled from the player distribution, and a ROS node.

imu.png

(original 3DM-GX2 coordinate system)

Who Should Use this Package?

  • If you are running on the PR2/Texas robot this driver should be running by default when you bring up the robot. You do not need to launch it yourself.
  • If you want to use 3DM-GX2 compatible IMU with ROS, use the imu_node.

  • For advanced users who want lower-level access to a 3DB-GX2 compatible IMU, the unsupported C++ API may be used.

Supported Hardware

This driver should work with IMUs that use the Microstrain 3DM-GX2 protocol.

API Stability

The ROS API of this node should be considered stable.

While a C++ API exists, it has not been reviewed and should be considered unstable.

ROS API

imu_node

imu_node is a driver for the 3DM-GX2 Inertial Measurement Unit. It publishes orientation, angular velocity and linear acceleration as well as their covariances, and complies with the IMU API. This node only provides streaming access to message 0xC8 (Acceleration, Angular Rate and Orientation), the unsupported C++ API gives access to a broader range of message types.

Published Topics

imu/data (sensor_msgs/Imu)
  • Streaming inertial data from the IMU. Includes acceleration, angular rates and orientation. The orientation is produced by the IMU firmware, which uses gravity, and in some cases the Earth's magnetic field, to remove integration drift. The orientation matrix is the transpose of the orientation matrix returned by the hardware, rotated 180 degrees around the y axis. This corresponds to a transformation from the IMU frame to the world frame, with the z axis point up.
diagnostics (diagnostic_msgs/DiagnosticArray)
  • Diagnostic status information.
imu/is_calibrated (std_msgs/Bool)
  • Latched topic indicating if the gyroscope biases have been calibrated.

Services

~self_test (diagnostic_msgs/SelfTest)
  • Starts the imu self test.
imu/calibrate (std_srvs/Empty)
  • Tells the IMU to (re)calibrate its gyroscope biases. The service call returns once calibration is complete. Calibration failure can be detected by subscribing to the imu/is_calibrated topic. A message will published to imu/is_calibrated for each call to imu/calibrate.

Parameters

~port (string, default: /dev/ttyUSB0)
  • The port the imu is running on.
~frame_id (string, default: imu)
  • The frame in which imu readings will be returned.
~autocalibrate (bool, default: true)
  • Whether the imu automatically computes its biases at startup (set to false if you intend to calibrate via the calibrate service).
~orientation_stdev (double, default: 0.035)
  • Square root of the orientation_covariance diagonal elements in rad. The default value, derived from the manufacturer datasheet, is very conservative.
~angular_velocity_stdev (double, default: 0.012)
  • Square root of the angular_velocity_covariance diagonal elements in rad/s. The default value, derived from the manufacturer datasheet, is very conservative.
~linear_acceleration_stdev (double, default: 0.098)
  • Square root of the linear_acceleration_covariance diagonal elements in m/s^2. The default value, derived from the manufacturer datasheet, is very conservative.
~max_drift_rate (double, default: 0.0001)
  • Just after performing a calibration, if the observed gyro rates are greater than this parameter, the calibration is assumed to have failed, and the imu starts reporting itself as uncalibrated. New in C Turtle
~assume_calibrated (bool, default: false)
  • Indicates whether the IMU should assume that it is calibrated at startup. New in C Turtle

Communication Protocol Manual

The 3DM-GX2 protocol can be found here.

Wiki: microstrain_3dmgx2_imu (last edited 2013-11-12 16:40:17 by autonomy)