903 lines
30 KiB
Plaintext
903 lines
30 KiB
Plaintext
|
<robot name="g1_23dof">
|
||
|
<mujoco>
|
||
|
<compiler meshdir="meshes" discardvisual="false"/>
|
||
|
</mujoco>
|
||
|
|
||
|
<!-- [CAUTION] uncomment when convert to mujoco -->
|
||
|
<!-- <link name="world"></link>
|
||
|
<joint name="floating_base_joint" type="floating">
|
||
|
<parent link="world"/>
|
||
|
<child link="pelvis"/>
|
||
|
</joint> -->
|
||
|
|
||
|
<link name="pelvis">
|
||
|
<inertial>
|
||
|
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
|
||
|
<mass value="3.813"/>
|
||
|
<inertia ixx="0.010549" ixy="0" ixz="2.1E-06" iyy="0.0093089" iyz="0" izz="0.0079184"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/pelvis.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<link name="pelvis_contour_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<mass value="0.001"/>
|
||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/pelvis_contour_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="pelvis_contour_joint" type="fixed">
|
||
|
<parent link="pelvis"/>
|
||
|
<child link="pelvis_contour_link"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- Legs -->
|
||
|
<link name="left_hip_pitch_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.002741 0.047791 -0.02606" rpy="0 0 0"/>
|
||
|
<mass value="1.35"/>
|
||
|
<inertia ixx="0.001811" ixy="3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="0.000171" izz="0.0012812"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_hip_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_hip_pitch_joint" type="revolute">
|
||
|
<origin xyz="0 0.064452 -0.1027" rpy="0 0 0"/>
|
||
|
<parent link="pelvis"/>
|
||
|
<child link="left_hip_pitch_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="left_hip_roll_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.029812 -0.001045 -0.087934" rpy="0 0 0"/>
|
||
|
<mass value="1.52"/>
|
||
|
<inertia ixx="0.0023773" ixy="-3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="1.84E-05" izz="0.0016595"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_hip_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_hip_roll_joint" type="revolute">
|
||
|
<origin xyz="0 0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||
|
<parent link="left_hip_pitch_link"/>
|
||
|
<child link="left_hip_roll_link"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<limit lower="-0.5236" upper="2.9671" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="left_hip_yaw_link">
|
||
|
<inertial>
|
||
|
<origin xyz="-0.057709 -0.010981 -0.15078" rpy="0 0 0"/>
|
||
|
<mass value="1.702"/>
|
||
|
<inertia ixx="0.0057774" ixy="-0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="-0.0007072" izz="0.003149"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_hip_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_hip_yaw_joint" type="revolute">
|
||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||
|
<parent link="left_hip_roll_link"/>
|
||
|
<child link="left_hip_yaw_link"/>
|
||
|
<axis xyz="0 0 1"/>
|
||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="left_knee_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.005457 0.003964 -0.12074" rpy="0 0 0"/>
|
||
|
<mass value="1.932"/>
|
||
|
<inertia ixx="0.011329" ixy="4.82E-05" ixz="-4.49E-05" iyy="0.011277" iyz="-0.0007146" izz="0.0015168"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_knee_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_knee_joint" type="revolute">
|
||
|
<origin xyz="-0.078273 0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||
|
<parent link="left_hip_yaw_link"/>
|
||
|
<child link="left_knee_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||
|
</joint>
|
||
|
<link name="left_ankle_pitch_link">
|
||
|
<inertial>
|
||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||
|
<mass value="0.074"/>
|
||
|
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_ankle_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_ankle_pitch_joint" type="revolute">
|
||
|
<origin xyz="0 -9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||
|
<parent link="left_knee_link"/>
|
||
|
<child link="left_ankle_pitch_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="left_ankle_roll_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||
|
<mass value="0.608"/>
|
||
|
<inertia ixx="0.0002231" ixy="2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="-1E-07" izz="0.0016667"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_ankle_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision>
|
||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision>
|
||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision>
|
||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_ankle_roll_joint" type="revolute">
|
||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||
|
<parent link="left_ankle_pitch_link"/>
|
||
|
<child link="left_ankle_roll_link"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="right_hip_pitch_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.002741 -0.047791 -0.02606" rpy="0 0 0"/>
|
||
|
<mass value="1.35"/>
|
||
|
<inertia ixx="0.001811" ixy="-3.68E-05" ixz="-3.44E-05" iyy="0.0014193" iyz="-0.000171" izz="0.0012812"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_hip_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_hip_pitch_joint" type="revolute">
|
||
|
<origin xyz="0 -0.064452 -0.1027" rpy="0 0 0"/>
|
||
|
<parent link="pelvis"/>
|
||
|
<child link="right_hip_pitch_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-2.5307" upper="2.8798" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="right_hip_roll_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.029812 0.001045 -0.087934" rpy="0 0 0"/>
|
||
|
<mass value="1.52"/>
|
||
|
<inertia ixx="0.0023773" ixy="3.8E-06" ixz="-0.0003908" iyy="0.0024123" iyz="-1.84E-05" izz="0.0016595"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_hip_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_hip_roll_joint" type="revolute">
|
||
|
<origin xyz="0 -0.052 -0.030465" rpy="0 -0.1749 0"/>
|
||
|
<parent link="right_hip_pitch_link"/>
|
||
|
<child link="right_hip_roll_link"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<limit lower="-2.9671" upper="0.5236" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="right_hip_yaw_link">
|
||
|
<inertial>
|
||
|
<origin xyz="-0.057709 0.010981 -0.15078" rpy="0 0 0"/>
|
||
|
<mass value="1.702"/>
|
||
|
<inertia ixx="0.0057774" ixy="0.0005411" ixz="-0.0023948" iyy="0.0076124" iyz="0.0007072" izz="0.003149"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_hip_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_hip_yaw_joint" type="revolute">
|
||
|
<origin xyz="0.025001 0 -0.12412" rpy="0 0 0"/>
|
||
|
<parent link="right_hip_roll_link"/>
|
||
|
<child link="right_hip_yaw_link"/>
|
||
|
<axis xyz="0 0 1"/>
|
||
|
<limit lower="-2.7576" upper="2.7576" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="right_knee_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.005457 -0.003964 -0.12074" rpy="0 0 0"/>
|
||
|
<mass value="1.932"/>
|
||
|
<inertia ixx="0.011329" ixy="-4.82E-05" ixz="4.49E-05" iyy="0.011277" iyz="0.0007146" izz="0.0015168"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_knee_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_knee_joint" type="revolute">
|
||
|
<origin xyz="-0.078273 -0.0021489 -0.17734" rpy="0 0.1749 0"/>
|
||
|
<parent link="right_hip_yaw_link"/>
|
||
|
<child link="right_knee_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-0.087267" upper="2.8798" effort="139" velocity="20"/>
|
||
|
</joint>
|
||
|
<link name="right_ankle_pitch_link">
|
||
|
<inertial>
|
||
|
<origin xyz="-0.007269 0 0.011137" rpy="0 0 0"/>
|
||
|
<mass value="0.074"/>
|
||
|
<inertia ixx="8.4E-06" ixy="0" ixz="-2.9E-06" iyy="1.89E-05" iyz="0" izz="1.26E-05"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_ankle_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_ankle_pitch_joint" type="revolute">
|
||
|
<origin xyz="0 9.4445E-05 -0.30001" rpy="0 0 0"/>
|
||
|
<parent link="right_knee_link"/>
|
||
|
<child link="right_ankle_pitch_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-0.87267" upper="0.5236" effort="50" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="right_ankle_roll_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.026505 0 -0.016425" rpy="0 0 0"/>
|
||
|
<mass value="0.608"/>
|
||
|
<inertia ixx="0.0002231" ixy="-2E-07" ixz="8.91E-05" iyy="0.0016161" iyz="1E-07" izz="0.0016667"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_ankle_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="-0.05 0.025 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision>
|
||
|
<origin xyz="-0.05 -0.025 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision>
|
||
|
<origin xyz="0.12 0.03 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
<collision>
|
||
|
<origin xyz="0.12 -0.03 -0.03" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<sphere radius="0.005"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_ankle_roll_joint" type="revolute">
|
||
|
<origin xyz="0 0 -0.017558" rpy="0 0 0"/>
|
||
|
<parent link="right_ankle_pitch_link"/>
|
||
|
<child link="right_ankle_roll_link"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<limit lower="-0.2618" upper="0.2618" effort="50" velocity="37"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- Torso -->
|
||
|
<link name="waist_yaw_fixed_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.003964 0 0.018769" rpy="0 0 0"/>
|
||
|
<mass value="0.244"/>
|
||
|
<inertia ixx="9.9587E-05" ixy="-1.833E-06" ixz="-1.2617E-05" iyy="0.00012411" iyz="-1.18E-07" izz="0.00015586"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/waist_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
</link>
|
||
|
<joint name="waist_yaw_fixed_joint" type="fixed">
|
||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="waist_yaw_fixed_link"/>
|
||
|
</joint>
|
||
|
<joint name="waist_yaw_joint" type="revolute">
|
||
|
<origin xyz="-0.0039635 0 0.054" rpy="0 0 0"/>
|
||
|
<parent link="pelvis"/>
|
||
|
<child link="torso_link"/>
|
||
|
<axis xyz="0 0 1"/>
|
||
|
<limit lower="-2.618" upper="2.618" effort="88" velocity="32"/>
|
||
|
</joint>
|
||
|
<link name="torso_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.002601 0.000257 0.153719" rpy="0 0 0"/>
|
||
|
<mass value="8.562"/>
|
||
|
<inertia ixx="0.065674966" ixy="-8.597E-05" ixz="-0.001737252" iyy="0.053535188" iyz="8.6899E-05" izz="0.030808125"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/torso_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/torso_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
|
||
|
<!-- LOGO -->
|
||
|
<joint name="logo_joint" type="fixed">
|
||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="logo_link"/>
|
||
|
</joint>
|
||
|
<link name="logo_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<mass value="0.001"/>
|
||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/logo_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/logo_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
|
||
|
<!-- Head -->
|
||
|
<link name="head_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.005267 0.000299 0.449869" rpy="0 0 0"/>
|
||
|
<mass value="1.036"/>
|
||
|
<inertia ixx="0.004085051" ixy="-2.543E-06" ixz="-6.9455E-05" iyy="0.004185212" iyz="-3.726E-06" izz="0.001807911"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/head_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="dark">
|
||
|
<color rgba="0.2 0.2 0.2 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/head_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="head_joint" type="fixed">
|
||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="head_link"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- Waist Support -->
|
||
|
<link name="waist_support_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<mass value="0.001"/>
|
||
|
<inertia ixx="1e-7" ixy="0" ixz="0" iyy="1e-7" iyz="0" izz="1e-7"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/waist_support_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/waist_support_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="waist_support_joint" type="fixed">
|
||
|
<origin xyz="0.0039635 0 -0.054" rpy="0 0 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="waist_support_link"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- IMU -->
|
||
|
<link name="imu_in_torso"></link>
|
||
|
<joint name="imu_in_torso_joint" type="fixed">
|
||
|
<origin xyz="-0.03959 -0.00224 0.13792" rpy="0 0 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="imu_in_torso"/>
|
||
|
</joint>
|
||
|
|
||
|
<link name="imu_in_pelvis"></link>
|
||
|
<joint name="imu_in_pelvis_joint" type="fixed">
|
||
|
<origin xyz="0.04525 0 -0.08339" rpy="0 0 0"/>
|
||
|
<parent link="pelvis"/>
|
||
|
<child link="imu_in_pelvis"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- d435 -->
|
||
|
<link name="d435_link"></link>
|
||
|
<joint name="d435_joint" type="fixed">
|
||
|
<origin xyz="0.0576235 0.01753 0.41987" rpy="0 0.8307767239493009 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="d435_link"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- mid360 -->
|
||
|
<link name="mid360_link"></link>
|
||
|
<joint name="mid360_joint" type="fixed">
|
||
|
<origin xyz="0.0002835 0.00003 0.40618" rpy="0 0.04014257279586953 0"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="mid360_link"/>
|
||
|
</joint>
|
||
|
|
||
|
<!-- Arm -->
|
||
|
<link name="left_shoulder_pitch_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0 0.035892 -0.011628" rpy="0 0 0"/>
|
||
|
<mass value="0.718"/>
|
||
|
<inertia ixx="0.0004291" ixy="-9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="2.26E-05" izz="0.000423"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_shoulder_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.03" length="0.05"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_shoulder_pitch_joint" type="revolute">
|
||
|
<origin xyz="0.0039563 0.10022 0.23778" rpy="0.27931 5.4949E-05 -0.00019159"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="left_shoulder_pitch_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="left_shoulder_roll_link">
|
||
|
<inertial>
|
||
|
<origin xyz="-0.000227 0.00727 -0.063243" rpy="0 0 0"/>
|
||
|
<mass value="0.643"/>
|
||
|
<inertia ixx="0.0006177" ixy="-1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="-5.3E-06" izz="0.0003894"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_shoulder_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="-0.004 0.006 -0.053" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.03" length="0.03"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_shoulder_roll_joint" type="revolute">
|
||
|
<origin xyz="0 0.038 -0.013831" rpy="-0.27925 0 0"/>
|
||
|
<parent link="left_shoulder_pitch_link"/>
|
||
|
<child link="left_shoulder_roll_link"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<limit lower="-1.5882" upper="2.2515" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="left_shoulder_yaw_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.010773 -0.002949 -0.072009" rpy="0 0 0"/>
|
||
|
<mass value="0.734"/>
|
||
|
<inertia ixx="0.0009988" ixy="7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="-2.86E-05" izz="0.0004354"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_shoulder_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_shoulder_yaw_joint" type="revolute">
|
||
|
<origin xyz="0 0.00624 -0.1032" rpy="0 0 0"/>
|
||
|
<parent link="left_shoulder_roll_link"/>
|
||
|
<child link="left_shoulder_yaw_link"/>
|
||
|
<axis xyz="0 0 1"/>
|
||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="left_elbow_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.064956 0.004454 -0.010062" rpy="0 0 0"/>
|
||
|
<mass value="0.6"/>
|
||
|
<inertia ixx="0.0002891" ixy="6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="-5.6E-06" izz="0.0004197"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_elbow_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="left_elbow_joint" type="revolute">
|
||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||
|
<parent link="left_shoulder_yaw_link"/>
|
||
|
<child link="left_elbow_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<joint name="left_wrist_roll_joint" type="revolute">
|
||
|
<origin xyz="0.100 0.00188791 -0.010" rpy="0 0 0"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<parent link="left_elbow_link"/>
|
||
|
<child link="left_wrist_roll_rubber_hand"/>
|
||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||
|
</joint>
|
||
|
<link name="left_wrist_roll_rubber_hand">
|
||
|
<inertial>
|
||
|
<origin xyz="0.10794656650 0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||
|
<mass value="0.35692864"/>
|
||
|
<inertia ixx="0.00019613494735" ixy="-0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="0.00000249774203" izz="0.00194181412808"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/left_wrist_roll_rubber_hand.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<link name="right_shoulder_pitch_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0 -0.035892 -0.011628" rpy="0 0 0"/>
|
||
|
<mass value="0.718"/>
|
||
|
<inertia ixx="0.0004291" ixy="9.2E-06" ixz="6.4E-06" iyy="0.000453" iyz="-2.26E-05" izz="0.000423"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_shoulder_pitch_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 -0.04 -0.01" rpy="0 1.5707963267948966 0"/>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.03" length="0.05"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_shoulder_pitch_joint" type="revolute">
|
||
|
<origin xyz="0.0039563 -0.10021 0.23778" rpy="-0.27931 5.4949E-05 0.00019159"/>
|
||
|
<parent link="torso_link"/>
|
||
|
<child link="right_shoulder_pitch_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-3.0892" upper="2.6704" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="right_shoulder_roll_link">
|
||
|
<inertial>
|
||
|
<origin xyz="-0.000227 -0.00727 -0.063243" rpy="0 0 0"/>
|
||
|
<mass value="0.643"/>
|
||
|
<inertia ixx="0.0006177" ixy="1E-06" ixz="8.7E-06" iyy="0.0006912" iyz="5.3E-06" izz="0.0003894"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_shoulder_roll_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="-0.004 -0.006 -0.053" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<cylinder radius="0.03" length="0.03"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_shoulder_roll_joint" type="revolute">
|
||
|
<origin xyz="0 -0.038 -0.013831" rpy="0.27925 0 0"/>
|
||
|
<parent link="right_shoulder_pitch_link"/>
|
||
|
<child link="right_shoulder_roll_link"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<limit lower="-2.2515" upper="1.5882" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="right_shoulder_yaw_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.010773 0.002949 -0.072009" rpy="0 0 0"/>
|
||
|
<mass value="0.734"/>
|
||
|
<inertia ixx="0.0009988" ixy="-7.9E-06" ixz="0.0001412" iyy="0.0010605" iyz="2.86E-05" izz="0.0004354"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_shoulder_yaw_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_shoulder_yaw_joint" type="revolute">
|
||
|
<origin xyz="0 -0.00624 -0.1032" rpy="0 0 0"/>
|
||
|
<parent link="right_shoulder_roll_link"/>
|
||
|
<child link="right_shoulder_yaw_link"/>
|
||
|
<axis xyz="0 0 1"/>
|
||
|
<limit lower="-2.618" upper="2.618" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<link name="right_elbow_link">
|
||
|
<inertial>
|
||
|
<origin xyz="0.064956 -0.004454 -0.010062" rpy="0 0 0"/>
|
||
|
<mass value="0.6"/>
|
||
|
<inertia ixx="0.0002891" ixy="-6.53E-05" ixz="1.72E-05" iyy="0.0004152" iyz="5.6E-06" izz="0.0004197"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_elbow_link.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
<joint name="right_elbow_joint" type="revolute">
|
||
|
<origin xyz="0.015783 0 -0.080518" rpy="0 0 0"/>
|
||
|
<parent link="right_shoulder_yaw_link"/>
|
||
|
<child link="right_elbow_link"/>
|
||
|
<axis xyz="0 1 0"/>
|
||
|
<limit lower="-1.0472" upper="2.0944" effort="25" velocity="37"/>
|
||
|
</joint>
|
||
|
<joint name="right_wrist_roll_joint" type="revolute">
|
||
|
<origin xyz="0.100 -0.00188791 -0.010" rpy="0 0 0"/>
|
||
|
<axis xyz="1 0 0"/>
|
||
|
<parent link="right_elbow_link"/>
|
||
|
<child link="right_wrist_roll_rubber_hand"/>
|
||
|
<limit effort="25" velocity="37" lower="-1.972222054" upper="1.972222054"/>
|
||
|
</joint>
|
||
|
<link name="right_wrist_roll_rubber_hand">
|
||
|
<inertial>
|
||
|
<origin xyz="0.10794656650 -0.00163511945 0.00202244863" rpy="0 0 0"/>
|
||
|
<mass value="0.35692864"/>
|
||
|
<inertia ixx="0.00019613494735" ixy="0.00000419816908" ixz="-0.00003950860580" iyy="0.00200280358206" iyz="-0.00000249774203" izz="0.00194181412808"/>
|
||
|
</inertial>
|
||
|
<visual>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||
|
</geometry>
|
||
|
<material name="white">
|
||
|
<color rgba="0.7 0.7 0.7 1"/>
|
||
|
</material>
|
||
|
</visual>
|
||
|
<collision>
|
||
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||
|
<geometry>
|
||
|
<mesh filename="meshes/right_wrist_roll_rubber_hand.STL"/>
|
||
|
</geometry>
|
||
|
</collision>
|
||
|
</link>
|
||
|
</robot>
|