add go2 rotor inertia
This commit is contained in:
parent
4f0a6b501b
commit
9912563845
|
@ -37,17 +37,23 @@
|
|||
<xacro:property name="hip_offset_x" value="0.1934"/>
|
||||
<xacro:property name="hip_offset_y" value="0.0465"/>
|
||||
<xacro:property name="hip_offset_z" value="0.0"/>
|
||||
|
||||
<xacro:property name="hip_rotor_offset_x" value="0.11215"/>
|
||||
<xacro:property name="hip_rotor_offset_y" value="0.04675"/>
|
||||
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
|
||||
|
||||
<xacro:property name="thigh_offset_x" value="0"/>
|
||||
<xacro:property name="thigh_offset_y" value="0.0955"/>
|
||||
<xacro:property name="thigh_offset_z" value="0.0"/>
|
||||
|
||||
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_offset_y" value="-0.00015"/>
|
||||
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
|
||||
|
||||
<xacro:property name="calf_offset_x" value="0.0"/>
|
||||
<xacro:property name="calf_offset_y" value="0.0"/>
|
||||
<xacro:property name="calf_offset_z" value="-0.213"/>
|
||||
|
||||
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_offset_y" value="-0.03235"/>
|
||||
<xacro:property name="calf_rotor_offset_z" value="0.0"/>
|
||||
|
||||
<!-- joint limits -->
|
||||
<xacro:property name="damping" value="0.0"/>
|
||||
|
@ -90,6 +96,17 @@
|
|||
<xacro:property name="hip_iyz" value="-1.42E-06"/>
|
||||
<xacro:property name="hip_izz" value="0.000596"/>
|
||||
|
||||
<xacro:property name="hip_rotor_mass" value="0.089"/>
|
||||
<xacro:property name="hip_rotor_com_x" value="0.0"/>
|
||||
<xacro:property name="hip_rotor_com_y" value="0.0"/>
|
||||
<xacro:property name="hip_rotor_com_z" value="0.0"/>
|
||||
<xacro:property name="hip_rotor_ixx" value="0.000111842"/>
|
||||
<xacro:property name="hip_rotor_ixy" value="0.0"/>
|
||||
<xacro:property name="hip_rotor_ixz" value="0.0"/>
|
||||
<xacro:property name="hip_rotor_iyy" value="0.000059647"/>
|
||||
<xacro:property name="hip_rotor_iyz" value="0.0"/>
|
||||
<xacro:property name="hip_rotor_izz" value="0.000059647"/>
|
||||
|
||||
<!-- thigh -->
|
||||
<xacro:property name="thigh_mass" value="1.152"/>
|
||||
<xacro:property name="thigh_com_x" value="-0.00374"/>
|
||||
|
@ -102,6 +119,17 @@
|
|||
<xacro:property name="thigh_iyz" value="0.000808"/>
|
||||
<xacro:property name="thigh_izz" value="0.00103"/>
|
||||
|
||||
<xacro:property name="thigh_rotor_mass" value="0.089"/>
|
||||
<xacro:property name="thigh_rotor_com_x" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_com_y" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_com_z" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_ixx" value="0.000059647"/>
|
||||
<xacro:property name="thigh_rotor_ixy" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_ixz" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_iyy" value="0.000111842"/>
|
||||
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
|
||||
<xacro:property name="thigh_rotor_izz" value="0.000059647"/>
|
||||
|
||||
<!-- calf -->
|
||||
<xacro:property name="calf_mass" value="0.154"/>
|
||||
<xacro:property name="calf_com_x" value="0.00548"/>
|
||||
|
@ -114,6 +142,16 @@
|
|||
<xacro:property name="calf_iyz" value="8.28E-06"/>
|
||||
<xacro:property name="calf_izz" value="3.29E-05"/>
|
||||
|
||||
<xacro:property name="calf_rotor_mass" value="0.089"/>
|
||||
<xacro:property name="calf_rotor_com_x" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_com_y" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_com_z" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_ixx" value="0.000059647"/>
|
||||
<xacro:property name="calf_rotor_ixy" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_ixz" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_iyy" value="0.000111842"/>
|
||||
<xacro:property name="calf_rotor_iyz" value="0.0"/>
|
||||
<xacro:property name="calf_rotor_izz" value="0.000059647"/>
|
||||
|
||||
<!-- foot -->
|
||||
<xacro:property name="foot_mass" value="0.06"/>
|
||||
|
|
|
@ -31,6 +31,22 @@
|
|||
</xacro:if>
|
||||
</joint>
|
||||
|
||||
<joint name="${name}_hip_rotor_joint" type="fixed">
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == True)}">
|
||||
<origin rpy="0 0 0" xyz="${hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == False) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${-hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<xacro:if value="${(mirror_dae == True) and (front_hind_dae == False)}">
|
||||
<origin rpy="0 0 0" xyz="${-hip_rotor_offset_x} ${hip_rotor_offset_y} 0"/>
|
||||
</xacro:if>
|
||||
<parent link="trunk"/>
|
||||
<child link="${name}_hip_rotor"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_hip">
|
||||
<visual>
|
||||
|
@ -67,6 +83,30 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="${name}_hip_rotor">
|
||||
<visual>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.035"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<!-- <collision>
|
||||
<origin rpy="0 ${PI/2.0} 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.035"/>
|
||||
</geometry>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${hip_rotor_com_x} ${hip_rotor_com_y} ${hip_rotor_com_z}"/>
|
||||
<mass value="${hip_rotor_mass}"/>
|
||||
<inertia
|
||||
ixx="${hip_rotor_ixx}" ixy="${hip_rotor_ixy}" ixz="${hip_rotor_ixz}"
|
||||
iyy="${hip_rotor_iyy}" iyz="${hip_rotor_iyz}"
|
||||
izz="${hip_rotor_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_thigh_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 ${thigh_offset*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
|
@ -76,6 +116,11 @@
|
|||
<limit effort="${thigh_torque_max}" velocity="${thigh_velocity_max}" lower="${thigh_position_min}" upper="${thigh_position_max}"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${name}_thigh_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="${thigh_rotor_offset_x} ${thigh_rotor_offset_y*mirror} 0"/>
|
||||
<parent link="${name}_hip"/>
|
||||
<child link="${name}_thigh_rotor"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_thigh">
|
||||
<visual>
|
||||
|
@ -106,6 +151,29 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="${name}_thigh_rotor">
|
||||
<visual>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.035"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<!-- <collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.035"/>
|
||||
</geometry>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${thigh_rotor_com_x} ${thigh_rotor_com_y} ${thigh_rotor_com_z}"/>
|
||||
<mass value="${thigh_rotor_mass}"/>
|
||||
<inertia
|
||||
ixx="${thigh_rotor_ixx}" ixy="${thigh_rotor_ixy}" ixz="${thigh_rotor_ixz}"
|
||||
iyy="${thigh_rotor_iyy}" iyz="${thigh_rotor_iyz}"
|
||||
izz="${thigh_rotor_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_calf_joint" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-thigh_length}"/>
|
||||
|
@ -116,6 +184,11 @@
|
|||
<limit effort="${calf_torque_max}" velocity="${calf_velocity_max}" lower="${calf_position_min}" upper="${calf_position_max}"/>
|
||||
</joint>
|
||||
|
||||
<joint name="${name}_calf_rotor_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="${calf_rotor_offset_x} ${calf_rotor_offset_y*mirror} 0"/>
|
||||
<parent link="${name}_thigh"/>
|
||||
<child link="${name}_calf_rotor"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_calf">
|
||||
<visual>
|
||||
|
@ -141,8 +214,31 @@
|
|||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="${name}_calf_rotor">
|
||||
<visual>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.035"/>
|
||||
</geometry>
|
||||
<material name="green"/>
|
||||
</visual>
|
||||
<!-- <collision>
|
||||
<origin rpy="${PI/2.0} 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.02" radius="0.035"/>
|
||||
</geometry>
|
||||
</collision> -->
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="${calf_rotor_com_x} ${calf_rotor_com_y} ${calf_rotor_com_z}"/>
|
||||
<mass value="${calf_rotor_mass}"/>
|
||||
<inertia
|
||||
ixx="${calf_rotor_ixx}" ixy="${calf_rotor_ixy}" ixz="${calf_rotor_ixz}"
|
||||
iyy="${calf_rotor_iyy}" iyz="${calf_rotor_iyz}"
|
||||
izz="${calf_rotor_izz}"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="${name}_foot_fixed" type="fixed">0
|
||||
<joint name="${name}_foot_fixed" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 ${-(calf_length)}"/>
|
||||
<parent link="${name}_calf"/>
|
||||
<child link="${name}_foot"/>
|
||||
|
|
Loading…
Reference in New Issue