diff --git a/ur10_moveit_config/.setup_assistant b/ur10_moveit_config/.setup_assistant index 6216ff43850bbbb3bc148739f2516e4a14b35284..475e26379112ad3688fed6100f61ed0d7a6fe44e 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: 1395339352 \ No newline at end of file + generated_timestamp: 1404841877 \ 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 ea35b789a5ac5fd8bd254603d2808c0126ffa4c5..a7300cf485a5f356bb99212771262be2e80911a0 100644 --- a/ur10_moveit_config/config/fake_controllers.yaml +++ b/ur10_moveit_config/config/fake_controllers.yaml @@ -6,4 +6,4 @@ controller_list: - elbow_joint - wrist_1_joint - wrist_2_joint - - wrist_3_joint + - wrist_3_joint \ No newline at end of file diff --git a/ur10_moveit_config/config/kinematics.yaml b/ur10_moveit_config/config/kinematics.yaml index 8168af825f6d52d4a1fa2c471f5a6f341d8c290e..969ba14252bfe9c5dc61a6a01a078447e08f69bb 100644 --- a/ur10_moveit_config/config/kinematics.yaml +++ b/ur10_moveit_config/config/kinematics.yaml @@ -2,10 +2,4 @@ manipulator: kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 - -manipulator_new: - kinematics_solver: ur_kinematics/UR10KinematicsPlugin - kinematics_solver_search_resolution: 0.005 - kinematics_solver_timeout: 0.005 - kinematics_solver_attempts: 3 + kinematics_solver_attempts: 3 \ No newline at end of file diff --git a/ur10_moveit_config/package.xml b/ur10_moveit_config/package.xml index 9a4f0d68795c7917dc84dd86c696597a451401f1..1507287d71fa2e9f5146873349e7253835f5eccf 100644 --- a/ur10_moveit_config/package.xml +++ b/ur10_moveit_config/package.xml @@ -1,7 +1,7 @@ <package> <name>ur10_moveit_config</name> - <version>1.0.2</version> + <version>1.0.3</version> <description> An automatically generated package with all the configuration and launch files for using the ur10 with the MoveIt Motion Planning Framework </description> diff --git a/ur5_moveit_config/.setup_assistant b/ur5_moveit_config/.setup_assistant index da441fc4e803b8ec4b31a21aec25365775cfe0e5..29410e59a6899f02f527a01a5287217fb0c882b6 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: 1395340824 \ No newline at end of file + generated_timestamp: 1404842691 \ No newline at end of file diff --git a/ur5_moveit_config/config/ur5.srdf b/ur5_moveit_config/config/ur5.srdf index 21165b5bc390e20362669d7249cf6b7ba8560264..a24eb2cd274e441daa0d005a378cea07bd6d020d 100644 --- a/ur5_moveit_config/config/ur5.srdf +++ b/ur5_moveit_config/config/ur5.srdf @@ -34,7 +34,7 @@ <!--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="shoulder_link" reason="Adjacent" /> + <disable_collisions link1="shoulder_link" link2="ur_base_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="shoulder_link" link2="upper_arm_link" reason="Adjacent" /> diff --git a/ur5_moveit_config/package.xml b/ur5_moveit_config/package.xml index 38abf305c49766bf24d174bdede1e5c8190e4e9a..110f8814e1134386b895557472b9f06457defd01 100644 --- a/ur5_moveit_config/package.xml +++ b/ur5_moveit_config/package.xml @@ -1,7 +1,7 @@ <package> <name>ur5_moveit_config</name> - <version>1.0.2</version> + <version>1.0.3</version> <description> An automatically generated package with all the configuration and launch files for using the ur5 with the MoveIt Motion Planning Framework </description> diff --git a/ur_description/urdf/ur10.urdf.xacro b/ur_description/urdf/ur10.urdf.xacro index d9564829c961132506754b7cab9b58e6f8385f00..f139dd42626a004f287d3fb34dcca807f3e79eb0 100644 --- a/ur_description/urdf/ur10.urdf.xacro +++ b/ur_description/urdf/ur10.urdf.xacro @@ -51,6 +51,15 @@ <xacro:macro name="ur10_robot" params="prefix"> <link name="${prefix}base_link" > + </link> + + <joint name="${prefix}base_link_joint" type="fixed"> + <parent link="${prefix}base_link" /> + <child link = "${prefix}ur_base_link" /> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + </joint> + + <link name="${prefix}ur_base_link" > <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" /> @@ -73,7 +82,7 @@ </link> <joint name="${prefix}shoulder_pan_joint" type="revolute"> - <parent link="${prefix}base_link" /> + <parent link="${prefix}ur_base_link" /> <child link = "${prefix}shoulder_link" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <axis xyz="0.0 0.0 1.0" /> diff --git a/ur_description/urdf/ur10_joint_limited.urdf.xacro b/ur_description/urdf/ur10_joint_limited.urdf.xacro index d7b9753b8b286df63046cbfe9989779ba5f175b2..1f4860ce6de766ec464d3e5a161a9fb139f578b2 100644 --- a/ur_description/urdf/ur10_joint_limited.urdf.xacro +++ b/ur_description/urdf/ur10_joint_limited.urdf.xacro @@ -51,6 +51,15 @@ <xacro:macro name="ur10_robot" params="prefix"> <link name="${prefix}base_link" > + </link> + + <joint name="${prefix}base_link_joint" type="fixed"> + <parent link="${prefix}base_link" /> + <child link = "${prefix}ur_base_link" /> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + </joint> + + <link name="${prefix}ur_base_link" > <visual> <geometry> <mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" /> @@ -73,7 +82,7 @@ </link> <joint name="${prefix}shoulder_pan_joint" type="revolute"> - <parent link="${prefix}base_link" /> + <parent link="${prefix}ur_base_link" /> <child link = "${prefix}shoulder_link" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <axis xyz="0.0 0.0 1.0" /> diff --git a/ur_description/urdf/ur5.urdf.xacro b/ur_description/urdf/ur5.urdf.xacro index 2cba88782b7522556c2d8a4d10f96f816ec72073..843f3859ea0f59766a8cbdf281b18ff8db028483 100644 --- a/ur_description/urdf/ur5.urdf.xacro +++ b/ur_description/urdf/ur5.urdf.xacro @@ -52,6 +52,15 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <xacro:macro name="ur5_robot" params="prefix"> <link name="${prefix}base_link" > + </link> + + <joint name="${prefix}base_link_joint" type="fixed"> + <parent link="${prefix}base_link" /> + <child link = "${prefix}ur_base_link" /> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + </joint> + + <link name="${prefix}ur_base_link" > <visual> <geometry> <mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" /> @@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, </link> <joint name="${prefix}shoulder_pan_joint" type="revolute"> - <parent link="${prefix}base_link" /> + <parent link="${prefix}ur_base_link" /> <child link = "${prefix}shoulder_link" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <axis xyz="0 0 1" /> diff --git a/ur_description/urdf/ur5_joint_limited.urdf.xacro b/ur_description/urdf/ur5_joint_limited.urdf.xacro index 0dd533c27143b46ad7c90797b8b4f4f42d869f3c..1fe33a401078815a7fc7eb1862527167331d99bf 100644 --- a/ur_description/urdf/ur5_joint_limited.urdf.xacro +++ b/ur_description/urdf/ur5_joint_limited.urdf.xacro @@ -52,6 +52,15 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, <xacro:macro name="ur5_robot" params="prefix"> <link name="${prefix}base_link" > + </link> + + <joint name="${prefix}base_link_joint" type="fixed"> + <parent link="${prefix}base_link" /> + <child link = "${prefix}ur_base_link" /> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + </joint> + + <link name="${prefix}ur_base_link" > <visual> <geometry> <mesh filename="package://ur_description/meshes/ur5/visual/Base.dae" /> @@ -71,7 +80,7 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, </link> <joint name="${prefix}shoulder_pan_joint" type="revolute"> - <parent link="${prefix}base_link" /> + <parent link="${prefix}ur_base_link" /> <child link = "${prefix}shoulder_link" /> <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" /> <axis xyz="0 0 1" />