Skip to content

Commit

Permalink
Further tune range
Browse files Browse the repository at this point in the history
  • Loading branch information
amalnanavati committed Dec 3, 2024
1 parent 130109d commit 5ea90f5
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions ada_moveit/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,15 @@ request_adapters: >-
default_planner_request_adapters/FixWorkspaceBounds
# Based on Kinova's parameters: https://github.com/Kinovarobotics/kinova-ros/blob/noetic-devel/kinova_moveit/robot_configs/j2n6s300_moveit_config/config/ompl_planning.yaml
planner_configs:
# NOTE: In practice, MoveIt2 hybridizes and shortcuts by default:
# https://github.com/moveit/moveit2/blob/e7872ebf92146bb80930ec98cf6c181e8384e99c/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp#L81
AnytimePathShortening:
type: geometric::AnytimePathShortening
shortcut: 1 # Attempt to shortcut all new solution paths
hybridize: 1 # Compute hybrid solution trajectories
max_hybrid_paths: 8 # Number of hybrid paths generated per iteration
num_planners: 4 # The number of default planners to use for planning
planners: "RRTConnect[intermediate_states=0 range=0.05]" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
planners: "RRTConnect[range=0.01]" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
SBLkConfigDefault:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
Expand Down Expand Up @@ -47,7 +49,7 @@ planner_configs:
RRTConnectkConfigDefault:
type: geometric::RRTConnect
intermediate_states: 0 # Whether to add intermediate states to the plan, default 0
range: 0.05 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
range: 0.01 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
RRTstarkConfigDefault:
type: geometric::RRTstar
range: 3.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() (in practice, for ADA, this default is ~7)
Expand Down

0 comments on commit 5ea90f5

Please sign in to comment.