From 9bfb7b236323e7b04af07e6e12d99c5c39659cd0 Mon Sep 17 00:00:00 2001 From: Chalongrath Pholsiri Date: Tue, 10 Sep 2024 11:57:44 -0500 Subject: [PATCH 1/7] Remove unused dh_parameters --- config/ur10/physical_parameters.yaml | 8 -------- config/ur10e/physical_parameters.yaml | 8 -------- config/ur16e/physical_parameters.yaml | 9 --------- config/ur20/physical_parameters.yaml | 9 --------- config/ur3/physical_parameters.yaml | 8 -------- config/ur30/physical_parameters.yaml | 9 --------- config/ur3e/physical_parameters.yaml | 8 -------- config/ur5/physical_parameters.yaml | 8 -------- config/ur5e/physical_parameters.yaml | 8 -------- urdf/inc/ur_common.xacro | 9 --------- 10 files changed, 84 deletions(-) diff --git a/config/ur10/physical_parameters.yaml b/config/ur10/physical_parameters.yaml index 4364a7b..880fe1c 100644 --- a/config/ur10/physical_parameters.yaml +++ b/config/ur10/physical_parameters.yaml @@ -1,13 +1,5 @@ # Physical parameters -dh_parameters: - d1: 0.1273 - a2: -0.612 - a3: -0.5723 - d4: 0.163941 - d5: 0.1157 - d6: 0.0922 - offsets: shoulder_offset: 0.220941 # measured from model elbow_offset: 0.049042 # measured from model diff --git a/config/ur10e/physical_parameters.yaml b/config/ur10e/physical_parameters.yaml index 34b4e3b..9de2a4e 100644 --- a/config/ur10e/physical_parameters.yaml +++ b/config/ur10e/physical_parameters.yaml @@ -1,13 +1,5 @@ # Physical parameters -dh_parameters: - d1: 0.181 - a2: -0.613 - a3: -0.571 - d4: 0.174 # wrist1_length = d4 - elbow_offset - shoulder_offset - d5: 0.120 - d6: 0.117 - offsets: shoulder_offset: 0.1762 # measured from model elbow_offset: 0.0393 # measured from model diff --git a/config/ur16e/physical_parameters.yaml b/config/ur16e/physical_parameters.yaml index 658d51d..e992ee6 100644 --- a/config/ur16e/physical_parameters.yaml +++ b/config/ur16e/physical_parameters.yaml @@ -1,14 +1,5 @@ # Physical parameters -# from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ -dh_parameters: - d1: 0.1807 - a2: -0.4784 - a3: -0.36 - d4: 0.17415 - d5: 0.11985 - d6: 0.11655 - offsets: shoulder_offset: 0.176 # measured from model elbow_offset: 0.040 # measured from model diff --git a/config/ur20/physical_parameters.yaml b/config/ur20/physical_parameters.yaml index 77d4499..795ef40 100644 --- a/config/ur20/physical_parameters.yaml +++ b/config/ur20/physical_parameters.yaml @@ -1,14 +1,5 @@ # Physical parameters -# from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ -dh_parameters: - d1: 0.2363 - a2: -0.8620 - a3: -0.7287 - d4: 0.201 - d5: 0.1593 - d6: 0.1543 - offsets: shoulder_offset: 0.260 # measured from model elbow_offset: 0.043 # measured from model diff --git a/config/ur3/physical_parameters.yaml b/config/ur3/physical_parameters.yaml index ce207b7..3a3483e 100644 --- a/config/ur3/physical_parameters.yaml +++ b/config/ur3/physical_parameters.yaml @@ -1,13 +1,5 @@ # Physical parameters -dh_parameters: - d1: 0.1519 - a2: -0.24365 - a3: -0.21325 - d4: 0.11235 - d5: 0.08535 - d6: 0.0819 - offsets: shoulder_offset: 0.1198 # measured from model elbow_offset: 0.0275 # measured from model diff --git a/config/ur30/physical_parameters.yaml b/config/ur30/physical_parameters.yaml index 695fe62..c84908b 100644 --- a/config/ur30/physical_parameters.yaml +++ b/config/ur30/physical_parameters.yaml @@ -1,14 +1,5 @@ # Physical parameters -# from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ -dh_parameters: - d1: 0.2363 - a2: -0.8620 - a3: -0.7287 - d4: 0.201 - d5: 0.1593 - d6: 0.1543 - offsets: shoulder_offset: 0.260 # measured from model elbow_offset: 0.043 # measured from model diff --git a/config/ur3e/physical_parameters.yaml b/config/ur3e/physical_parameters.yaml index a8d0b10..7c7ec5c 100644 --- a/config/ur3e/physical_parameters.yaml +++ b/config/ur3e/physical_parameters.yaml @@ -1,13 +1,5 @@ # Physical parameters -dh_parameters: - d1: 0.152 - a2: -0.244 - a3: -0.213 - d4: 0.131 # wrist1_length = d4 - elbow_offset - shoulder_offset - d5: 0.085 - d6: 0.092 - offsets: shoulder_offset: 0.120 # measured from model elbow_offset: 0.027 # measured from model diff --git a/config/ur5/physical_parameters.yaml b/config/ur5/physical_parameters.yaml index 07d1ebc..0ce6e54 100644 --- a/config/ur5/physical_parameters.yaml +++ b/config/ur5/physical_parameters.yaml @@ -1,13 +1,5 @@ # Physical parameters -dh_parameters: - d1: 0.089159 - a2: -0.42500 - a3: -0.39225 - d4: 0.10915 - d5: 0.09465 - d6: 0.0823 - offsets: shoulder_offset: 0.13585 # measured from model elbow_offset: 0.0165 # measured from model diff --git a/config/ur5e/physical_parameters.yaml b/config/ur5e/physical_parameters.yaml index 6686a21..c7a31e9 100644 --- a/config/ur5e/physical_parameters.yaml +++ b/config/ur5e/physical_parameters.yaml @@ -1,13 +1,5 @@ # Physical parameters -dh_parameters: - d1: 0.163 - a2: -0.42500 - a3: -0.39225 - d4: 0.134 # wrist1_length = d4 - elbow_offset - shoulder_offset - d5: 0.100 - d6: 0.100 - offsets: shoulder_offset: 0.138 # measured from model elbow_offset: 0.007 # measured from model diff --git a/urdf/inc/ur_common.xacro b/urdf/inc/ur_common.xacro index a763e78..c6db338 100644 --- a/urdf/inc/ur_common.xacro +++ b/urdf/inc/ur_common.xacro @@ -52,7 +52,6 @@ - @@ -84,14 +83,6 @@ - - - - - - - - From 4bf42f1b7ae77ac2ecce97a3d1731b2070786ac1 Mon Sep 17 00:00:00 2001 From: Chalongrath Pholsiri Date: Tue, 10 Sep 2024 12:57:37 -0500 Subject: [PATCH 2/7] Rename prop__wrist_2_cog to prop_wrist_2_cog for consistency --- urdf/inc/ur_common.xacro | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/urdf/inc/ur_common.xacro b/urdf/inc/ur_common.xacro index c6db338..d7adb8c 100644 --- a/urdf/inc/ur_common.xacro +++ b/urdf/inc/ur_common.xacro @@ -162,14 +162,14 @@ - + - + From a9b2cb0cd39d64bcd96376a9213e08433757412f Mon Sep 17 00:00:00 2001 From: Chalongrath Pholsiri Date: Tue, 10 Sep 2024 14:17:12 -0500 Subject: [PATCH 3/7] Update mass and cog and use full inertia matrix. --- config/ur10/physical_parameters.yaml | 107 ++++++++++++++++++++---- config/ur10e/physical_parameters.yaml | 107 ++++++++++++++++++++---- config/ur16e/physical_parameters.yaml | 109 +++++++++++++++++++----- config/ur20/physical_parameters.yaml | 112 ++++++++++++++++++++----- config/ur3/physical_parameters.yaml | 110 ++++++++++++++++++++---- config/ur30/physical_parameters.yaml | 116 +++++++++++++++++++++----- config/ur3e/physical_parameters.yaml | 110 ++++++++++++++++++++---- config/ur5/physical_parameters.yaml | 109 ++++++++++++++++++++---- config/ur5e/physical_parameters.yaml | 109 ++++++++++++++++++++---- urdf/inc/ur_common.xacro | 61 ++++++++++++++ urdf/ur_macro.xacro | 91 +++++++++++++++----- 11 files changed, 951 insertions(+), 190 deletions(-) diff --git a/config/ur10/physical_parameters.yaml b/config/ur10/physical_parameters.yaml index 880fe1c..b98f0b0 100644 --- a/config/ur10/physical_parameters.yaml +++ b/config/ur10/physical_parameters.yaml @@ -45,26 +45,97 @@ inertia_parameters: center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00244 - z: -0.037 + x: 0.021 # model.x + y: -0.027 # -model.z + z: 0.0 # model.y upper_arm_cog: - x: 0.00001 - y: 0.15061 - z: 0.38757 + x: -0.232 # model.x - upper_arm_length + y: 0.0 # model.y + z: 0.158 # model.z forearm_cog: - x: -0.00012 - y: 0.06112 - z: 0.1984 + x: -0.3323 # model.x - forearm_length + y: 0.0 # model.y + z: 0.068 # model.z wrist_1_cog: - x: -0.00021 - y: -0.00112 - z: 0.02269 + x: 0.0 # model.x + y: -0.018 # -model.z + z: 0.007 # model.y wrist_2_cog: - x: -0.00021 - y: 0.00112 - z: 0.002269 + x: 0.0 # model.x + y: 0.018 # model.z + z: -0.007 # -model.y wrist_3_cog: - x: 0.0 - y: -0.001156 - z: -0.00149 + x: 0.0 # model.x + y: 0 # model.y + z: -0.026 # model.z + + rotation: + shoulder: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 0 + yaw: 0 + forearm: + roll: 0 + pitch: 0 + yaw: 0 + wrist_1: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + wrist_2: + roll: -1.570796326794897 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + # extracted from URSim + tensor: + shoulder: + ixx: 0.03408 + ixy: 0.00002 + ixz: -0.00425 + iyy: 0.03529 + iyz: 0.00008 + izz: 0.02156 + upper_arm: + ixx: 0.02814 + ixy: 0.00005 + ixz: -0.01561 + iyy: 0.77068 + iyz: 0.00002 + izz: 0.76943 + forearm: + ixx: 0.01014 + ixy: 0.00008 + ixz: 0.00916 + iyy: 0.30928 + iyz: 0.0 + izz: 0.30646 + wrist_1: + ixx: 0.00296 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00222 + iyz: -0.00024 + izz: 0.00258 + wrist_2: + ixx: 0.00296 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00222 + iyz: -0.00024 + izz: 0.00258 + wrist_3: + ixx: 0.00040 + ixy: 0.0 + ixz: 0.0 + iyy: 0.00041 + iyz: 0.0 + izz: 0.00034 diff --git a/config/ur10e/physical_parameters.yaml b/config/ur10e/physical_parameters.yaml index 9de2a4e..a162fb6 100644 --- a/config/ur10e/physical_parameters.yaml +++ b/config/ur10e/physical_parameters.yaml @@ -43,28 +43,99 @@ inertia_parameters: radius: 0.045 length: 0.05 + # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00244 - z: -0.037 + x: 0.021 # model.x + y: -0.027 # -model.z + z: 0.0 # model.y upper_arm_cog: - x: 0.00001 - y: 0.15061 - z: 0.38757 + x: -0.2327 # model.x - upper_arm_length + y: 0.0 # model.y + z: 0.158 # model.z forearm_cog: - x: -0.00012 - y: 0.06112 - z: 0.1984 + x: -0.33155 # model.x - forearm_length + y: 0.0 # model.y + z: 0.068 # model.z wrist_1_cog: - x: -0.00021 - y: -0.00112 - z: 0.02269 + x: 0.0 # model.x + y: -0.018 # -model.z + z: 0.007 # model.y wrist_2_cog: - x: -0.00021 - y: 0.00112 - z: 0.002269 + x: 0.0 # model.x + y: 0.018 # model.z + z: -0.007 # -model.y wrist_3_cog: - x: 0.0 - y: -0.001156 - z: -0.00149 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.026 # model.z + + rotation: + shoulder: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 0 + yaw: 0 + forearm: + roll: 0 + pitch: 0 + yaw: 0 + wrist_1: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + wrist_2: + roll: -1.570796326794897 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + tensor: + shoulder: + ixx: 0.03408 + ixy: 0.00002 + ixz: -0.00425 + iyy: 0.03529 + iyz: 0.00008 + izz: 0.02156 + upper_arm: + ixx: 0.02814 + ixy: 0.00005 + ixz: -0.01561 + iyy: 0.77068 + iyz: 0.00002 + izz: 0.76943 + forearm: + ixx: 0.01014 + ixy: 0.00008 + ixz: 0.00916 + iyy: 0.30928 + iyz: 0.0 + izz: 0.30646 + wrist_1: + ixx: 0.00296 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00222 + iyz: -0.00024 + izz: 0.00258 + wrist_2: + ixx: 0.00296 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00222 + iyz: -0.00024 + izz: 0.00258 + wrist_3: + ixx: 0.00040 + ixy: 0.0 + ixz: 0.0 + iyy: 0.00041 + iyz: 0.0 + izz: 0.00034 diff --git a/config/ur16e/physical_parameters.yaml b/config/ur16e/physical_parameters.yaml index e992ee6..c75b4e9 100644 --- a/config/ur16e/physical_parameters.yaml +++ b/config/ur16e/physical_parameters.yaml @@ -44,28 +44,99 @@ inertia_parameters: radius: 0.045 length: 0.05 - center_of_mass: # Adjusted manually + # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ + center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00244 - z: -0.037 + x: 0.0 # model.x + y: -0.030 # -model.z + z: -0.016 # model.y upper_arm_cog: - x: 0.00001 - y: 0.15061 - z: 0.38757 + x: -0.1764 # model.x - upperarm_length + y: 0.0 # model.y + z: 0.16 # model.z forearm_cog: - x: -0.00012 - y: 0.06112 - z: 0.1984 + x: -0.166 # model.x - forearm_length + y: 0.0 # model.y + z: 0.065 # model.z wrist_1_cog: - x: -0.00021 - y: -0.00112 - z: 0.02269 + x: 0.0 # model.x + y: -0.011 # -model.z + z: -0.009 # model.y wrist_2_cog: - x: -0.00021 - y: 0.00112 - z: 0.002269 + x: 0.0 # model.x + y: 0.012 # model.z + z: -0.018 # -model.y wrist_3_cog: - x: 0.0 - y: -0.001156 - z: -0.00149 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.044 # model.z + + rotation: + shoulder: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 0 + yaw: 0 + forearm: + roll: 0 + pitch: 0 + yaw: 0 + wrist_1: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + wrist_2: + roll: -1.570796326794897 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + tensor: + shoulder: + ixx: 0.03351 + ixy: 0.00002 + ixz: -0.00001 + iyy: 0.03374 + iyz: 0.00374 + izz: 0.02100 + upper_arm: + ixx: 0.02796 + ixy: -0.00010 + ixz: -0.00720 + iyy: 0.47558 + iyz: 0.00003 + izz: 0.47635 + forearm: + ixx: 0.01091 + ixy: 0.00006 + ixz: 0.01012 + iyy: 0.12060 + iyz: 0.00001 + izz: 0.11714 + wrist_1: + ixx: 0.00609 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00245 + iyz: 0.00083 + izz: 0.00579 + wrist_2: + ixx: 0.00389 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00219 + iyz: -0.00045 + izz: 0.00363 + wrist_3: + ixx: 0.00117 + ixy: 0.0 + ixz: 0.0 + iyy: 0.00118 + iyz: 0.0 + izz: 0.00084 diff --git a/config/ur20/physical_parameters.yaml b/config/ur20/physical_parameters.yaml index 795ef40..1f2620b 100644 --- a/config/ur20/physical_parameters.yaml +++ b/config/ur20/physical_parameters.yaml @@ -5,7 +5,7 @@ offsets: elbow_offset: 0.043 # measured from model inertia_parameters: - # taken from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ + # taken from https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ base_mass: 4.0 # This mass might be incorrect shoulder_mass: 16.343 upper_arm_mass: 29.632 @@ -13,7 +13,7 @@ inertia_parameters: forearm_mass: 7.879 wrist_1_mass: 3.054 wrist_2_mass: 3.126 - wrist_3_mass: 0.846 + wrist_3_mass: 0.926 shoulder_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE upper_arm_radius: x0.054 # FROM UR5 CURRENTLY NOT USED ANYMORE @@ -44,28 +44,98 @@ inertia_parameters: radius: 0.045 length: 0.05 - center_of_mass: # Adjusted manually + center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00244 - z: -0.037 + x: 0.0 # model.x + y: -0.0062 # -model.z + z: -0.061 # model.y upper_arm_cog: - x: 0.00001 - y: 0.15061 - z: 0.48757 + x: -0.3394 # model.x - upperarm_length + y: 0.0 # model.y + z: 0.2098 # model.z forearm_cog: - x: -0.00012 - y: 0.06112 - z: 0.2984 + x: -0.4053 # model.x - forearm_length + y: 0.0 # model.y + z: 0.0604 # model.z wrist_1_cog: - x: -0.00021 - y: -0.00112 - z: 0.02269 + x: 0.0 # model.x + y: -0.0393 # -model.z + z: -0.0026 # model.y wrist_2_cog: - x: -0.00021 - y: 0.00112 - z: 0.002269 + x: 0.0 # model.x + y: 0.0379 # model.z + z: -0.0024 # -model.y wrist_3_cog: - x: 0.0 - y: -0.001156 - z: -0.00149 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.0293 # model.z + + rotation: + shoulder: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 0 + yaw: 0 + forearm: + roll: 0 + pitch: 0 + yaw: 0 + wrist_1: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + wrist_2: + roll: -1.570796326794897 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + tensor: + shoulder: + ixx: 0.08866 + ixy: -0.00011 + ixz: -0.00011 + iyy: 0.07632 + iyz: 0.00720 + izz: 0.08418 + upper_arm: + ixx: 0.14670 + ixy: 0.00019 + ixz: -0.05163 + iyy: 4.66590 + iyz: 0.00004 + izz: 4.63480 + forearm: + ixx: 0.02612 + ixy: -0.00005 + ixz: -0.02898 + iyy: 0.75763 + iyz: -0.00001 + izz: 0.75327 + wrist_1: + ixx: 0.00555 + ixy: -0.00001 + ixz: -0.00002 + iyy: 0.00537 + iyz: 0.00036 + izz: 0.00402 + wrist_2: + ixx: 0.00586 + ixy: -0.00001 + ixz: -0.00002 + iyy: 0.00578 + iyz: -0.00037 + izz: 0.00427 + wrist_3: + ixx: 0.00092 + ixy: 0.0 + ixz: 0.0 + iyy: 0.00091 + iyz: 0.0 + izz: 0.00117 diff --git a/config/ur3/physical_parameters.yaml b/config/ur3/physical_parameters.yaml index 3a3483e..179b762 100644 --- a/config/ur3/physical_parameters.yaml +++ b/config/ur3/physical_parameters.yaml @@ -43,28 +43,102 @@ inertia_parameters: radius: 0.032 length: 0.04 + # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: shoulder_cog: - x: 0.0 - y: -0.02 - z: 0.0 + x: 0.0 # model.x + y: 0.0 # -model.z + z: -0.02 # model.y upper_arm_cog: - x: 0.13 - y: 0.0 - z: 0.1157 + x: -0.11365 # model.x - upper_arm_length + y: 0.0 # model.y + z: 0.1157 # model.z forearm_cog: - x: 0.05 - y: 0.0 - z: 0.0238 + x: -0.16325 # model.x - forearm_length + y: 0.0 # model.y + z: 0.0238 # model.z wrist_1_cog: - x: 0.0 - y: 0.0 - z: 0.01 + x: 0.0 # model.x + y: -0.01 # -model.z + z: 0.0 # model.y wrist_2_cog: - x: 0.0 - y: 0.0 - z: 0.01 + x: 0.0 # model.x + y: 0.01 # model.z + z: 0.0 # -model.y wrist_3_cog: - x: 0.0 - y: 0.0 - z: -0.02 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.02 # model.z + + # compatible with cylinder approximation + rotation: + shoulder: + roll: 0 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + forearm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + wrist_1: + roll: 0 + pitch: 0 + yaw: 0 + wrist_2: + roll: 0 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + + # generated using cylinder approximation + tensor: + shoulder: + ixx: 0.008093166666666665 + ixy: 0 + ixz: 0 + iyy: 0.008093166666666665 + iyz: 0 + izz: 0.005625 + upper_arm: + ixx: 0.021728491912499998 + ixy: 0 + ixz: 0 + iyy: 0.021728491912499998 + iyz: 0 + izz: 0.00961875 + forearm: + ixx: 0.0065468090625 + ixy: 0 + ixz: 0 + iyy: 0.0065468090625 + iyz: 0 + izz: 0.00354375 + wrist_1: + ixx: 0.0016106414999999998 + ixy: 0 + ixz: 0 + iyy: 0.0016106414999999998 + iyz: 0 + izz: 0.00225 + wrist_2: + ixx: 0.0015721739999999998 + ixy: 0 + ixz: 0 + iyy: 0.0015721739999999998 + iyz: 0 + izz: 0.00225 + wrist_3: + ixx: 0.00013626666666666665 + ixy: 0 + ixz: 0 + iyy: 0.00013626666666666665 + iyz: 0 + izz: 0.0001792 diff --git a/config/ur30/physical_parameters.yaml b/config/ur30/physical_parameters.yaml index c84908b..a9e09c8 100644 --- a/config/ur30/physical_parameters.yaml +++ b/config/ur30/physical_parameters.yaml @@ -5,15 +5,15 @@ offsets: elbow_offset: 0.043 # measured from model inertia_parameters: - # taken from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ + # taken from https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ base_mass: 4.0 # This mass might be incorrect shoulder_mass: 16.343 - upper_arm_mass: 29.632 + upper_arm_mass: 28.542 upper_arm_inertia_offset: 0.275 # measured from model - forearm_mass: 7.879 + forearm_mass: 7.156 wrist_1_mass: 3.054 wrist_2_mass: 3.126 - wrist_3_mass: 0.846 + wrist_3_mass: 0.926 shoulder_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE upper_arm_radius: x0.054 # FROM UR5 CURRENTLY NOT USED ANYMORE @@ -44,28 +44,98 @@ inertia_parameters: radius: 0.045 length: 0.05 - center_of_mass: # Adjusted manually + center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00244 - z: -0.037 + x: -0.0001 # model.x + y: -0.0069 # -model.z + z: -0.06 # model.y upper_arm_cog: - x: 0.00001 - y: 0.15061 - z: 0.40757 + x: -0.2476 # model.x - upperarm_length + y: 0.0 # model.y + z: 0.2103 # model.z forearm_cog: - x: -0.00012 - y: 0.06112 - z: 0.2084 + x: -0.278 # model.x - forearm_length + y: 0.0 # model.y + z: 0.0629 # model.z wrist_1_cog: - x: -0.00021 - y: -0.00112 - z: 0.02269 + x: 0.0 # model.x + y: -0.0353 # -model.z + z: -0.0048 # model.y wrist_2_cog: - x: -0.00021 - y: 0.00112 - z: 0.002269 + x: 0.0 # model.x + y: 0.0341 # model.z + z: -0.0046 # -model.y wrist_3_cog: - x: 0.0 - y: -0.001156 - z: -0.00149 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.0293 # model.z + + rotation: + shoulder: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 0 + yaw: 0 + forearm: + roll: 0 + pitch: 0 + yaw: 0 + wrist_1: + roll: 1.570796326794897 + pitch: 0 + yaw: 0 + wrist_2: + roll: -1.570796326794897 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + tensor: + shoulder: + ixx: 0.03351 + ixy: 0.00002 + ixz: -0.00001 + iyy: 0.03374 + iyz: 0.00374 + izz: 0.02100 + upper_arm: + ixx: 0.02796 + ixy: -0.00010 + ixz: -0.00720 + iyy: 0.47558 + iyz: 0.00003 + izz: 0.47635 + forearm: + ixx: 0.01091 + ixy: 0.00006 + ixz: 0.01012 + iyy: 0.12060 + iyz: 0.00001 + izz: 0.11714 + wrist_1: + ixx: 0.00609 + ixy: -0.00001 + ixz: 0.0 + iyy: 0.00245 + iyz: 0.00083 + izz: 0.00579 + wrist_2: + ixx: 0.00389 + ixy: 0.00001 + ixz: 0.0 + iyy: 0.00219 + iyz: -0.00045 + izz: 0.00363 + wrist_3: + ixx: 0.00117 + ixy: 0.0 + ixz: 0.0 + iyy: 0.00118 + iyz: 0.0 + izz: 0.00084 diff --git a/config/ur3e/physical_parameters.yaml b/config/ur3e/physical_parameters.yaml index 7c7ec5c..aed7ba3 100644 --- a/config/ur3e/physical_parameters.yaml +++ b/config/ur3e/physical_parameters.yaml @@ -43,28 +43,102 @@ inertia_parameters: radius: 0.032 length: 0.04 + # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: shoulder_cog: - x: 0.0 - y: -0.02 - z: 0.0 + x: 0.0 # model.x + y: 0.0 # -model.z + z: -0.02 # model.y upper_arm_cog: - x: 0.13 - y: 0.0 - z: 0.1157 + x: -0.11355 # model.x - upper_arm_length + y: 0.0 # model.y + z: 0.1157 # model.z forearm_cog: - x: 0.05 - y: 0.0 - z: 0.0238 + x: -0.1632 # model.x - forearm_length + y: 0.0 # model.y + z: 0.0238 # model.z wrist_1_cog: - x: 0.0 - y: 0.0 - z: 0.01 + x: 0.0 # model.x + y: -0.01 # -model.z + z: 0.0 # model.y wrist_2_cog: - x: 0.0 - y: 0.0 - z: 0.01 + x: 0.0 # model.x + y: 0.01 # model.z + z: 0.0 # -model.y wrist_3_cog: - x: 0.0 - y: 0.0 - z: -0.02 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.02 # model.z + + # compatible with cylinder approximation + rotation: + shoulder: + roll: 0 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + forearm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + wrist_1: + roll: 0 + pitch: 0 + yaw: 0 + wrist_2: + roll: 0 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + # generated using cylinder approximation + tensor: + shoulder: + ixx: 0.008093166666666665 + ixy: 0 + ixz: 0 + iyy: 0.008093166666666665 + iyz: 0 + izz: 0.005625 + upper_arm: + ixx: 0.021728491912499998 + ixy: 0 + ixz: 0 + iyy: 0.021728491912499998 + iyz: 0 + izz: 0.00961875 + forearm: + ixx: 0.006544570199999999 + ixy: 0 + ixz: 0 + iyy: 0.006544570199999999 + iyz: 0 + izz: 0.00354375 + wrist_1: + ixx: 0.0020849999999999996 + ixy: 0 + ixz: 0 + iyy: 0.0020849999999999996 + iyz: 0 + izz: 0.00225 + wrist_2: + ixx: 0.0020849999999999996 + ixy: 0 + ixz: 0 + iyy: 0.0020849999999999996 + iyz: 0 + izz: 0.00225 + wrist_3: + ixx: 0.00013626666666666665 + ixy: 0 + ixz: 0 + iyy: 0.00013626666666666665 + iyz: 0 + izz: 0.0001792 + diff --git a/config/ur5/physical_parameters.yaml b/config/ur5/physical_parameters.yaml index 0ce6e54..4e0346f 100644 --- a/config/ur5/physical_parameters.yaml +++ b/config/ur5/physical_parameters.yaml @@ -52,28 +52,101 @@ inertia_parameters: radius: 0.0375 length: 0.0305 + # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00193 - z: -0.02561 + x: 0.0 # model.x + y: -0.00193 # -model.z + z: -0.02561 # model.y upper_arm_cog: - x: 0.0 - y: -0.024201 - z: 0.2125 + x: -0.2125 # model.x - upper_arm_length + y: 0.0 # model.y + z: 0.11336 # model.z forearm_cog: - x: 0.0 - y: 0.0265 - z: 0.11993 + x: -0.24225 # model.x - forearm_length + y: 0.0 # model.y + z: 0.0265 # model.z wrist_1_cog: - x: 0.0 - y: 0.110949 - z: 0.01634 + x: 0.0 # model.x + y: -0.01634 # -model.z + z: -0.0018 # model.y wrist_2_cog: - x: 0.0 - y: 0.0018 - z: 0.11099 + x: 0.0 # model.x + y: 0.01634 # model.z + z: -0.0018 # -model.y wrist_3_cog: - x: 0.0 - y: 0.001159 - z: 0.0 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.001159 # model.z + + # compatible with cylinder approximation + rotation: + shoulder: + roll: 0 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + forearm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + wrist_1: + roll: 0 + pitch: 0 + yaw: 0 + wrist_2: + roll: 0 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + # generated using cylinder approximation + tensor: + shoulder: + ixx: 0.014972358333333331 + ixy: 0 + ixz: 0 + iyy: 0.014972358333333331 + iyz: 0 + izz: 0.01040625 + upper_arm: + ixx: 0.13388583541666665 + ixy: 0 + ixz: 0 + iyy: 0.13388583541666665 + iyz: 0 + izz: 0.0151074 + forearm: + ixx: 0.031216803515624995 + ixy: 0 + ixz: 0 + iyy: 0.031216803515624995 + iyz: 0 + izz: 0.004095 + wrist_1: + ixx: 0.002013889583333333 + ixy: 0 + ixz: 0 + iyy: 0.002013889583333333 + iyz: 0 + izz: 0.0021942 + wrist_2: + ixx: 0.0018310395833333333 + ixy: 0 + ixz: 0 + iyy: 0.0018310395833333333 + iyz: 0 + izz: 0.0021942 + wrist_3: + ixx: 8.062475833333332e-05 + ixy: 0 + ixz: 0 + iyy: 8.062475833333332e-05 + iyz: 0 + izz: 0.0001321171875 diff --git a/config/ur5e/physical_parameters.yaml b/config/ur5e/physical_parameters.yaml index c7a31e9..8652758 100644 --- a/config/ur5e/physical_parameters.yaml +++ b/config/ur5e/physical_parameters.yaml @@ -43,28 +43,101 @@ inertia_parameters: radius: 0.0375 length: 0.0458 + # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: shoulder_cog: - x: 0.0 - y: 0.00193 - z: -0.02561 + x: 0.0 # model.x + y: -0.00193 # -model.z + z: -0.02561 # model.y upper_arm_cog: - x: 0.0 - y: -0.024201 - z: 0.2125 + x: -0.2125 # model.x - upper_arm_length + y: 0.0 # model.y + z: 0.11336 # model.z forearm_cog: - x: 0.0 - y: 0.0265 - z: 0.11993 + x: -0.2422 # model.x - forearm_length + y: 0.0 # model.y + z: 0.0265 # model.z wrist_1_cog: - x: 0.0 - y: 0.110949 - z: 0.01634 + x: 0.0 # model.x + y: -0.01634 # -model.z + z: -0.0018 # model.y wrist_2_cog: - x: 0.0 - y: 0.0018 - z: 0.11099 + x: 0.0 # model.x + y: 0.01634 # model.z + z: -0.0018 # -model.y wrist_3_cog: - x: 0.0 - y: 0.001159 - z: 0.0 + x: 0.0 # model.x + y: 0.0 # model.y + z: -0.001159 # model.z + + # compatible with cylinder approximation + rotation: + shoulder: + roll: 0 + pitch: 0 + yaw: 0 + upper_arm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + forearm: + roll: 0 + pitch: 1.570796326794897 + yaw: 0 + wrist_1: + roll: 0 + pitch: 0 + yaw: 0 + wrist_2: + roll: 0 + pitch: 0 + yaw: 0 + wrist_3: + roll: 0 + pitch: 0 + yaw: 0 + + # generated using cylinder approximation + tensor: + shoulder: + ixx: 0.010267499999999999 + ixy: 0 + ixz: 0 + iyy: 0.010267499999999999 + iyz: 0 + izz: 0.00666 + upper_arm: + ixx: 0.13388583541666665 + ixy: 0 + ixz: 0 + iyy: 0.13388583541666665 + iyz: 0 + izz: 0.0151074 + forearm: + ixx: 0.03120936758333333 + ixy: 0 + ixz: 0 + iyy: 0.03120936758333333 + iyz: 0 + izz: 0.004095 + wrist_1: + ixx: 0.0025599 + ixy: 0 + ixz: 0 + iyy: 0.0025599 + iyz: 0 + izz: 0.0021942 + wrist_2: + ixx: 0.0025599 + ixy: 0 + ixz: 0 + iyy: 0.0025599 + iyz: 0 + izz: 0.0021942 + wrist_3: + ixx: 9.890414008333333e-05 + ixy: 0 + ixz: 0 + iyy: 9.890414008333333e-05 + iyz: 0 + izz: 0.0001321171875 diff --git a/urdf/inc/ur_common.xacro b/urdf/inc/ur_common.xacro index d7adb8c..d40dda0 100644 --- a/urdf/inc/ur_common.xacro +++ b/urdf/inc/ur_common.xacro @@ -171,6 +171,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/ur_macro.xacro b/urdf/ur_macro.xacro index 39c094d..bde7e7e 100644 --- a/urdf/ur_macro.xacro +++ b/urdf/ur_macro.xacro @@ -107,10 +107,18 @@ - - - - + + + + + @@ -124,9 +132,18 @@ - - - + + + + + @@ -141,9 +158,18 @@ - - - + + + + + @@ -159,9 +185,18 @@ - - - + + + + + @@ -177,9 +212,18 @@ - - - + + + + + @@ -195,9 +239,18 @@ - - - + + + + + From cf973ee3b9cdf28f0b7fa3ccb77bf5fd78f3585d Mon Sep 17 00:00:00 2001 From: Chalongrath Pholsiri Date: Tue, 10 Sep 2024 14:42:15 -0500 Subject: [PATCH 4/7] Update max_efforts (torque limits) --- config/ur10e/joint_limits.yaml | 6 +++--- config/ur16e/joint_limits.yaml | 6 +++--- config/ur20/joint_limits.yaml | 12 ++++++------ config/ur30/joint_limits.yaml | 12 ++++++------ config/ur3e/joint_limits.yaml | 10 +++++----- 5 files changed, 23 insertions(+), 23 deletions(-) diff --git a/config/ur10e/joint_limits.yaml b/config/ur10e/joint_limits.yaml index a7adb67..44be1f4 100644 --- a/config/ur10e/joint_limits.yaml +++ b/config/ur10e/joint_limits.yaml @@ -54,7 +54,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 @@ -64,7 +64,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 @@ -74,7 +74,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 diff --git a/config/ur16e/joint_limits.yaml b/config/ur16e/joint_limits.yaml index 33182a6..84e547c 100644 --- a/config/ur16e/joint_limits.yaml +++ b/config/ur16e/joint_limits.yaml @@ -54,7 +54,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 @@ -64,7 +64,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 @@ -74,7 +74,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 diff --git a/config/ur20/joint_limits.yaml b/config/ur20/joint_limits.yaml index b122784..0d4b0fb 100644 --- a/config/ur20/joint_limits.yaml +++ b/config/ur20/joint_limits.yaml @@ -11,7 +11,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 730.0 + max_effort: 738.0 max_position: !degrees 360.0 max_velocity: !degrees 120.0 min_position: !degrees -360.0 @@ -21,7 +21,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 730.0 + max_effort: 738.0 max_position: !degrees 360.0 max_velocity: !degrees 120.0 min_position: !degrees -360.0 @@ -31,7 +31,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 430.0 + max_effort: 433.0 # we artificially limit this joint to half its actual joint position limit # to avoid (MoveIt/OMPL) planning problems, as due to the physical # construction of the robot, it's impossible to rotate the 'elbow_joint' @@ -51,7 +51,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 100.0 + max_effort: 107.0 max_position: !degrees 360.0 max_velocity: !degrees 210.0 min_position: !degrees -360.0 @@ -61,7 +61,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 100.0 + max_effort: 107.0 max_position: !degrees 360.0 max_velocity: !degrees 210.0 min_position: !degrees -360.0 @@ -71,7 +71,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 100.0 + max_effort: 107.0 max_position: !degrees 360.0 max_velocity: !degrees 210.0 min_position: !degrees -360.0 diff --git a/config/ur30/joint_limits.yaml b/config/ur30/joint_limits.yaml index b122784..0d4b0fb 100644 --- a/config/ur30/joint_limits.yaml +++ b/config/ur30/joint_limits.yaml @@ -11,7 +11,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 730.0 + max_effort: 738.0 max_position: !degrees 360.0 max_velocity: !degrees 120.0 min_position: !degrees -360.0 @@ -21,7 +21,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 730.0 + max_effort: 738.0 max_position: !degrees 360.0 max_velocity: !degrees 120.0 min_position: !degrees -360.0 @@ -31,7 +31,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 430.0 + max_effort: 433.0 # we artificially limit this joint to half its actual joint position limit # to avoid (MoveIt/OMPL) planning problems, as due to the physical # construction of the robot, it's impossible to rotate the 'elbow_joint' @@ -51,7 +51,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 100.0 + max_effort: 107.0 max_position: !degrees 360.0 max_velocity: !degrees 210.0 min_position: !degrees -360.0 @@ -61,7 +61,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 100.0 + max_effort: 107.0 max_position: !degrees 360.0 max_velocity: !degrees 210.0 min_position: !degrees -360.0 @@ -71,7 +71,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 100.0 + max_effort: 107.0 max_position: !degrees 360.0 max_velocity: !degrees 210.0 min_position: !degrees -360.0 diff --git a/config/ur3e/joint_limits.yaml b/config/ur3e/joint_limits.yaml index 203a3a3..21fad58 100644 --- a/config/ur3e/joint_limits.yaml +++ b/config/ur3e/joint_limits.yaml @@ -14,7 +14,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 @@ -24,7 +24,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 56.0 + max_effort: 54.0 max_position: !degrees 360.0 max_velocity: !degrees 180.0 min_position: !degrees -360.0 @@ -54,7 +54,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 12.0 + max_effort: 9.0 max_position: !degrees 360.0 max_velocity: !degrees 360.0 min_position: !degrees -360.0 @@ -64,7 +64,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 12.0 + max_effort: 9.0 max_position: !degrees 360.0 max_velocity: !degrees 360.0 min_position: !degrees -360.0 @@ -74,7 +74,7 @@ joint_limits: has_effort_limits: true has_position_limits: true has_velocity_limits: true - max_effort: 12.0 + max_effort: 9.0 max_position: !degrees 360.0 max_velocity: !degrees 360.0 min_position: !degrees -360.0 From 8dd1cafbbc14a6c07d3ed9f1c08274ded90c2257 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Rune=20S=C3=B8e-Knudsen?= <41109954+urrsk@users.noreply.github.com> Date: Thu, 12 Sep 2024 08:35:15 +0200 Subject: [PATCH 5/7] Remove trailing whitespaces --- config/ur16e/physical_parameters.yaml | 2 +- config/ur20/physical_parameters.yaml | 2 +- config/ur30/physical_parameters.yaml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/config/ur16e/physical_parameters.yaml b/config/ur16e/physical_parameters.yaml index c75b4e9..bacfbe0 100644 --- a/config/ur16e/physical_parameters.yaml +++ b/config/ur16e/physical_parameters.yaml @@ -45,7 +45,7 @@ inertia_parameters: length: 0.05 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ - center_of_mass: + center_of_mass: shoulder_cog: x: 0.0 # model.x y: -0.030 # -model.z diff --git a/config/ur20/physical_parameters.yaml b/config/ur20/physical_parameters.yaml index 1f2620b..398141a 100644 --- a/config/ur20/physical_parameters.yaml +++ b/config/ur20/physical_parameters.yaml @@ -44,7 +44,7 @@ inertia_parameters: radius: 0.045 length: 0.05 - center_of_mass: + center_of_mass: shoulder_cog: x: 0.0 # model.x y: -0.0062 # -model.z diff --git a/config/ur30/physical_parameters.yaml b/config/ur30/physical_parameters.yaml index a9e09c8..692e6a5 100644 --- a/config/ur30/physical_parameters.yaml +++ b/config/ur30/physical_parameters.yaml @@ -44,7 +44,7 @@ inertia_parameters: radius: 0.045 length: 0.05 - center_of_mass: + center_of_mass: shoulder_cog: x: -0.0001 # model.x y: -0.0069 # -model.z From ac08c469fde32862fc93a9b7e16e117a18a008cd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Rune=20S=C3=B8e-Knudsen?= <41109954+urrsk@users.noreply.github.com> Date: Thu, 12 Sep 2024 09:03:56 +0200 Subject: [PATCH 6/7] End of file format fix --- config/ur3e/physical_parameters.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/config/ur3e/physical_parameters.yaml b/config/ur3e/physical_parameters.yaml index aed7ba3..11472af 100644 --- a/config/ur3e/physical_parameters.yaml +++ b/config/ur3e/physical_parameters.yaml @@ -141,4 +141,3 @@ inertia_parameters: iyy: 0.00013626666666666665 iyz: 0 izz: 0.0001792 - From e9efbdd6fedb0d079cc6893891d516ae539d19d7 Mon Sep 17 00:00:00 2001 From: Chalongrath Pholsiri Date: Thu, 19 Sep 2024 13:36:49 -0500 Subject: [PATCH 7/7] Remove code and values that are no longer needed. --- config/ur10/physical_parameters.yaml | 19 ------------------ config/ur10e/physical_parameters.yaml | 19 ------------------ config/ur16e/physical_parameters.yaml | 19 ------------------ config/ur20/physical_parameters.yaml | 19 ------------------ config/ur3/physical_parameters.yaml | 19 ------------------ config/ur30/physical_parameters.yaml | 19 ------------------ config/ur3e/physical_parameters.yaml | 19 ------------------ config/ur5/physical_parameters.yaml | 28 --------------------------- config/ur5e/physical_parameters.yaml | 19 ------------------ urdf/inc/ur_common.xacro | 13 ------------- 10 files changed, 193 deletions(-) diff --git a/config/ur10/physical_parameters.yaml b/config/ur10/physical_parameters.yaml index b98f0b0..4f57ad9 100644 --- a/config/ur10/physical_parameters.yaml +++ b/config/ur10/physical_parameters.yaml @@ -8,7 +8,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 7.1 upper_arm_mass: 12.7 - upper_arm_inertia_offset: 0.175 forearm_mass: 4.27 wrist_1_mass: 2.0 wrist_2_mass: 2.0 @@ -24,24 +23,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.612 - forearm: - radius: 0.075 - length: 0.5723 - wrist_1: - radius: 0.075 - length: 0.12 - wrist_2: - radius: 0.075 - length: 0.09 - wrist_3: - radius: 0.045 - length: 0.0305 center_of_mass: shoulder_cog: diff --git a/config/ur10e/physical_parameters.yaml b/config/ur10e/physical_parameters.yaml index a162fb6..daaae73 100644 --- a/config/ur10e/physical_parameters.yaml +++ b/config/ur10e/physical_parameters.yaml @@ -8,7 +8,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 7.369 upper_arm_mass: 13.051 - upper_arm_inertia_offset: 0.175 # measured from model forearm_mass: 3.989 wrist_1_mass: 2.1 wrist_2_mass: 1.98 @@ -24,24 +23,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.612 - forearm: - radius: 0.075 - length: 0.57155 - wrist_1: - radius: 0.075 - length: 0.12 - wrist_2: - radius: 0.075 - length: 0.12 - wrist_3: - radius: 0.045 - length: 0.05 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: diff --git a/config/ur16e/physical_parameters.yaml b/config/ur16e/physical_parameters.yaml index bacfbe0..b9d27fb 100644 --- a/config/ur16e/physical_parameters.yaml +++ b/config/ur16e/physical_parameters.yaml @@ -9,7 +9,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 7.369 upper_arm_mass: 10.450 - upper_arm_inertia_offset: 0.175 # measured from model forearm_mass: 4.321 wrist_1_mass: 2.180 wrist_2_mass: 2.033 @@ -25,24 +24,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.4784 - forearm: - radius: 0.075 - length: 0.36 - wrist_1: - radius: 0.075 - length: 0.12 - wrist_2: - radius: 0.075 - length: 0.12 - wrist_3: - radius: 0.045 - length: 0.05 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: diff --git a/config/ur20/physical_parameters.yaml b/config/ur20/physical_parameters.yaml index 398141a..71e7314 100644 --- a/config/ur20/physical_parameters.yaml +++ b/config/ur20/physical_parameters.yaml @@ -9,7 +9,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 16.343 upper_arm_mass: 29.632 - upper_arm_inertia_offset: 0.275 # measured from model forearm_mass: 7.879 wrist_1_mass: 3.054 wrist_2_mass: 3.126 @@ -25,24 +24,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.852 - forearm: - radius: 0.075 - length: 0.7287 - wrist_1: - radius: 0.075 - length: 0.12 - wrist_2: - radius: 0.075 - length: 0.12 - wrist_3: - radius: 0.045 - length: 0.05 center_of_mass: shoulder_cog: diff --git a/config/ur3/physical_parameters.yaml b/config/ur3/physical_parameters.yaml index 179b762..e5715df 100644 --- a/config/ur3/physical_parameters.yaml +++ b/config/ur3/physical_parameters.yaml @@ -8,7 +8,6 @@ inertia_parameters: base_mass: 2.0 # This mass might be incorrect shoulder_mass: 2.0 upper_arm_mass: 3.42 - upper_arm_inertia_offset: 0.12 forearm_mass: 1.26 wrist_1_mass: 0.8 wrist_2_mass: 0.8 @@ -24,24 +23,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.24365 - forearm: - radius: 0.075 - length: 0.21325 - wrist_1: - radius: 0.075 - length: 0.08535 - wrist_2: - radius: 0.075 - length: 0.0819 - wrist_3: - radius: 0.032 - length: 0.04 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: diff --git a/config/ur30/physical_parameters.yaml b/config/ur30/physical_parameters.yaml index 692e6a5..ca80fd5 100644 --- a/config/ur30/physical_parameters.yaml +++ b/config/ur30/physical_parameters.yaml @@ -9,7 +9,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 16.343 upper_arm_mass: 28.542 - upper_arm_inertia_offset: 0.275 # measured from model forearm_mass: 7.156 wrist_1_mass: 3.054 wrist_2_mass: 3.126 @@ -25,24 +24,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.637 - forearm: - radius: 0.075 - length: 0.5037 - wrist_1: - radius: 0.075 - length: 0.12 - wrist_2: - radius: 0.075 - length: 0.12 - wrist_3: - radius: 0.045 - length: 0.05 center_of_mass: shoulder_cog: diff --git a/config/ur3e/physical_parameters.yaml b/config/ur3e/physical_parameters.yaml index 11472af..4dbff96 100644 --- a/config/ur3e/physical_parameters.yaml +++ b/config/ur3e/physical_parameters.yaml @@ -8,7 +8,6 @@ inertia_parameters: base_mass: 2.0 # This mass might be incorrect shoulder_mass: 1.98 upper_arm_mass: 3.4445 - upper_arm_inertia_offset: 0.12 # measured from model forearm_mass: 1.437 wrist_1_mass: 0.871 wrist_2_mass: 0.805 @@ -24,24 +23,6 @@ inertia_parameters: base: radius: 0.075 length: 0.038 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.075 - length: 0.24365 - forearm: - radius: 0.075 - length: 0.2132 - wrist_1: - radius: 0.075 - length: 0.12 - wrist_2: - radius: 0.075 - length: 0.12 - wrist_3: - radius: 0.032 - length: 0.04 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: diff --git a/config/ur5/physical_parameters.yaml b/config/ur5/physical_parameters.yaml index 4e0346f..52eb585 100644 --- a/config/ur5/physical_parameters.yaml +++ b/config/ur5/physical_parameters.yaml @@ -8,7 +8,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 3.7000 upper_arm_mass: 8.3930 - upper_arm_inertia_offset: 0.136 forearm_mass: 2.33 wrist_1_mass: 1.2190 wrist_2_mass: 1.2190 @@ -24,33 +23,6 @@ inertia_parameters: base: radius: 0.06 length: 0.05 - shoulder: - radius: 0.075 - length: 0.178 - upperarm: - radius: 0.06 - length: 0.425 - forearm: - radius: 0.06 - length: 0.39225 - wrist_1: - radius: 0.06 - length: 0.12 - wrist_2: - radius: 0.06 - length: 0.12 - wrist_3: - radius: 0.0375 - length: 0.0345 - wrist_1: - radius: 0.06 - length: 0.095 - wrist_2: - radius: 0.06 - length: 0.085 - wrist_3: - radius: 0.0375 - length: 0.0305 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: diff --git a/config/ur5e/physical_parameters.yaml b/config/ur5e/physical_parameters.yaml index 8652758..8779dbe 100644 --- a/config/ur5e/physical_parameters.yaml +++ b/config/ur5e/physical_parameters.yaml @@ -8,7 +8,6 @@ inertia_parameters: base_mass: 4.0 # This mass might be incorrect shoulder_mass: 3.761 upper_arm_mass: 8.058 - upper_arm_inertia_offset: 0.138 # measured from model forearm_mass: 2.846 wrist_1_mass: 1.37 wrist_2_mass: 1.3 @@ -24,24 +23,6 @@ inertia_parameters: base: radius: 0.06 length: 0.05 - shoulder: - radius: 0.06 - length: 0.15 - upperarm: - radius: 0.06 - length: 0.425 - forearm: - radius: 0.06 - length: 0.3922 - wrist_1: - radius: 0.06 - length: 0.12 - wrist_2: - radius: 0.06 - length: 0.12 - wrist_3: - radius: 0.0375 - length: 0.0458 # model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/ center_of_mass: diff --git a/urdf/inc/ur_common.xacro b/urdf/inc/ur_common.xacro index d40dda0..54f0b44 100644 --- a/urdf/inc/ur_common.xacro +++ b/urdf/inc/ur_common.xacro @@ -135,7 +135,6 @@ - @@ -144,18 +143,6 @@ - - - - - - - - - - - -