From 93ba9e5e7090d07ef1c610daa33aba2012100ace Mon Sep 17 00:00:00 2001 From: ipa-fxm <felix.messmer@ipa.fhg.de> Date: Tue, 21 Oct 2014 07:54:27 +0000 Subject: [PATCH] re-run moveit_setup_assistant with new collision meshes --- ur5_moveit_config/.setup_assistant | 2 +- ur5_moveit_config/config/fake_controllers.yaml | 5 ++++- ur5_moveit_config/config/ompl_planning.yaml | 15 ++++++++++++++- ur5_moveit_config/config/ur5.srdf | 14 +++++--------- 4 files changed, 24 insertions(+), 12 deletions(-) diff --git a/ur5_moveit_config/.setup_assistant b/ur5_moveit_config/.setup_assistant index 0a983ec..fccc0b6 100644 --- a/ur5_moveit_config/.setup_assistant +++ b/ur5_moveit_config/.setup_assistant @@ -5,4 +5,4 @@ moveit_setup_assistant_config: SRDF: relative_path: config/ur5.srdf CONFIG: - generated_timestamp: 1409142284 \ No newline at end of file + generated_timestamp: 1413877529 \ No newline at end of file diff --git a/ur5_moveit_config/config/fake_controllers.yaml b/ur5_moveit_config/config/fake_controllers.yaml index a7300cf..5e24f94 100644 --- a/ur5_moveit_config/config/fake_controllers.yaml +++ b/ur5_moveit_config/config/fake_controllers.yaml @@ -6,4 +6,7 @@ controller_list: - elbow_joint - wrist_1_joint - wrist_2_joint - - wrist_3_joint \ No newline at end of file + - wrist_3_joint + - name: fake_endeffector_controller + joints: + [] \ No newline at end of file diff --git a/ur5_moveit_config/config/ompl_planning.yaml b/ur5_moveit_config/config/ompl_planning.yaml index d866c6a..6d2133f 100644 --- a/ur5_moveit_config/config/ompl_planning.yaml +++ b/ur5_moveit_config/config/ompl_planning.yaml @@ -35,4 +35,17 @@ manipulator: - PRMkConfigDefault - PRMstarkConfigDefault projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) - longest_valid_segment_fraction: 0.05 \ No newline at end of file + longest_valid_segment_fraction: 0.05 +endeffector: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault \ No newline at end of file diff --git a/ur5_moveit_config/config/ur5.srdf b/ur5_moveit_config/config/ur5.srdf index d5aba4a..9b13ceb 100644 --- a/ur5_moveit_config/config/ur5.srdf +++ b/ur5_moveit_config/config/ur5.srdf @@ -10,10 +10,10 @@ <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> <group name="manipulator"> - <chain base_link="base_link" tip_link="ee_link"/> + <chain base_link="base_link" tip_link="ee_link" /> </group> <group name="endeffector"> - <link name="ee_link"/> + <link name="ee_link" /> </group> <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> <group_state name="home" group="manipulator"> @@ -37,18 +37,14 @@ <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)--> <virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" /> <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> - <disable_collisions link1="base_link" link2="forearm_link" reason="Never" /> <disable_collisions link1="base_link" link2="shoulder_link" reason="Adjacent" /> - <disable_collisions link1="base_link" link2="upper_arm_link" reason="Never" /> - <disable_collisions link1="forearm_link" link2="shoulder_link" reason="Never" /> + <disable_collisions link1="ee_link" link2="wrist_1_link" reason="Never" /> + <disable_collisions link1="ee_link" link2="wrist_2_link" reason="Never" /> + <disable_collisions link1="ee_link" link2="wrist_3_link" reason="Adjacent" /> <disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" /> <disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" /> - <disable_collisions link1="forearm_link" link2="wrist_2_link" reason="Never" /> - <disable_collisions link1="forearm_link" link2="wrist_3_link" reason="Never" /> <disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" /> - <disable_collisions link1="upper_arm_link" link2="wrist_1_link" reason="Never" /> <disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent" /> <disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never" /> <disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent" /> - <disable_collisions link1="ee_link" link2="wrist_3_link" reason="Adjacent" /> </robot> -- GitLab