ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Would you mind posting your entire launch file and a sample message from each input that you have? Feel free to remove comments from the launch file to make it less cluttered. It sounds like there may be some issues with frame IDs.
2 | No.2 Revision |
Would you mind posting your entire launch file and a sample message from each input that you have? Feel free to remove comments from the launch file to make it less cluttered. It sounds like there may be some issues with frame IDs.
EDIT: OK, I've got this sorted. First, I'll give you an updated launch file:
<launch>
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true">
<param name="frequency" value="30"/>
<param name="sensor_timeout" value="0.1"/>
<param name="two_d_mode" value="false"/>
<param name="map_frame" value="odom_imu"/>
<param name="odom_frame" value="odom"/>
<param name="base_link_frame" value="base_projected"/>
<param name="world_frame" value="odom_imu"/>
<param name="odom0" value="/odom"/>
<param name="imu0" value="/imu/data"/>
<rosparam param="odom0_config">[true, true, false,
false, false, true,
false, true, true,
false, false, false,
false, false, false]</rosparam>
<rosparam param="imu0_config">[false, false, false,
true, true, true,
false, false, false,
false, false, false,
false, false, false]</rosparam>
<param name="odom0_differential" value="true"/>
<param name="imu0_differential" value="true"/>
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<param name="debug" value="true"/>
<param name="debug_out_file" value="debug_ekf.txt"/>
<rosparam param="process_noise_covariance">[0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015]</rosparam>
</node>
</launch>
Now some notes:
ekf_localization_node
or ukf_localization_node
for generating the map->odom transform AND were using differential integration of absolute measurements. I'm surprised you were getting position estimates that jumped around (perhaps that's not what you meant), but they were inaccurate. odom0_config
, I enabled fusing Y and Z velocity, as your robot appears to be ground-based an nonholonomic. See this page.odom
) and the filtered output (odometry/filtered
), they will appear right on top of one another no matter what. This indicates that the odom_imu->odom transform is being computed correctly, and rviz
is just carrying out the transform before drawing the odometry.3 | No.3 Revision |
Would you mind posting your entire launch file and a sample message from each input that you have? Feel free to remove comments from the launch file to make it less cluttered. It sounds like there may be some issues with frame IDs.
EDIT: OK, I've got this sorted. First, I'll give you an updated launch file:
<launch>
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true">
<param name="frequency" value="30"/>
<param name="sensor_timeout" value="0.1"/>
<param name="two_d_mode" value="false"/>
<param name="map_frame" value="odom_imu"/>
<param name="odom_frame" value="odom"/>
<param name="base_link_frame" value="base_projected"/>
<param name="world_frame" value="odom_imu"/>
<param name="odom0" value="/odom"/>
<param name="imu0" value="/imu/data"/>
<rosparam param="odom0_config">[true, true, false,
false, false, true,
false, true, true,
false, false, false,
false, false, false]</rosparam>
<rosparam param="imu0_config">[false, false, false,
true, true, true,
false, false, false,
false, false, false,
false, false, false]</rosparam>
<param name="odom0_differential" value="true"/>
<param name="imu0_differential" value="true"/>
<param name="imu0_remove_gravitational_acceleration" value="true"/>
<param name="debug" value="true"/>
<param name="debug_out_file" value="debug_ekf.txt"/>
<rosparam param="process_noise_covariance">[0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0,
0.0, 0.0, 0.0, 0.0, 0.00, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015]</rosparam>
</node>
</launch>
Now some notes:
ekf_localization_node
or ukf_localization_node
for generating the map->odom transform AND were using differential integration of absolute measurements. I'm surprised you were getting position estimates that jumped around (perhaps that's not what you meant), but they were inaccurate. odom0_config
, I enabled fusing Y and Z velocity, as your robot appears to be ground-based an nonholonomic. See this page.odom
) and the filtered output (odometry/filtered
), they will appear right on top of one another no matter what. This indicates that the odom_imu->odom transform is being computed correctly, and rviz
is just carrying out the transform before drawing the odometry.