The ROS package can calibrate a IMU sensor.
Bias correction is required when measuring geomagnetic field with magnetic sensors. In magnetic calibration, the robot is rotated and the bias is estimated from the magnetic field data.
In this calibration, the following minimization problem is solved under the assumption that the collected magnetic field data form a circle on the same plane.
where
duration
: Duration of correction sensor data (default:60.0[s]
)velocity
: Angular velocity of rotation (default:0.2[rad/s]
)output_file
: Output file name (default:"path/to/imu_calibration/config/mag.yaml"
)visualize
: Visualize the calibration result (default:false
)
mag
(sensor_msgs/MagneticField)
Sensor value of the magnetic field to be calibrated
cmd_vel
(geometry_msgs/Twist)
Command to rotate the robot
roslaunch imu_calibration magnetic_calibration.launch
Please remap topics if necessary.
If visualize==true
, you will get the result shown in the figure below after the calibration is completed.
The results output to log and output_file can be used as correction parameters for the IMU driver node or for imu_filter_madgwick.
Collect data from IMU that is stationary and analyze Allan variance.
duration
: Duration of correction sensor data (default:60.0[s]
)rate
: Sensing rate (default:100[Hz]
)
data
(sensor_msgs/Imu)
Sensor value of the IMU
roslaunch imu_calibration analyze_imu.launch
Collect data from IMU that is stationary and calibrate the accelerometer tilt.
duration
: Duration of correction sensor data (default:60.0[s]
)base_frame
: Parent frame name (default:base_link
)result_file
: Output file name (default:"path/to/imu_calibration/launch/calibrated_tf.launch"
)
data
(sensor_msgs/Imu)
Sensor value of the IMU
roslaunch imu_calibration imu_calibration.launch
The args in calibrated_imu_tf node will be updated.
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<node name="calibrated_imu_tf" pkg="tf2_ros" type="static_transform_publisher" args="0.0 0.0 0.365 -0.021576252090569317 0.03782048416212938 0.0 0.9990515884194701 base_link imu_link"/>
</launch>