Project

General

Profile

Statistics
| Branch: | Revision:

robobuggy / buggygazebo / tricycle / model.xml @ 4421bfa5

History | View | Annotate | Download (2.21 KB)

1
<?xml version='1.0'?>
2
<sdf version='1.4'>
3
  <model name="buggytry1">
4
    <static>true</static>
5
    <link name='chassis'>
6
      <pose>0 0 .1 0 0 0</pose>
7
      <collision name='collision'>
8
        <geometry>
9
          <box>
10
            <size>.4 .2 .1</size>
11
          </box>
12
        </geometry>
13
      </collision>
14
      
15
      <visual name='visual'>
16
        <geometry>
17
          <box>
18
            <size>.4 .2 .1</size>
19
          </box>
20
        </geometry>
21
      </visual>
22
      
23
      <collision name='caster_collision'>
24
        <pose>-0.15 0 -0.05 0 0 0</pose>
25
        <geometry>
26
          <sphere>
27
            <radius>.05</radius>
28
          </sphere>
29
        </geometry>
30
        
31
        <surface>
32
          <friction>
33
            <ode>
34
              <mu>0</mu>
35
              <mu2>0</mu2>
36
              <slip1>1.0</slip1>
37
              <slip2>1.0</slip2>
38
            </ode>
39
          </friction>
40
        </surface>
41
      </collision>
42
      
43
      <visual name='caster_visual'>
44
        <pose>-0.15 0 -0.05 0 0 0</pose>
45
        <geometry>
46
          <sphere>
47
            <radius>.05</radius>
48
          </sphere>
49
        </geometry>
50
      </visual>
51
    </link>     
52
    
53
    <link name="left_wheel">
54
      <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
55
      <collision name="collision">
56
        <geometry>
57
          <cylinder>
58
            <radius>.1</radius>
59
            <length>.05</length>
60
          </cylinder>
61
        </geometry>
62
      </collision>
63
      <visual name="visual">
64
        <geometry>
65
          <cylinder>
66
            <radius>.1</radius>
67
            <length>.05</length>
68
          </cylinder>
69
        </geometry>
70
      </visual>
71
    </link>
72
    
73
    <link name="right_wheel">
74
      <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
75
      <collision name="collision">
76
        <geometry>
77
          <cylinder>
78
            <radius>.1</radius>
79
            <length>.05</length>
80
          </cylinder>
81
        </geometry>
82
      </collision>
83
      <visual name="visual">
84
        <geometry>
85
          <cylinder>
86
            <radius>.1</radius>
87
            <length>.05</length>
88
          </cylinder>
89
        </geometry>
90
      </visual>
91
    </link>
92
    
93
    <joint type="revolute" name="left_wheel_hinge">
94
      <pose>0 0 -0.03 0 0 0</pose>
95
      <child>left_wheel</child>
96
      <parent>chassis</parent>
97
      <axis>
98
        <xyz>0 1 0</xyz>
99
      </axis>
100
    </joint>
101
    
102
    <joint type="revolute" name="right_wheel_hinge">
103
      <pose>0 0 0.03 0 0 0</pose>
104
      <child>right_wheel</child>
105
      <parent>chassis</parent>
106
      <axis>
107
        <xyz>0 1 0</xyz>
108
      </axis>
109
    </joint>
110
  </model>
111
</sdf>