From 8f827358e54bf0518893169700ce9ef2c63942bc Mon Sep 17 00:00:00 2001 From: Guilhem Saurel <guilhem.saurel@laas.fr> Date: Fri, 5 Mar 2021 23:41:13 +0100 Subject: [PATCH] ur5 &_ur5_gripper: set default link mass to 0 --- robots/ur_description/urdf/ur5_gripper.urdf | 20 ++++++++++++++++-- robots/ur_description/urdf/ur5_robot.urdf | 23 ++++++++++++++++++--- 2 files changed, 38 insertions(+), 5 deletions(-) diff --git a/robots/ur_description/urdf/ur5_gripper.urdf b/robots/ur_description/urdf/ur5_gripper.urdf index eaf5b05..45f2901 100644 --- a/robots/ur_description/urdf/ur5_gripper.urdf +++ b/robots/ur_description/urdf/ur5_gripper.urdf @@ -17,7 +17,7 @@ <timeout>5</timeout> <powerStateTopic>power_state</powerStateTopic> <powerStateRate>10.0</powerStateRate> - <fullChargeCapacity>87.78</fullChargeCapacity> + <fullChargeCapacity>87.78</fullChargeCapacity> <dischargeRate>-474</dischargeRate> <chargeRate>525</chargeRate> <dischargeVoltage>15.52</dischargeVoltage> @@ -256,6 +256,11 @@ <origin rpy="0.0 0.0 1.570796325" xyz="0.0 0.0823 0.0"/> </joint> <link name="ee_link"> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> <collision> <geometry> <box size="0.01 0.01 0.01"/> @@ -319,7 +324,13 @@ </transmission> <!-- nothing to do here at the moment --> <!-- ROS base_link to UR 'Base' Coordinates transform --> - <link name="base"/> + <link name="base"> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> + </link> <joint name="base_link-base_fixed_joint" type="fixed"> <!-- NOTE: this rotation is only needed as long as base_link itself is not corrected wrt the real robot (ie: rotated over 180 @@ -331,6 +342,11 @@ </joint> <!-- Frame coincident with all-zeros TCP on UR controller --> <link name="tool0"> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> <visual> <geometry> <box size="0.005 0.02 0.05" /> diff --git a/robots/ur_description/urdf/ur5_robot.urdf b/robots/ur_description/urdf/ur5_robot.urdf index cce6b6a..49d6cc5 100644 --- a/robots/ur_description/urdf/ur5_robot.urdf +++ b/robots/ur_description/urdf/ur5_robot.urdf @@ -16,7 +16,7 @@ <timeout>5</timeout> <powerStateTopic>power_state</powerStateTopic> <powerStateRate>10.0</powerStateRate> - <fullChargeCapacity>87.78</fullChargeCapacity> + <fullChargeCapacity>87.78</fullChargeCapacity> <dischargeRate>-474</dischargeRate> <chargeRate>525</chargeRate> <dischargeVoltage>15.52</dischargeVoltage> @@ -232,6 +232,11 @@ <origin rpy="0.0 0.0 1.57079632679" xyz="0.0 0.0823 0.0"/> </joint> <link name="ee_link"> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> <collision> <geometry> <box size="0.01 0.01 0.01"/> @@ -315,7 +320,13 @@ <selfCollide>true</selfCollide> </gazebo> <!-- ROS base_link to UR 'Base' Coordinates transform --> - <link name="base"/> + <link name="base"> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> + </link> <joint name="base_link-base_fixed_joint" type="fixed"> <!-- NOTE: this rotation is only needed as long as base_link itself is not corrected wrt the real robot (ie: rotated over 180 @@ -326,7 +337,13 @@ <child link="base"/> </joint> <!-- Frame coincident with all-zeros TCP on UR controller --> - <link name="tool0"/> + <link name="tool0"> + <inertial> + <mass value="0"/> + <origin rpy="0 0 0" xyz="0 0 0"/> + <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + </inertial> + </link> <joint name="wrist_3_link-tool0_fixed_joint" type="fixed"> <origin rpy="-1.57079632679 0 0" xyz="0 0.0823 0"/> <parent link="wrist_3_link"/> -- GitLab