Skip to content

Commit

Permalink
config - parameters retuned for socially-complaint behaviour and re…
Browse files Browse the repository at this point in the history
…asonable performance [#92]

- tested in, e.g., crossing, overtaking scenarios
  • Loading branch information
rayvburn committed Dec 19, 2023
1 parent c4694da commit 273dc82
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions cfg/HuberoPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ group_limits = gen.add_group("Limits", type="tab")
group_limits_generic_lp = group_limits.add_group("BaseLocalPlanner", type="hide")
add_generic_localplanner_params(group_limits_generic_lp)
group_limits_custom = group_limits.add_group("Custom", type="hide")
group_limits_custom.add("twist_rotation_compensation", double_t, 0, "Damping factor (inverted?) of the forceToVelocity transformation, ref. to (Ferrer, 2017). Defines how much the robot tries to additionally follow force direction compared to pure transformation of force into local velocity.", 0.25, 0.0, 2.0)
group_limits_custom.add("twist_rotation_compensation", double_t, 0, "Damping factor (inverted?) of the forceToVelocity transformation, ref. to (Ferrer, 2017). Defines how much the robot tries to additionally follow force direction compared to pure transformation of force into local velocity.", 0.40, 0.0, 2.0)
group_limits_custom.add("maintain_vel_components_rate", bool_t, 0, "When true and any vel. component is not within limits, others will be modified according to the one that cannot be changed as requested; others will be proportionally scaled; setting this to true loosely corresponds to agreeing with dynamics violation, but keeping the path as intended.", False)

#
Expand Down Expand Up @@ -165,7 +165,7 @@ group_traj_social_cp.add("sfm_cp_amplifier_granularity", double_t, 0, "", +2.00,
## Slightly performance-affecting, but also a good choice is a triplet of (min: +0.50, max: +4.50, gran.: +2.00).
group_traj_social_aw = group_traj_social.add_group("Aw", type="hide")
group_traj_social_aw.add("sfm_aw_amplifier_min", double_t, 0, "-1.0 might also be tried if performance is not an issue", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_max", double_t, 0, "+2.50 with a granularity of 1.0 is also a reasonable pair", +100.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_max", double_t, 0, "+2.50 with a granularity of 1.0 is also a reasonable pair", +51.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_granularity", double_t, 0, "", +50.00, STG_GRN_MIN, STG_GRN_MAX)
## Bw: effective range is 0.0 - 4.0 (visible at a granularity up to 1.0).
group_traj_social_bw = group_traj_social.add_group("Bw", type="hide")
Expand All @@ -185,10 +185,10 @@ group_cost = gen.add_group("Cost", type="tab")
## Weights/scales of the cost functions
# Performance tuning was performed using `path_distance_scale` initially set to 7.7. Values up to 14.0 provide
# reasonable results (9.9, 11.0, 12.0 were also tested).
group_cost.add("path_distance_scale", double_t, 0, "The weight for the path distance part of the cost function", 10.0, 0.0)
group_cost.add("path_distance_scale", double_t, 0, "The weight for the path distance part of the cost function", 15.0, 0.0)
# Note that `goal_distance_scale` at 17.5 may slow down the robot just before the goal (e.g., near walls).
group_cost.add("goal_distance_scale", double_t, 0, "The weight for the goal distance part of the cost function", 17.5, 0.0)
group_cost.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.02, 0.0)
group_cost.add("goal_distance_scale", double_t, 0, "The weight for the goal distance part of the cost function", 25.5, 0.0)
group_cost.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.05, 0.0)
group_cost.add("occdist_sum_scores", bool_t, 0, "Whether to sum up the scores along the path or use the maximum one", False)
group_cost.add("occdist_separation", double_t, 0, "The minimum separation that should be kept from obstacles", 0.025, 0.0)
occdist_kernel = gen.enum([
Expand Down

0 comments on commit 273dc82

Please sign in to comment.