Skip to content

Commit

Permalink
F config - parameters tuned for socially-complaint behaviour and re…
Browse files Browse the repository at this point in the history
…asonable performance [#92]
  • Loading branch information
rayvburn committed Sep 22, 2023
1 parent a0e5072 commit c538c60
Showing 1 changed file with 16 additions and 9 deletions.
25 changes: 16 additions & 9 deletions cfg/HuberoPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ group_sfm.add("sfm_fov_factor_method", int_t, 0, "Select the formulation that co
group_sfm.add("mass", double_t, 0, "Description", 14.5, 0.1, 250.0)
group_sfm.add("internal_force_factor", double_t, 0, "How much robot tries to reach the goal position using shortest path to goal. For non-planning approach keep it at approx. 4.2", 0.75, 0.0, 50.0)
group_sfm.add("static_interaction_force_factor", double_t, 0, "How much robot tries to maintain safe distance from static obstacles. For non-planning approach keep it at approx. 11.0", 4.9, 0.0, 300.0)
group_sfm.add("dynamic_interaction_force_factor", double_t, 0, "How much robot tries to maintain safe distance from dynamic obstacles", 5.0, 0.0, 300.0)
group_sfm.add("dynamic_interaction_force_factor", double_t, 0, "How much robot tries to maintain safe distance from dynamic obstacles", 10.0, 0.0, 300.0)
group_sfm.add("min_force", double_t, 0, "Minimum force - vectors shorter than that will be extended, which may prevent from being stuck.", 5.0, 0.0, 100.0)
group_sfm.add("max_force", double_t, 0, "Maximum force - vectors longer than that will be truncated", 300.0, 0.0, 1500.0)
group_sfm.add("heterogenous_population", bool_t, 0, "Setting true causes SFM params to be defined in non-deterministic way (std deviation around mean value)", False)
Expand Down Expand Up @@ -132,31 +132,38 @@ group_traj_social_bn.add("sfm_bn_amplifier_granularity", double_t, 0, "", +1.00,
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, "", +1.00, STG_GRN_MIN, STG_GRN_MAX) # consider +2.0 for performance
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)
## 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)
## 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_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.
## The biggest spread (with dynamic objects) observed at -6.0 - -4.0 with a granularity of 0.5. However, such a range
## 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, "", -2.00, STG_AMP_MIN, STG_AMP_MAX) # gives a wider spread than -4.0
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, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_cp.add("sfm_cp_amplifier_granularity", double_t, 0, "", +3.00, STG_GRN_MIN, STG_GRN_MAX)
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.
group_traj_social_aw = group_traj_social.add_group("Aw", type="hide")
group_traj_social_aw.add("sfm_aw_amplifier_min", double_t, 0, "", +0.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_min", double_t, 0, "", +0.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_max", double_t, 0, "", +2.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_aw.add("sfm_aw_amplifier_granularity", double_t, 0, "", +1.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, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bw.add("sfm_bw_amplifier_max", double_t, 0, "", +2.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_bw.add("sfm_bw_amplifier_granularity", double_t, 0, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
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_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.
group_traj_social_as = group_traj_social.add_group("As", type="hide")
Expand Down

0 comments on commit c538c60

Please sign in to comment.