Skip to content

Commit

Permalink
Update planning pipeline configs (#189)
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Nov 21, 2023
1 parent 3d6a737 commit 7162dcd
Show file tree
Hide file tree
Showing 7 changed files with 62 additions and 54 deletions.
21 changes: 11 additions & 10 deletions dual_arm_panda_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
planning_plugin: ompl_interface/OMPLPlanner
# To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below
# default_planner_request_adapters/AddRuckigTrajectorySmoothing
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
start_state_max_bounds_error: 0.1
# To optionally use Ruckig for jerk-limited smoothing, add this line to the response 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:
SBLkConfigDefault:
type: geometric::SBL
Expand Down
16 changes: 9 additions & 7 deletions fanuc_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
planning_plugin: chomp_interface/CHOMPPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
start_state_max_bounds_error: 0.1
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
planning_time_limit: 10.0
max_iterations: 200
max_iterations_after_collision_free: 5
Expand Down
21 changes: 11 additions & 10 deletions fanuc_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
planning_plugin: ompl_interface/OMPLPlanner
# To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below
# default_planner_request_adapters/AddRuckigTrajectorySmoothing
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
start_state_max_bounds_error: 0.1
# To optionally use Ruckig for jerk-limited smoothing, add this line to the response 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:
AnytimePathShortening:
type: geometric::AnytimePathShortening
Expand Down
14 changes: 7 additions & 7 deletions panda_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
planning_plugin: chomp_interface/CHOMPPlanner
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
start_state_max_bounds_error: 0.1
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
planning_time_limit: 10.0
max_iterations: 200
max_iterations_after_collision_free: 5
Expand Down
19 changes: 10 additions & 9 deletions panda_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
planning_plugin: ompl_interface/OMPLPlanner
# To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below
# default_planner_request_adapters/AddRuckigTrajectorySmoothing
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
start_state_max_bounds_error: 0.1
# 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:
APSConfigDefault:
type: geometric::AnytimePathShortening
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
planning_plugin: pilz_industrial_motion_planner/CommandPlanner
request_adapters: >-
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
request_adapters:
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision

default_planner_config: PTP
capabilities: >-
pilz_industrial_motion_planner/MoveGroupSequenceAction
Expand Down
15 changes: 9 additions & 6 deletions panda_moveit_config/config/stomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,13 @@
planning_plugin: stomp_moveit/StompPlanner
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
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

stomp_moveit:
num_timesteps: 60
Expand Down

0 comments on commit 7162dcd

Please sign in to comment.