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

Revision history [back]

A look at REP105 will tell you that there typically are two frames odom and map. It further says that odom should be continuous whereas map can be discontinuous. This is mentioned in the excellent robot_localization wiki too. Per the recommendation there, you can have two instances of robot_localization running at the same time. One will integrate wheel odometry and imu (both continuous) to generate an estimate of your position in the http://docs.ros.org/en/melodic/api/robot_localization/html/state_estimation_nodes.html#published-transforms frame. This may drift over time! The second instance can integrate these again but with added VO (which might be discontinuous). This will generate an estimate in the map frame.

The image here shows such usage with gps but you can just replace the gps with VO.

You don't have to create two base_links. Both these instances will link to the same base_link and hence only one robot is needed for visualization. I believe this is the right way of setting up the robot_localization package. Of course, you can have just one instance that integrates all the above mentioned sensors in the frame of your choice (but this would go against convention).

This is an example of a launch file that can launch two instances simultaneously: <launch>

  <!-- robot_localization for fusing continous data (odom -> base_link) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_local" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_local.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/local" />
  </node>

  <!-- robot_localization for fusing discontinous data (map -> odom) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_global" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_global.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <remap from="vo_odom" to="/your/odom/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/global" />
  </node>

</launch>

An example param file. As in the launch file above, you will need two of these. For the global param file, replace world_frame with map and you should be set.

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom

frequency: 20

imu0: imu
imu0_config: [false, false, false,
              true, true, true,
              false, false, false,
              true, true, false,
              true, true, true]
imu0_differential: false
imu0_relative: false
imu0_queue_size: 1
imu0_remove_gravitational_acceleration: false

odom0: wheel_odom
odom0_config: [true, true, false,
               false, false, false,
               false, false, false,
               false, false, false,
               false, false, false]
odom0_differential: false
odom0_queue_size: 1

odom1: vo_odom
odom1_config: [true, true, true,    # x, y, z
               true, true, true,    # r, p, y
               false, false, false, # vx, vy, vz
               false, false, false, # wx, wy, wz
               false, false, false] # ax, ay, az
odom1_differential: false
odom1_queue_size: 2

A look at REP105 will tell you that there typically are two frames odom and map. It further says that odom should be continuous whereas map can be discontinuous. This is mentioned in the excellent robot_localization wiki too. Per the recommendation there, you can have two instances of robot_localization running at the same time. One will integrate wheel odometry and imu (both continuous) to generate an estimate of your position in the http://docs.ros.org/en/melodic/api/robot_localization/html/state_estimation_nodes.html#published-transforms frame. This may drift over time! The second instance can integrate these again but with added VO (which might be discontinuous). This will generate an estimate in the map frame.

The image here shows such usage with gps but you can just replace the gps with VO.

You don't have to create two base_links. Both these instances will link to the same base_link and hence only one robot is needed for visualization. I believe this is the right way of setting up the robot_localization package. Of course, you can have just one instance that integrates all the above mentioned sensors in the frame of your choice (but this would go against convention).

This is an example of a launch file that can launch two instances simultaneously: <launch>

  <!-- robot_localization for fusing continous data (odom -> base_link) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_local" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_local.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/local" />
  </node>

  <!-- robot_localization for fusing discontinous data (map -> odom) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_global" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_global.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <remap from="vo_odom" to="/your/odom/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/global" />
  </node>

</launch>

An example param file. As in the launch file above, you will need two of these. For the global param file, replace world_frame with map and you should be set.

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom

frequency: 20

imu0: imu
imu0_config: [false, false, false,
              true, true, true,
              false, false, false,
              true, true, false,
              true, true, true]
imu0_differential: false
imu0_relative: false
imu0_queue_size: 1
imu0_remove_gravitational_acceleration: false

odom0: wheel_odom
odom0_config: [true, true, false,
               false, false, false,
               false, false, false,
               false, false, false,
               false, false, false]
odom0_differential: false
odom0_queue_size: 1

odom1: vo_odom
odom1_config: [true, true, true,    # x, y, z
               true, true, true,    # r, p, y
               false, false, false, # vx, vy, vz
               false, false, false, # wx, wy, wz
               false, false, false] # ax, ay, az
odom1_differential: false
odom1_queue_size: 2

A look at REP105 will tell you that there typically are two frames odom and map. It further says that odom should be continuous whereas map can be discontinuous. This is mentioned in the excellent robot_localization wiki too. Per the recommendation there, you can have two instances of robot_localization running at the same time. One will integrate wheel odometry and imu (both continuous) to generate an estimate of your position in the http://docs.ros.org/en/melodic/api/robot_localization/html/state_estimation_nodes.html#published-transforms odom frame. This may drift over time! The second instance can integrate these again but with added VO (which might be discontinuous). This will generate an estimate in the map frame.

The image here shows such usage with gps but you can just replace the gps with VO.

You don't have to create two base_links. Both these instances will link to the same base_link and hence only one robot is needed for visualization. I believe this is the right way of setting up the robot_localization package. Of course, you can have just one instance that integrates all the above mentioned sensors in the frame of your choice (but this would go against convention).

This is an example of a launch file that can launch two instances simultaneously: <launch>

  <!-- robot_localization for fusing continous data (odom -> base_link) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_local" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_local.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/local" />
  </node>

  <!-- robot_localization for fusing discontinous data (map -> odom) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_global" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_global.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <remap from="vo_odom" to="/your/odom/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/global" />
  </node>

</launch>

An example param file. As in the launch file above, you will need two of these. For the global param file, replace world_frame with map and you should be set.

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom

frequency: 20

imu0: imu
imu0_config: [false, false, false,
              true, true, true,
              false, false, false,
              true, true, false,
              true, true, true]
imu0_differential: false
imu0_relative: false
imu0_queue_size: 1
imu0_remove_gravitational_acceleration: false

odom0: wheel_odom
odom0_config: [true, true, false,
               false, false, false,
               false, false, false,
               false, false, false,
               false, false, false]
odom0_differential: false
odom0_queue_size: 1

odom1: vo_odom
odom1_config: [true, true, true,    # x, y, z
               true, true, true,    # r, p, y
               false, false, false, # vx, vy, vz
               false, false, false, # wx, wy, wz
               false, false, false] # ax, ay, az
odom1_differential: false
odom1_queue_size: 2

A look at REP105 will tell you that there typically are two frames odom and map. It further says that odom should be continuous whereas map can be discontinuous. This is mentioned in the excellent robot_localization wiki too. Per the recommendation there, you can have two instances of robot_localization running at the same time. One will integrate wheel odometry and imu (both continuous) to generate an estimate of your position in the odom frame. This may drift over time! The second instance can integrate these again but with added VO (which might be discontinuous). This will generate an estimate in the map frame.

The image here shows such usage with gps but you can just replace the gps with VO.

You don't have to create two base_links. Both these instances will link to the same base_link and hence only one robot is needed for visualization. I believe this is the right way of setting up the robot_localization package. Of course, you can have just one instance that integrates all the above mentioned sensors in the frame of your choice (but this would go against convention).

This is an example of a launch file that can launch two instances simultaneously: <launch> simultaneously:

  <launch> 

  <!-- robot_localization for fusing continous data (odom -> base_link) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_local" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_local.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/local" />
  </node>

  <!-- robot_localization for fusing discontinous data (map -> odom) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_global" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_global.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <remap from="vo_odom" to="/your/odom/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/global" />
  </node>

</launch>

An example param file. As in the launch file above, you will need two of these. For the global param file, replace world_frame with map and you should be set.

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom

frequency: 20

imu0: imu
imu0_config: [false, false, false,
              true, true, true,
              false, false, false,
              true, true, false,
              true, true, true]
imu0_differential: false
imu0_relative: false
imu0_queue_size: 1
imu0_remove_gravitational_acceleration: false

odom0: wheel_odom
odom0_config: [true, true, false,
               false, false, false,
               false, false, false,
               false, false, false,
               false, false, false]
odom0_differential: false
odom0_queue_size: 1

odom1: vo_odom
odom1_config: [true, true, true,    # x, y, z
               true, true, true,    # r, p, y
               false, false, false, # vx, vy, vz
               false, false, false, # wx, wy, wz
               false, false, false] # ax, ay, az
odom1_differential: false
odom1_queue_size: 2

A look at REP105 will tell you that there typically are two frames odom and map. It further says that odom should be continuous whereas map can be discontinuous. This is mentioned in the excellent robot_localization wiki too. Per the recommendation there, you can have two instances of robot_localization running at the same time. One will integrate wheel odometry and imu (both continuous) to generate an estimate of your position in the odom frame. This may drift over time! The second instance can integrate these again but with added VO (which might be discontinuous). This will generate an estimate in the map frame.

The image here shows such usage with gps but you can just replace the gps with VO.

You don't have to create two base_links. Both these instances will link to the same base_link and hence only one robot is needed for visualization. I believe this is the right way of setting up the robot_localization package. Of course, you can have just one instance that integrates all the above mentioned sensors in the frame of your choice (but this would go against convention).

This is an example of a launch file that can launch two instances simultaneously:

  <launch> 

  <!-- robot_localization for fusing continous data (odom -> base_link) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_local" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_local.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/local" />
  </node>

  <!-- robot_localization for fusing discontinous data (map -> odom) -->
  <node pkg="robot_localization" type="ekf_localization_node" name="ekf_global" clear_params="true" if="true" >
    <!-- param -->
    <rosparam command="load" file="/your/path/params/ekf_global.yaml" />
    <!-- input -->
    <remap from="wheel_odom" to="/your/odom/topic" />
    <remap from="imu" to="/your/imu/topic" />
    <remap from="vo_odom" to="/your/odom/topic" />
    <!-- output -->
    <remap from="/odometry/filtered" to="/odometry/filtered/global" />
  </node>

</launch>

An example param file. As in the launch file above, you will need two of these. For the global param file, replace world_frame with map and you should be set.

map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom

frequency: 20

imu0: imu
imu0_config: [false, false, false,
              true, true, true,
              false, false, false,
              true, true, false,
              true, true, true]
imu0_differential: false
imu0_relative: false
imu0_queue_size: 1
imu0_remove_gravitational_acceleration: false

odom0: wheel_odom
odom0_config: [true, true, false,
               false, false, false,
               false, false, false,
               false, false, false,
               false, false, false]
odom0_differential: false
odom0_queue_size: 1

odom1: vo_odom
odom1_config: [true, true, true,    # x, y, z
               true, true, true,    # r, p, y
               false, false, false, # vx, vy, vz
               false, false, false, # wx, wy, wz
               false, false, false] # ax, ay, az
odom1_differential: false
odom1_queue_size: 2

Make sure you have the P and Q matrices set per your application