From d2e7fa76a2cfa155d85a08142b15752f764359ab Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 16 Apr 2025 09:43:09 -0500 Subject: [PATCH 1/4] Add OMPL config to moveit_cpp.yaml --- doc/examples/moveit_cpp/config/moveit_cpp.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/doc/examples/moveit_cpp/config/moveit_cpp.yaml b/doc/examples/moveit_cpp/config/moveit_cpp.yaml index 0dbd6f88ee..36710d6286 100644 --- a/doc/examples/moveit_cpp/config/moveit_cpp.yaml +++ b/doc/examples/moveit_cpp/config/moveit_cpp.yaml @@ -10,6 +10,8 @@ planning_scene_monitor_options: planning_pipelines: #namespace: "moveit_cpp" # optional, default is ~ pipeline_names: ["ompl"] +ompl: + planning_plugin: ompl_interface/OMPLPlanner plan_request_params: planning_attempts: 1 From bb88a32ec3bf2d89430a5a009968153780dc31c6 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 16 Apr 2025 10:03:47 -0500 Subject: [PATCH 2/4] Update doc/examples/moveit_cpp/config/moveit_cpp.yaml --- doc/examples/moveit_cpp/config/moveit_cpp.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/examples/moveit_cpp/config/moveit_cpp.yaml b/doc/examples/moveit_cpp/config/moveit_cpp.yaml index 36710d6286..e146af8918 100644 --- a/doc/examples/moveit_cpp/config/moveit_cpp.yaml +++ b/doc/examples/moveit_cpp/config/moveit_cpp.yaml @@ -12,7 +12,7 @@ planning_pipelines: pipeline_names: ["ompl"] ompl: planning_plugin: ompl_interface/OMPLPlanner - + # Add additional planning pipeline config here plan_request_params: planning_attempts: 1 planning_pipeline: ompl From 25597036684dfdc1b5ef2017b9b2f177e13bee9f Mon Sep 17 00:00:00 2001 From: AndyZe Date: Thu, 17 Apr 2025 11:40:38 -0500 Subject: [PATCH 3/4] Add additional planner config --- doc/examples/moveit_cpp/config/moveit_cpp.yaml | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/doc/examples/moveit_cpp/config/moveit_cpp.yaml b/doc/examples/moveit_cpp/config/moveit_cpp.yaml index e146af8918..1ddfe22626 100644 --- a/doc/examples/moveit_cpp/config/moveit_cpp.yaml +++ b/doc/examples/moveit_cpp/config/moveit_cpp.yaml @@ -12,6 +12,19 @@ planning_pipelines: pipeline_names: ["ompl"] ompl: planning_plugin: ompl_interface/OMPLPlanner + request_adapters: >- + default_planner_request_adapters/AddTimeOptimalParameterization + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints + planner_configs: + PRMstarkConfigDefault: + type: geometric::PRMstar + # Define planner(s) for each move_group + panda_arm: + planner_configs: + - PRMstarkConfigDefault # Add additional planning pipeline config here plan_request_params: planning_attempts: 1 From 57fa2898bd33f40078541e7adc71dd8355aefbfa Mon Sep 17 00:00:00 2001 From: AndyZe Date: Sat, 19 Apr 2025 11:08:07 -0500 Subject: [PATCH 4/4] Update adapter format for Rolling --- .../moveit_cpp/config/moveit_cpp.yaml | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/doc/examples/moveit_cpp/config/moveit_cpp.yaml b/doc/examples/moveit_cpp/config/moveit_cpp.yaml index 1ddfe22626..6a0179cd02 100644 --- a/doc/examples/moveit_cpp/config/moveit_cpp.yaml +++ b/doc/examples/moveit_cpp/config/moveit_cpp.yaml @@ -12,12 +12,19 @@ planning_pipelines: pipeline_names: ["ompl"] ompl: planning_plugin: ompl_interface/OMPLPlanner - request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints + planning_plugins: + - ompl_interface/OMPLPlanner + # To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below + # default_planning_request_adapters/AddRuckigTrajectorySmoothing + request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision + response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath planner_configs: PRMstarkConfigDefault: type: geometric::PRMstar