ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

  1. Yes, an "absolute" measurement means a measurement that is relative to the world (typically map or odom, but can be anything) frame.
  2. For your setup, I would suggest the following:
  3. You need something to generate the odom->base_link transform. For some robots, the node that generates the wheel encoder-based odometry message can also broadcast the odom->base_link transform. If yours does that, I would suggest turning that on (it may be on by default). If you were to add an IMU, I would stop your robot's driver from generating the odom->base_link transform and add another ekf_localization_node instance that fuses just the odometry and IMU data, and has the world_frame parameter set to odom.
  4. Assuming that you have something generating the the odom->base_link transform, then I think your configuration above is pretty good. As it is, it will generate that world->odom transform. I would ditch all the _rejection_threshold settings except for pose0_rejection_threshold. You can use that value to reject your noisy measurements from your visual tracker.
  1. Yes, an "absolute" measurement means a measurement that is relative to the world (typically map or odom, but can be anything) frame.
  2. For your setup, I would suggest the following:
  3. following:
    • You need something to generate the odom->base_link transform. For some robots, the node that generates the wheel encoder-based odometry message can also broadcast the odom->base_link transform. If yours does that, I would suggest turning that on (it may be on by default). If you were to add an IMU, I would stop your robot's driver from generating the odom->base_link transform and add another ekf_localization_node instance that fuses just the odometry and IMU data, and has the world_frame parameter set to odom.
    • Assuming that you have something generating the the odom->base_link transform, then I think your configuration above is pretty good. As it is, it will generate that world->odom transform. I would ditch all the _rejection_threshold settings except for pose0_rejection_threshold. You can use that value to reject your noisy measurements from your visual tracker.
  1. Yes, an "absolute" measurement means a measurement that is relative to the world (typically map or odom, but can be anything) frame.
  2. For your setup, I would suggest the following:
    • You need something to generate the odom->base_link transform. For some robots, the node that generates the wheel encoder-based odometry message can also broadcast the odom->base_link transform. If yours does that, I would suggest turning that on (it may be on by default). If you were to add an IMU, I would stop your robot's driver from generating the odom->base_link transform and add another ekf_localization_node instance that fuses just the odometry and IMU data, and has the world_frame parameter set to odom.
    • Assuming that you have something generating the the odom->base_link transform, then I think your configuration above is pretty good. As it is, it will generate that world->odom transform. I would ditch all the _rejection_threshold settings except for pose0_rejection_threshold. You can use that value to reject your noisy measurements from your visual tracker.

EDIT

Part of the trouble you're having is that your /odom topic is reported in the odom frame, but the filter needs to transform it to the map frame before fusing it. Since the filter itself is responsible for the map->odom transform and the headings between the two frames disagree, the transform heading keeps shifting, and you get the result you see.

This can be fixed, however. Does your /odom topic report linear and rotational velocity? If so, you should set X velocity, Y velocity, and yaw velocity for that topic to true, rather than X, Y, and yaw. Your bag file doesn't contain any motion, so it's hard to tell whether those are reported for your robot. You can leave your pose0 configuration in your latest bag file alone. I filtered your bag file to remove the transforms created by the EKF, edited your launch file, and ran everything, and it worked for me. Here's the launch file (eliminating covariance matrices for the sake of brevity):

<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="true"/>

    <param name="map_frame" value="world"/>
    <param name="odom_frame" value="odom"/>
    <param name="base_link_frame" value="base_link"/>
    <param name="world_frame" value="world"/>

    <param name="transform_time_offset" value="0.0"/>

    <param name="odom0" value="odom"/>
    <param name="pose0" value="robot_2d_geometry_pose"/>

    <rosparam param="odom0_config">[false, false, false,
                                  false, false, false,
                                  true, true, false,
                                  false, false, true,
                                  false, false, false]</rosparam>

    <rosparam param="pose0_config">[true,  true,  false,
                                  false, false, false,
                                  false, false, false,
                                  false, false, false,
                                  false, false, false]</rosparam>

    <param name="odom0_differential" value="true"/>
    <param name="pose0_differential" value="false"/>

    <param name="odom0_relative" value="false"/>

    <param name="print_diagnostics" value="true"/>

    <param name="odom0_queue_size" value="4"/>

    <param name="pose0_rejection_threshold" value="2"/>

    <param name="debug"           value="true"/>
    <param name="debug_out_file"  value="/Users/ayrton/Desktop/debug_ekf_localization.txt"/>

  </node>

</launch>

One thing I should change about the EKF is that it should let you turn on differential mode in this case and work. As of now, the messages get filtered out if they can't be transformed into the target frame, even if that sensor is just going to use differential mode.

  1. Yes, an "absolute" measurement means a measurement that is relative to the world (typically map or odom, but can be anything) frame.
  2. For your setup, I would suggest the following:
    • You need something to generate the odom->base_link transform. For some robots, the node that generates the wheel encoder-based odometry message can also broadcast the odom->base_link transform. If yours does that, I would suggest turning that on (it may be on by default). If you were to add an IMU, I would stop your robot's driver from generating the odom->base_link transform and add another ekf_localization_node instance that fuses just the odometry and IMU data, and has the world_frame parameter set to odom.
    • Assuming that you have something generating the the odom->base_link transform, then I think your configuration above is pretty good. As it is, it will generate that world->odom transform. I would ditch all the _rejection_threshold settings except for pose0_rejection_threshold. You can use that value to reject your noisy measurements from your visual tracker.

EDIT

Part of the trouble you're having is that your /odom topic is reported in the odom frame, but the filter needs to transform it to the map frame before fusing it. Since the filter itself is responsible for the map->odom transform and the headings between the two frames disagree, the transform heading keeps shifting, and you get the result you see.

This can be fixed, however. Does your /odom topic report linear and rotational velocity? If so, you should set X velocity, Y velocity, and yaw velocity for that topic to true, rather than X, Y, and yaw. Your bag file doesn't contain any motion, so it's hard to tell whether those are reported for your robot. You can leave your pose0 configuration in your latest bag file alone. I filtered your bag file to remove the transforms created by the EKF, edited your launch file, and ran everything, and it worked for me. Here's the launch file (eliminating covariance matrices for the sake of brevity):

<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="true"/>

    <param name="map_frame" value="world"/>
    <param name="odom_frame" value="odom"/>
    <param name="base_link_frame" value="base_link"/>
    <param name="world_frame" value="world"/>

    <param name="transform_time_offset" value="0.0"/>

    <param name="odom0" value="odom"/>
    <param name="pose0" value="robot_2d_geometry_pose"/>

    <rosparam param="odom0_config">[false, false, false,
                                  false, false, false,
                                  true, true, false,
                                  false, false, true,
                                  false, false, false]</rosparam>

    <rosparam param="pose0_config">[true,  true,  false,
                                  false, false, false,
                                  false, false, false,
                                  false, false, false,
                                  false, false, false]</rosparam>

    <param name="odom0_differential" value="true"/>
    <param name="pose0_differential" value="false"/>

    <param name="odom0_relative" value="false"/>

    <param name="print_diagnostics" value="true"/>

    <param name="odom0_queue_size" value="4"/>

    <param name="pose0_rejection_threshold" value="2"/>

    <param name="debug"           value="true"/>
value="false"/>
    <param name="debug_out_file"  value="/Users/ayrton/Desktop/debug_ekf_localization.txt"/>
value="debug_ekf_localization.txt"/>

  </node>

</launch>

One thing I should change about the EKF is that it should let you turn on differential mode in this case and work. As of now, the messages get filtered out if they can't be transformed into the target frame, even if that sensor is just going to use differential mode.

  1. Yes, an "absolute" measurement means a measurement that is relative to the world (typically map or odom, but can be anything) frame.
  2. For your setup, I would suggest the following:
    • You need something to generate the odom->base_link transform. For some robots, the node that generates the wheel encoder-based odometry message can also broadcast the odom->base_link transform. If yours does that, I would suggest turning that on (it may be on by default). If you were to add an IMU, I would stop your robot's driver from generating the odom->base_link transform and add another ekf_localization_node instance that fuses just the odometry and IMU data, and has the world_frame parameter set to odom.
    • Assuming that you have something generating the the odom->base_link transform, then I think your configuration above is pretty good. As it is, it will generate that world->odom transform. I would ditch all the _rejection_threshold settings except for pose0_rejection_threshold. You can use that value to reject your noisy measurements from your visual tracker.

EDIT

Part of the trouble you're having is that your /odom topic is reported in the odom frame, but the filter needs to transform it to the map frame before fusing it. Since the filter itself is responsible for the map->odom transform and the headings between the two frames disagree, the transform heading keeps shifting, and you get the result you see.

This can be fixed, however. Does your /odom topic report linear and rotational velocity? If so, you should set X velocity, Y velocity, and yaw velocity for that topic to true, rather than X, Y, and yaw. Your bag file doesn't contain any motion, so it's hard to tell whether those are reported for your robot. You can leave your pose0 configuration in your latest bag file alone. I filtered your bag file to remove the transforms created by the EKF, edited your launch file, and ran everything, and it worked for me. Here's the launch file (eliminating covariance matrices for the sake of brevity):

<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="true"/>

    <param name="map_frame" value="world"/>
    <param name="odom_frame" value="odom"/>
    <param name="base_link_frame" value="base_link"/>
    <param name="world_frame" value="world"/>

    <param name="transform_time_offset" value="0.0"/>

    <param name="odom0" value="odom"/>
    <param name="pose0" value="robot_2d_geometry_pose"/>

    <rosparam param="odom0_config">[false, false, false,
                                  false, false, false,
                                  true, true, false,
                                  false, false, true,
                                  false, false, false]</rosparam>

    <rosparam param="pose0_config">[true,  true,  false,
                                  false, false, false,
                                  false, false, false,
                                  false, false, false,
                                  false, false, false]</rosparam>

    <param name="odom0_differential" value="true"/>
    <param name="pose0_differential" value="false"/>

    <param name="odom0_relative" value="false"/>

    <param name="print_diagnostics" value="true"/>

    <param name="odom0_queue_size" value="4"/>

    <param name="pose0_rejection_threshold" value="2"/>

    <param name="debug"           value="false"/>
    <param name="debug_out_file"  value="debug_ekf_localization.txt"/>

  </node>

</launch>

One thing I should change about the EKF is that it should let you turn on differential mode in this case and work. As of now, the messages get filtered out if they can't be transformed into the target frame, even if that sensor is just going to use differential mode.

EDIT 2

However the odom frame keeps on moving w.r.t. to the world frame. Is this normal?

Sorry, do you mean the transform from world->odom is moving? One way to validate that everything is working is to visualize both odometry messages in rviz. If they overlay one another perfectly, then the transform is fine.

Then I wanted to ask, what's the right way to tune the process_noise_covariance matrix and the initial_estimate_covariance matrix?

The initial_estimate_covariance is straightforward: for every variable in the state vector that you're measuring, just make its diagonal value in the initial_estimate_covariance larger than the variances in the measurements.

The process_noise_covariance is harder. There are methods in the literature for tuning it, but it would require you to have pretty deep knowledge of the motion model I'm using and how well it matches your system. I tend to not do very much with it.