diff --git a/ur10_moveit_config/.setup_assistant b/ur10_moveit_config/.setup_assistant index 026a76bc594333c47ad87c4c1a5fe7b0ade1a185..9129e624cd4cba038e454dd481e2c9369f57d787 100644 --- a/ur10_moveit_config/.setup_assistant +++ b/ur10_moveit_config/.setup_assistant @@ -5,4 +5,4 @@ moveit_setup_assistant_config: SRDF: relative_path: config/ur10.srdf CONFIG: - generated_timestamp: 1409148189 \ No newline at end of file + generated_timestamp: 1413893323 \ No newline at end of file diff --git a/ur10_moveit_config/config/fake_controllers.yaml b/ur10_moveit_config/config/fake_controllers.yaml index a7300cf485a5f356bb99212771262be2e80911a0..5e24f945159e712dd79a50a75d5986c317669474 100644 --- a/ur10_moveit_config/config/fake_controllers.yaml +++ b/ur10_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/ur10_moveit_config/config/ompl_planning.yaml b/ur10_moveit_config/config/ompl_planning.yaml index d866c6a8b084ffbf5c702f81987cb345eb5845eb..6d2133f845494e5bdfd36bca616ebeab01db14a9 100644 --- a/ur10_moveit_config/config/ompl_planning.yaml +++ b/ur10_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/ur10_moveit_config/config/ur10.srdf b/ur10_moveit_config/config/ur10.srdf index d943a92ca160934284b24c390e83bf07b6db47ec..dc3b1b817d37c6a835d4dc202fe953be2c0ffe37 100644 --- a/ur10_moveit_config/config/ur10.srdf +++ b/ur10_moveit_config/config/ur10.srdf @@ -37,16 +37,17 @@ <!--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="base_link" link2="wrist_1_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="shoulder_link" link2="wrist_1_link" reason="Never" /> + <disable_collisions link1="shoulder_link" link2="wrist_2_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" />