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 the `crossing` scenario
  • Loading branch information
rayvburn committed Jan 19, 2024
1 parent afb87f2 commit f521773
Showing 1 changed file with 15 additions and 16 deletions.
31 changes: 15 additions & 16 deletions cfg/HumapPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -125,33 +125,32 @@ group_traj_social_speed.add("sfm_desired_speed_amplifier_granularity", double_t,
## An: **slightly** affects trajectories but only when there are dynamic objects nearby.
## Meaningful range: -50.0 - 200.00 with a granularity of 100.0.
group_traj_social_an = group_traj_social.add_group("An", type="hide")
group_traj_social_an.add("sfm_an_amplifier_min", double_t, 0, "", -12.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_an.add("sfm_an_amplifier_min", double_t, 0, "", -0.40, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_an.add("sfm_an_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_an.add("sfm_an_amplifier_granularity", double_t, 0, "", +13.00, STG_GRN_MIN, STG_GRN_MAX)
## Bn: some effect of manipulating the amplifier values between -1.0 and 1.0
group_traj_social_an.add("sfm_an_amplifier_granularity", double_t, 0, "", +0.70, STG_GRN_MIN, STG_GRN_MAX)
## Bn: some effect of manipulating the amplifier values between -10.0 and 10.0
## When the performance allows, set "min" to 0.0 and "max" to 1.0.
group_traj_social_bn = group_traj_social.add_group("Bn", type="hide")
group_traj_social_bn.add("sfm_bn_amplifier_min", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bn.add("sfm_bn_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bn.add("sfm_bn_amplifier_granularity", double_t, 0, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
## Cn: negative amp. values produce failures in static obstacle interaction forces (NaNs).
## Introduces some effects for values from -1.0 to 1.0 with a granularity of 0.1, but still, rather very similar
## trajectories will be obtained.
## Introduces significant effects for values from -1.0 to 1.0 with a granularity of 0.1 (when dynamic object is nearby)
group_traj_social_cn = group_traj_social.add_group("Cn", type="hide")
group_traj_social_cn.add("sfm_cn_amplifier_min", double_t, 0, "", -1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cn.add("sfm_cn_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cn.add("sfm_cn_amplifier_granularity", double_t, 0, "Consider setting to +1.0 when the performance is not an issue", +2.00, STG_GRN_MIN, STG_GRN_MAX)
group_traj_social_cn.add("sfm_cn_amplifier_min", double_t, 0, "", -0.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cn.add("sfm_cn_amplifier_max", double_t, 0, "", +2.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cn.add("sfm_cn_amplifier_granularity", double_t, 0, "Consider setting to +1.0 when the performance is not an issue", +1.50, STG_GRN_MIN, STG_GRN_MAX)
## Ap: the effects are visible when dynamic objects are nearby.
## Effective range from -60 to 80 (with granularity of 5.0).
group_traj_social_ap = group_traj_social.add_group("Ap", type="hide")
group_traj_social_ap.add("sfm_ap_amplifier_min", double_t, 0, "", -10.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_max", double_t, 0, "Even +30.0 makes sense here when performance is not an issue", +5.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_granularity", double_t, 0, "", +15.00, STG_GRN_MIN, STG_GRN_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_min", double_t, 0, "", -0.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_max", double_t, 0, "Even +30.0 makes sense here when performance is not an issue", +1.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_granularity", double_t, 0, "", +2.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).
## Including 0 amplifier is cricital to differentiate trajectories but the additional ones are not very reasonable.
## Setting 1.0 in "max" might be sufficient when only static obstacles are nearby.
group_traj_social_bp = group_traj_social.add_group("Bp", type="hide")
group_traj_social_bp.add("sfm_bp_amplifier_min", double_t, 0, "", +0.50, STG_AMP_MIN, STG_AMP_MAX)
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, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bp.add("sfm_bp_amplifier_granularity", double_t, 0, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
## Cp: changing this parameter produces quite similar trajectories, but increasing the values helps to produce
Expand All @@ -161,8 +160,8 @@ group_traj_social_bp.add("sfm_bp_amplifier_granularity", double_t, 0, "", +1.00,
## might lead to trajectories that are not feasible (e.g., violate min vel. limits).
group_traj_social_cp = group_traj_social.add_group("Cp", type="hide")
group_traj_social_cp.add("sfm_cp_amplifier_min", double_t, 0, "Starting from -1.0 gives a wider spread than -4.0 or -2.0", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cp.add("sfm_cp_amplifier_max", double_t, 0, "", +10.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cp.add("sfm_cp_amplifier_granularity", double_t, 0, "", +9.00, STG_GRN_MIN, STG_GRN_MAX)
group_traj_social_cp.add("sfm_cp_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cp.add("sfm_cp_amplifier_granularity", double_t, 0, "", +1.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 - +200.0 with a granularity of 5.0. Remember that this won't affect trajectories when only dynamic objects
Expand All @@ -177,9 +176,9 @@ group_traj_social_aw.add("sfm_aw_amplifier_granularity", double_t, 0, "", +0.50,
## Bw: effective range is 0.0 - 4.0 (visible at a granularity up to 1.0).
## With some sets of other parameters, setting only 1.0 may affect producing only non-feasible trajectories!
group_traj_social_bw = group_traj_social.add_group("Bw", type="hide")
group_traj_social_bw.add("sfm_bw_amplifier_min", double_t, 0, "", +2.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bw.add("sfm_bw_amplifier_min", double_t, 0, "", +1.00, 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)
group_traj_social_bw.add("sfm_bw_amplifier_granularity", double_t, 0, "", +3.50, 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.
group_traj_social_as = group_traj_social.add_group("As", type="hide")
Expand Down

0 comments on commit f521773

Please sign in to comment.