Skip to content

Commit 9bd50ec

Browse files
committed
Add Anytime Path Shortening
1 parent 9323099 commit 9bd50ec

File tree

1 file changed

+8
-0
lines changed

1 file changed

+8
-0
lines changed

ada_moveit/config/ompl_planning.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,13 @@ request_adapters: >-
88
default_planner_request_adapters/FixWorkspaceBounds
99
# 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
1010
planner_configs:
11+
AnytimePathShortening:
12+
type: geometric::AnytimePathShortening
13+
shortcut: 1 # Attempt to shortcut all new solution paths
14+
hybridize: 1 # Compute hybrid solution trajectories
15+
max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
16+
num_planners: 4 # The number of default planners to use for planning
17+
planners: "RRTConnect" # 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]"
1118
SBLkConfigDefault:
1219
type: geometric::SBL
1320
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
@@ -65,6 +72,7 @@ jaco_arm:
6572
enforce_constrained_state_space: true
6673
projection_evaluator: joints(j2n6s200_joint_1,j2n6s200_joint_2)
6774
planner_configs:
75+
- AnytimePathShortening
6876
- SBLkConfigDefault
6977
- ESTkConfigDefault
7078
- LBKPIECEkConfigDefault

0 commit comments

Comments
 (0)