This package includes ROS driver software for the InvenSense MPU9250 9DoF IMU. A ROS node publishes data from the IMU, and permits configuration through the ROS Parameter Server. A Raspberry Pi driver is included, but users may also easily create other device-specific drivers by extending the base driver class.
License: MIT
Author: Paul D'Angio
To build from source, clone the latest version from this repository into your catkin workspace and compile the package using
# Switch to your catkin workspace directory.
cd catkin_workspace
# Clone the package into the workspace src directory.
git clone https://github.com/pcdangio/ros-driver_mpu9250.git src/driver_mpu9250
# Build the package.
catkin_make
This package includes a ROS node that publishes data from the IMU and permits configuration through the ROS Parameter Server.
The table below describes parameters may be set on the ROS Parameter Server to configure the MPU9250. These parameters must be set before the ROS node is run. Recall that ~
is the node's private namespace.
Parameter | Type | Default | Description |
---|---|---|---|
~/i2c_bus |
int | 1 | The I2C bus number to communicate with the MPU9250 over. |
~/i2c_address |
int | 0x68 | The I2C address of the MPU9250. |
~/interrupt_gpio_pin |
int | 0 | The GPIO input pin connected to the MPU9250's interrupt pin. NOTE: You must use GPIO numbers, not pin numbers. |
~/gyro_dlpf_frequency |
int | 0 | An enum value representing the digital low pass filter (DLPF) cutoff frequency for the gyroscopes and temperature sensor. See table for enumerated DLPF values to select from. |
~/accel_dlpf_frequency |
int | 0 | An enum value representing the digital low pass filter (DLPF) cutoff frequency for the accelerometers. See table for enumerated DLPF values to select from. |
~/gyro_fsr |
int | 0 | The full scale range (FSR) of the gyroscopes. See table for enumerated FSR values to select from. |
~/accel_fsr |
int | 0 | The full scale range (FSR) of the accelerometers. See table for enumerated FSR values to select from. |
~/max_data_rate |
float | 8000 | The maximum allowable sensor data rate, in Hz. The sensor's data rate is normally calculated from the DLPF frequencies, but this parameter may be used to set a lower cap on the data rate. |
~/calibration/accelerometer |
float[16] | empty | The 4x4 calibration matrix for the accelerometer in row-major order. See the calibration section for more information. |
~/calibration/magnetometer |
float[16] | empty | The 4x4 calibration matrix for the magnetometer in row-major order. See the calibration section for more information. |
Run any of the driver nodes with (where xxx is the driver type):
rosrun driver_mpu9250 driver_mpu9250_xxx
To use the driver node for a Raspberry Pi:
# Make sure that the linux user has been added to the "gpio" group.
# In one terminal, start up the PiGPIO Daemon.
sudo pigpiod
# In a second terminal, start up the driver.
rosrun driver_mpu9250 driver_mpu9250_rpi
Topic | Message Type | Description |
---|---|---|
imu/accelerometer |
sensor_msgs_ext/accelerometer | The 3D acceleration measurements from the MPU9250. |
imu/gyroscope |
sensor_msgs_ext/gyroscope | The 3D gyroscope measurements from the MPU9250. |
imu/magnetometer |
sensor_msgs_ext/magnetometer | The 3D magnetic field measurements from the onboard AK8963 compass. |
imu/temperature |
sensor_msgs_ext/temperature | The die temperature of the MPU9250 sensor |
Service | Service Type | Description |
---|---|---|
imu/calibrate_gyroscope |
sensor_msgs_ext/calibrate_gyroscope | Calibrates the gyroscope by calculating and removing gyroscope bias. The bias is calculated by averaging gyroscope data over an averaging period. See the calibration section below for more detail. |
This package uses polymorphism with a base driver class to enable drivers to be easily built for a variety of hardware interfaces. To create your own device-specific driver:
src/driver.h
src/ros_node.h
instance through polymorphism before running the node.You can refer to the following files in this package as an example for creating your custom device driver:
src/rpi_driver.h
src/rpi_driver.cpp
src/main_rpi.cpp
CMakeLists.txt
If you have created and tested a driver for a device not already covered in this package, please feel free to submit a pull request!
The "full-scale range", or FSR, of a sensor specifies the range of measurements that must be sensed. Smaller ranges will measure at higher resolution, while larger ranges will measure at lower resolution. The MPU9250 has several full-scale ranges to select from, as shown in the table below. The Enumerated Value is the integer that should be used in the ~/gyro_fsr
and ~/accel_fsr
ROS parameters during configuration.
Enumerated Value | Gyroscope Range | Accelerometer Range |
---|---|---|
0 | +/- 250 deg/sec | +/- 2g |
1 | +/- 500 deg/sec | +/- 4g |
2 | +/- 1000 deg/sec | +/- 8g |
3 | +/- 2000 deg/sec | +/- 16g |
The MPU9250 has internal Digital Low-Pass Filters (DLPF) that can be used to filter out unwanted noise from the gyroscope, accelerometer, and temperature measurements. The table below lists the available cutoff frequencies that can be chosen. Lower cutoff frequencies will filter out more noise, but will increase the lag (delay) of the measurements. The cutoff frequency selected for the gyroscopes is also applied to the temperature sensor. The Enumerated Value is the integer that should be used in the ~/gyro_dlpf_frequency
and ~/accel_dlpf_frequency
ROS parameters during configuration.
Enumerated Value | Gyroscope Cutoff | Gyroscope Delay | Accelerometer Cutoff | Accelerometer Delay |
---|---|---|---|---|
0 | 250 Hz | 0.97ms | 218.1 Hz | 1.88ms |
1 | 184 Hz | 2.9ms | - | - |
2 | 92 Hz | 3.9ms | 99 Hz | 2.88ms |
3 | 41 Hz | 5.9ms | 44.4 Hz | 4.88ms |
4 | 20 Hz | 9.9ms | 21.2 Hz | 8.87ms |
5 | 10 Hz | 17.85ms | 10.2 Hz | 16.83ms |
6 | 5 Hz | 33.48ms | 5.05 Hz | 32.48ms |
The data rate is the frequency at which the sensor makes measurements and publishes them through ROS. This driver automatically calculates the appropriate data rate based on the cutoff frequencies of the DLPFs of the acceleremeters and gyroscopes. The driver finds which DLPF has the highest cutoff frequency, and multiplies that frequency by 2.5 to calculate a data rate with a proper Nyquist sampling rate. The calculated data rate is output to the node's ROS log at startup.
The ~/max_data_rate
parameter can be used to override the calculated data rate to a lower frequency.
Accelerometers, gyroscopes, and magnetometers all require calibration to provide accurate measurements:
This driver handles calibrations differently for each sensor:
The MPU9250's 3-axis accelerometer and 3-axis magnetometer have relatively stable bias (assuming no changes in sensor mounting and metals/magnets surrounding the magnetometer). Thus, the driver uses static calibration matrices to make adjustments to sensor data before it is published through ROS. These matrices can be calculated using the calibration_imu package, and set as parameters for the driver to load and use. NOTE: You should recalibrate the accelerometer and magnetometer any time you make hardware changes to your platform.
The MPU9250's 3-axis gyroscope, like all MEMs gyroscopes, suffers from continuous bias drift. Thus, it is necessary to regularly recalibrate the gyroscope when it is known that the IMU is not in motion. This calibration routine can be called through a service, which calculates the current bias of the gyroscope and subtracts it from future measurements.