91 lines
2.7 KiB
XML
91 lines
2.7 KiB
XML
<?xml version="1.0"?>
|
|
|
|
<robot name="lite3" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
<xacro:include filename="$(find lite3_description)/xacro/const.xacro"/>
|
|
<xacro:include filename="$(find lite3_description)/xacro/leg.xacro"/>
|
|
|
|
<xacro:arg name="GAZEBO" default="false"/>
|
|
<xacro:arg name="CLASSIC" default="false"/>
|
|
|
|
|
|
<xacro:if value="$(arg GAZEBO)">
|
|
<xacro:if value="$(arg CLASSIC)">
|
|
<xacro:include filename="$(find lite3_description)/xacro/gazebo_classic.xacro"/>
|
|
</xacro:if>
|
|
<xacro:unless value="$(arg CLASSIC)">
|
|
<xacro:include filename="$(find lite3_description)/xacro/gazebo.xacro"/>
|
|
</xacro:unless>
|
|
</xacro:if>
|
|
<xacro:unless value="$(arg GAZEBO)">
|
|
<xacro:include filename="$(find lite3_description)/xacro/ros2_control.xacro"/>
|
|
</xacro:unless>
|
|
|
|
<link name="base">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</visual>
|
|
</link>
|
|
|
|
<joint name="floating_base" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="base"/>
|
|
<child link="TORSO"/>
|
|
</joint>
|
|
|
|
<link name="TORSO">
|
|
<visual>
|
|
<origin rpy="0 0 3.1416" xyz="0.0 0.0 0.0"/>
|
|
<geometry>
|
|
<mesh filename="file://$(find lite3_description)/meshes/Lite3.dae"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<box size="0.35 0.184 0.08"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin xyz="0.004098 -0.000663 -0.002069"/>
|
|
<mass value="4.130"/>
|
|
<inertia ixx="0.016982120" ixy="2.1294E-05" ixz="6.0763E-05" iyy="0.030466501" iyz="1.7968E-05"
|
|
izz="0.042609956"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="imu_joint" type="fixed">
|
|
<parent link="TORSO"/>
|
|
<child link="imu_link"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</joint>
|
|
|
|
<link name="imu_link">
|
|
<inertial>
|
|
<mass value="0.001"/>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size=".001 .001 .001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
<xacro:leg name="FR" mirror="-1" mirror_dae="False" front_hind="1" front_hind_dae="True"/>
|
|
<xacro:leg name="FL" mirror="1" mirror_dae="True" front_hind="1" front_hind_dae="True"/>
|
|
<xacro:leg name="HR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False"/>
|
|
<xacro:leg name="HL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False"/>
|
|
|
|
</robot>
|