modbus_test/urdf/sample.urdf

176 lines
4.5 KiB
XML

<?xml version="1.0"?>
<robot name="sample_robot">
<!-- Materials -->
<material name="grey">
<color rgba="0.0 0 0 1.0" />
</material>
<material name="red">
<color rgba="1.0 0.0 0.0 1.0" />
</material>
<material name="blue">
<color rgba="0 0.0 1.0 1.0" />
</material>
<material name="lightblue">
<color rgba="0.0 0.22 1.0 1.0" />
</material>
<material name="yellow">
<color rgba="0.96 0.76 0.13 1.0" />
</material>
<material name="orange">
<color rgba="1.0 0.5 0.0 1.0" />
</material>
<material name="black">
<color rgba="0.15 0.15 0.15 1.0" />
</material>
<!-- Links: main serial chain -->
<link name="base_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<mesh filename="../urdf_support/sample/1.stl" />
</geometry>
<material name="grey" />
</visual>
</link>
<link name="link_1">
<visual>
<origin rpy="0 0 0" xyz="0 0 0.23445" />
<geometry>
<mesh filename="../urdf_support/sample/2.stl" />
</geometry>
<material name="red" />
</visual>
</link>
<link name="link_2">
<visual>
<origin rpy="0 0 0" xyz="0.0 -0.103 0" />
<geometry>
<mesh filename="../urdf_support/sample/3.stl" />
</geometry>
<material name="blue" />
</visual>
</link>
<link name="link_3">
<visual>
<origin rpy="0 0 0" xyz="0 -0.103 0" />
<geometry>
<mesh filename="../urdf_support/sample/4.stl" />
</geometry>
<material name="lightblue" />
</visual>
</link>
<link name="link_4">
<visual>
<origin rpy="0 0 0" xyz="0.23345 0 0" />
<geometry>
<mesh filename="../urdf_support/sample/5.stl" />
</geometry>
<material name="yellow" />
</visual>
</link>
<link name="link_5">
<visual>
<origin rpy="0 0 0" xyz="0.02 0.04 0.0" />
<geometry>
<mesh filename="../urdf_support/sample/6.stl" />
</geometry>
<material name="orange" />
</visual>
</link>
<link name="link_6">
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0" />
<geometry>
<mesh filename="../urdf_support/sample/777.stl" />
</geometry>
<material name="black" />
</visual>
</link>
<link name="welding_gun_body">
<visual>
<geometry>
<mesh filename="../urdf_support/sample/7.stl" /> <!-- Замените на путь к вашему STL-файлу -->
</geometry>
<material name="metal" />
<origin xyz="0 0 0" rpy="0 0 0" />
</visual>
</link>
<!-- Joints: main serial chain -->
<joint name="joint_1" type="revolute">
<limit lower="-2.705" upper="2.705" effort="0" velocity="0" />
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="base_link" />
<child link="link_1" />
<axis xyz="0 0 1" />
</joint>
<joint name="joint_2" type="revolute">
<limit lower="-2.444" upper="1.135" effort="0" velocity="0" />
<parent link="link_1" />
<child link="link_2" />
<axis xyz="0 -1 0" />
<origin rpy="0 0 0" xyz="0.17045 0 0.4946" />
</joint>
<joint name="joint_3" type="revolute">
<limit lower="-1.309" upper="1.919" effort="0" velocity="0" />
<parent link="link_2" />
<child link="link_3" />
<axis xyz="0 -1 0" />
<origin rpy="0 0 0" xyz="0 -0.001963 0.729921" />
</joint>
<joint name="joint_4" type="revolute">
<limit lower="-3.142" upper="3.142" effort="0" velocity="0" />
<parent link="link_3" />
<child link="link_4" />
<axis xyz="1 0 0" />
<origin rpy="0 0 0" xyz="0 0 0.098277" />
</joint>
<joint name="joint_5" type="revolute">
<limit lower="-2.007" upper="2.007" effort="0" velocity="0" />
<parent link="link_4" />
<child link="link_5" />
<axis xyz="0 -1 0" />
<origin rpy="0 0 0" xyz="1.109039 0 0" />
</joint>
<joint name="joint_6" type="revolute">
<limit lower="-6.283" upper="6.283" effort="0" velocity="0" />
<parent link="link_5" />
<child link="link_6" />
<axis xyz="1 0 0" />
<origin rpy="0 0 0" xyz="0.117 0 0" />
</joint>
<joint name="welding_gun_fixed_joint" type="fixed">
<parent link="link_6" />
<child link="welding_gun_body" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<link name="tcp">
<visual>
<geometry>
<box size="0.05 0.05 0.05" />
</geometry>
<material name="red" />
</visual>
</link>
<joint name="tcp_joint" type="fixed">
<parent link="welding_gun_body" />
<child link="tcp" />
<origin xyz="0.353774 0.009203 -0.033794" rpy="110.766 1.620 -89.636" />
</joint>
</robot>