move_base generating path in unknown space
Hi,
I am trying to use ROS navigation stack with RPlidar A2.
currently, I am running gmapping
with move_base
and explore_lite
so that robot can do auto-exploration and do SLAM.
the problem is, even though I set allow_unkown
to false in dwa_local_planner_params.yaml, the path generated by move_base is going through the unknown space (I also checked the value being false with rosparam get)
Thank you for your help!
This is my costmap_common_parmas.yaml
obstacle_range: 2.5 #maximum obstale size
raytrace_range: 3.0 #robot will clear out space up to 3 meters
footprint: [[-0.30,-0.177], [0.105,-0.177], [0.105, 0.177], [-0.30,0.177]] #not sure, from legacy
robot_radius: 0.2
inflation_radius: 0.3 #0.55
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: laser_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
This is my global_costmap.yaml
global_costmap:
global_frame: map
robot_base_frame: base_link
update_frequency: 5.0
This is my local_costmap_params.yaml
local_costmap:
global_frame: odom # NEW!! odom
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true # will remain centered around the robot as the robot moves around
width: 5.0 #meters
height: 5.0
resolution: 0.01 #tend to set them equally as the static map
static_map: true #if we use map_sever, keep it true
and I am using dwa_local_planner and A* for global_planner.
EDIT
After accepting the answer, I worked on properly setting the costmap yaml files and now it works properly. I have played with 'track_unkown_space' param and I decided to set them like these. These are the files I have written.
common_costmap.yaml
obstacle_range: 2.5 #maximum obstale size
raytrace_range: 3.0 #robot will clear out space up to 3 meters
footprint: [[-0.30,-0.177], [0.105,-0.177], [0.105, 0.177], [-0.30,0.177]] #not sure, from legacy
robot_radius: 0.2
inflation_radius: 0.3 #0.55
global_costmap.yaml (here, I set 'track_unkown_space' to true, since I wanted A* planner to only plan in known & free space) - make sure you load these in move_base.xml file with namespace global_costmap.
global_frame: map
robot_base_frame: base_link
update_frequency: 3.0
publish_frequency: 2.0
static_map: true #if we use map_sever, keep it true
# obstacle_layer: {enabled: true, lethal_cost_threshold: 100, track_unknown_space: true, unknown_cost_value: -1}
# static_layer: {enabled: true, lethal_cost_threshold: 100, track_unknown_space: true, unknown_cost_value: -1}
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
static_layer:
unknown_cost_value: 0 # default: 0
lethal_cost_threshold: 100 # default: 100
map_topic: map # default: "map"
obstacle_layer:
combination_method: 1 #default 1, meaning we will combine the layers
observation_sources: laser_scan_sensor
track_unknown_space: true
map_type: costmap
laser_scan_sensor:
sensor_frame: laser_frame # default: ""
topic: scan # or /scan?
data_type: LaserScan # default: "PointCloud"
marking: true # default: true
clearing: true # default: false
inflation_layer:
inflation_radius: 0.45 # default: 0.55
local_costmap.yaml (here, I set 'track_unknown_space' to false, since DWA planner works fine with this param being false.) I got this idea from this link text
global_frame: map # NEW!! odom
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true # will remain centered around the robot as the robot ...
I've seen some posts about setting
track_unknown_space
to true, but since my costmap doesn't have layers, I thought wouldn't need to worry about that parameter. (or maybe I'm understanding it wrong)