Skip to content

Commit

Permalink
HuberoPlanner.cfg - tuning results from 2022 Q2/Q3
Browse files Browse the repository at this point in the history
  • Loading branch information
rayvburn committed Jan 30, 2023
1 parent 24e83a0 commit 0596a1a
Showing 1 changed file with 10 additions and 10 deletions.
20 changes: 10 additions & 10 deletions cfg/HuberoPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ 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, "Defines how much robot tries to 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, "Defines how much robot tries to additionally follow force direction compared to pure transformation of force into local velocity. This is related to experimental twist computation heuristics that strains vector field assumptions.", 0.0, 0.0, 2.0)

#
group_general = gen.add_group("General", type="tab")

group_general.add("planning_approach", bool_t, 0, "Whether to use planning (True) or proactive approach (False) for trajectory generation", True)
group_general.add("sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 1.8, 0)
group_general.add("sim_granularity", double_t, 0, "The granularity with which to check for collisions along each trajectory in meters", 0.085, 0)
group_general.add("sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 2.0, 0)
group_general.add("sim_granularity", double_t, 0, "The granularity with which to check for collisions along each trajectory in meters", 0.2, 0)
group_general.add("angular_sim_granularity", double_t, 0, "The granularity with which to check for collisions for rotations in radians", 0.1, 0)
group_general.add("local_goal_distance", double_t, 0, "The distance from the center point of the robot to place a local goal. Try to keep it below 0.5 m for proactive approach. Must not exceed local costmap bounds.", 1.0, 0.25, 3.0)
group_general.add("obstacle_extension_multiplier", double_t, 0, "The factor by which robot's inscribed radius will be multiplied to caluclate distance between closest points of the robot footprint and environment object (static/dynamic)", 0.0, 0.0, 2.0)
Expand All @@ -33,8 +33,8 @@ group_sfm = gen.add_group("SFM", type="tab")

group_sfm.add("fov", double_t, 0, "Half of the field of view of the robot", 2.00, 0.0, +3.14)
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", 4.2, 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", 50.0, 0.0, 300.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", 1.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)
Expand Down Expand Up @@ -131,16 +131,16 @@ group_traj_social_as.add("fis_as_amplifier_granularity", double_t, 0, "", 1.0, 0
group_cost = gen.add_group("Cost", type="tab")

group_cost.add("path_distance_scale", double_t, 0, "The weight for the path distance part of the cost function", 1.5, 0.0)
group_cost.add("goal_distance_scale", double_t, 0, "The weight for the goal distance part of the cost function", 7.4, 0.0)
group_cost.add("goal_distance_scale", double_t, 0, "The weight for the goal distance part of the cost function", 8.8, 0.0)
group_cost.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.2, 0.0)
group_cost.add("alignment_scale", double_t, 0, "The weight for the alignment with the global plan. In a classical DWA implementation equal to `path_distance_scale`", 1.4, 0.0)
group_cost.add("goal_front_scale", double_t, 0, "The weight for the achievement of the additional goal point placed in front of the mobile base. In a classical DWA implementation equal to `goal_distance_scale`", 1.5, 0.0)
group_cost.add("goal_front_scale", double_t, 0, "The weight for the achievement of the additional goal point placed in front of the mobile base. In a classical DWA implementation equal to `goal_distance_scale`", 0.0, 0.0)
group_cost.add("backward_scale", double_t, 0, "The weight for the backward motion penalisation", 0.08, 0.0)
group_cost.add("ttc_scale", double_t, 0, "The weight for the time to collision cost function (scores whole trajectory instead of a single cell)", 3.0, 0.0)
group_cost.add("chc_scale", double_t, 0, "The weight for the cost function that penalizes robot heading changes", 11.0, 0.0)
group_cost.add("speedy_goal_scale", double_t, 0, "The weight for the cost function that penalizes high speeds near global goal", 12.0, 0.0)
group_cost.add("velocity_smoothness_scale", double_t, 0, "The weight for the cost function that penalizes velocity changes along trajectory", 9.0, 0.0)
group_cost.add("contextualized_costs_scale", double_t, 0, "The weight for the cost function that penalizes trajectories based on contexts embedded into costmap", 0.07, 0.0)
group_cost.add("speedy_goal_scale", double_t, 0, "The weight for the cost function that penalizes high speeds near global goal", 0.2, 0.0)
group_cost.add("velocity_smoothness_scale", double_t, 0, "The weight for the cost function that penalizes velocity changes along trajectory", 15.0, 0.0)
group_cost.add("contextualized_costs_scale", double_t, 0, "The weight for the cost function that penalizes trajectories based on contexts embedded into costmap", 0.06, 0.0)
group_cost.add("disturbance_scale", double_t, 0, "The weight for the cost function that penalizes trajectories that people may find disturbing", 7.0, 0.0)

group_cost.add("oscillation_reset_dist", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", 0.05, 0.0)
Expand Down

0 comments on commit 0596a1a

Please sign in to comment.