~shadowrobot/sr-ros-interface/Feature_update_controller_params

« back to all changes in this revision

Viewing changes to sr_hand/model/hand_urdf/finger/proximal/proximal.urdf.xacro

  • Committer: Ugo Cupcic
  • Date: 2012-07-23 12:23:16 UTC
  • Revision ID: ugo@shadowrobot.com-20120723122316-6i0bxukylymyg4xi
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/finger/proximal/proximal.transmission.xacro" />
10
 
 
11
 
  <xacro:macro name="proximal" params="link_prefix joint_prefix parent">
12
 
 
13
 
    <link name="${link_prefix}proximal">
14
 
      <inertial>
15
 
        <mass value="0.014" />
16
 
        <origin xyz="0 0 0.0225" />
17
 
        <inertia  ixx="0.1" ixy="0.0"  ixz="0.0"  iyy="0.1"  iyz="0.0"
18
 
        izz="0.0" />
19
 
      </inertial>
20
 
      <visual>
21
 
        <origin xyz="0 0 0" rpy="0 0 0" />
22
 
        <geometry name="proximal_visual">
23
 
      <mesh filename="package://sr_hand/model/meshes/F3.dae" scale="0.001 0.001 0.001" />
24
 
      </geometry>
25
 
      <material name="Grey" />
26
 
      </visual>
27
 
      <collision>
28
 
        <origin xyz="0 0 0.025" rpy="0 0 0 " />
29
 
        <geometry name="proximal_collision_geom">
30
 
          <box size="0.008 0.008 0.04" />
31
 
        </geometry>
32
 
      </collision>
33
 
    </link>
34
 
    <gazebo reference="${link_prefix}proximal">
35
 
      <sensor:contact name="${link_prefix}proximal_contact_sensor">
36
 
        <geom>${link_prefix}proximal_geom</geom>
37
 
       <updateRate>100.0</updateRate>
38
 
        <controller:gazebo_ros_bumper name="${link_prefix}proximal_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
39
 
          <alwaysOn>true</alwaysOn>
40
 
          <updateRate>100.0</updateRate>
41
 
          <frameName>${link_prefix}proximal</frameName>
42
 
          <bumperTopicName>${link_prefix}proximal_bumper</bumperTopicName>
43
 
          <interface:bumper name="${link_prefix}proximal_gazebo_ros_bumper_iface" />
44
 
        </controller:gazebo_ros_bumper>
45
 
      </sensor:contact>
46
 
      <material>Gazebo/Grey</material>
47
 
    </gazebo>
48
 
 
49
 
    <joint name="${joint_prefix}J3" type="revolute">
50
 
      <parent link="${parent}"/>
51
 
      <child link="${link_prefix}proximal"/>
52
 
      <origin xyz="0 0 0" rpy="0 0 0" />
53
 
      <axis xyz="1 0 0" />
54
 
      <limit lower="0" upper="${M_PI/2}" effort="10"
55
 
      velocity="1.0"/>
56
 
      <dynamics damping="50.5"/>
57
 
    </joint>
58
 
 
59
 
    <xacro:proximal_transmission />
60
 
 
61
 
  </xacro:macro>
62
 
 
63
 
</robot>