quadruped_ros2_control/descriptions/unitree/aliengo_description/xacro/robot.xacro

112 lines
3.3 KiB
Plaintext
Raw Normal View History

2024-09-26 20:24:03 +08:00
<?xml version="1.0"?>
<robot name="aliengo" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:arg name="DEBUG" default="false"/>
2024-10-10 22:44:32 +08:00
<xacro:arg name="GAZEBO" default="false"/>
<xacro:arg name="CLASSIC" default="false"/>
2024-09-26 20:24:03 +08:00
<xacro:include filename="$(find aliengo_description)/xacro/const.xacro"/>
<xacro:include filename="$(find aliengo_description)/xacro/materials.xacro"/>
<xacro:include filename="$(find aliengo_description)/xacro/leg.xacro"/>
2024-10-10 22:44:32 +08:00
<xacro:if value="$(arg GAZEBO)">
<xacro:if value="$(arg CLASSIC)">
<xacro:include filename="$(find aliengo_description)/xacro/gazebo_classic.xacro"/>
</xacro:if>
<xacro:unless value="$(arg CLASSIC)">
<xacro:include filename="$(find aliengo_description)/xacro/gazebo.xacro"/>
</xacro:unless>
2024-10-10 22:44:32 +08:00
</xacro:if>
<xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find aliengo_description)/xacro/ros2_control.xacro"/>
2024-10-10 22:44:32 +08:00
</xacro:unless>
2024-09-26 20:24:03 +08:00
<!-- 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"/>
<parent link="world"/>
<child link="base"/>
</joint>
</xacro:if>
<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="trunk"/>
</joint>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file://$(find aliengo_description)/meshes/trunk.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="${trunk_length} ${trunk_width} ${trunk_height}"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="${trunk_com_x} ${trunk_com_y} ${trunk_com_z}"/>
<mass value="${trunk_mass}"/>
<inertia
ixx="${trunk_ixx}" ixy="${trunk_ixy}" ixz="${trunk_ixz}"
iyy="${trunk_iyy}" iyz="${trunk_iyz}"
izz="${trunk_izz}"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="trunk"/>
<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>
<material name="red"/>
</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="RR" mirror="-1" mirror_dae="False" front_hind="-1" front_hind_dae="False"/>
<xacro:leg name="RL" mirror="1" mirror_dae="True" front_hind="-1" front_hind_dae="False"/>
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
</robot>