Fusing absolute position information and IMU-data using the ekf_localization_node
Hello,
I have a robot car with a laser-scanner and an imu and would like to fuse the position information of the two sensors.
For laser based localization I am using the hector_mapping node which produces a /poseupdate topic. Additionally I am using an imu producing the /imu/data topic.
Those two shall be fused to provide a more accurate position estimate at a higher rate.
After incorporating the suggestions from Tom Moore my launch files look like this:
Edit 1
I am getting better behaviour now. What I did is based on the following thoughts: The odom->baselink transformation according to Rep105 should only be computed by odometry sources (by def. relativ/differential information). However before I was using differential set to false in the /imu0 data of the odom->baselink ekf, so the odometry got the absolute heading information from the imu. Could this have caused the orientation errors?
As I understood Rep105 the map->odom transform is computed indirectly by using absolute sensory information. So I thought it needs the absolute information from all source. That is why I set, differential to false for the imu topic of the map->odom ekf.
Here are my updated launchfiles (the mess with hector frames reverted):
The odom-baselink ekf-instance:
<launch>
<!-- Start Navigation Stack -->
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/>
<param name="map_size" value="2048"/>
<param name="pub_map_odom_transform" value="false"/>
<param name="pub_map_scanmatch_transform" value="false"/>
</node>
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_node" output="screen">
<param name="print_diagnostics" value="true"/>
<param name="frequency" value="100"/>
<param name="two_d_mode" value="true"/>
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/>
<param name="world_frame" value="odom"/>
<param name="base_link_frame" value="base_link"/>
<param name="pose0" value="/poseupdate"/>
<rosparam param="pose0_config">
[true, true, false, <!-- You have two_d_mode on, so making Z true does nothing -->
false, false, true,
false, false, false,
false, false, false,
false, false, false]
</rosparam>
<param name="pose0_differential" value="true"/>
<param name="imu0" value="/imu"/>
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<rosparam param="imu0_config">
[false, false, false,
false, false, true, <!-- 2D mode, so roll and pitch do nothing -->
false, false, false,
false, false, true, <!-- As above -->
true, true, false] <!-- Start with these turned off, verify that everything works, then turn X and Y back on (Z does nothing in 2D mode) -->
</rosparam>
<param name="imu0_relative" value="true"/>
<param name="imu0_differential" value="true"/>
</node>
The map-odom ekf:
<launch>
<node pkg="robot_localization" type="ekf_localization_node" name="aux_ekf_localization_node" output="screen">
<param name="print_diagnostics" value="true"/>
<param name="frequency" value="100"/>
<param name="two_d_mode" value="true"/>
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/>
<param name="world_frame" value="map"/>
<param name="base_link_frame" value="base_link"/>
<param name="pose0" value="/poseupdate"/>
<rosparam param="pose0_config">
[true, true, false,
false, false, true,
false, false, false,
false, false, false,
false, false, false]
</rosparam>
<param name="pose0_differential" value="false"/>
<param name="imu0" value="/imu"/>
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<rosparam param="imu0_config">
[false, false, false,
false, false, true,
false ...