Costmap timeout
When using amcl having set the initial pose I'm getting a lot of warnings related to costmap:
Costmap2DROS transform timeout
Eventually followed by:
[ERROR] [1301261347.311430182]: Connectivity Error: Could not find a common time /base_link and /map.
My costmap parameters look like the following:
local_costmap:
global_frame: /odom
robot_base_frame: /base_link
update_frequency: 2.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 5.0
height: 5.0
resolution: 0.1
transform_tolerance: 0.5
global_costmap:
global_frame: /map
robot_base_frame: /base_link
update_frequency: 2.0
publish_frequency: 2.0
static_map: true
transform_tolerance: 0.5
rolling_window: true
width: 20.0
height: 20.0
resolution: 0.1
obstacle_range: 2.5
raytrace_range: 3.0
robot_radius: 0.3
footprint: [[-0.18, -0.24], [0.11, -0.24], [0.11, 0.24], [-0.18, 0.24]]
inflation_radius: 0.4
observation_sources: scan
scan: {sensor_frame: /kinect_fake_laser, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
I've checked /odom and it is indeed being published regularly throughout. Any ideas on what might be causing the above warnings and errors?
RESULTS: for all Frames
Frames:
Frame: /base published by /robot_state_publisher Average Delay: 0.00295674 Max Delay: 0.00692934
Frame: /base_link published by /odometry Average Delay: 0.0201343 Max Delay: 0.0437646
Frame: /collar published by /robot_state_publisher Average Delay: 0.00296054 Max Delay: 0.00693374
Frame: /front_side published by /robot_state_publisher Average Delay: 0.00296375 Max Delay: 0.00693695
Frame: /head_pan_bracket published by /robot_state_publisher Average Delay: 0.00296677 Max Delay: 0.00693988
Frame: /head_tilt_servo published by /robot_state_publisher Average Delay: 0.0029704 Max Delay: 0.00694373
Frame: /head_tilt_support_left published by /robot_state_publisher Average Delay: 0.00297362 Max Delay: 0.00694736
Frame: /head_tilt_support_right published by /robot_state_publisher Average Delay: 0.00297716 Max Delay: 0.0069512
Frame: /joystick published by /robot_state_publisher Average Delay: 0.00298044 Max Delay: 0.00695455
Frame: /joystick_box published by /robot_state_publisher Average Delay: 0.00298363 Max Delay: 0.00695825
Frame: /kinect_depth_camera published by /robot_state_publisher Average Delay: 0.00298672 Max Delay: 0.00696168
Frame: /kinect_fake_laser published by /robot_state_publisher Average Delay: 0.0029899 Max Delay: 0.00696531
Frame: /kinect_illumination published by /robot_state_publisher Average Delay: 0.00299316 Max Delay: 0.00696894
Frame: /kinect_illumination2 published by /robot_state_publisher Average Delay: 0.00299688 Max Delay: 0.00697271
Frame: /kinect_pivot published by /robot_state_publisher Average Delay: 0.00300013 Max Delay: 0.00697634
Frame: /kinect_rgb_camera published by /robot_state_publisher Average Delay: 0.0030034 Max Delay: 0.0069799
Frame: /kinect_sensor published by /robot_state_publisher Average Delay: 0.00300658 Max Delay: 0.0069834
Frame: /left_axel published by /robot_state_publisher Average Delay: 0.00300997 Max Delay: 0.00698717
Frame: /left_castor published by /robot_state_publisher Average Delay: 0.00301312 Max Delay: 0.00699108
Frame: /left_castor_stand published by /robot_state_publisher Average Delay: 0.00301631 Max Delay: 0.00699457
Frame: /left_castor_stand_support1 published by /robot_state_publisher Average Delay: 0.00301972 Max Delay: 0.00699834
Frame: /left_castor_stand_support2 published by /robot_state_publisher Average Delay: 0.00302338 Max Delay: 0.00700246
Frame: /left_castor_stand_support3 published by /robot_state_publisher Average Delay: 0.00302763 Max Delay: 0.00700686
Frame: /left_castor_stand_support4 published by /robot_state_publisher Average Delay: 0.00303146 Max Delay: 0.0070114
Frame: /left_motor published by /robot_state_publisher Average Delay: 0.0030348 Max Delay: 0.00701503
Frame: /left_side published by /robot_state_publisher ...