diff --git a/stretch_moveit_config/config/ompl_planning.yaml b/stretch_moveit_config/config/ompl_planning.yaml index d2b037a..e59094e 100644 --- a/stretch_moveit_config/config/ompl_planning.yaml +++ b/stretch_moveit_config/config/ompl_planning.yaml @@ -128,7 +128,7 @@ planner_configs: dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 max_failures: 5000 # maximum consecutive failure limit. default: 5000 stretch_arm: - default_planner_config: None + default_planner_config: RRTConnect planner_configs: - AnytimePathShortening - SBL @@ -155,7 +155,7 @@ stretch_arm: - SPARS - SPARStwo stretch_gripper: - default_planner_config: "" + default_planner_config: RRTConnect planner_configs: - AnytimePathShortening - SBL