diff --git a/ur10_moveit_config/config/ompl_planning.yaml b/ur10_moveit_config/config/ompl_planning.yaml
index 2af548e441d8962dd5eeeec147cf96c33ff2aa3d..8f743830fed5ded3d98a82e8bde4876a46b7048e 100644
--- a/ur10_moveit_config/config/ompl_planning.yaml
+++ b/ur10_moveit_config/config/ompl_planning.yaml
@@ -34,6 +34,8 @@ manipulator:
     - TRRTkConfigDefault
     - PRMkConfigDefault
     - PRMstarkConfigDefault
+  ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE
+  #projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
   longest_valid_segment_fraction: 0.05
 endeffector:
   planner_configs:
diff --git a/ur5_moveit_config/config/ompl_planning.yaml b/ur5_moveit_config/config/ompl_planning.yaml
index 2af548e441d8962dd5eeeec147cf96c33ff2aa3d..8f743830fed5ded3d98a82e8bde4876a46b7048e 100644
--- a/ur5_moveit_config/config/ompl_planning.yaml
+++ b/ur5_moveit_config/config/ompl_planning.yaml
@@ -34,6 +34,8 @@ manipulator:
     - TRRTkConfigDefault
     - PRMkConfigDefault
     - PRMstarkConfigDefault
+  ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE
+  #projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
   longest_valid_segment_fraction: 0.05
 endeffector:
   planner_configs: