From d6a0d846492ba4716b06b42e20e785ae2e0737fb Mon Sep 17 00:00:00 2001
From: Gregory LeMasurier <gregorylemasurier@gmail.com>
Date: Wed, 18 Sep 2024 15:38:29 -0400
Subject: [PATCH] Revert "Update Humble"

---
 CHANGELOG.rst                         | 14 --------------
 README.md                             |  2 +-
 config/ur10/physical_parameters.yaml  | 12 ++++++------
 config/ur10e/physical_parameters.yaml | 12 ++++++------
 config/ur3e/physical_parameters.yaml  | 12 ++++++------
 config/ur5/physical_parameters.yaml   |  2 +-
 config/ur5e/physical_parameters.yaml  | 12 ++++++------
 package.xml                           |  2 +-
 urdf/ur.ros2_control.xacro            |  1 -
 9 files changed, 27 insertions(+), 42 deletions(-)

diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index 5d0b37a..6bf2a68 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -2,20 +2,6 @@
 Changelog for package ur_description
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
-2.1.7 (2024-09-10)
-------------------
-* Fix masses of robot links (backport of `#187 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/187>`_)
-* Contributors: Felix Exner
-
-2.1.6 (2024-08-09)
-------------------
-* Fixed typo in README.md (`#176 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/176>`_)
-* Added dynamics tag when using mock_components/GenericSystem (backport of `#175 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/175>`_)
-* Auto-update pre-commit hooks (`#171 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/171>`_) (`#172 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/172>`_)
-* Remove ros2_control limit params (`#168 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/168>`_)
-* Add Jazzy to the README (`#163 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/163>`_)
-* Contributors: Filippo Bosi, Niccolo, Felix Exner
-
 2.1.5 (2024-04-25)
 ------------------
 * Fix multi-line strings in DeclareLaunchArgument ( backport of `#140 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/140>`_) (`#153 <https://github.com/UniversalRobots/Universal_Robots_ROS2_Description/issues/153>`_)
diff --git a/README.md b/README.md
index d9f40fb..7695c44 100644
--- a/README.md
+++ b/README.md
@@ -59,7 +59,7 @@ Basically, the description can be modified using configuration values stored in
    should be used.
 
 The four configuration files have to be passed to `ur_macro.urdf` (more specific to the macro
-defined in that file) which is done inside the `ur.urdf.xacro`. Contents of the files are parsed
+defined in that file) which is done inside the `ur.urdf.macro`. Contents of the files are parsed
 inside `ur_common.xacro`.
 
 Arguments that have to be passed to the main `ur.urdf.xacro` file are:
diff --git a/config/ur10/physical_parameters.yaml b/config/ur10/physical_parameters.yaml
index 4364a7b..e651538 100644
--- a/config/ur10/physical_parameters.yaml
+++ b/config/ur10/physical_parameters.yaml
@@ -14,13 +14,13 @@ offsets:
 
 inertia_parameters:
   base_mass: 4.0  # This mass might be incorrect
-  shoulder_mass: 7.1
-  upper_arm_mass: 12.7
+  shoulder_mass: 7.778
+  upper_arm_mass: 12.93
   upper_arm_inertia_offset: 0.175
-  forearm_mass: 4.27
-  wrist_1_mass: 2.0
-  wrist_2_mass: 2.0
-  wrist_3_mass: 0.365
+  forearm_mass: 3.87
+  wrist_1_mass: 1.96
+  wrist_2_mass: 1.96
+  wrist_3_mass: 0.202
 
   shoulder_radius: x0.060   # FROM UR5 DON'T USE
   upper_arm_radius: x0.054  # FROM UR5 DON'T USE
diff --git a/config/ur10e/physical_parameters.yaml b/config/ur10e/physical_parameters.yaml
index 34b4e3b..e72ee84 100644
--- a/config/ur10e/physical_parameters.yaml
+++ b/config/ur10e/physical_parameters.yaml
@@ -14,13 +14,13 @@ offsets:
 
 inertia_parameters:
   base_mass: 4.0  # This mass might be incorrect
-  shoulder_mass: 7.369
-  upper_arm_mass: 13.051
+  shoulder_mass: 7.778
+  upper_arm_mass: 12.93
   upper_arm_inertia_offset: 0.175 # measured from model
-  forearm_mass: 3.989
-  wrist_1_mass: 2.1
-  wrist_2_mass: 1.98
-  wrist_3_mass: 0.615
+  forearm_mass: 3.87
+  wrist_1_mass: 1.96
+  wrist_2_mass: 1.96
+  wrist_3_mass: 0.202
 
   shoulder_radius: x0.060   # FROM UR5 DON'T USE
   upper_arm_radius: x0.054  # FROM UR5 DON'T USE
diff --git a/config/ur3e/physical_parameters.yaml b/config/ur3e/physical_parameters.yaml
index a8d0b10..e7b1d68 100644
--- a/config/ur3e/physical_parameters.yaml
+++ b/config/ur3e/physical_parameters.yaml
@@ -14,13 +14,13 @@ offsets:
 
 inertia_parameters:
   base_mass: 2.0  # This mass might be incorrect
-  shoulder_mass: 1.98
-  upper_arm_mass: 3.4445
+  shoulder_mass: 2.0
+  upper_arm_mass: 3.42
   upper_arm_inertia_offset: 0.12 # measured from model
-  forearm_mass: 1.437
-  wrist_1_mass: 0.871
-  wrist_2_mass: 0.805
-  wrist_3_mass: 0.261
+  forearm_mass: 1.26
+  wrist_1_mass: 0.8
+  wrist_2_mass: 0.8
+  wrist_3_mass: 0.35
 
   shoulder_radius: 0.060   # manually measured
   upper_arm_radius: 0.054  # manually measured
diff --git a/config/ur5/physical_parameters.yaml b/config/ur5/physical_parameters.yaml
index 07d1ebc..9d0a403 100644
--- a/config/ur5/physical_parameters.yaml
+++ b/config/ur5/physical_parameters.yaml
@@ -17,7 +17,7 @@ inertia_parameters:
   shoulder_mass: 3.7000
   upper_arm_mass: 8.3930
   upper_arm_inertia_offset: 0.136
-  forearm_mass: 2.33
+  forearm_mass: 2.2750
   wrist_1_mass: 1.2190
   wrist_2_mass: 1.2190
   wrist_3_mass: 0.1879
diff --git a/config/ur5e/physical_parameters.yaml b/config/ur5e/physical_parameters.yaml
index 6686a21..f552860 100644
--- a/config/ur5e/physical_parameters.yaml
+++ b/config/ur5e/physical_parameters.yaml
@@ -14,13 +14,13 @@ offsets:
 
 inertia_parameters:
   base_mass: 4.0  # This mass might be incorrect
-  shoulder_mass: 3.761
-  upper_arm_mass: 8.058
+  shoulder_mass: 3.7000
+  upper_arm_mass: 8.3930
   upper_arm_inertia_offset: 0.138 # measured from model
-  forearm_mass: 2.846
-  wrist_1_mass: 1.37
-  wrist_2_mass: 1.3
-  wrist_3_mass: 0.365
+  forearm_mass: 2.2750
+  wrist_1_mass: 1.2190
+  wrist_2_mass: 1.2190
+  wrist_3_mass: 0.1879
 
   shoulder_radius: 0.060   # manually measured
   upper_arm_radius: 0.054  # manually measured
diff --git a/package.xml b/package.xml
index 2663737..e81ded6 100644
--- a/package.xml
+++ b/package.xml
@@ -2,7 +2,7 @@
 <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
 <package format="3">
   <name>ur_description</name>
-  <version>2.1.7</version>
+  <version>2.1.5</version>
   <description>
     URDF description for Universal Robots
   </description>
diff --git a/urdf/ur.ros2_control.xacro b/urdf/ur.ros2_control.xacro
index 8582351..f85c086 100644
--- a/urdf/ur.ros2_control.xacro
+++ b/urdf/ur.ros2_control.xacro
@@ -35,7 +35,6 @@
           <plugin>mock_components/GenericSystem</plugin>
           <param name="fake_sensor_commands">${fake_sensor_commands}</param>
           <param name="state_following_offset">0.0</param>
-          <param name="calculate_dynamics">true</param>
         </xacro:if>
         <xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}">
           <plugin>ur_robot_driver/URPositionHardwareInterface</plugin>