| | <?xml version="1.0" encoding="utf-8"?>
|
| | |
| | |
| | |
| |
|
| | <robot
|
| | name="h1_description">
|
| | <mujoco>
|
| | <compiler meshdir="../meshes" discardvisual="false" />
|
| | </mujoco>
|
| |
|
| |
|
| |
|
| | |
| | |
| | |
| | |
| |
|
| |
|
| |
|
| | <link
|
| | name="pelvis">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.0002 4E-05 -0.04522"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="5.39" />
|
| | <inertia
|
| | ixx="0.044582"
|
| | ixy="8.7034E-05"
|
| | ixz="-1.9893E-05"
|
| | iyy="0.0082464"
|
| | iyz="4.021E-06"
|
| | izz="0.049021" />
|
| | </inertial>
|
| | <visual>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/pelvis.STL" />
|
| | </geometry>
|
| | <material
|
| | name="white">
|
| | <color
|
| | rgba="0.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | </collision>
|
| | </link>
|
| | <link
|
| | name="left_hip_yaw_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.04923 0.0001 0.0072"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="2.244" />
|
| | <inertia
|
| | ixx="0.0025731"
|
| | ixy="9.159E-06"
|
| | ixz="-0.00051948"
|
| | iyy="0.0030444"
|
| | iyz="1.949E-06"
|
| | izz="0.0022883" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| |
|
| | <collision>
|
| | |
| | |
| | |
| | |
| | |
| |
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_hip_yaw"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0.0875 -0.1742"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="pelvis" />
|
| | <child
|
| | link="left_hip_yaw_link" />
|
| | <axis
|
| | xyz="0 0 1" />
|
| | <limit
|
| | lower="-0.43"
|
| | upper="0.43"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="left_hip_roll_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.0058 -0.00319 -9E-05"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="2.232" />
|
| | <inertia
|
| | ixx="0.0020603"
|
| | ixy="3.2115E-05"
|
| | ixz="2.878E-06"
|
| | iyy="0.0022482"
|
| | iyz="-7.813E-06"
|
| | izz="0.0024323" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0.01 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.1 0.12 0.1" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_hip_roll"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0.039468 0 0"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="left_hip_yaw_link" />
|
| | <child
|
| | link="left_hip_roll_link" />
|
| | <axis
|
| | xyz="1 0 0" />
|
| | <limit
|
| | lower="-0.43"
|
| | upper="0.43"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="left_hip_pitch_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.00746 -0.02346 -0.08193"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="4.152" />
|
| | <inertia
|
| | ixx="0.082618"
|
| | ixy="-0.00066654"
|
| | ixz="0.0040725"
|
| | iyy="0.081579"
|
| | iyz="0.0072024"
|
| | izz="0.0060081" />
|
| | </inertial>
|
| | <visual>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/left_hip_pitch_link.STL" />
|
| | </geometry>
|
| | <material
|
| | name="white">
|
| | <color
|
| | rgba="0.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0.03 0 -0.16"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.06 0.05 0.44" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_hip_pitch"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0.11536 0"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="left_hip_roll_link" />
|
| | <child
|
| | link="left_hip_pitch_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-1.57"
|
| | upper="1.57"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="left_knee_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.00136 -0.00512 -0.1384"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="1.721" />
|
| | <inertia
|
| | ixx="0.012205"
|
| | ixy="-6.8431E-05"
|
| | ixz="0.0010862"
|
| | iyy="0.012509"
|
| | iyz="0.00022549"
|
| | izz="0.0020629" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0.025 0 -0.18"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.05 0.05 0.36" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_knee"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 -0.4"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="left_hip_pitch_link" />
|
| | <child
|
| | link="left_knee_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-0.26"
|
| | upper="2.05"
|
| | effort="300"
|
| | velocity="14" />
|
| | </joint>
|
| | <link
|
| | name="left_ankle_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.048568 0 -0.045609"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.552448" />
|
| | <inertia
|
| | ixx="0.000156"
|
| | ixy="0"
|
| | ixz="0.000143"
|
| | iyy="0.003620"
|
| | iyz="0"
|
| | izz="0.003551" />
|
| | </inertial>
|
| | <visual>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/left_ankle_link_modified.STL" />
|
| | </geometry>
|
| | <material
|
| | name="white">
|
| | <color
|
| | rgba="0.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/left_ankle_link_modified.STL" />
|
| | </geometry>
|
| |
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_ankle"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 -0.4"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="left_knee_link" />
|
| | <child
|
| | link="left_ankle_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-0.87"
|
| | upper="0.52"
|
| | effort="40"
|
| | velocity="9" />
|
| | </joint>
|
| | <link
|
| | name="right_hip_yaw_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.04923 -0.0001 0.0072"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="2.244" />
|
| | <inertia
|
| | ixx="0.0025731"
|
| | ixy="-9.159E-06"
|
| | ixz="-0.00051948"
|
| | iyy="0.0030444"
|
| | iyz="-1.949E-06"
|
| | izz="0.0022883" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| |
|
| | <collision>
|
| | |
| | |
| | |
| | |
| | |
| |
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_hip_yaw"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 -0.0875 -0.1742"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="pelvis" />
|
| | <child
|
| | link="right_hip_yaw_link" />
|
| | <axis
|
| | xyz="0 0 1" />
|
| | <limit
|
| | lower="-0.43"
|
| | upper="0.43"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="right_hip_roll_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.0058 0.00319 -9E-05"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="2.232" />
|
| | <inertia
|
| | ixx="0.0020603"
|
| | ixy="-3.2115E-05"
|
| | ixz="2.878E-06"
|
| | iyy="0.0022482"
|
| | iyz="7.813E-06"
|
| | izz="0.0024323" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 -0.01 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.1 0.12 0.1" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_hip_roll"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0.039468 0 0"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="right_hip_yaw_link" />
|
| | <child
|
| | link="right_hip_roll_link" />
|
| | <axis
|
| | xyz="1 0 0" />
|
| | <limit
|
| | lower="-0.43"
|
| | upper="0.43"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="right_hip_pitch_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.00746 0.02346 -0.08193"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="4.152" />
|
| | <inertia
|
| | ixx="0.082618"
|
| | ixy="0.00066654"
|
| | ixz="0.0040725"
|
| | iyy="0.081579"
|
| | iyz="-0.0072024"
|
| | izz="0.0060081" />
|
| | </inertial>
|
| | <visual>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/right_hip_pitch_link.STL" />
|
| | </geometry>
|
| | <material
|
| | name="white">
|
| | <color
|
| | rgba="0.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0.03 0 -0.16"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.06 0.05 0.44" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_hip_pitch"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 -0.11536 0"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="right_hip_roll_link" />
|
| | <child
|
| | link="right_hip_pitch_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-1.57"
|
| | upper="1.57"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="right_knee_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="-0.00136 0.00512 -0.1384"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="1.721" />
|
| | <inertia
|
| | ixx="0.012205"
|
| | ixy="6.8431E-05"
|
| | ixz="0.0010862"
|
| | iyy="0.012509"
|
| | iyz="-0.00022549"
|
| | izz="0.0020629" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0.025 0 -0.18"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.05 0.05 0.36" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_knee"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 -0.4"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="right_hip_pitch_link" />
|
| | <child
|
| | link="right_knee_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-0.26"
|
| | upper="2.05"
|
| | effort="300"
|
| | velocity="14" />
|
| | </joint>
|
| | <link
|
| | name="right_ankle_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.048568 0 -0.045609"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.552448" />
|
| | <inertia
|
| | ixx="0.000156"
|
| | ixy="0"
|
| | ixz="0.000143"
|
| | iyy="0.003620"
|
| | iyz="0"
|
| | izz="0.003551" />
|
| | </inertial>
|
| | <visual>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/right_ankle_link_modified.STL" />
|
| | </geometry>
|
| | <material
|
| | name="white">
|
| | <color
|
| | rgba="0.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/right_ankle_link_modified.STL" />
|
| | </geometry>
|
| |
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_ankle"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 -0.4"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="right_knee_link" />
|
| | <child
|
| | link="right_ankle_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-0.87"
|
| | upper="0.52"
|
| | effort="40"
|
| | velocity="9" />
|
| | </joint>
|
| | <link
|
| | name="torso_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.000489 0.002797 0.20484"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="17.789" />
|
| | <inertia
|
| | ixx="0.4873"
|
| | ixy="-0.00053763"
|
| | ixz="0.0020276"
|
| | iyy="0.40963"
|
| | iyz="-0.00074582"
|
| | izz="0.12785" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 0.245"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box
|
| | size="0.14 0.2 0.45" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="torso"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="pelvis" />
|
| | <child
|
| | link="torso_link" />
|
| | <axis
|
| | xyz="0 0 1" />
|
| | <limit
|
| | lower="-2.35"
|
| | upper="2.35"
|
| | effort="200"
|
| | velocity="23" />
|
| | </joint>
|
| | <link
|
| | name="left_shoulder_pitch_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.005045 0.053657 -0.015715"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="1.033" />
|
| | <inertia
|
| | ixx="0.0012985"
|
| | ixy="-1.7333E-05"
|
| | ixz="8.683E-06"
|
| | iyy="0.00087279"
|
| | iyz="3.9656E-05"
|
| | izz="0.00097338" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | </link>
|
| | <joint
|
| | name="left_shoulder_pitch"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0.0055 0.15535 0.42999"
|
| | rpy="0.43633 0 0" />
|
| | <parent
|
| | link="torso_link" />
|
| | <child
|
| | link="left_shoulder_pitch_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-2.87"
|
| | upper="2.87"
|
| | effort="40"
|
| | velocity="9" />
|
| | </joint>
|
| | <link
|
| | name="left_shoulder_roll_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.000679 0.00115 -0.094076"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.793" />
|
| | <inertia
|
| | ixx="0.0015742"
|
| | ixy="2.298E-06"
|
| | ixz="-7.2265E-05"
|
| | iyy="0.0016973"
|
| | iyz="-6.3691E-05"
|
| | izz="0.0010183" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 -0.045"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.09 0.09 0.16" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_shoulder_roll"
|
| | type="revolute">
|
| | <origin
|
| | xyz="-0.0055 0.0565 -0.0165"
|
| | rpy="-0.43633 0 0" />
|
| | <parent
|
| | link="left_shoulder_pitch_link" />
|
| | <child
|
| | link="left_shoulder_roll_link" />
|
| | <axis
|
| | xyz="1 0 0" />
|
| | <limit
|
| | lower="-0.34"
|
| | upper="3.11"
|
| | effort="40"
|
| | velocity="9" />
|
| | </joint>
|
| | <link
|
| | name="left_shoulder_yaw_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.01365 0.002767 -0.16266"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.839" />
|
| | <inertia
|
| | ixx="0.003664"
|
| | ixy="-1.0671E-05"
|
| | ixz="0.00034733"
|
| | iyy="0.0040789"
|
| | iyz="7.0213E-05"
|
| | izz="0.00066383" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 -0.08"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.06 0.06 0.16" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_shoulder_yaw"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 -0.1343"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="left_shoulder_roll_link" />
|
| | <child
|
| | link="left_shoulder_yaw_link" />
|
| | <axis
|
| | xyz="0 0 1" />
|
| | <limit
|
| | lower="-1.3"
|
| | upper="4.45"
|
| | effort="18"
|
| | velocity="20" />
|
| | </joint>
|
| | <link
|
| | name="left_elbow_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.15908 -0.000144 -0.015776"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.669" />
|
| | <inertia
|
| | ixx="0.00042388"
|
| | ixy="-3.6086E-05"
|
| | ixz="0.00029293"
|
| | iyy="0.0060062"
|
| | iyz="4.664E-06"
|
| | izz="0.0060023" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0.18 0 -0.013"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.28 0.06 0.06" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="left_elbow"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0.0185 0 -0.198"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="left_shoulder_yaw_link" />
|
| | <child
|
| | link="left_elbow_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-1.25"
|
| | upper="2.61"
|
| | effort="18"
|
| | velocity="20" />
|
| | </joint>
|
| |
|
| |
|
| | <link name="left_wrist_pitch_link">
|
| | |
| | |
| | |
| | |
| |
|
| | <visual>
|
| | <geometry>
|
| | <sphere radius="0.0001"/>
|
| | </geometry>
|
| | </visual>
|
| | |
| | |
| | |
| | |
| |
|
| | </link>
|
| | <joint name="left_wrist_pitch" type="fixed">
|
| | <origin xyz="0.28 0 -0.02" rpy="0 0 0"/>
|
| | <parent link="left_elbow_link"/>
|
| | <child link="left_wrist_pitch_link"/>
|
| | <axis xyz="0 1 0"/>
|
| | <limit lower="-0.47" upper="0.47" effort="19" velocity="31.4"/>
|
| | </joint>
|
| |
|
| | <link
|
| | name="right_shoulder_pitch_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.005045 -0.053657 -0.015715"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="1.033" />
|
| | <inertia
|
| | ixx="0.0012985"
|
| | ixy="1.7333E-05"
|
| | ixz="8.683E-06"
|
| | iyy="0.00087279"
|
| | iyz="-3.9656E-05"
|
| | izz="0.00097338" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_shoulder_pitch"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0.0055 -0.15535 0.42999"
|
| | rpy="-0.43633 0 0" />
|
| | <parent
|
| | link="torso_link" />
|
| | <child
|
| | link="right_shoulder_pitch_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-2.87"
|
| | upper="2.87"
|
| | effort="40"
|
| | velocity="9" />
|
| | </joint>
|
| | <link
|
| | name="right_shoulder_roll_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.000679 -0.00115 -0.094076"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.793" />
|
| | <inertia
|
| | ixx="0.0015742"
|
| | ixy="-2.298E-06"
|
| | ixz="-7.2265E-05"
|
| | iyy="0.0016973"
|
| | iyz="6.3691E-05"
|
| | izz="0.0010183" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 -0.045"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.09 0.09 0.16" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_shoulder_roll"
|
| | type="revolute">
|
| | <origin
|
| | xyz="-0.0055 -0.0565 -0.0165"
|
| | rpy="0.43633 0 0" />
|
| | <parent
|
| | link="right_shoulder_pitch_link" />
|
| | <child
|
| | link="right_shoulder_roll_link" />
|
| | <axis
|
| | xyz="1 0 0" />
|
| | <limit
|
| | lower="-3.11"
|
| | upper="0.34"
|
| | effort="40"
|
| | velocity="9" />
|
| | </joint>
|
| | <link
|
| | name="right_shoulder_yaw_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.01365 -0.002767 -0.16266"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.839" />
|
| | <inertia
|
| | ixx="0.003664"
|
| | ixy="1.0671E-05"
|
| | ixz="0.00034733"
|
| | iyy="0.0040789"
|
| | iyz="-7.0213E-05"
|
| | izz="0.00066383" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0 0 -0.08"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.06 0.06 0.16" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_shoulder_yaw"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0 0 -0.1343"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="right_shoulder_roll_link" />
|
| | <child
|
| | link="right_shoulder_yaw_link" />
|
| | <axis
|
| | xyz="0 0 1" />
|
| | <limit
|
| | lower="-4.45"
|
| | upper="1.3"
|
| | effort="18"
|
| | velocity="20" />
|
| | </joint>
|
| | <link
|
| | name="right_elbow_link">
|
| | <inertial>
|
| | <origin
|
| | xyz="0.15908 0.000144 -0.015776"
|
| | rpy="0 0 0" />
|
| | <mass
|
| | value="0.669" />
|
| | <inertia
|
| | ixx="0.00042388"
|
| | ixy="3.6086E-05"
|
| | ixz="0.00029293"
|
| | iyy="0.0060062"
|
| | iyz="-4.664E-06"
|
| | izz="0.0060023" />
|
| | </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.1 0.1 0.1 1" />
|
| | </material>
|
| | </visual>
|
| | <collision>
|
| | <origin
|
| | xyz="0.18 0 -0.013"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <box size="0.28 0.06 0.06" />
|
| | </geometry>
|
| | </collision>
|
| | </link>
|
| | <joint
|
| | name="right_elbow"
|
| | type="revolute">
|
| | <origin
|
| | xyz="0.0185 0 -0.198"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="right_shoulder_yaw_link" />
|
| | <child
|
| | link="right_elbow_link" />
|
| | <axis
|
| | xyz="0 1 0" />
|
| | <limit
|
| | lower="-1.25"
|
| | upper="2.61"
|
| | effort="18"
|
| | velocity="20" />
|
| | </joint>
|
| |
|
| |
|
| | <link name="right_wrist_pitch_link">
|
| | |
| | |
| | |
| | |
| |
|
| | <visual>
|
| | <geometry>
|
| | <sphere radius="0.0001"/>
|
| | </geometry>
|
| | </visual>
|
| | |
| | |
| | |
| | |
| |
|
| | </link>
|
| | <joint name="right_wrist_pitch" type="fixed">
|
| | <origin xyz="0.28 0 -0.02" rpy="0 0 0"/>
|
| | <parent link="right_elbow_link"/>
|
| | <child link="right_wrist_pitch_link"/>
|
| | <axis xyz="0 1 0"/>
|
| | <limit lower="-0.47" upper="0.47" effort="19" velocity="31.4"/>
|
| | </joint>
|
| |
|
| | <link name="imu_link"></link>
|
| | <joint
|
| | name="imu"
|
| | type="fixed">
|
| | <origin
|
| | xyz="-0.04452 -0.01891 0.27756"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="torso_link" />
|
| | <child
|
| | link="imu_link" />
|
| | </joint>
|
| | <link
|
| | name="logo_link">
|
| | <visual>
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <geometry>
|
| | <mesh
|
| | filename="../meshes/logo_link.STL" />
|
| | </geometry>
|
| | <material
|
| | name="white">
|
| | <color
|
| | rgba="1 1 1 1" />
|
| | </material>
|
| | </visual>
|
| | </link>
|
| | <joint
|
| | name="logo"
|
| | type="fixed">
|
| | <origin
|
| | xyz="0 0 0"
|
| | rpy="0 0 0" />
|
| | <parent
|
| | link="torso_link" />
|
| | <child
|
| | link="logo_link" />
|
| | <axis
|
| | xyz="0 0 0" />
|
| | </joint>
|
| | </robot>
|
| |
|