diff --git a/ur_bringup/launch/ur10.launch b/ur_bringup/launch/ur10.launch deleted file mode 100644 index 88ab03bb823e872e81c564b25650a095c4d58f5a..0000000000000000000000000000000000000000 --- a/ur_bringup/launch/ur10.launch +++ /dev/null @@ -1,22 +0,0 @@ -<?xml version="1.0"?> -<!-- - Universal robot ur10 launch. Loads ur10 robot description (see ur_common.launch - for more info) - - Usage: - ur10.launch robot_ip:=<value> ---> -<launch> - - <!-- robot_ip: IP-address of the robot's socket-messaging server --> - <arg name="robot_ip" /> - - <!-- robot model --> - <include file="$(find ur_description)/launch/ur10_upload.launch" /> - - <!-- ur common --> - <include file="$(find ur_bringup)/launch/ur_common.launch"> - <arg name="robot_ip" value="$(arg robot_ip)" /> - </include> - -</launch> diff --git a/ur_bringup/launch/ur5.launch b/ur_bringup/launch/ur5.launch deleted file mode 100644 index e508bb034645481638231c8cdbe6bce21f428f6c..0000000000000000000000000000000000000000 --- a/ur_bringup/launch/ur5.launch +++ /dev/null @@ -1,22 +0,0 @@ -<?xml version="1.0"?> -<!-- - Universal robot ur5 launch. Loads ur5 robot description (see ur_common.launch - for more info) - - Usage: - ur5.launch robot_ip:=<value> ---> -<launch> - - <!-- robot_ip: IP-address of the robot's socket-messaging server --> - <arg name="robot_ip" /> - - <!-- robot model --> - <include file="$(find ur_description)/launch/ur5_upload.launch" /> - - <!-- ur common --> - <include file="$(find ur_bringup)/launch/ur_common.launch"> - <arg name="robot_ip" value="$(arg robot_ip)" /> - </include> - -</launch> diff --git a/ur_description/meshes/ur10/Base.stl b/ur_description/meshes/ur10/collision/Base.stl similarity index 100% rename from ur_description/meshes/ur10/Base.stl rename to ur_description/meshes/ur10/collision/Base.stl diff --git a/ur_description/meshes/ur10/Forearm.stl b/ur_description/meshes/ur10/collision/Forearm.stl similarity index 100% rename from ur_description/meshes/ur10/Forearm.stl rename to ur_description/meshes/ur10/collision/Forearm.stl diff --git a/ur_description/meshes/ur10/Shoulder.stl b/ur_description/meshes/ur10/collision/Shoulder.stl similarity index 100% rename from ur_description/meshes/ur10/Shoulder.stl rename to ur_description/meshes/ur10/collision/Shoulder.stl diff --git a/ur_description/meshes/ur10/UpperArm.stl b/ur_description/meshes/ur10/collision/UpperArm.stl similarity index 100% rename from ur_description/meshes/ur10/UpperArm.stl rename to ur_description/meshes/ur10/collision/UpperArm.stl diff --git a/ur_description/meshes/ur10/Wrist1.stl b/ur_description/meshes/ur10/collision/Wrist1.stl similarity index 100% rename from ur_description/meshes/ur10/Wrist1.stl rename to ur_description/meshes/ur10/collision/Wrist1.stl diff --git a/ur_description/meshes/ur10/Wrist2.stl b/ur_description/meshes/ur10/collision/Wrist2.stl similarity index 100% rename from ur_description/meshes/ur10/Wrist2.stl rename to ur_description/meshes/ur10/collision/Wrist2.stl diff --git a/ur_description/meshes/ur10/Wrist3.stl b/ur_description/meshes/ur10/collision/Wrist3.stl similarity index 100% rename from ur_description/meshes/ur10/Wrist3.stl rename to ur_description/meshes/ur10/collision/Wrist3.stl diff --git a/ur_description/meshes/ur10/visual/Base.stl b/ur_description/meshes/ur10/visual/Base.stl new file mode 100644 index 0000000000000000000000000000000000000000..0ac507704937ad22a3a9bfa96b304465986e9073 Binary files /dev/null and b/ur_description/meshes/ur10/visual/Base.stl differ diff --git a/ur_description/meshes/ur10/visual/Forearm.stl b/ur_description/meshes/ur10/visual/Forearm.stl new file mode 100644 index 0000000000000000000000000000000000000000..5a2d56815395d3dfabcaa96c88b5f5e8fd9f2f21 Binary files /dev/null and b/ur_description/meshes/ur10/visual/Forearm.stl differ diff --git a/ur_description/meshes/ur10/visual/Shoulder.stl b/ur_description/meshes/ur10/visual/Shoulder.stl new file mode 100644 index 0000000000000000000000000000000000000000..4de55907b784289a2a4634253ab2f859f452ea91 Binary files /dev/null and b/ur_description/meshes/ur10/visual/Shoulder.stl differ diff --git a/ur_description/meshes/ur10/visual/UpperArm.stl b/ur_description/meshes/ur10/visual/UpperArm.stl new file mode 100644 index 0000000000000000000000000000000000000000..3690528f03f001d12278ddcb2e304dbc51c8ef00 Binary files /dev/null and b/ur_description/meshes/ur10/visual/UpperArm.stl differ diff --git a/ur_description/meshes/ur10/visual/Wrist1.stl b/ur_description/meshes/ur10/visual/Wrist1.stl new file mode 100644 index 0000000000000000000000000000000000000000..6003010b45a24020496d32c8784b91bc0192ce93 Binary files /dev/null and b/ur_description/meshes/ur10/visual/Wrist1.stl differ diff --git a/ur_description/meshes/ur10/visual/Wrist2.stl b/ur_description/meshes/ur10/visual/Wrist2.stl new file mode 100644 index 0000000000000000000000000000000000000000..b3ea078051c9b61bcf06904ecbf3f0fa4b88f1a9 Binary files /dev/null and b/ur_description/meshes/ur10/visual/Wrist2.stl differ diff --git a/ur_description/meshes/ur10/visual/Wrist3.stl b/ur_description/meshes/ur10/visual/Wrist3.stl new file mode 100644 index 0000000000000000000000000000000000000000..01b26bf93baa6c786e76aec5a1a96f7ca93273f9 Binary files /dev/null and b/ur_description/meshes/ur10/visual/Wrist3.stl differ diff --git a/ur_description/urdf/ur10.urdf.xacro b/ur_description/urdf/ur10.urdf.xacro index 593dd6801d6380e3b2d2f77e7c2393579b6ba780..9421d2d5415fad6c5eb9af8ce71c32863da749bd 100644 --- a/ur_description/urdf/ur10.urdf.xacro +++ b/ur_description/urdf/ur10.urdf.xacro @@ -52,23 +52,23 @@ - <xacro:macro name="ur10_robot" params="parent name *origin"> + <xacro:macro name="ur10_robot" params="prefix"> - <!-- joint between base_link and ur_base_link --> - <joint name="${name}_base_joint" type="fixed" > - <insert_block name="origin" /> - <parent link="${parent}" /> - <child link="${name}_base_link" /> - </joint> - - <link name="${name}_base_link" > + <link name="${prefix}base_link" > <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Base.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" /> </geometry> <origin xyz="0.0 0.0 0.003" rpy="0.0 0.0 ${3.0 * pi / 4.0}" /> <material name="UR/Blue" /> </visual> + + <collision> + <geometry> + <mesh filename="package://ur_description/meshes/ur10/collision/Base.stl" /> + </geometry> + <origin xyz="0.0 0.0 0.003" rpy="0.0 0.0 ${3.0 * pi / 4.0}" /> + </collision> <inertial> <mass value="${base_mass}" /> @@ -76,26 +76,26 @@ </inertial> </link> - <joint name="${name}_shoulder_pan_joint" type="revolute"> - <parent link="${name}_base_link" /> - <child link = "${name}_shoulder_link" /> + <joint name="${prefix}shoulder_pan_joint" type="revolute"> + <parent link="${prefix}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" /> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/> <dynamics damping="10" friction="0.1"/> </joint> - <link name="${name}_shoulder_link"> + <link name="${prefix}shoulder_link"> <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Shoulder.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/Shoulder.stl" /> </geometry> <material name="UR/Grey" /> </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Shoulder.stl" /> + <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.stl" /> </geometry> </collision> @@ -106,19 +106,19 @@ </inertial> </link> - <joint name="${name}_shoulder_lift_joint" type="revolute"> - <parent link="${name}_shoulder_link" /> - <child link = "${name}_upper_arm_link" /> + <joint name="${prefix}shoulder_lift_joint" type="revolute"> + <parent link="${prefix}shoulder_link" /> + <child link = "${prefix}upper_arm_link" /> <origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" /> <axis xyz="0.0 1.0 0.0" /> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/> <dynamics damping="10" friction="0.1"/> </joint> - <link name="${name}_upper_arm_link"> + <link name="${prefix}upper_arm_link"> <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/UpperArm.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/UpperArm.stl" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> <material name="UR/Blue" /> @@ -126,7 +126,7 @@ <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/UpperArm.stl" /> + <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.stl" /> </geometry> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> </collision> @@ -138,26 +138,26 @@ </inertial> </link> - <joint name="${name}_elbow_joint" type="revolute"> - <parent link="${name}_upper_arm_link" /> - <child link = "${name}_forearm_link" /> + <joint name="${prefix}elbow_joint" type="revolute"> + <parent link="${prefix}upper_arm_link" /> + <child link = "${prefix}forearm_link" /> <origin xyz="0.0 ${-elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" /> <axis xyz="0.0 1.0 0.0" /> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/> <dynamics damping="10" friction="0.1"/> </joint> - <link name="${name}_forearm_link"> + <link name="${prefix}forearm_link"> <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Forearm.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/Forearm.stl" /> </geometry> <material name="UR/Grey" /> </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Forearm.stl" /> + <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.stl" /> </geometry> </collision> @@ -168,19 +168,19 @@ </inertial> </link> - <joint name="${name}_wrist_1_joint" type="revolute"> - <parent link="${name}_forearm_link" /> - <child link = "${name}_wrist_1_link" /> + <joint name="${prefix}wrist_1_joint" type="revolute"> + <parent link="${prefix}forearm_link" /> + <child link = "${prefix}wrist_1_link" /> <origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" /> <axis xyz="0.0 1.0 0.0" /> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/> <dynamics damping="10" friction="0.1"/> </joint> - <link name="${name}_wrist_1_link"> + <link name="${prefix}wrist_1_link"> <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Wrist1.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/Wrist1.stl" /> </geometry> <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0 0.0" /> <material name="UR/Blue" /> @@ -188,7 +188,7 @@ <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Wrist1.stl" /> + <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.stl" /> </geometry> <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0 0.0" /> </collision> @@ -200,19 +200,19 @@ </inertial> </link> - <joint name="${name}_wrist_2_joint" type="revolute"> - <parent link="${name}_wrist_1_link" /> - <child link = "${name}_wrist_2_link" /> + <joint name="${prefix}wrist_2_joint" type="revolute"> + <parent link="${prefix}wrist_1_link" /> + <child link = "${prefix}wrist_2_link" /> <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" /> <axis xyz="0.0 0.0 1.0" /> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/> <dynamics damping="10" friction="0.1"/> </joint> - <link name="${name}_wrist_2_link"> + <link name="${prefix}wrist_2_link"> <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Wrist2.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/Wrist2.stl" /> </geometry> <origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" /> <material name="UR/Grey" /> @@ -220,7 +220,7 @@ <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Wrist2.stl" /> + <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.stl" /> </geometry> <origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" /> </collision> @@ -232,19 +232,19 @@ </inertial> </link> - <joint name="${name}_wrist_3_joint" type="revolute"> - <parent link="${name}_wrist_2_link" /> - <child link = "${name}_wrist_3_link" /> + <joint name="${prefix}wrist_3_joint" type="revolute"> + <parent link="${prefix}wrist_2_link" /> + <child link = "${prefix}wrist_3_link" /> <origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" /> <axis xyz="0.0 1.0 0.0" /> <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/> <dynamics damping="10" friction="0.1"/> </joint> - <link name="${name}_wrist_3_link"> + <link name="${prefix}wrist_3_link"> <visual> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Wrist3.stl" /> + <mesh filename="package://ur_description/meshes/ur10/visual/Wrist3.stl" /> </geometry> <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 0" /> <material name="UR/Blue" /> @@ -252,7 +252,7 @@ <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/Wrist3.stl" /> + <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.stl" /> </geometry> <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 0" /> </collision> @@ -264,8 +264,8 @@ </inertial> </link> - <xacro:ur10_arm_transmission name="${name}" /> - <xacro:ur10_arm_gazebo name="${name}" /> + <xacro:ur10_arm_transmission name="${prefix}" /> + <xacro:ur10_arm_gazebo name="${prefix}" /> </xacro:macro> </robot> diff --git a/ur_description/urdf/ur10_robot.urdf.xacro b/ur_description/urdf/ur10_robot.urdf.xacro index 00c9fb4493fce5bcdc97ac0a882c5821d54fef39..ec027faca1efb8a5b82f6367a4a456b2e4be09f7 100644 --- a/ur_description/urdf/ur10_robot.urdf.xacro +++ b/ur_description/urdf/ur10_robot.urdf.xacro @@ -7,38 +7,12 @@ <!-- common stuff --> <include filename="$(find ur_description)/urdf/gazebo.urdf.xacro" /> - <!--include filename="$(find ur_description)/urdf/materials.urdf.xacro" /--> <!-- ur10 --> <include filename="$(find ur_description)/urdf/ur10.urdf.xacro" /> - <!-- foot for arm --> - <link name="base_link"> - <inertial> - <origin xyz="0 0 -10" rpy="0 0 0"/> - <mass value="1000.0"/> - <inertia ixx="100.0" ixy="0" ixz="0" iyy="100.0" iyz="0" izz="100.0" /> - </inertial> - - <visual> - <origin xyz="0 0 0.25" rpy="0 0 0" /> - <geometry> - <cylinder radius="0.1" length="0.5"/> - </geometry> - <material name="Grey" /> - </visual> - - <collision> - <origin xyz="0 0 0.25" rpy="0 0 0" /> - <geometry> - <cylinder radius="0.1" length="0.5"/> - </geometry> - </collision> - </link> - <!-- arm --> - <xacro:ur10_robot name="arm" parent="base_link"> - <origin xyz="0 0 0.5" rpy="0 0 0" /> + <xacro:ur10_robot prefix=""> </xacro:ur10_robot> diff --git a/ur_description/urdf/ur5.urdf.xacro b/ur_description/urdf/ur5.urdf.xacro index 6f5ee47849863334c631ba1e9ff2647f4a5c080f..aca612375cb0dc1c58ec100fb5d754bc2da79c8b 100644 --- a/ur_description/urdf/ur5.urdf.xacro +++ b/ur_description/urdf/ur5.urdf.xacro @@ -5,8 +5,9 @@ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:xacro="http://ros.org/wiki/xacro"> -<include filename="$(find ur_description)/urdf/ur5.transmission.xacro" /> + <include filename="$(find ur_description)/urdf/ur5.transmission.xacro" /> <include filename="$(find ur_description)/urdf/ur5.gazebo.xacro" /> + <include filename="$(find ur_description)/urdf/materials.urdf.xacro" /> <!-- DH for UR5: a = [0.00000, -0.42500, -0.39225, 0.00000, 0.00000, 0.0000] @@ -250,37 +251,6 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, </joint> <link name="${prefix}ee_link" /> - - - - <!-- Extra links for collision model --> - <!-- Somehow don't work with gazebo TODO: fix this - <joint name="${prefix}shoulder_collision_joint" type="fixed"> - <parent link="${prefix}upper_arm_link" /> - <child link = "${prefix}shoulder_collision_link" /> - </joint> - <link name="${prefix}shoulder_collision_link"> - <collision> - <geometry> - <cylinder length="${shoulder_collision_length}" radius="${shoulder_radius}"/> - </geometry> - <origin xyz="0.0 ${-shoulder_collision_offset} 0.0" rpy="${-pi / 2.0} 0.0 0.0" /> - </collision> - </link> - - <joint name="${prefix}elbow_collision_joint" type="fixed"> - <parent link="${prefix}upper_arm_link" /> - <child link = "${prefix}elbow_collision_link" /> - </joint> - <link name="${prefix}elbow_collision_link"> - <collision> - <geometry> - <cylinder length="${elbow_collision_length}" radius="${elbow_radius}"/> - </geometry> - <origin xyz="0.0 ${-elbow_collision_offset} ${upper_arm_length}" rpy="${pi / 2.0} 0.0 0.0" /> - </collision> - </link> - --> <xacro:ur_arm_transmission name="${prefix}" /> diff --git a/ur_description/urdf/ur5_robot.urdf.xacro b/ur_description/urdf/ur5_robot.urdf.xacro index f1a7359960615cce3836804d996d2a46013af515..367d05438972f7f900f5f56c462dacd38f57e968 100644 --- a/ur_description/urdf/ur5_robot.urdf.xacro +++ b/ur_description/urdf/ur5_robot.urdf.xacro @@ -7,7 +7,6 @@ <!-- common stuff --> <include filename="$(find ur_description)/urdf/gazebo.urdf.xacro" /> - <include filename="$(find ur_description)/urdf/materials.urdf.xacro" /> <!-- ur5 --> <include filename="$(find ur_description)/urdf/ur5.urdf.xacro" />