From f518c4c09b68e271befa673d73d0a186a1ae4237 Mon Sep 17 00:00:00 2001 From: Marco Esposito <marco.esposito@tum.de> Date: Tue, 14 Jul 2015 13:01:38 +0200 Subject: [PATCH] Adding comment explaining the choice of default planning algorithm --- ur10_moveit_config/config/ompl_planning.yaml | 2 ++ ur5_moveit_config/config/ompl_planning.yaml | 2 ++ 2 files changed, 4 insertions(+) diff --git a/ur10_moveit_config/config/ompl_planning.yaml b/ur10_moveit_config/config/ompl_planning.yaml index 2af548e..8f74383 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 2af548e..8f74383 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: -- GitLab