ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Your frame_ids
need some attention.
First, I'd read REP-105. ROS navigation generally assumes that you have three frames:
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.move_base
.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