Unable to avoid obstacles & robot can't go in a straight line using ros-kinetic, move_base, and SLAM_gmapping.
Attempting to use the ros navigation stack for autonomy. I'm able to get Laserscan information in rviz, but unable to avoid obstacles using the rplidar, SLAMgmapping, and movebase. When giving the robot a 2d nav_goal in rviz the robot shifts right and left then fails to go in a straight line. Any feedback would be appreciated. Most of the necessary files are below!
gmapping.launch
<launch>
<arg name="scan_topic" default="scan" />
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="odom_frame" value="odom"/>
<param name="base_frame" value="base_link"/>
<param name="map_frame" value="map"/>
<!-- Process 1 out of every this many scans (set it to a higher number to skip more scans) -->
<param name="throttle_scans" value="1"/>
<param name="map_update_interval" value="5.0"/> <!-- default: 5.0 -->
<!-- The maximum usable range of the laser. A beam is cropped to this value. -->
<param name="maxUrange" value="5.5"/>
<!-- The maximum range of the sensor. If regions with no obstacles within the range of the sensor should appear as free space in the map, set maxUrange < maximum range of the real sensor <= maxRange -->
<param name="maxRange" value="15.0"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="minimumScore" value="0.0"/>
<!-- Number of beams to skip in each scan. -->
<param name="lskip" value="0"/>
<param name="srr" value="0.1"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.1"/>
<param name="stt" value="0.02"/>
<!-- Process a scan each time the robot translates this far -->
<param name="linearUpdate" value="0.2"/>
<!-- Process a scan each time the robot rotates this far -->
<param name="angularUpdate" value="0.25"/>
<param name="temporalUpdate" value="5.0"/>
<param name="resampleThreshold" value="0.5"/>
<!-- Number of particles in the filter. default 30 -->
<param name="particles" value="100"/>
<!-- Initial map size -->
<param name="xmin" value="-10.0"/>
<param name="ymin" value="-10.0"/>
<param name="xmax" value="10.0"/>
<param name="ymax" value="10.0"/>
<!-- Processing parameters (resolution of the map) -->
<param name="delta" value="0.025"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
</launch>
move_base.launch
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find robot_navigation)/params/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find robot_navigation)/params/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find robot_navigation)/params/map_nav_params/local_costmap_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/params/map_nav_params/global_costmap_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/params/base_local_planner_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/params/move_base_params.yaml" command="load" />
<param name="base_global_planner" type="string" value="navfn/NavfnROS" />
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>
<!-- param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS"/-->
</node>
</launch>
move_base.yaml
shutdown_costmaps: false
track_unkown_sources: true
controller_frequency: 5.0
controller_patience: 15.0
planner_frequency: 2.0
planner_patience: 2.0
oscillation_timeout: 0.0
oscillation_distance: 0.5
recovery_behavior_enabled: true
clearing_rotation_allowed: true
baselocalplanner.yaml
TrajectoryPlannerROS:
# Robot Configuration Parameters
# Set the aceleration limits of the robot
acc_lim_x: 2.5
acc_im_y: 0.0
# The rotational acceleration limit of the robot (default setting)
acc_lim_theta: 3.2
# Set the velocity limits of the robot
max_vel_x: 2.0
min_vel_x: -2.0
max_vel_theta: 4.0
min_vel_theta: -4.0
max_rotational_vel: 1.0
min_in_place_rotational_vel: 2.0
min_in_place_vel_theta: 2.0
y_vels: [0, 0, 0, 0]
# The velocity the robot will command when trying to escape from a stuck situation
escape_vel: -1.0
holonomic_robot: false
# Goal Tolerance Default Parameters
yaw_goal_tolerance: 0.05
xy_goal_tolerance: 0.10
latch_xy_goal_tolerance: false
# Forward Simulation Parameters
sim_time: 1.5
sim_granularity: 0.025
angular_sim_granularity: 0.02
vx_samples: 15.0
vtheta_samples: 20.0
controller_frequency: 10.0
# Trajectory scoring parameters
meter_scoring: true
occdist_scale: 0.1
pdist_scale: 0.75
heading_lookahead: 0.325
heading_scoring: false
heading_scoring_timestep: 0.8
dwa: false
simple_attractor: false
publish_cost_grid_pc: true
oscillation_reset_dist: 0.05
escape_reset_dist: 0.1
escape_reset_theta: 0.1
costmapcommonparams.yaml
map_type: costmap_2d
origin_z: 0.0
z_resolution: 1
z_voxels: 2
obstacle_range: 2.5
raytrace_range: 3.0
publish_voxel_map: false
transform_tolerance: 0.5
meter_scoring: true
footprint: [[-0.21, -0.165], [-0.21, 0.165], [0.21, 0.165], [0.21, -0.165]]
footprint_padding: 0.1
observation_sources: laser_scan_sensor
laser_scan_sensor: [sensor_frame: /laser , data_type: LaserScan, topic: /scan, marking: true, clearing: true]
plugins:
- {name: obstacles_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflater_layer, type: "costmap_2d::InflationLayer"}
obstacles_layer:
observation_sources: scan
enabled: true
scan: {sensor_frame: /laser, data_type: LaserScan, topic: /scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 2.5, raytrace_range: 3.0}
inflater_layer:
enabled: true
cost_scaling_factor: 5.0
inflation_radius: 0.10
localcostmapparams.yaml
local_costmap:
global_frame: "map"
robot_base_frame: "base_link"
tansform_tolerance: 0.2
update_frequency: 1.0
publish_frequency: 10.0
width: 15.0
height: 15.0
resolution: 0.05
origin_x: 0.0
origin_y: 0.0
static_map: false
rolling_window: true
always_send_full_costmap: false
plugins:
#- {name: static_layer, type: "costmap_2d::StaticLayer"}#
- {name: obstacles_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflater_layer, type: "costmap_2d::InflationLayer"}
##static_layer:
##unknown_cost_value: -1.0
##lethal_cost_threshold: 100
##map_topic: "map"
##first_map_only: false
##subscribe_to_updates: false
##track_unknown_space: true
##use_maximum: false
##trinary_costmap: true
obstacles_layer:
track_unknown_space: false
footprint_clearing_enabled: true
inflater_layer:
inflation_radius: 0.10
cost_scaling_factor: 5.0
globalcostmapparams.yaml
global_costmap:
global_frame: "map"
robot_base_frame: "base_link"
tansform_tolerance: 0.2
update_frequency: 1.0
publish_frequency: 10.0
width: 15.0
height: 15.0
resolution: 0.05
origin_x: 0.0
origin_y: 0.0
static_map: true
rolling_window: false
always_send_full_costmap: false
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacles_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflater_layer, type: "costmap_2d::InflationLayer"}
static_layer:
unknown_cost_value: -1.0
lethal_cost_threshold: 100
map_topic: "map"
first_map_only: false
subscribe_to_updates: false
track_unknown_space: true
use_maximum: false
trinary_costmap: true
obstacles_layer:
track_unknown_space: false
footprint_clearing_enabled: true
inflater_layer:
inflation_radius: 0.10
cost_scaling_factor: 5.0
Asked by StewartHemm74 on 2019-02-20 10:18:10 UTC
Comments
If you can show a video capture of rviz - would help a lot
Asked by kolya_rage on 2019-02-21 03:48:21 UTC
I'm unable to post a video capture of rviz
Asked by StewartHemm74 on 2019-02-21 08:20:34 UTC