ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Regarding the Control loop missed its desired rate
warning check out this answer. You might need to reduce the
controller_frequency
parameter in move_base.launch. Also check if the scanner is actually publishing LaserScan messages on the /scan
topic.
In addition, what do you think by local costmap stays empty"? No new obstacles can be seen in the local costmap but the ones from the map are seen on the static global costmap? In move_base case the global planner plans a path around the obstacles detected in global_costmap and and local planner tries to avoid obstacles on the path detected in local_costmap.
I checked you costmap_common_params.yaml
file and I see that you have commented out some sensor parameters in the obstacle_layer. Try setting it like this and recheck if the frame/topics are correct:
obstacle_layer:
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true, min_obstacle_height: 0.0, max_obstacle_height: 5.0, obstacle_range: 6.0, raytrace_range: 8.5}
Also no point in having the global_frame and robot_base_frame in costmap_common_params.yaml if you are reinitializing them in the local and global costmap params files. Plus be careful with any namespaces and "/" in the names.
I would put the plugins before the layer description in costmap_common_params.yaml:
plugins:
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
and move the static_layer into your global_costmap params file
static_layer:
map_topic: /map
subscribe_to_updates: true
static_map: true
2 | No.2 Revision |
Regarding the Control loop missed its desired rate
warning check out this answer. You might need to reduce the
controller_frequency
parameter in move_base.launch. Also check if the scanner is actually publishing LaserScan messages on the /scan
topic.
In addition, what do you think by local costmap stays empty"? No new obstacles can be seen in the local costmap but the ones from the map are seen on the static global costmap? In move_base case the global planner plans a path around the obstacles detected in global_costmap and and local planner tries to avoid obstacles on the path detected in local_costmap.
I checked you costmap_common_params.yaml
file and I see that you have commented out some sensor parameters in the obstacle_layer. Try setting it like this and recheck if the frame/topics are correct:
obstacle_layer:
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true, min_obstacle_height: 0.0, max_obstacle_height: 5.0, obstacle_range: 6.0, raytrace_range: 8.5}
Also no point in having the global_frame and robot_base_frame in costmap_common_params.yaml if you are reinitializing them in the local and global costmap params files. Plus be careful with any namespaces and "/" in the names.
I would put the plugins before the layer description in costmap_common_params.yaml:
plugins:
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
and move the static_layer into your global_costmap params file
static_layer:
map_topic: /map
subscribe_to_updates: true
static_map: true
For example you can always checkout the jackal_navgation package which gives a good example on the configuration files