From 2d26506c79d9149a8f0460903ef6168e58997c8c Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 4 Sep 2024 16:11:58 +0200 Subject: [PATCH] Fix masses of robot links I think this goes way back but this should match the actual specifications. --- 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 ++++++------ 5 files changed, 25 insertions(+), 25 deletions(-) diff --git a/config/ur10/physical_parameters.yaml b/config/ur10/physical_parameters.yaml index e651538..4364a7b 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.778 - upper_arm_mass: 12.93 + shoulder_mass: 7.1 + upper_arm_mass: 12.7 upper_arm_inertia_offset: 0.175 - forearm_mass: 3.87 - wrist_1_mass: 1.96 - wrist_2_mass: 1.96 - wrist_3_mass: 0.202 + forearm_mass: 4.27 + wrist_1_mass: 2.0 + wrist_2_mass: 2.0 + wrist_3_mass: 0.365 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 e72ee84..34b4e3b 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.778 - upper_arm_mass: 12.93 + shoulder_mass: 7.369 + upper_arm_mass: 13.051 upper_arm_inertia_offset: 0.175 # measured from model - forearm_mass: 3.87 - wrist_1_mass: 1.96 - wrist_2_mass: 1.96 - wrist_3_mass: 0.202 + forearm_mass: 3.989 + wrist_1_mass: 2.1 + wrist_2_mass: 1.98 + wrist_3_mass: 0.615 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 e7b1d68..a8d0b10 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: 2.0 - upper_arm_mass: 3.42 + shoulder_mass: 1.98 + upper_arm_mass: 3.4445 upper_arm_inertia_offset: 0.12 # measured from model - forearm_mass: 1.26 - wrist_1_mass: 0.8 - wrist_2_mass: 0.8 - wrist_3_mass: 0.35 + forearm_mass: 1.437 + wrist_1_mass: 0.871 + wrist_2_mass: 0.805 + wrist_3_mass: 0.261 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 9d0a403..07d1ebc 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.2750 + forearm_mass: 2.33 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 f552860..6686a21 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.7000 - upper_arm_mass: 8.3930 + shoulder_mass: 3.761 + upper_arm_mass: 8.058 upper_arm_inertia_offset: 0.138 # measured from model - forearm_mass: 2.2750 - wrist_1_mass: 1.2190 - wrist_2_mass: 1.2190 - wrist_3_mass: 0.1879 + forearm_mass: 2.846 + wrist_1_mass: 1.37 + wrist_2_mass: 1.3 + wrist_3_mass: 0.365 shoulder_radius: 0.060 # manually measured upper_arm_radius: 0.054 # manually measured