~shadowrobot/sr-ros-interface/stable

« back to all changes in this revision

Viewing changes to shadow_robot/sr_hand/model/hand_urdf/thumb/thmiddle.urdf.xacro

  • Committer: Ugo Cupcic
  • Date: 2011-11-21 16:31:23 UTC
  • mfrom: (1.1.164 sr-ros-interface)
  • Revision ID: ugo@shadowrobot.com-20111121163123-k5q6e8l00w81f5hx
0.1.0

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
<robot xmlns:xacro="http://ros.org/wiki/xacro"
 
2
        xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
 
3
       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
 
4
       xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#slider"
 
5
       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
 
6
       xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
 
7
       xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom">
 
8
 
 
9
  <include filename="$(find sr_hand)/model/hand_urdf/thumb/thmiddle.transmission.xacro" />
 
10
 
 
11
  <xacro:macro name="thmiddle" params="parent">
 
12
 
 
13
    <link name="thmiddle">
 
14
      <inertial>
 
15
        <mass value="0.016" />
 
16
        <origin xyz="0 0 0" rpy="0 0 0"/>
 
17
        <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="0.0"  iyz="0.0"
 
18
        izz="0.0" />
 
19
      </inertial>
 
20
      <visual>
 
21
        <origin xyz="0 0 0" rpy="0 0 0" />
 
22
        <geometry name="thmiddle_visual">
 
23
        <mesh filename="package://sr_hand/model/meshes/TH2_z.mesh" scale="0.001 0.001 0.001" />
 
24
      </geometry>
 
25
      <material name="shadow_thmiddle_material">
 
26
          <color rgba="0.2 0.2 0.2 1.0"/>
 
27
        </material>
 
28
      </visual>
 
29
      <collision>
 
30
        <origin xyz="0 0 0.025" rpy="0 0 0 " />
 
31
        <geometry name="thmiddle_collision_geom">
 
32
          <box size="0.005 0.005 0.015" />
 
33
        </geometry>
 
34
      </collision>
 
35
    </link>
 
36
    <gazebo reference="thmiddle">
 
37
      <sensor:contact name="thmiddle_contact_sensor">
 
38
        <geom>thmiddle_geom</geom>
 
39
       <updateRate>100.0</updateRate>
 
40
        <controller:gazebo_ros_bumper name="thmiddle_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
 
41
          <alwaysOn>true</alwaysOn>
 
42
          <updateRate>100.0</updateRate>
 
43
          <frameName>thmiddle</frameName>
 
44
          <bumperTopicName>thmiddle_bumper</bumperTopicName>
 
45
          <interface:bumper name="thmiddle_gazebo_ros_bumper_iface" />
 
46
        </controller:gazebo_ros_bumper>
 
47
      </sensor:contact>
 
48
      <material>Gazebo/Grey</material>
 
49
    </gazebo>
 
50
 
 
51
    <joint name="THJ2" type="revolute">
 
52
      <parent link="${parent}"/>
 
53
      <child link="thmiddle"/>
 
54
      <origin xyz="0 0 0" rpy="0 0 0" />
 
55
      <axis xyz="0 -1 0" />
 
56
      <limit lower="-0.5237" upper="0.5237" effort="10"
 
57
      velocity="1.0" />
 
58
      <dynamics damping="50.5"/>
 
59
    </joint>
 
60
 
 
61
    <xacro:thmiddle_transmission />
 
62
 
 
63
  </xacro:macro>
 
64
 
 
65
</robot>