Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

adjusted dwb_local_planner_params #43

Closed
wants to merge 1 commit into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 17 additions & 14 deletions mir_navigation/config/dwb_local_planner_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,13 @@ DWBLocalPlanner:
xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2
#latch_xy_goal_tolerance: true

# Whether to split the path into segments or not
split_path: true

# Forward simulation (trajectory generation)
trajectory_generator_name: dwb_plugins::StandardTrajectoryGenerator # or dwb_plugins::LimitedAccelGenerator
sim_time: 1.2
vx_samples: 10
sim_time: 0.8
vx_samples: 15
vy_samples: 1 # diff drive robot, there is only one sample
vtheta_samples: 15
discretize_by_time: false
Expand All @@ -45,25 +48,25 @@ DWBLocalPlanner:

# Critics (trajectory scoring)
#default_critic_namespaces: [dwb_critics, mir_dwb_critics]
critics: [RotateToGoal, Oscillation, ObstacleFootprint, PathAlign, PathDistPruned, PathProgress]
critics: [RotateToGoal, ObstacleFootprint, PathDistPruned, PathProgress]
RotateToGoal:
scale: 1.0
scale: 100.0
# lookahead_time: -1.0
# slowing_factor: 5.0
Oscillation:
#scale: 1.0 # scale doesn't matter: the OscillationCritic always gives a score of 0 for valid trajectories, and throws an exception for oscillating trajectories
oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags, in m
oscillation_reset_angle: 0.2 # 0.2 - the angle the robot must turn before resetting Oscillation flags, in rad
oscillation_reset_time: -1.0
x_only_threshold: 0.1
# Oscillation:
# #scale: 1.0 # scale doesn't matter: the OscillationCritic always gives a score of 0 for valid trajectories, and throws an exception for oscillating trajectories
# oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags, in m
# oscillation_reset_angle: 0.2 # 0.2 - the angle the robot must turn before resetting Oscillation flags, in rad
# oscillation_reset_time: -1.0
# x_only_threshold: 0.1
ObstacleFootprint:
scale: 0.01 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles
max_scaling_factor: 0.2 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed.
scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint
sum_scores: false # if true, return sum of scores of all trajectory points instead of only last one
PathAlign:
scale: 16.0
forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point
# PathAlign:
# scale: 16.0
# forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point
PathDistPruned:
scale: 32.0 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan
class: 'mir_dwb_critics::PathDistPruned'
Expand All @@ -73,7 +76,7 @@ DWBLocalPlanner:
class: 'mir_dwb_critics::PathProgress'
xy_local_goal_tolerance: 0.20
angle_threshold: 0.78539816 # 45 degrees


# Prune already passed poses from plan
prune_plan: true
Expand Down