Skip to content

Commit

Permalink
Define full inertia tensors
Browse files Browse the repository at this point in the history
For the UR16e I used the parameters extracted from URSim
  • Loading branch information
fmauch committed Jul 7, 2020
1 parent e63b1cf commit 415952d
Show file tree
Hide file tree
Showing 3 changed files with 205 additions and 18 deletions.
71 changes: 71 additions & 0 deletions ur_description/config/ur16e/physical_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -78,3 +78,74 @@ inertia_parameters:
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

# extracted from URSim
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
62 changes: 62 additions & 0 deletions ur_description/urdf/inc/ur_common.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,68 @@
<xacro:property name="wrist_1_cog" value="${__wrist_1_cog['x']} ${__wrist_1_cog['y']} ${__wrist_1_cog['z']}" scope="parent"/>
<xacro:property name="wrist_2_cog" value="${__wrist_2_cog['x']} ${__wrist_2_cog['y']} ${__wrist_2_cog['z']}" scope="parent"/>
<xacro:property name="wrist_3_cog" value="${__wrist_3_cog['x']} ${__wrist_3_cog['y']} ${__wrist_3_cog['z']}" scope="parent"/>

<!-- inertia rotation -->
<xacro:property name="__shoulder_inertia_rotation" value="${__inertia_parameters['rotation']['shoulder']}" scope="parent"/>
<xacro:property name="__upper_arm_inertia_rotation" value="${__inertia_parameters['rotation']['upper_arm']}" scope="parent"/>
<xacro:property name="__forearm_inertia_rotation" value="${__inertia_parameters['rotation']['forearm']}" scope="parent"/>
<xacro:property name="__wrist_1_inertia_rotation" value="${__inertia_parameters['rotation']['wrist_1']}" scope="parent"/>
<xacro:property name="__wrist_2_inertia_rotation" value="${__inertia_parameters['rotation']['wrist_2']}" scope="parent"/>
<xacro:property name="__wrist_3_inertia_rotation" value="${__inertia_parameters['rotation']['wrist_3']}" scope="parent"/>

<xacro:property name="shoulder_inertia_rotation" value="${__shoulder_inertia_rotation['roll']} ${__shoulder_inertia_rotation['pitch']} ${__shoulder_inertia_rotation['yaw']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_rotation" value="${__upper_arm_inertia_rotation['roll']} ${__upper_arm_inertia_rotation['pitch']} ${__upper_arm_inertia_rotation['yaw']}" scope="parent"/>
<xacro:property name="forearm_inertia_rotation" value="${__forearm_inertia_rotation['roll']} ${__forearm_inertia_rotation['pitch']} ${__forearm_inertia_rotation['yaw']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_rotation" value="${__wrist_1_inertia_rotation['roll']} ${__wrist_1_inertia_rotation['pitch']} ${__wrist_1_inertia_rotation['yaw']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_rotation" value="${__wrist_2_inertia_rotation['roll']} ${__wrist_2_inertia_rotation['pitch']} ${__wrist_2_inertia_rotation['yaw']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_rotation" value="${__wrist_3_inertia_rotation['roll']} ${__wrist_3_inertia_rotation['pitch']} ${__wrist_3_inertia_rotation['yaw']}" scope="parent"/>


<!-- tensors -->
<xacro:property name="__shoulder_inertia" value="${__inertia_parameters['tensor']['shoulder']}" scope="parent"/>
<xacro:property name="__upper_arm_inertia" value="${__inertia_parameters['tensor']['upper_arm']}" scope="parent"/>
<xacro:property name="__forearm_inertia" value="${__inertia_parameters['tensor']['forearm']}" scope="parent"/>
<xacro:property name="__wrist_1_inertia" value="${__inertia_parameters['tensor']['wrist_1']}" scope="parent"/>
<xacro:property name="__wrist_2_inertia" value="${__inertia_parameters['tensor']['wrist_2']}" scope="parent"/>
<xacro:property name="__wrist_3_inertia" value="${__inertia_parameters['tensor']['wrist_3']}" scope="parent"/>

<xacro:property name="shoulder_inertia_ixx" value="${__shoulder_inertia['ixx']}" scope="parent"/>
<xacro:property name="shoulder_inertia_ixy" value="${__shoulder_inertia['ixy']}" scope="parent"/>
<xacro:property name="shoulder_inertia_ixz" value="${__shoulder_inertia['ixz']}" scope="parent"/>
<xacro:property name="shoulder_inertia_iyy" value="${__shoulder_inertia['iyy']}" scope="parent"/>
<xacro:property name="shoulder_inertia_iyz" value="${__shoulder_inertia['iyz']}" scope="parent"/>
<xacro:property name="shoulder_inertia_izz" value="${__shoulder_inertia['izz']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_ixx" value="${__upper_arm_inertia['ixx']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_ixy" value="${__upper_arm_inertia['ixy']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_ixz" value="${__upper_arm_inertia['ixz']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_iyy" value="${__upper_arm_inertia['iyy']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_iyz" value="${__upper_arm_inertia['iyz']}" scope="parent"/>
<xacro:property name="upper_arm_inertia_izz" value="${__upper_arm_inertia['izz']}" scope="parent"/>
<xacro:property name="forearm_inertia_ixx" value="${__forearm_inertia['ixx']}" scope="parent"/>
<xacro:property name="forearm_inertia_ixy" value="${__forearm_inertia['ixy']}" scope="parent"/>
<xacro:property name="forearm_inertia_ixz" value="${__forearm_inertia['ixz']}" scope="parent"/>
<xacro:property name="forearm_inertia_iyy" value="${__forearm_inertia['iyy']}" scope="parent"/>
<xacro:property name="forearm_inertia_iyz" value="${__forearm_inertia['iyz']}" scope="parent"/>
<xacro:property name="forearm_inertia_izz" value="${__forearm_inertia['izz']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_ixx" value="${__wrist_1_inertia['ixx']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_ixy" value="${__wrist_1_inertia['ixy']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_ixz" value="${__wrist_1_inertia['ixz']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_iyy" value="${__wrist_1_inertia['iyy']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_iyz" value="${__wrist_1_inertia['iyz']}" scope="parent"/>
<xacro:property name="wrist_1_inertia_izz" value="${__wrist_1_inertia['izz']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_ixx" value="${__wrist_2_inertia['ixx']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_ixy" value="${__wrist_2_inertia['ixy']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_ixz" value="${__wrist_2_inertia['ixz']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_iyy" value="${__wrist_2_inertia['iyy']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_iyz" value="${__wrist_2_inertia['iyz']}" scope="parent"/>
<xacro:property name="wrist_2_inertia_izz" value="${__wrist_2_inertia['izz']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_ixx" value="${__wrist_3_inertia['ixx']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_ixy" value="${__wrist_3_inertia['ixy']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_ixz" value="${__wrist_3_inertia['ixz']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_iyy" value="${__wrist_3_inertia['iyy']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_iyz" value="${__wrist_3_inertia['iyz']}" scope="parent"/>
<xacro:property name="wrist_3_inertia_izz" value="${__wrist_3_inertia['izz']}" scope="parent"/>

<!-- cylinder radius -->
<xacro:property name="shoulder_radius" value="${__inertia_parameters['shoulder_radius']}" scope="parent"/>
<xacro:property name="upper_arm_radius" value="${__inertia_parameters['upper_arm_radius']}" scope="parent"/>
Expand Down
90 changes: 72 additions & 18 deletions ur_description/urdf/ur_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,18 @@
<mesh filename="${shoulder_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${shoulder_inertia_radius}" length="${shoulder_inertia_length}" mass="${shoulder_mass}">
<origin xyz="${shoulder_cog}" rpy="0 0 0" />
</xacro:cylinder_inertial>
<inertial>
<mass value="${shoulder_mass}"/>
<origin rpy="${shoulder_inertia_rotation}" xyz="${shoulder_cog}"/>
<inertia
ixx="${shoulder_inertia_ixx}"
ixy="${shoulder_inertia_ixy}"
ixz="${shoulder_inertia_ixz}"
iyy="${shoulder_inertia_iyy}"
iyz="${shoulder_inertia_iyz}"
izz="${shoulder_inertia_izz}"
/>
</inertial>
</link>
<link name="${prefix}upper_arm_link">
<visual>
Expand All @@ -133,9 +142,18 @@
<mesh filename="${upper_arm_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${upperarm_inertia_radius}" length="${upperarm_inertia_length}" mass="${upper_arm_mass}">
<origin xyz="${upper_arm_cog}" rpy="0 ${pi/2} 0" />
</xacro:cylinder_inertial>
<inertial>
<mass value="${upper_arm_mass}"/>
<origin rpy="${upper_arm_inertia_rotation}" xyz="${upper_arm_cog}"/>
<inertia
ixx="${upper_arm_inertia_ixx}"
ixy="${upper_arm_inertia_ixy}"
ixz="${upper_arm_inertia_ixz}"
iyy="${upper_arm_inertia_iyy}"
iyz="${upper_arm_inertia_iyz}"
izz="${upper_arm_inertia_izz}"
/>
</inertial>
</link>
<link name="${prefix}forearm_link">
<visual>
Expand All @@ -153,9 +171,18 @@
<mesh filename="${forearm_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${forearm_inertia_radius}" length="${forearm_inertia_length}" mass="${forearm_mass}">
<origin xyz="${forearm_cog}" rpy="0 ${pi/2} 0" />
</xacro:cylinder_inertial>
<inertial>
<mass value="${forearm_mass}"/>
<origin rpy="${forearm_inertia_rotation}" xyz="${forearm_cog}"/>
<inertia
ixx="${forearm_inertia_ixx}"
ixy="${forearm_inertia_ixy}"
ixz="${forearm_inertia_ixz}"
iyy="${forearm_inertia_iyy}"
iyz="${forearm_inertia_iyz}"
izz="${forearm_inertia_izz}"
/>
</inertial>
</link>
<link name="${prefix}wrist_1_link">
<visual>
Expand All @@ -174,9 +201,18 @@
<mesh filename="${wrist_1_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_1_inertia_radius}" length="${wrist_1_inertia_length}" mass="${wrist_1_mass}">
<origin xyz="${wrist_1_cog}" rpy="0 0 0" />
</xacro:cylinder_inertial>
<inertial>
<mass value="${wrist_1_mass}"/>
<origin rpy="${wrist_1_inertia_rotation}" xyz="${wrist_1_cog}"/>
<inertia
ixx="${wrist_1_inertia_ixx}"
ixy="${wrist_1_inertia_ixy}"
ixz="${wrist_1_inertia_ixz}"
iyy="${wrist_1_inertia_iyy}"
iyz="${wrist_1_inertia_iyz}"
izz="${wrist_1_inertia_izz}"
/>
</inertial>
</link>
<link name="${prefix}wrist_2_link">
<visual>
Expand All @@ -194,9 +230,18 @@
<mesh filename="${wrist_2_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_2_inertia_radius}" length="${wrist_2_inertia_length}" mass="${wrist_2_mass}">
<origin xyz="${wrist_2_cog}" rpy="0 0 0" />
</xacro:cylinder_inertial>
<inertial>
<mass value="${wrist_2_mass}"/>
<origin rpy="${wrist_2_inertia_rotation}" xyz="${wrist_2_cog}"/>
<inertia
ixx="${wrist_2_inertia_ixx}"
ixy="${wrist_2_inertia_ixy}"
ixz="${wrist_2_inertia_ixz}"
iyy="${wrist_2_inertia_iyy}"
iyz="${wrist_2_inertia_iyz}"
izz="${wrist_2_inertia_izz}"
/>
</inertial>
</link>
<link name="${prefix}wrist_3_link">
<visual>
Expand All @@ -214,9 +259,18 @@
<mesh filename="${wrist_3_collision_mesh}"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_3_inertia_radius}" length="${wrist_3_inertia_length}" mass="${wrist_3_mass}">
<origin xyz="${wrist_3_cog}" rpy="0 0 0" />
</xacro:cylinder_inertial>
<inertial>
<mass value="${wrist_3_mass}"/>
<origin rpy="${wrist_3_inertia_rotation}" xyz="${wrist_3_cog}"/>
<inertia
ixx="${wrist_3_inertia_ixx}"
ixy="${wrist_3_inertia_ixy}"
ixz="${wrist_3_inertia_ixz}"
iyy="${wrist_3_inertia_iyy}"
iyz="${wrist_3_inertia_iyz}"
izz="${wrist_3_inertia_izz}"
/>
</inertial>
</link>

<!-- joints: main serial chain -->
Expand Down

0 comments on commit 415952d

Please sign in to comment.