update costmap, planner, amcl parameters. Might fix

This commit is contained in:
Your Name 2025-02-10 10:23:34 +01:00
parent 53d07ef946
commit f217658f66
5 changed files with 70 additions and 17 deletions

View File

@ -0,0 +1,8 @@
obstacle_range: 2.5
raytrace_range: 3.0
robot_radius: 0.25
inflation_radius: 0.15
max_obstacle_height: 0.6
min_obstacle_height: 0.0
observation_sources: scan
scan: {data_type: LaserScan, topic: /scan_filtered, marking: true, clearing: true, expected_update_rate: 0}

View File

@ -1,12 +1,12 @@
controller_frequency: 5.0
recovery_behavior_enabled: false
recovery_behavior_enabled: true #false
clearing_rotation_allowed: false
DWAPlannerROS:
max_vel_trans: 1.0
min_vel_trans: 0.2
min_vel_trans: 0.1 #0.2
max_vel_x: 1.0
min_vel_x: 0.2
min_vel_x: 0.1 #0.2
max_vel_y: 0.0 # zero for a differential drive robot
min_vel_y: 0.0
min_in_place_vel_theta: 0.5
@ -26,16 +26,26 @@ DWAPlannerROS:
heading_lookahead: 0.325
heading_scoring: false
heading_scoring_timestep: 0.8
occdist_scale: 0.1
#occdist_scale: 0.1
oscillation_reset_dist: 0.05
publish_cost_grid_pc: false
prune_plan: true
# Forward Simulation Parameters
sim_time: 2.5
sim_granularity: 0.025
angular_sim_granularity: 0.025
vx_samples: 8
vy_samples: 0 # zero for a differential drive robot
vy_samples: 1 #0 # zero for a differential drive robot
vtheta_samples: 20
dwa: true
simple_attractor: false
# Trajectory Scoring Parameters
path_distance_bias: 64.0 # 32.0 - weighting for how much it should stick to the global path plan
goal_distance_bias: 24.0 # 24.0 - wighting for how much it should attempt to reach its goal
occdist_scale: 0.5 # 0.01 - weighting for how much the controller should avoid obstacles
forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point
stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj.
scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint
max_scaling_factor: 0.2 # 0.2 - how much to scale the robot's footprint when at speed.

View File

@ -0,0 +1,10 @@
global_costmap:
global_frame: map
robot_base_frame: base_link
update_frequency: 5.0 # 1.0
publish_frequency: 1.0 #0
static_map: true
rolling_window: false
resolution: 0.01
transform_tolerance: 0.5
map_type: costmap

View File

@ -0,0 +1,12 @@
local_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 5.0 #1.0
publish_frequency: 1.0
static_map: false
rolling_window: true
width: 6.0
height: 6.0
resolution: 0.01
transform_tolerance: 0.5
map_type: costmap

View File

@ -12,22 +12,30 @@
<!-- ********** AMCL algorithm *********** -->
<node pkg="amcl" type="amcl" name="amcl">
<param name="min_particles" value="500"/>
<param name="max_particles" value="3000"/>
<!-- <param name="max_particles" value="3000"/> -->
<param name="max_particles" value="5000"/>
<param name="kld_err" value="0.02"/>
<param name="update_min_d" value="0.20"/>
<param name="update_min_a" value="0.20"/>
<!-- <param name="update_min_a" value="0.20"/> -->
<param name="update_min_a" value="0.50"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.00"/>
<param name="recovery_alpha_fast" value="0.00"/>
<!-- <param name="transform_tolerance" value="0.5"/> -->
<param name="transform_tolerance" value="0.1"/>
<!-- <param name="recovery_alpha_slow" value="0.00"/> -->
<param name="recovery_alpha_slow" value="0.001"/>
<!-- <param name="recovery_alpha_fast" value="0.00"/> -->
<param name="recovery_alpha_fast" value="0.01"/>
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>
<param name="gui_publish_rate" value="50.0"/>
<!-- <param name="gui_publish_rate" value="50.0"/> -->
<param name="gui_publish_rate" value="20.0"/>
<remap from="scan" to="$(arg scan_topic)"/>
<param name="laser_max_range" value="16.0"/>
<param name="laser_max_beams" value="180"/>
<!-- <param name="laser_max_range" value="16.0"/> -->
<param name="laser_max_range" value="12.0"/>
<!-- <param name="laser_max_beams" value="180"/> -->
<param name="laser_max_beams" value="60"/>
<param name="laser_z_hit" value="0.5"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
@ -37,11 +45,16 @@
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- odom paramters: may raise alphas to compensate for bad odometry-->
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.1"/>
<param name="odom_alpha2" value="0.1"/>
<param name="odom_alpha3" value="0.1"/>
<param name="odom_alpha4" value="0.1"/>
<!-- <param name="odom_alpha1" value="0.1"/> -->
<param name="odom_alpha1" value="0.2"/>
<!-- <param name="odom_alpha2" value="0.1"/> -->
<param name="odom_alpha2" value="0.2"/>
<!-- <param name="odom_alpha3" value="0.1"/> -->
<param name="odom_alpha3" value="0.8"/>
<!-- <param name="odom_alpha4" value="0.1"/> -->
<param name="odom_alpha4" value="0.2"/>
<param name="odom_frame_id" value="odom"/>
<param name="base_frame_id" value="base_link"/>
<!--