2
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
4
<include filename="$(find sr_description)/arm/xacro/trunk/shadowarm_trunk.transmission.xacro" />
6
<xacro:macro name="shadowarm_trunk" params="parent">
8
<link name="shadowarm_trunk">
10
<origin xyz="0 0 0.26525" rpy="0 0 0" />
12
<inertia ixx="1.47" ixy="0.0" ixz="0.0" iyy="1.47" iyz="0.0" izz="2.4" />
15
<origin xyz="0 0 0.005" rpy="0 0 0" />
16
<geometry name="shadowarm_trunk_visual">
17
<mesh filename="package://sr_description/arm/model/arm_trunk.dae" scale="0.001 0.001 0.001" />
19
<material name="Grey" />
22
<origin xyz="0 0 0.26525" rpy="0 0 0"/>
23
<geometry name="shadowarm_trunk_collision">
24
<box size="0.03 0.03 0.52"/>
28
<gazebo reference="shadowarm_trunk">
29
<material>Gazebo/Grey</material>
30
<selfCollide>true</selfCollide>
33
<joint name="ShoulderJRotate" type="revolute">
34
<parent link="${parent}"/>
35
<child link="shadowarm_trunk"/>
36
<origin xyz="0 0 0.01" rpy="0.0 0.0 0.0" />
38
<limit lower="-${M_PI/4}" upper="${M_PI/2}"
39
effort="10" velocity="1.0"/>
40
<dynamics damping="200.5"/>
43
<xacro:shadowarm_trunk_transmission />