mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2025-02-22 14:06:47 +00:00
Update dwa_base_local_planner_params.yaml
This commit is contained in:
parent
838c88e1c7
commit
019a359a5c
@ -23,8 +23,8 @@ DWAPlannerROS:
|
|||||||
gdist_scale: 0.6
|
gdist_scale: 0.6
|
||||||
#meter_scoring: true
|
#meter_scoring: true
|
||||||
|
|
||||||
heading_lookahead: 0.325
|
heading_lookahead: 1.5 #0.325
|
||||||
heading_scoring: false
|
heading_scoring: true #false
|
||||||
heading_scoring_timestep: 0.8
|
heading_scoring_timestep: 0.8
|
||||||
#occdist_scale: 0.1
|
#occdist_scale: 0.1
|
||||||
oscillation_reset_dist: 0.05
|
oscillation_reset_dist: 0.05
|
||||||
@ -32,10 +32,10 @@ DWAPlannerROS:
|
|||||||
prune_plan: true
|
prune_plan: true
|
||||||
|
|
||||||
# Forward Simulation Parameters
|
# Forward Simulation Parameters
|
||||||
sim_time: 2.5 #5.0 #1.0 #5.0 #2.5
|
sim_time: 5.0 #1.0 #5.0 #2.5
|
||||||
sim_granularity: 0.025
|
sim_granularity: 0.025
|
||||||
angular_sim_granularity: 0.025
|
angular_sim_granularity: 0.025
|
||||||
vx_samples: 8
|
vx_samples: 20 #8
|
||||||
vy_samples: 1 #0 # zero for a differential drive robot
|
vy_samples: 1 #0 # zero for a differential drive robot
|
||||||
vtheta_samples: 20
|
vtheta_samples: 20
|
||||||
dwa: true
|
dwa: true
|
||||||
@ -44,7 +44,7 @@ DWAPlannerROS:
|
|||||||
# # Trajectory Scoring Parameters
|
# # Trajectory Scoring Parameters
|
||||||
path_distance_bias: 64.0 # 32.0 - weighting for how much it should stick to the global path plan
|
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
|
goal_distance_bias: 24.0 # 24.0 - wighting for how much it should attempt to reach its goal
|
||||||
occdist_scale: 10.0 #2.0 #0.5 # 0.01 - weighting for how much the controller should avoid obstacles
|
occdist_scale: 50.0 #2.0 #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
|
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.
|
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
|
scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint
|
||||||
|
Loading…
Reference in New Issue
Block a user