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

TF problems while using robot_localization with navigation stack/move_base in a static map environment

asked 2019-09-30 07:56:49 -0500

enthusiast.australia gravatar image

updated 2019-10-02 11:04:33 -0500

hello everyone, i have updated my question because of finding the error i have. I am using a static map which i provide to map server through this launch file.

<launch>

      <arg name="map_file" default="$(find provide_map)/maps/map.yaml"/>

      <!-- Run the map server -->
      <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" >
            <param name="frame_id" value="odom"/>
     </node>

    </launch>

If i launch this file without fram id=odom, it gives me error in rviz that no Transform from map to odom.

Now i am using robot_localization along with navigation stack/move_base. THe robot detects its position in map, go to goal accordingly. The only problem is of base_footprint. It is relying only on odomtery and not on output of robot_localization. Error, when i pick and place rabot randomly, it works but sometimes base_footprint goes out of map, resulting in no path generation. Below is a picture of RVIZ to enlighten the problem.

image description

My move_base launch file is

<launch>
  <!-- Arguments -->
  <arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
  <arg name="cmd_vel_topic" default="/cmd_vel" />
  <arg name="odom_topic" default="odom" />
  <arg name="move_forward_only" default="false"/>

      <!-- move_base -->
      <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
        <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
        <rosparam file="$(find turtlebot3_2dnav)/param/costmap_common_params_$(arg model).yaml" command="load" ns="global_costmap" />
        <rosparam file="$(find turtlebot3_2dnav)/param/costmap_common_params_$(arg model).yaml" command="load" ns="local_costmap" />
        <rosparam file="$(find turtlebot3_2dnav)/param/local_costmap_params.yaml" command="load" />
        <rosparam file="$(find turtlebot3_2dnav)/param/global_costmap_params.yaml" command="load" />
        <rosparam file="$(find turtlebot3_2dnav)/param/base_local_planner_params.yaml" command="load" />
        <rosparam file="$(find turtlebot3_2dnav)/param/dwa_local_planner_params_$(arg model).yaml" command="load" />
        <remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
        <remap from="odom" to="$(arg odom_topic)"/>
        <param name="DWAPlannerROS/min_vel_x" value="0.0" if="$(arg move_forward_only)" />
      </node>
    </launch>

Local_coatmap.yaml

local_costmap:
  global_frame: base_footprint
  robot_base_frame: base_link

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5  

  static_map: true  
  rolling_window: true
  width: 3
  height: 3
  resolution: 0.05

Global_costmap:

global_costmap:
  global_frame: odom
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5

  static_map: true

If i change the value of robot_base frame to base_link, it gives me error. Could not get robot pose. How should i make my tf tree and which frame should be used in which file?

Ekf_template.yaml

   frequency: 30
    sensor_timeout: 0.1
    two_d_mode: false
    transform_time_offset: 0.0
    transform_timeout: 0.0
    print_diagnostics: true
    debug: false
    debug_out_file: /path/to/debug/file.txt
    publish_tf: true
    map_frame: map            
    odom_frame: odom           
    base_link_frame: base_footprint
    world_frame: odom           
    odom0: odom

    odom0_config: [false, false,  false,
                   false, false, true,
                   false, false, false,
                   false, false, false,
                   false, false, false]

    odom0_queue_size: 2
    odom0_nodelay: false
    odom0_differential: false
    odom0_relative: false
    odom0_pose_rejection_threshold: 5
    odom0_twist_rejection_threshold: 1

    odom1: odom1
    odom1_config: [true, true, false,
                   false, false, false,
                   false, false, false,
                   false, false, false,
                   false, false, false]
    odom1_differential: false
    odom1_relative: true
    odom1_queue_size: 2
    odom1_pose_rejection_threshold: 2
    odom1_twist_rejection_threshold: 0.2
    odom1_nodelay: false
    use_control: false
    stamped_control ...
(more)
edit retag flag offensive close merge delete

Comments

Your odom0_config says that you are not taking x,y and z of odom0 into account.

Choco93 gravatar image Choco93  ( 2019-09-30 09:07:05 -0500 )edit

yes. I am doing so. But i am taking x,y from odom1 instead of Odom0. And it is not working. Is my approach not possible/valid?

enthusiast.australia gravatar image enthusiast.australia  ( 2019-09-30 09:13:37 -0500 )edit

Should be possible, but there was some problem with it if I remember correctly. Try switching, make odom0 odom1 and vice versa

Choco93 gravatar image Choco93  ( 2019-09-30 09:17:17 -0500 )edit

I tried but still same error which i have mentioned in my main question.

enthusiast.australia gravatar image enthusiast.australia  ( 2019-09-30 10:27:04 -0500 )edit

can you also share your tf_tree?

Choco93 gravatar image Choco93  ( 2019-10-01 02:37:52 -0500 )edit

I have provided the tf tree in my updated question

enthusiast.australia gravatar image enthusiast.australia  ( 2019-10-01 04:40:48 -0500 )edit

Did you solve the issue?

Ahmed1212 gravatar image Ahmed1212  ( 2019-10-06 14:51:02 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2019-11-28 04:35:19 -0500

Tom Moore gravatar image

Your frame_ids need some attention.

First, I'd read REP-105. ROS navigation generally assumes that you have three frames:

  • map - Your robot's pose in the map frame is meant to be referenced from the map itself, i.e., it should either come from something that's, e.g., matching laser scans to a map, or it could come from an r_l EKF instance that is fusing the output of a scan-to-map matching node. The robot's pose in the map frame should be very accurate, but may be subject to discrete discontinuities ("jumps"). move_base generates its plans in this frame.
  • odom - Your robot's pose in the odom frame is usually not referenced to the map, and will drift over time. Your pose estimate in this frame will come from things like wheel encoders, or an EKF instance that is fusing wheel odometry data. This is the frame in which control/local planning happens in move_base.
  • base_link (or base_footprint) - The coordinate frame whose origin is (usually) at your robot's centroid, or center of mass, projected into the ground plane.

Your robot's pose in the map frame is given by the map->base_link transform. Your robot's pose in the odom frame is given by the odom->base_link transform. But tf doesn't let you have two parents to the same frame, so we apply some simple transformation math and end up with a transform chain that goes map->odom->base_link.

It seems to me that you are trying to operate just in the odom frame for everything. That's fine to start, and will work well for simulation. However, tf will also be very unhappy if you let two different nodes publish the same transform. In this case, your EKF instance is generating odom->base_footprint. I'm thinking that whatever is generating your wheel encoder odometry is also publishing that transform, so you need to see if the node in question has a parameter to stop it from publishing that transform (most do).

Also, your move_base config is not going to work well, I think. I'd change it to this:

local_costmap:
  global_frame: odom
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5  

  static_map: true  
  rolling_window: true
  width: 3
  height: 3
  resolution: 0.05

global_costmap:
  global_frame: odom
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5

  static_map: true
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-09-30 07:56:49 -0500

Seen: 577 times

Last updated: Nov 28 '19