~shadowrobot/sr-ros-interface/trunk

« back to all changes in this revision

Viewing changes to sr_description/arm/xacro/lower_arm/shadowarm_lowerarm.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
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
2
 
 
3
  <include filename="$(find sr_description)/arm/xacro/lower_arm/shadowarm_lowerarm.transmission.xacro" />
 
4
 
 
5
  <xacro:macro name="shadowarm_lowerarm" params="parent">
 
6
 
 
7
    <link name="shadowarm_lowerarm">
 
8
        <inertial>
 
9
          <origin xyz="0.08 0 0.0625" rpy="0 0 0" />
 
10
          <mass value="1.7" />
 
11
          <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="0.0"  iyz="0.0"  izz="0.0" />
 
12
        </inertial>
 
13
        <visual>
 
14
          <origin xyz="0.03 0 0.036" rpy="0 0 0"/>
 
15
          <geometry name="shadowarm_lowerarm_visual">
 
16
            <mesh filename="package://sr_description/arm/model/elbow_flex.dae" scale="0.001 0.001 0.001" />
 
17
          </geometry>
 
18
          <material name="Grey" />
 
19
        </visual>
 
20
        <collision>
 
21
          <origin xyz="0.08 0 0.0625" rpy="0 0 0"/>
 
22
          <geometry name="shadowarm_lowerarm_collision">
 
23
            <box size="0.03 0.03 0.10"/>
 
24
          </geometry>
 
25
        </collision>
 
26
    </link>
 
27
    <gazebo reference="shadowarm_lowerarm">
 
28
        <material>Gazebo/Grey</material>
 
29
        <selfCollide>true</selfCollide>
 
30
    </gazebo>
 
31
 
 
32
    <joint name="ElbowJSwing" type="revolute">
 
33
      <parent link="${parent}"/>
 
34
      <child link="shadowarm_lowerarm"/>
 
35
      <origin xyz="0 0 0.369" rpy="0 0 0" />
 
36
      <axis xyz="0 -1 0" />
 
37
      <limit lower="0.52" upper="2.09439510239"
 
38
      effort="10" velocity="1.0"/>
 
39
      <dynamics damping="50.5"/>
 
40
    </joint>
 
41
 
 
42
    <xacro:shadowarm_lowerarm_transmission />
 
43
 
 
44
  </xacro:macro>
 
45
 
 
46
</robot>