Skip to content

Tacha-S/imu_calibration

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

14 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

IMU calibration

The ROS package can calibrate a IMU sensor.

Magnetic calibration

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.

$$ \text{Minimize}: \sum_i ((x_i-b_1)^2 + (y_i-b_2)^2 + (z_i-b_3)^2 - r^2)^2 + (a_1(x_i-b_1) + a_2(y_i-b_2)+a_3(z_i-b_3))^2 $$

where $x_i,y_i,z_i$ is the measurement data, $r$ is the radius of the circle, $\vec{a}$ is the normal vector of the plane and $\vec{b}$ is the bias.

Parameters

  • 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)

Inputs

Outputs

Example

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.

calibration_result

The results output to log and output_file can be used as correction parameters for the IMU driver node or for imu_filter_madgwick.

IMU analysis

Collect data from IMU that is stationary and analyze Allan variance.

Parameters

  • duration: Duration of correction sensor data (default: 60.0[s])
  • rate: Sensing rate (default: 100[Hz])

Inputs

Example

roslaunch imu_calibration analyze_imu.launch

analyze_result

IMU calibration

Collect data from IMU that is stationary and calibrate the accelerometer tilt.

Parameters

  • 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")

Inputs

Example

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>

About

No description, website, or topics provided.

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published