From 5d0ea453c69afead82063337a7f62a5d69475ae0 Mon Sep 17 00:00:00 2001
From: Marco Esposito <marco_esposito@mytum.de>
Date: Fri, 10 Apr 2015 14:31:28 +0200
Subject: [PATCH] Use RRTConnect by default for UR5

Fixes bug #193 about slow planning on Indigo

LBKPIECE1 (the previous default) looks to be the wrong planning algorithm for the robot
See https://groups.google.com/forum/#!topic/moveit-users/M71T-GaUNgg
---
 ur5_moveit_config/config/ompl_planning.yaml | 3 +--
 1 file changed, 1 insertion(+), 2 deletions(-)

diff --git a/ur5_moveit_config/config/ompl_planning.yaml b/ur5_moveit_config/config/ompl_planning.yaml
index 6d2133f..2af548e 100644
--- a/ur5_moveit_config/config/ompl_planning.yaml
+++ b/ur5_moveit_config/config/ompl_planning.yaml
@@ -34,7 +34,6 @@ manipulator:
     - TRRTkConfigDefault
     - PRMkConfigDefault
     - PRMstarkConfigDefault
-  projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
   longest_valid_segment_fraction: 0.05
 endeffector:
   planner_configs:
@@ -48,4 +47,4 @@ endeffector:
     - RRTstarkConfigDefault
     - TRRTkConfigDefault
     - PRMkConfigDefault
-    - PRMstarkConfigDefault
\ No newline at end of file
+    - PRMstarkConfigDefault
-- 
GitLab