#keywords imu, drivers, driver, inertial measurement unit, gyro <> <> {{attachment:IMUs.jpg}} == Supported Hardware == The following drivers implement the IMU API: * !MicroStrain 3DM-GX2 IMU: supported in the [[microstrain_3dmgx2_imu]] package. * Wiimote with Wii Motion Plus: supported by the [[wiimote]] package in the [[joystick_drivers]] stack. * !PhidgetsSpatial devices (3/3/3 Basic/High Resolution): supported by the [[phidgets_imu|phidgets_imu]] package. Other IMU drivers can be found here: * Driver for Xsens MTx/MTi/MTi-G: [[xsens_driver]] * Drivers for the Xsens MTI IMU: [[xsens_mti]], [[lse_xsens_mti]] * Driver for LP-RESEARCH IMU sensors: [[openzen_sensor]] == IMU Usage Examples == * The [[robot_pose_ekf]] package combines pose information coming from an IMU and other sensors to determine the pose of the robot. == ROS API == <> {{{#!clearsilver CS/NodeAPI node.0 { name=IMU Nodes desc=To encourage compatibility between IMU nodes, it is recommended that IMU nodes provide the following minimal API: pub{ 0.name= imu/data 0.type= sensor_msgs/Imu 0.desc= Streaming inertial data from the IMU, which can include angular rates, acceleration and orientation. Because orientation is an integrated quantity, and different IMUs have different strategies for removing drift from their integrated measurements, the precise meaning of the orientation matrix is device-dependent. 1.name= imu/is_calibrated 1.type= std_msgs/Bool 1.desc= Latched topic indicating if the gyroscope biases have been calibrated. } srv{ 0.name= imu/calibrate 0.type= std_srvs/Empty 0.desc= 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`. } } }}} == Report a Bug == <> ##Please create this page with template "PackageReviewIndex" ## CategoryStack ## CategoryStackROSPKG