Function 1: Provide ROS drivers for Xsens Mti series.
Function 2: Generate odometry message by median discrete integral of IMU data.
Function 3: Calibrate the noise and random walk noise of bias of IMU.
git clone --recursive https://github.com/yanliang-wang/imu_ws.git
Modify imu_ws/src/code_utils/src/sumpixel_test.cpp
: #include "backward.hpp"
--> #include “code_utils/backward.hpp”
catkin_make -DCATKIN_WHITELIST_PACKAGES="code_utils"
catkin_make -DCATKIN_WHITELIST_PACKAGES=""
roslaunch imu_odom read_data.launch
If there is an error called [ERROR] [1627211303.220970]: Fatal: could not find proper MT device.
May the following code will solve the problem.
sudo chmod 777 /dev/ttyUSB0
Modify imu_ws/src/imu_odom/config/test.yaml
imu_odom:
{
hz: 200, # the rate of odom published
g_vec: [0.0, 0.0, -9.81], # the gravity vector relative to initial frame
enable_position: false, # enable display of position of odom
sub_imu_topic: /imu/data, # the topic name of IMU to subscribe
pub_odom_topic: /imu/odom # the topic name of Odom to publish
}
roslaunch imu_odom test.launch
- Orientation change with low drift.
- Position change with high drift( IMU is stationary in this case ).
Refer to imu_utils.
Step:
- collect the data while the IMU is Stationary, with a two hours duration, at least two hours suggested;
- modify the param of the launch file;
<launch>
<node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
<param name="imu_topic" type="string" value= "/imu/data"/>
<param name="imu_name" type="string" value= "xsens"/>
<param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
<param name="max_time_min" type="int" value= "200"/> <!-- the duration of your bag (Unit: minute) -->
<param name="max_cluster" type="int" value= "100"/>
</node>
</launch>
- roslaunch the rosnode and play the bag file;
roslaunch imu_utils xsens.launch
rosbag play -r 200 XXX.bag
- see the result;
The calibration result is saved in imu_ws/src/imu_utils/data
.