Sample code illustrating how to develop ROS applications using the Intel® RealSense™ ZR300 camera for Object Library (OR), Person Library (PT), and Simultaneous Localization And Mapping (SLAM).
Apache License 2.0
127
stars
92
forks
source link
questions about imu information of ZR300, how to calibrate the raw imu data #15
I am trying to use ZR300 to run VINS-Mono(https://github.com/HKUST-Aerial-Robotics/VINS-Mono). I find that the output of the imu date topic:/camera/imu/data_raw has not been calibrated.
Then I get the calibration information of IMU data ZR300 ROS driver(https://github.com/IntelRealSense/realsense_samples_ros/tree/kinetic-devel/realsense_ros_camera), the output of topic /camera/accel/imu_info is like this:
data: [1.0236904621124268, 0.0, 0.0, -0.0455622673034668, 0.0, 1.0147671699523926, 0.0, 0.14746201038360596, 0.0, 0.0, 0.9979372620582581, -0.41241949796676636]
noise_variances: [0.14709974825382233, 0.14709974825382233, 0.14709974825382233]
bias_variances: [9.999999747378752e-05, 9.999999747378752e-05, 9.999999747378752e-05]
I think this 12-dimensions matrix is the calibration info. It can be rewritten like this:
data: [ 1.0236904621124268, 0.0, 0.0, -0.0455622673034668,
0.0, 1.0147671699523926, 0.0, 0.14746201038360596,
0.0, 0.0, 0.9979372620582581, -0.41241949796676636]
It looks like a Homogeneous transformation matrix. So I use it to calibrate the accel data[accel_x, accel_y,accel_z]'. I'm not sure how to do it. I try a reasonable way:
calibrated_accel_x= (accel_x-(-0.0455622673034668))*1.0236904621124268
the other two axes are calibrated in the same way. But it doesn't work. Actually, I have tried all possible combinations to calibrate the raw data. None of them provide a reasonable result.
So is this calibration information of IMU reliable? Is there any SDK to calibrate the raw imu data?
System Configuration
I am trying to use ZR300 to run VINS-Mono(https://github.com/HKUST-Aerial-Robotics/VINS-Mono). I find that the output of the imu date topic:/camera/imu/data_raw has not been calibrated. Then I get the calibration information of IMU data ZR300 ROS driver(https://github.com/IntelRealSense/realsense_samples_ros/tree/kinetic-devel/realsense_ros_camera), the output of topic /camera/accel/imu_info is like this: data: [1.0236904621124268, 0.0, 0.0, -0.0455622673034668, 0.0, 1.0147671699523926, 0.0, 0.14746201038360596, 0.0, 0.0, 0.9979372620582581, -0.41241949796676636] noise_variances: [0.14709974825382233, 0.14709974825382233, 0.14709974825382233] bias_variances: [9.999999747378752e-05, 9.999999747378752e-05, 9.999999747378752e-05]
I think this 12-dimensions matrix is the calibration info. It can be rewritten like this: data: [ 1.0236904621124268, 0.0, 0.0, -0.0455622673034668, 0.0, 1.0147671699523926, 0.0, 0.14746201038360596, 0.0, 0.0, 0.9979372620582581, -0.41241949796676636] It looks like a Homogeneous transformation matrix. So I use it to calibrate the accel data[accel_x, accel_y,accel_z]'. I'm not sure how to do it. I try a reasonable way:
calibrated_accel_x= (accel_x-(-0.0455622673034668))*1.0236904621124268 the other two axes are calibrated in the same way. But it doesn't work. Actually, I have tried all possible combinations to calibrate the raw data. None of them provide a reasonable result.
So is this calibration information of IMU reliable? Is there any SDK to calibrate the raw imu data?