Skip to content

Commit

Permalink
config - cleanup among SFM params, stddevs and STG amplifiers
Browse files Browse the repository at this point in the history
  • Loading branch information
rayvburn committed Sep 24, 2023
1 parent 942707e commit d2f9f0f
Showing 1 changed file with 58 additions and 51 deletions.
109 changes: 58 additions & 51 deletions cfg/HuberoPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -54,32 +54,35 @@ group_sfm.add("filter_forces", bool_t, 0, "Whether to apply filtering operations
group_sfm.add("disable_interaction_forces", bool_t, 0, "Description", False)

group_param_eqn_mean = group_sfm.add_group("EquationParams", type="hide")
group_param_eqn_mean.add("an", double_t, 0, "Default multiplier: -8.0", -8.0 * 0.2615, -300.0, +300.0)
group_param_eqn_mean.add("bn", double_t, 0, "Default multiplier: +5.0", +5.0 * 0.4026, -300.0, +300.0)
group_param_eqn_mean.add("cn", double_t, 0, "Default multiplier: +1.5", +1.5 * 2.1614, -300.0, +300.0)
group_param_eqn_mean.add("ap", double_t, 0, "Default multiplier: +1.0", +1.0 * 1.5375, -300.0, +300.0)
group_param_eqn_mean.add("bp", double_t, 0, "Default multiplier: +2.0", +2.0 * 0.4938, -300.0, +300.0)
group_param_eqn_mean.add("cp", double_t, 0, "Default multiplier: +0.8", +0.8 * 0.5710, -300.0, +300.0)
group_param_eqn_mean.add("aw", double_t, 0, "Default multiplier: +123.139", +123.139 * 0.3280, -300.0, +300.0)
group_param_eqn_mean.add("bw", double_t, 0, "Default multiplier: +1.2", +1.2 * 0.1871, -300.0, +300.0)
group_param_eqn_mean.add("speed_desired", double_t, 0, "Default: 1.29", 1.29, 0.0, 3.0)
group_param_eqn_mean.add("relaxation_time", double_t, 0, "Default: 0.54", 0.54, 0.0, 3.0)
SFM_PARAM_MIN = -50.0
SFM_PARAM_MAX = +50.0
group_param_eqn_mean.add("an", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 0.2615 * -8.000, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("bn", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 0.4026 * +5.000, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("cn", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 2.1614 * +1.500, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("ap", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 1.5375 * +1.000, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("bp", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 0.4938 * +2.000, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("cp", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 0.5710 * +0.800, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("aw", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 0.3280 * +123.139, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("bw", double_t, 0, "Base parameter value estimated in a paper Seer et al., 2014, here multiplied by a custom multiplier", 0.1871 * +1.200, SFM_PARAM_MIN, SFM_PARAM_MAX)
group_param_eqn_mean.add("speed_desired", double_t, 0, "Base parameter value estimated in a paper Moussaid et al., 2009", 1.29, 0.0, SFM_PARAM_MAX)
group_param_eqn_mean.add("relaxation_time", double_t, 0, "Base parameter value estimated in a paper Moussaid et al., 2009", 0.54, 0.0, SFM_PARAM_MAX)

group_param_eqn_stddev = group_sfm.add_group("EquationParamsStdDev", type="hide")
group_param_eqn_stddev.add("an_stddev", double_t, 0, "", 0.0551, -300.0, +300.0)
group_param_eqn_stddev.add("bn_stddev", double_t, 0, "", 0.1238, -300.0, +300.0)
group_param_eqn_stddev.add("cn_stddev", double_t, 0, "", 0.3728, -300.0, +300.0)
group_param_eqn_stddev.add("ap_stddev", double_t, 0, "", 0.3084, -300.0, +300.0)
group_param_eqn_stddev.add("bp_stddev", double_t, 0, "", 0.1041, -300.0, +300.0)
group_param_eqn_stddev.add("cp_stddev", double_t, 0, "", 0.1409, -300.0, +300.0)
group_param_eqn_stddev.add("aw_stddev", double_t, 0, "", 0.1481, -300.0, +300.0)
group_param_eqn_stddev.add("bw_stddev", double_t, 0, "", 0.0563, -300.0, +300.0)
group_param_eqn_stddev.add("speed_desired_stddev", double_t, 0, "", 0.19, -300.0, +300.0)
group_param_eqn_stddev.add("relaxation_time_stddev", double_t, 0, "", 0.05, -300.0, +300.0)
SFM_STDDEV_MIN = -5.0
SFM_STDDEV_MAX = +5.0
group_param_eqn_stddev.add("an_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.0551, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("bn_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.1238, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("cn_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.3728, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("ap_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.3084, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("bp_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.1041, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("cp_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.1409, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("aw_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.1481, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("bw_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Seer et al., 2014", 0.0563, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("speed_desired_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Moussaid et al., 2009", 0.19, SFM_STDDEV_MIN, SFM_STDDEV_MAX)
group_param_eqn_stddev.add("relaxation_time_stddev", double_t, 0, "Standard deviation; default value of the parameter was estimated in Moussaid et al., 2009", 0.05, SFM_STDDEV_MIN, SFM_STDDEV_MAX)

# Fuzzy Inference System group parameters
group_fis = gen.add_group("FIS", type="tab")

group_fis.add("force_factor", double_t, 0, "Factor to multiply resultant human action force with", 30.0, 0.0, 100.0)
group_fis.add("human_action_range", double_t, 0, "Distance at which any human action force fade completely", 8.0, 0.0, 10.0)
fov_enum = gen.enum([gen.const("FisFovGaussian", int_t, 0, "Compute a value of the Gaussian in the normalized angle domain"),
Expand All @@ -101,46 +104,50 @@ group_traj_gen.add("equisampled_min_vel_x", double_t, 0, "Minimum linear velocit

# Trajectory sampling group parameters
group_traj_social = gen.add_group("TrajectorySocial", type="tab")
STG_AMP_MIN = -20.0 # default minimum value of an amplifier
STG_AMP_MAX = +20.0 # default maximum value of an amplifier
STG_GRN_MIN = 0.0 # default minimum value of an amplifier's granularity
STG_GRN_MAX = +20.0 # default minimum value of an amplifier's granularity
group_traj_social_speed = group_traj_social.add_group("SpeedDesired", type="hide")
group_traj_social_speed.add("sfm_desired_speed_amplifier_min", double_t, 0, "", 0.5, -300.0, +300.0)
group_traj_social_speed.add("sfm_desired_speed_amplifier_max", double_t, 0, "", 1.5, -300.0, +300.0)
group_traj_social_speed.add("sfm_desired_speed_amplifier_granularity", double_t, 0, "", 0.5, -300.0, +300.0)
group_traj_social_speed.add("sfm_desired_speed_amplifier_min", double_t, 0, "", +0.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_speed.add("sfm_desired_speed_amplifier_max", double_t, 0, "", +1.50, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_speed.add("sfm_desired_speed_amplifier_granularity", double_t, 0, "", +0.50, STG_GRN_MIN, STG_GRN_MAX)
group_traj_social_an = group_traj_social.add_group("An", type="hide")
group_traj_social_an.add("sfm_an_amplifier_min", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_an.add("sfm_an_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_an.add("sfm_an_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
group_traj_social_an.add("sfm_an_amplifier_min", double_t, 0, "", +1.00, 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, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
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.0, -300.0, +300.0)
group_traj_social_bn.add("sfm_bn_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_bn.add("sfm_bn_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
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)
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.0, -300.0, +300.0)
group_traj_social_cn.add("sfm_cn_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_cn.add("sfm_cn_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
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)
group_traj_social_ap = group_traj_social.add_group("Ap", type="hide")
group_traj_social_ap.add("sfm_ap_amplifier_min", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_ap.add("sfm_ap_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_ap.add("sfm_ap_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
group_traj_social_ap.add("sfm_ap_amplifier_min", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_ap.add("sfm_ap_amplifier_granularity", double_t, 0, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
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.0, -300.0, +300.0)
group_traj_social_bp.add("sfm_bp_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_bp.add("sfm_bp_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
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)
group_traj_social_cp = group_traj_social.add_group("Cp", type="hide")
group_traj_social_cp.add("sfm_cp_amplifier_min", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_cp.add("sfm_cp_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_cp.add("sfm_cp_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
group_traj_social_cp.add("sfm_cp_amplifier_min", double_t, 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, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
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, -300.0, +300.0)
group_traj_social_aw.add("sfm_aw_amplifier_max", double_t, 0, "", +1.0, -300.0, +300.0)
group_traj_social_aw.add("sfm_aw_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
group_traj_social_aw.add("sfm_aw_amplifier_min", double_t, 0, "", -1.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_granularity", double_t, 0, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)
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.0, -300.0, +300.0)
group_traj_social_bw.add("sfm_bw_amplifier_max", double_t, 0, "", 2.0, -300.0, +300.0)
group_traj_social_bw.add("sfm_bw_amplifier_granularity", double_t, 0, "", 0.25, 0.0, +300.0)
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, "", +0.25, STG_GRN_MIN, STG_GRN_MAX)
group_traj_social_as = group_traj_social.add_group("As", type="hide")
group_traj_social_as.add("fis_as_amplifier_min", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_as.add("fis_as_amplifier_max", double_t, 0, "", 1.0, -300.0, +300.0)
group_traj_social_as.add("fis_as_amplifier_granularity", double_t, 0, "", 1.0, 0.0, +300.0)
group_traj_social_as.add("fis_as_amplifier_min", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_as.add("fis_as_amplifier_max", double_t, 0, "", +1.00, STG_AMP_MIN, STG_AMP_MAX)
group_traj_social_as.add("fis_as_amplifier_granularity", double_t, 0, "", +1.00, STG_GRN_MIN, STG_GRN_MAX)

# Trajectory generation group parameters
group_cost = gen.add_group("Cost", type="tab")
Expand Down

0 comments on commit d2f9f0f

Please sign in to comment.