problem with narrow passage
Hi
My robot behaves strangely when passing through a narrow passage. The robot seems to hesitate to cross the narrow passage.
If I disable the "obstacle_layer" of "local_costmap" the robot goes smoothly through the passage.
Videos/Images:
RVIZ: https://drive.google.com/file/d/1v9L9...
Real with "obstacle_layer" enabled: https://drive.google.com/file/d/1-BYy...
Real with "obstacle_layer" disabled: https://drive.google.com/file/d/1K0qn...
Width of passage: https://drive.google.com/file/d/1-EHU...
my settings files:
costmap_common_params.yaml:
obstacle_range: 2.5
raytrace_range: 3.0
footprint: [[-0.17,-0.17],[-0.17,0.17],[0.17,0.17],[0.17,-0.17]]
observation_sources: scan
scan: {sensor_frame: rplidar_link, observation_persistence: 0.0, max_obstacle_height: 0.4, min_obstacle_height: 0.0, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
inflation_layer:
inflation_radius: 0.3 #default 0.55
global_costmap_params.yaml
global_costmap:
global_frame: /map
robot_base_frame: /base_footprint
transform_tolerance: 0.5
update_frequency: 7.0
publish_frequency: 7.0
static_map: true
rolling_window: false
local_costmap_params.yaml
local_costmap:
global_frame: /map
robot_base_frame: /base_footprint
update_frequency: 7.0
publish_frequency: 7.0
static_map: false
rolling_window: true
width: 5.0
height: 5.0
resolution: 0.02 #defaul 0.02
transform_tolerance: 0.5
move_base.launch:
<?xml version="1.0"?>
<launch>
<!-- Run the map server -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find autonomo)/maps/map.yaml" output="screen"/>
<include file="$(find autonomo)/launch/amcl_diff.launch" >
</include>
<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 autonomo)/launch/move_base.yaml" command="load"/>
<rosparam file="$(find autonomo)/launch/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find autonomo)/launch/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find autonomo)/launch/local_costmap_params.yaml" command="load" />
<rosparam file="$(find autonomo)/launch/global_costmap_params.yaml" command="load" />
</node>
</launch>
move_base.yaml:
controller_patience: 15.0
planner_frequency: 3.0
controller_frequency: 15.0
TrajectoryPlannerROS:
max_vel_x: 0.20
min_vel_x: 0.05
max_vel_theta: 1.0
min_vel_theta: -1.0
max_rotational_vel: 0.6
min_in_place_rotational_vel: 0.6
max_in_place_vel_theta: 1.0
min_in_place_vel_theta: 1.0
holonomic_robot: false
escape_reset_dist: 0.0
escape_reset_theta: 0.0
Is something wrong with my setup? Are there any parameters I could adjust to improve this?
Thaks
I was so free to delete the two clones of this question.
First: In the video the robot footprint looks bigger then the robot model. The footprint has a width and height of 34cm and the inflation radius is set to 30cm. Is there a reason for the difference of the size between robot model and footprint?
hi, modifying the footprint to the actual dimensions of the robot ([[-0.045,-0.10],[-0.045,0.10],[0.17,0.10],[0.17,-0.10]]) the lethal area (cyan color) decreases to 0.045 m which is the smallest of the robot's measurements. I believe this could be dangerous. Print: https://drive.google.com/file/d/1_GdL...
I usually tune the dangerous zone with the parameter inflation_radius and cost_scaling_factor of the inflation layer.