286 lines
8.1 KiB
XML
Executable File
286 lines
8.1 KiB
XML
Executable File
<?xml version="1.0"?>
|
|
|
|
<robot name="g1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
<xacro:arg name="DEBUG" default="false"/>
|
|
|
|
<xacro:include filename="$(find g1_description)/xacro/gazebo.xacro"/>
|
|
<xacro:include filename="$(find g1_description)/xacro/const.xacro"/>
|
|
<xacro:include filename="$(find g1_description)/xacro/leg.xacro"/>
|
|
<xacro:include filename="$(find g1_description)/xacro/arm.xacro"/>
|
|
<!-- Rotor related joint and link is only for demonstrate location. -->
|
|
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
|
|
|
|
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
|
|
<xacro:if value="$(arg DEBUG)">
|
|
<link name="world"/>
|
|
<joint name="base_static_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0.5"/>
|
|
<parent link="world"/>
|
|
<child link="pelvis"/>
|
|
</joint>
|
|
</xacro:if>
|
|
|
|
<!-- Torso -->
|
|
<link name="torso_link">
|
|
<inertial>
|
|
<origin xyz="${torso_link_com_x} ${torso_link_com_y} ${torso_link_com_z}" rpy="0 0 0"/>
|
|
<mass value="${torso_link_mass}"/>
|
|
<inertia
|
|
ixx="${torso_link_ixx}" ixy="${torso_link_ixy}" ixz="${torso_link_ixz}"
|
|
iyy="${torso_link_iyy}" iyz="${torso_link_iyz}"
|
|
izz="${torso_link_izz}"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://g1_description/meshes/torso_link.STL"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="0.7 0.7 0.7 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0.055 0.055 -0.020" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="0.055 -0.055 -0.020" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.055 0.055 -0.020" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.055 -0.055 -0.020" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
<collision>
|
|
<origin xyz="0.063 0.088 0.065" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="0.063 -0.088 0.065" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.063 0.088 0.065" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.063 -0.088 0.065" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
<collision>
|
|
<origin xyz="0.063 0.088 0.30" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="0.063 -0.088 0.30" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.066 0.088 0.30" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.066 -0.088 0.30" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<joint name="torso_joint" type="revolute">
|
|
<origin xyz="${torso_joint_offset_x} ${torso_joint_offset_y} ${torso_joint_offset_z}" rpy="0 0 0"/>
|
|
<parent link="pelvis"/>
|
|
<child link="torso_link"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit lower="${torso_joint_position_min}" upper="${torso_joint_position_max}" effort="${torso_joint_torque_max}" velocity="${torso_joint_velocity_max}"/>
|
|
</joint>
|
|
|
|
<link name="pelvis">
|
|
<inertial>
|
|
<origin xyz="0 0 -0.07605" rpy="0 0 0"/>
|
|
<mass value="2.86"/>
|
|
<inertia ixx="0.0079143" ixy="0" ixz="1.6E-06" iyy="0.0069837" iyz="0" izz="0.0059404"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://g1_description/meshes/pelvis.STL"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="0.7 0.7 0.7 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0.050 0.060 -0.060" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="0.050 -0.060 -0.060" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.050 0.060 -0.060" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.050 -0.060 -0.060" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
|
|
|
|
<collision>
|
|
<origin xyz="0.050 0.060 -0.135" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="0.050 -0.060 -0.135" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.050 0.060 -0.135" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.050 -0.060 -0.135" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="pelvis_contour_link">
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://g1_description/meshes/pelvis_contour_link.STL"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="0.2 0.2 0.2 1"/>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
<joint name="pelvis_contour_joint" type="fixed">
|
|
<parent link="pelvis"/>
|
|
<child link="pelvis_contour_link"/>
|
|
</joint>
|
|
|
|
|
|
<!-- Head -->
|
|
<link name="head_link">
|
|
<inertial>
|
|
<origin xyz="0.00138066852 0.00028430950 0.42034187824" rpy="0 0 0"/>
|
|
<mass value="1.17976522"/>
|
|
<inertia ixx="0.00543236042361" ixy="0.00000140137425" ixz="0.00034554752228" iyy="0.00552885306699" iyz="0.00001501216392" izz="0.00165378108136"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://g1_description/meshes/head_link.STL"/>
|
|
</geometry>
|
|
<material name="">
|
|
<color rgba="0.2 0.2 0.2 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0.055 0.055 0.48" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="0.055 -0.055 0.48" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.055 0.040 0.48" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin xyz="-0.055 -0.040 0.48" rpy="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
|
|
<joint name="head_joint" type="fixed">
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<parent link="torso_link"/>
|
|
<child link="head_link"/>
|
|
</joint>
|
|
|
|
<!-- IMU -->
|
|
<link name="imu_link"></link>
|
|
|
|
<joint name="imu_joint" type="fixed">
|
|
<origin xyz="-0.04233868314 0.00166 0.152067" rpy="0 0 0"/>
|
|
<parent link="torso_link"/>
|
|
<child link="imu_link"/>
|
|
</joint>
|
|
|
|
|
|
<xacro:leg name="left" mirror="1"/>
|
|
<xacro:leg name="right" mirror="-1"/>
|
|
<xacro:arm name="left" mirror="1"/>
|
|
<xacro:arm name="right" mirror="-1"/>
|
|
|
|
<transmission name="torso_tran">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="torso_joint">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="torso_motor">
|
|
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
</robot>
|