File: model.xml

package info (click to toggle)
mujoco 2.2.2-3.2
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 39,796 kB
  • sloc: ansic: 28,947; cpp: 28,897; cs: 14,241; python: 10,465; xml: 5,104; sh: 93; makefile: 34
file content (150 lines) | stat: -rw-r--r-- 5,666 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
<mujoco>
  <option iterations="10" tolerance="0" gravity="-1 0 -10" jacobian="dense">
    <flag fwdinv="enable" energy="enable"/>
  </option>

  <asset>
    <mesh name="icosahedron" scale=".05 .05 .05"
          vertex="0         1       1.618
                  0        -1       1.618
                  0         1      -1.618
                  0        -1      -1.618
                  1         1.618   0
                 -1         1.618   0
                  1        -1.618   0
                 -1        -1.618   0
                  1.618     0       1
                  1.618     0      -1
                 -1.618     0       1
                 -1.618     0      -1"/>
    <hfield name="hfield" nrow="3" ncol="3" size=".2 .2 .1 .03"/>
  </asset>

  <default>
    <site rgba=".5 .5 .5 .5"/>
    <joint armature="1" damping="10"/>
    <general ctrllimited="true" ctrlrange="-1 1"/>
    <default class="hip0">
      <joint springref="30" stiffness="60"/>
    </default>
    <default class="hip1">
      <joint limited="true" range="-60 60" stiffness="10"/>
    </default>
    <default class="wheel">
      <joint damping=".1" armature=".1"/>
    </default>
  </default>

  <worldbody>
    <light pos="0 0 3"/>
    <geom type="plane" size="4 4 .1"/>
    <geom type="hfield" hfield="hfield" pos="-.4 .6 .05" rgba="0 0 1 1"/>
    <body name="head" pos="0 0 .7">
      <geom type="ellipsoid" size=".2 .2 .4" rgba="1 1 0 1" density="100"/>
      <site name="head" pos="0 0 .4" size=".1 .1 .05" type="box"/>
      <site name="anchor0" pos="0 .2 0"/>
      <site name="rf" pos="0 0 -0.41" zaxis="0 0 -1"/>
      <freejoint/>
      <body euler="0 0 0" pos=".2 0 -.2">
        <joint name="hipz_0" class="hip1" axis="0 0 1"/>
        <joint name="hipy_0" class="hip0" axis="0 1 0"/>
        <geom type="capsule" size=".05" rgba="1 0 0 1" fromto="0 0 0 .3 0 0"/>
        <body pos=".3 0 0">
          <site name="knee"/>
          <geom type="capsule" size=".05" rgba="1 0 0 1" fromto="0 0 0 .1 0 -.3"/>
          <body pos=".1 0 -.3">
            <joint name="wheel_0" type="ball" class="wheel"/>
            <site name="wheel_0" type="box" size=".1 .1 .1"/>
            <geom size=".1 .2 .1"  rgba="0 1 0 1" type="ellipsoid"/>
          </body>
        </body>
      </body>
      <body euler="0 0 120" pos="-.15 .2 -.2">
        <joint name="hipz_1" class="hip1" axis="0 0 1"/>
        <joint name="hipy_1" class="hip0" axis="0 1 0"/>
        <geom type="box" size=".05" rgba="1 0 0 1" fromto="0 0 0 .3 0 0"/>
        <geom type="box" size=".05" rgba="1 0 0 1" fromto=".3 0 0 .4 0 -.3"/>
        <body pos=".45 0 -.3">
          <joint name="wheel_1" axis="1 0 0" class="wheel"/>
          <geom size=".1"  rgba="0 1 0 1" type="cylinder" fromto="0 0 0 .03 0 0"/>
          <site name="wheel_1" type="box" size=".02 .11 .11" pos=".015 0 0"/>
        </body>
      </body>
      <body euler="0 0 240" pos="-.15 -.2 -.2">
        <joint name="hipz_2" class="hip1" axis="0 0 1"/>
        <joint name="hipy_2" class="hip0" axis="0 1 0"/>
        <geom type="capsule" size=".05" rgba="1 0 0 1" fromto="0 0 0 .3 0 0"/>
        <geom type="capsule" size=".05" rgba="1 0 0 1" fromto=".3 0 0 .4 0 -.3"/>
        <body pos=".45 0 -.3">
          <joint name="wheel_2" axis="1 0 0" class="wheel"/>
          <geom size=".1"  rgba="0 1 0 1" type="cylinder" fromto="0 0 0 .03 0 0"/>
          <site name="wheel_2" size=".13"  rgba="0 0 0 0.1" type="cylinder" fromto="-.01 0 0 .04 0 0"/>
        </body>
      </body>
    </body>
    <body pos="-.33 0 1">
      <joint name="slider" type="slide" axis="0 0 1" limited="true" range="-.2 .5"/>
      <joint type="hinge" axis="0 1 0"/>
      <geom type="mesh" mesh="icosahedron" size=".1" rgba="0 0 1 1"/>
    </body>
    <body name="cylinder" pos="-.5 .3 .7">
      <freejoint/>
      <geom name="wrapping" type="cylinder" size=".04" fromto="-.1 -.2 0 .1 .4 0"/>
      <site name="cylinder"/>
    </body>
    <site name="sidesite" pos="-.5 .4 1"/>
    <body pos="-.3 .6 .8">
      <freejoint/>
      <geom type="box" size=".05 .05 .05" rgba="0 0 1 1"/>
      <site name="anchor1" pos=".05 .05 .05"/>
    </body>
    <body pos="-.6 .4 .8">
      <freejoint/>
      <geom type="box" size=".05 .05 .05" rgba="0 0 1 1"/>
      <site name="anchor2" pos=".05 .05 .05"/>
    </body>
  </worldbody>

  <equality>
    <weld body1="cylinder" body2="world"/>
  </equality>

  <tendon>
    <spatial name="spatial" limited="true" range="0 .7" rgba="1 0 1 1">
      <site site="anchor0"/>
      <site site="anchor1"/>
      <geom geom="wrapping" sidesite="sidesite"/>
      <site site="anchor2"/>
    </spatial>
    <fixed name="fixed">
      <joint joint="hipy_0" coef="1"/>
      <joint joint="hipy_1" coef="1"/>
    </fixed>
  </tendon>

  <actuator>
    <motor tendon="fixed" gear="100"/>
    <motor tendon="spatial" gear="10"/>
    <motor joint="hipy_2" gear="100"/>
    <position joint="hipz_1" kp="100"/>
    <position joint="hipz_2" kp="100"/>
    <velocity joint="wheel_2" kv="1"/>
    <intvelocity joint="hipz_0" kp="100" actrange="-1 1"/>
    <general site="wheel_0" gear="0 0 0 0 10 0" dyntype="filter" dynprm="1"/>
    <general joint="wheel_1" biastype="affine" dyntype="integrator" dynprm="1" biasprm="0 -1"/>
  </actuator>

  <sensor>
    <framepos objtype="site" objname="wheel_0" reftype="site" refname="wheel_2"/>
    <rangefinder site="rf"/>
    <gyro site="wheel_2"/>
    <touch site="wheel_1"/>
    <force site="knee"/>
    <torque site="knee"/>
    <force site="cylinder"/>
    <torque site="cylinder"/>
    <jointlimitfrc joint="slider"/>
    <accelerometer site="head"/>
    <subtreeangmom body="head"/>
  </sensor>
</mujoco>