Skip to content

Commit

Permalink
config - parameters retuned (SFM amplifiers and `maintain_vel_compo…
Browse files Browse the repository at this point in the history
…nents_rate`) [#92]
  • Loading branch information
rayvburn committed Jan 15, 2024
1 parent 8e732c2 commit 66d4545
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions cfg/HumapPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ 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("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.", True)
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)

#
group_general = gen.add_group("General", type="tab")
Expand Down Expand Up @@ -141,8 +141,8 @@ group_traj_social_ap.add("sfm_ap_amplifier_max", double_t, 0, "Even +30.
group_traj_social_ap.add("sfm_ap_amplifier_granularity", double_t, 0, "", +15.00, STG_GRN_MIN, STG_GRN_MAX)
## Bp: negligible (minimal effect observed for the range 0.0 - 5.0 with a granularity of 5.0).
group_traj_social_bp = group_traj_social.add_group("Bp", type="hide")
group_traj_social_bp.add("sfm_bp_amplifier_min", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bp.add("sfm_bp_amplifier_max", double_t, 0, "", +5.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bp.add("sfm_bp_amplifier_min", double_t, 0, "", +0.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bp.add("sfm_bp_amplifier_max", double_t, 0, "", +4.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bp.add("sfm_bp_amplifier_granularity", double_t, 0, "", +4.00, STG_GRN_MIN, STG_GRN_MAX)
## Cp: changing this parameter produces very similar trajectories, except the negative values.
## Meaningful range is from -6.0 to 1.0.
Expand All @@ -154,17 +154,17 @@ group_traj_social_cp.add("sfm_cp_amplifier_max", double_t, 0, "", +1.00,
group_traj_social_cp.add("sfm_cp_amplifier_granularity", double_t, 0, "", +2.00, STG_GRN_MIN, STG_GRN_MAX)
# Parameters related to the interaction forces with static objects
## Aw: amplyfing the parameter has a significant impact on generated trajectories for the range
## of -10.0 - +65.0 with a granularity of 5.0. Remember that this won't affect trajectories when only dynamic objects
## of -10.0 - +200.0 with a granularity of 5.0. Remember that this won't affect trajectories when only dynamic objects
## are nearby.
## 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", +0.50, 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", +2.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_granularity", double_t, 0, "", +2.00, STG_GRN_MIN, STG_GRN_MAX)
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_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")
group_traj_social_bw.add("sfm_bw_amplifier_min", double_t, 0, "", +0.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bw.add("sfm_bw_amplifier_max", double_t, 0, "", +2.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bw.add("sfm_bw_amplifier_max", double_t, 0, "", +4.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bw.add("sfm_bw_amplifier_granularity", double_t, 0, "", +2.00, STG_GRN_MIN, STG_GRN_MAX)
## As: tested with dynamic objects in front of the robot. Slight differences in trajectories with amplifiers
## within 1.0 - 51.0 (gran. 50.0). Increasing the main As factor makes more sense here.
Expand Down

0 comments on commit 66d4545

Please sign in to comment.