diff --git a/ur_description/urdf/ur10_joint_limited_robot.urdf b/ur_description/urdf/ur10_joint_limited_robot.urdf index 7ccfc3c332ef7f8d7bde974a7f69d0c6b533f2a8..b2c3bba13460bf9df4ff38e3e269b1cb9af7965b 100644 --- a/ur_description/urdf/ur10_joint_limited_robot.urdf +++ b/ur_description/urdf/ur10_joint_limited_robot.urdf @@ -35,7 +35,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Base.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/> </geometry> </collision> <inertial> @@ -60,7 +60,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/> </geometry> </collision> <inertial> @@ -85,7 +85,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/upper_arm.stl"/> </geometry> </collision> <inertial> @@ -110,7 +110,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/> </geometry> </collision> <inertial> @@ -135,7 +135,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/wrist_1.stl"/> </geometry> </collision> <inertial> @@ -160,7 +160,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/wrist_2.stl"/> </geometry> </collision> <inertial> @@ -185,7 +185,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/wrist_3.stl"/> </geometry> </collision> <inertial> @@ -199,7 +199,14 @@ <child link="ee_link"/> <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0922 0.0"/> </joint> - <link name="ee_link"/> + <link name="ee_link"> + <collision> + <geometry> + <box size="0.01 0.01 0.01"/> + </geometry> + <origin rpy="0 0 0" xyz="-0.01 0 0"/> + </collision> + </link> <transmission name="shoulder_pan_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="shoulder_pan_joint"/> diff --git a/ur_description/urdf/ur10_robot.urdf b/ur_description/urdf/ur10_robot.urdf index 810b5d81d8cf145ca8cb128587c6249b510a88c8..7287ffb392d41d51d5a23cd4b6acf9c40c1eedf0 100644 --- a/ur_description/urdf/ur10_robot.urdf +++ b/ur_description/urdf/ur10_robot.urdf @@ -35,7 +35,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Base.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/> </geometry> </collision> <inertial> @@ -60,7 +60,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/shoulder.stl"/> </geometry> </collision> <inertial> @@ -85,7 +85,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/upper_arm.stl"/> </geometry> </collision> <inertial> @@ -110,7 +110,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Forearm.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/> </geometry> </collision> <inertial> @@ -135,7 +135,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/wrist_1.stl"/> </geometry> </collision> <inertial> @@ -160,7 +160,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/wrist_2.stl"/> </geometry> </collision> <inertial> @@ -185,7 +185,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.dae"/> + <mesh filename="package://ur_description/meshes/ur10/collision/wrist_3.stl"/> </geometry> </collision> <inertial> @@ -199,7 +199,14 @@ <child link="ee_link"/> <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0922 0.0"/> </joint> - <link name="ee_link"/> + <link name="ee_link"> + <collision> + <geometry> + <box size="0.01 0.01 0.01"/> + </geometry> + <origin rpy="0 0 0" xyz="-0.01 0 0"/> + </collision> + </link> <transmission name="shoulder_pan_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="shoulder_pan_joint"/> diff --git a/ur_description/urdf/ur5_joint_limited_robot.urdf b/ur_description/urdf/ur5_joint_limited_robot.urdf index b0c992b45df90056ec670bdde60cfe914abc841f..671e2f8e431243fb7f2e7c125d28364fa189c0a1 100644 --- a/ur_description/urdf/ur5_joint_limited_robot.urdf +++ b/ur_description/urdf/ur5_joint_limited_robot.urdf @@ -35,7 +35,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Base.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/base.stl"/> </geometry> </collision> <inertial> @@ -60,7 +60,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Shoulder.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/> </geometry> </collision> <inertial> @@ -85,7 +85,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/UpperArm.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/upper_arm.stl"/> </geometry> </collision> <inertial> @@ -110,7 +110,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Forearm.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl"/> </geometry> </collision> <inertial> @@ -135,7 +135,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Wrist1.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/wrist_1.stl"/> </geometry> </collision> <inertial> @@ -160,7 +160,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Wrist2.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/wrist_2.stl"/> </geometry> </collision> <inertial> @@ -185,7 +185,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Wrist3.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/wrist_3.stl"/> </geometry> </collision> <inertial> @@ -199,7 +199,14 @@ <child link="ee_link"/> <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/> </joint> - <link name="ee_link"/> + <link name="ee_link"> + <collision> + <geometry> + <box size="0.01 0.01 0.01"/> + </geometry> + <origin rpy="0 0 0" xyz="-0.01 0 0"/> + </collision> + </link> <transmission name="shoulder_pan_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="shoulder_pan_joint"/> diff --git a/ur_description/urdf/ur5_robot.urdf b/ur_description/urdf/ur5_robot.urdf index 74103fa54f91ae1cf0a2721f61b82ef1e3916fff..d516f3dfbe701d1e3e168357f760be6054298f38 100644 --- a/ur_description/urdf/ur5_robot.urdf +++ b/ur_description/urdf/ur5_robot.urdf @@ -35,7 +35,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Base.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/base.stl"/> </geometry> </collision> <inertial> @@ -60,7 +60,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Shoulder.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/> </geometry> </collision> <inertial> @@ -85,7 +85,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/UpperArm.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/upper_arm.stl"/> </geometry> </collision> <inertial> @@ -110,7 +110,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Forearm.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl"/> </geometry> </collision> <inertial> @@ -135,7 +135,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Wrist1.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/wrist_1.stl"/> </geometry> </collision> <inertial> @@ -160,7 +160,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Wrist2.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/wrist_2.stl"/> </geometry> </collision> <inertial> @@ -185,7 +185,7 @@ </visual> <collision> <geometry> - <mesh filename="package://ur_description/meshes/ur5/collision/Wrist3.dae"/> + <mesh filename="package://ur_description/meshes/ur5/collision/wrist_3.stl"/> </geometry> </collision> <inertial> @@ -199,7 +199,14 @@ <child link="ee_link"/> <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/> </joint> - <link name="ee_link"/> + <link name="ee_link"> + <collision> + <geometry> + <box size="0.01 0.01 0.01"/> + </geometry> + <origin rpy="0 0 0" xyz="-0.01 0 0"/> + </collision> + </link> <transmission name="shoulder_pan_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="shoulder_pan_joint"/>