~shadowrobot/sr-ros-interface/trunk

« back to all changes in this revision

Viewing changes to sr_description/arm/xacro/trunk/shadowarm_trunk.urdf.xacro

  • Committer: Ugo Cupcic
  • Date: 2012-07-23 12:23:41 UTC
  • Revision ID: ugo@shadowrobot.com-20120723122341-vlkm85bisxyv2wsw
just moved all the models out of sr_hand into sr_description, not rewritten yet

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
 
 
2
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
3
 
 
4
  <include filename="$(find sr_description)/arm/xacro/trunk/shadowarm_trunk.transmission.xacro" />
 
5
 
 
6
  <xacro:macro name="shadowarm_trunk" params="parent">
 
7
 
 
8
    <link name="shadowarm_trunk">
 
9
        <inertial>
 
10
          <origin xyz="0 0 0.26525" rpy="0 0 0" />
 
11
          <mass value="10" />
 
12
          <inertia  ixx="1.47" ixy="0.0"  ixz="0.0"  iyy="1.47"  iyz="0.0"  izz="2.4" />
 
13
        </inertial>
 
14
        <visual>
 
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" />
 
18
          </geometry>
 
19
          <material name="Grey" />
 
20
        </visual>
 
21
        <collision>
 
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"/>
 
25
          </geometry>
 
26
        </collision>
 
27
      </link>
 
28
      <gazebo reference="shadowarm_trunk">
 
29
        <material>Gazebo/Grey</material>
 
30
        <selfCollide>true</selfCollide>
 
31
      </gazebo>
 
32
 
 
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" />
 
37
      <axis xyz="0 0 1" />
 
38
      <limit lower="-${M_PI/4}" upper="${M_PI/2}"
 
39
      effort="10" velocity="1.0"/>
 
40
      <dynamics damping="200.5"/>
 
41
    </joint>
 
42
 
 
43
    <xacro:shadowarm_trunk_transmission />
 
44
 
 
45
  </xacro:macro>
 
46
 
 
47
</robot>