soft-robot/soft_arm_sim/urdf/soft_arm.urdf.xacro

57 lines
2.1 KiB
Plaintext
Raw Normal View History

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="soft_arm">
<xacro:property name="disk_radius" value="0.04" />
<xacro:property name="disk_height" value="0.005" />
<!-- Base Link -->
<link name="base_link">
<visual>
<geometry>
<box size="0.1 0.1 0.02"/>
</geometry>
<material name="grey">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</visual>
</link>
<!-- Macro for a Disk -->
<xacro:macro name="pcc_disk" params="name parent color">
<link name="${name}">
<visual>
<geometry>
<cylinder radius="${disk_radius}" length="${disk_height}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="${color}_mat">
<color rgba="${color} 1"/>
</material>
</visual>
</link>
<!-- !!!核心修改在这里!!! -->
<!-- 必须添加 Joint否则 robot_state_publisher 会崩溃 -->
<!-- type="floating" 表示这个关节是浮动的,位置由外部 TF 决定 -->
<joint name="${name}_joint" type="floating">
<parent link="${parent}"/>
<child link="${name}"/>
</joint>
</xacro:macro>
<!-- Section 1 -->
<xacro:pcc_disk name="sec1_disk1" parent="base_link" color="1 0 0"/>
<xacro:pcc_disk name="sec1_disk2" parent="base_link" color="1 0 0"/>
<xacro:pcc_disk name="sec1_disk3" parent="base_link" color="1 0 0"/>
<!-- Section 2 -->
<xacro:pcc_disk name="sec2_disk1" parent="base_link" color="0 1 0"/>
<xacro:pcc_disk name="sec2_disk2" parent="base_link" color="0 1 0"/>
<xacro:pcc_disk name="sec2_disk3" parent="base_link" color="0 1 0"/>
<!-- Section 3 -->
<xacro:pcc_disk name="sec3_disk1" parent="base_link" color="0 0 1"/>
<xacro:pcc_disk name="sec3_disk2" parent="base_link" color="0 0 1"/>
<xacro:pcc_disk name="sec3_disk3" parent="base_link" color="0 0 1"/>
</robot>