Skip to content

Commit b8f954c

Browse files
authored
Add moveitcpp planning pipeline config (#1040)
1 parent 612b27a commit b8f954c

File tree

1 file changed

+16
-0
lines changed

1 file changed

+16
-0
lines changed

doc/examples/moveit_cpp/config/moveit_cpp.yaml

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,22 @@ planning_scene_monitor_options:
1010
planning_pipelines:
1111
#namespace: "moveit_cpp" # optional, default is ~
1212
pipeline_names: ["ompl"]
13+
ompl:
14+
planning_plugin: ompl_interface/OMPLPlanner
15+
request_adapters: >-
16+
default_planner_request_adapters/AddTimeOptimalParameterization
17+
default_planner_request_adapters/FixWorkspaceBounds
18+
default_planner_request_adapters/FixStartStateBounds
19+
default_planner_request_adapters/FixStartStateCollision
20+
default_planner_request_adapters/FixStartStatePathConstraints
21+
planner_configs:
22+
PRMstarkConfigDefault:
23+
type: geometric::PRMstar
24+
# Define planner(s) for each move_group
25+
panda_arm:
26+
planner_configs:
27+
- PRMstarkConfigDefault
28+
# Add additional planning pipeline config here
1329

1430
plan_request_params:
1531
planning_attempts: 1

0 commit comments

Comments
 (0)