85 lines
3.2 KiB
XML
85 lines
3.2 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
<xacro:property name="arm_base_length" value="0.1"/>
|
|
<xacro:property name="arm_base_width" value="0.1"/>
|
|
<xacro:property name="arm_base_height" value="0.02"/>
|
|
|
|
<xacro:property name="arm_radius" value="0.02"/>
|
|
<xacro:property name="arm_forearm_length" value="0.3"/>
|
|
<xacro:property name="arm_hand_length" value="0.3"/>
|
|
|
|
<link name="arm_base_link">
|
|
<visual>
|
|
<geometry>
|
|
<box size="${arm_base_length} ${arm_base_width} ${arm_base_height}"/>
|
|
</geometry>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<material name="orange"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<box size="${arm_base_length} ${arm_base_width} ${arm_base_height}"/>
|
|
</geometry>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
</collision>
|
|
<xacro:box_inertia m="0.5" l="${arm_base_length}" w="${arm_base_width}" h="${arm_base_height}"
|
|
xyz="0 0 0" rpy="0 0 0"/>
|
|
</link>
|
|
|
|
<link name="forearm_link">
|
|
<visual>
|
|
<geometry>
|
|
<cylinder radius="${arm_radius}" length="${arm_forearm_length}"/>
|
|
</geometry>
|
|
<origin xyz="0 0 ${arm_forearm_length/2}" rpy="0 0 0"/>
|
|
<material name="yellow"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<cylinder radius="${arm_radius}" length="${arm_forearm_length}"/>
|
|
</geometry>
|
|
<origin xyz="0 0 ${arm_forearm_length/2}" rpy="0 0 0"/>
|
|
</collision>
|
|
<xacro:cylinder_inertia m="0.3" r="${arm_radius}" h="${arm_forearm_length}"
|
|
xyz="0 0 ${arm_forearm_length/2}" rpy="0 0 0"/>
|
|
</link>
|
|
|
|
|
|
<link name="hand_link">
|
|
<visual>
|
|
<geometry>
|
|
<cylinder radius="${arm_radius}" length="${arm_hand_length}"/>
|
|
</geometry>
|
|
<origin xyz="0 0 ${arm_hand_length/2}" rpy="0 0 0"/>
|
|
<material name="orange"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<cylinder radius="${arm_radius}" length="${arm_hand_length}"/>
|
|
</geometry>
|
|
<origin xyz="0 0 ${arm_hand_length/2}" rpy="0 0 0"/>
|
|
</collision>
|
|
<xacro:cylinder_inertia m="0.3" r="${arm_radius}" h="${arm_hand_length}"
|
|
xyz="0 0 ${arm_hand_length/2}" rpy="0 0 0"/>
|
|
</link>
|
|
|
|
<joint name="arm_base_forearm_joint" type="revolute">
|
|
<parent link="arm_base_link" />
|
|
<child link="forearm_link" />
|
|
<origin xyz="0 0 ${arm_base_height/2}" rpy="0 0 0" />
|
|
<axis xyz="0 1 0"/>
|
|
<limit lower="0" upper="${pi/2}" velocity="100" effort="100" />
|
|
<dynamics friction="0.05" damping="0.1" />
|
|
</joint>
|
|
|
|
<joint name="forearm_hand_joint" type="revolute">
|
|
<parent link="forearm_link" />
|
|
<child link="hand_link" />
|
|
<origin xyz="0 0 ${arm_hand_length}" rpy="0 0 0" />
|
|
<axis xyz="0 1 0"/>
|
|
<limit lower="0" upper="${pi/2}" velocity="100" effort="100" />
|
|
<dynamics friction="0.05" damping="0.1" />
|
|
</joint>
|
|
|
|
</robot> |