Skip to content

Commit

Permalink
Update configs
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Oct 17, 2023
1 parent 3c006c3 commit 591f4a3
Show file tree
Hide file tree
Showing 5 changed files with 9 additions and 7 deletions.
3 changes: 2 additions & 1 deletion moveit_configs_utils/default_configs/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
planning_plugin: chomp_interface/CHOMPPlanner
planning_plugin:
- chomp_interface/CHOMPPlanner
enable_failure_recovery: true
jiggle_fraction: 0.05
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
Expand Down
3 changes: 2 additions & 1 deletion moveit_configs_utils/default_configs/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
planning_plugin: ompl_interface/OMPLPlanner
planning_plugins:
- ompl_interface/OMPLPlanner
start_state_max_bounds_error: 0.1
jiggle_fraction: 0.05
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
planning_plugin: pilz_industrial_motion_planner/CommandPlanner
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
planning_plugins:
- pilz_industrial_motion_planner/CommandPlanner
request_adapters: ""
default_planner_config: PTP
capabilities: >-
Expand Down
4 changes: 2 additions & 2 deletions moveit_configs_utils/default_configs/stomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
planning_plugin: stomp_moveit/StompPlanner
# The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
planning_plugins:
- stomp_moveit/StompPlanner
request_adapters:
- default_planner_request_adapters/ResolveConstraintFrames
- default_planner_request_adapters/FixWorkspaceBounds
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ void planning_pipeline::PlanningPipeline::configure()
// Check if planner is not NULL
if (!planner_instance)
{
throw std::runtime_error("Unable to initialize planning plugin " + planner_name);
throw std::runtime_error("Unable to initialize planning plugin " + planner_name + ". Planner instance is nullptr.");
}

// Initialize planner
Expand Down

0 comments on commit 591f4a3

Please sign in to comment.