~shadowrobot/sr-ros-interface/trunk

« back to all changes in this revision

Viewing changes to sr_description/hand/xacro/thumb/thdistal_ellipsoid.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://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/thdistal.transmission.xacro" />
 
10
 
 
11
  <xacro:macro name="thdistal" params="parent">
 
12
 
 
13
    <link name="thdistal">
 
14
      <inertial>
 
15
        <mass value="0.016" />
 
16
        <origin xyz="0 0 0.01375" rpy="0 0 0"/>
 
17
        <inertia  ixx="0.1" ixy="0.0"  ixz="0.0"  iyy="0.1"  iyz="0.0"
 
18
                  izz="0.1" />
 
19
      </inertial>
 
20
      <visual>
 
21
        <origin xyz="0 0.002 0.0025" rpy="0 0 0" />
 
22
        <geometry name="thdistal_visual">
 
23
          <mesh filename="package://sr_hand/model/meshes/distal_ellipsoid.dae" 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.002 0.0025" rpy="0 0 0 " />
 
31
        <geometry name="thmiddle_collision_geom">
 
32
          <mesh filename="package://sr_hand/model/meshes/distal_ellipsoid.dae" scale="0.001 0.001 0.001" />
 
33
        </geometry>
 
34
      </collision>
 
35
    </link>
 
36
    <gazebo reference="thdistal">
 
37
      <sensor:contact name="thdistal_contact_sensor">
 
38
        <geom>thdistal_geom</geom>
 
39
        <updateRate>100.0</updateRate>
 
40
        <controller:gazebo_ros_bumper name="thdistal_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
 
41
          <alwaysOn>true</alwaysOn>
 
42
          <updateRate>100.0</updateRate>
 
43
          <frameName>thdistal</frameName>
 
44
          <bumperTopicName>thdistal_bumper</bumperTopicName>
 
45
          <interface:bumper name="thdistal_gazebo_ros_bumper_iface" />
 
46
        </controller:gazebo_ros_bumper>
 
47
      </sensor:contact>
 
48
      <mu1 value="500.0" />
 
49
      <mu2 value="500.0" />
 
50
      <kp  value="10000000.0" />
 
51
      <kd  value="1.0" />
 
52
 
 
53
      <material>Gazebo/Grey</material>
 
54
      <selfCollide>false</selfCollide>
 
55
    </gazebo>
 
56
 
 
57
    <joint name="THJ1" type="revolute">
 
58
      <parent link="${parent}"/>
 
59
      <child link="thdistal"/>
 
60
      <origin xyz="0 0 0.032" rpy="0 0 -1.570796327" />
 
61
      <axis xyz="1 0 0" />
 
62
      <limit lower="0" upper="1.571" effort="10"
 
63
             velocity="1.0" />
 
64
      <dynamics damping="50.5"/>
 
65
    </joint>
 
66
 
 
67
    <link name="thtip">
 
68
      <inertial>
 
69
        <mass value="0.001" />
 
70
        <inertia  ixx="0.0" ixy="0.0"  ixz="0.0"  iyy="0.0"  iyz="0.0" izz="0.0" />
 
71
      </inertial>
 
72
    </link>
 
73
    <joint name="thtip" type="fixed">
 
74
      <parent link="thdistal"/>
 
75
      <child link="thtip"/>
 
76
      <origin xyz="0 0 0.0275" rpy="0 0 0" />
 
77
    </joint>
 
78
 
 
79
 
 
80
    <xacro:thdistal_transmission />
 
81
 
 
82
  </xacro:macro>
 
83
 
 
84
</robot>