Skip to content

Commit d3fb11a

Browse files
committed
adding the model files
1 parent ebacbf7 commit d3fb11a

145 files changed

Lines changed: 83521 additions & 5 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

model/adhesion/README.md

Lines changed: 9 additions & 0 deletions

model/adhesion/active_adhesion.xml

Lines changed: 139 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,139 @@
1+
<mujoco model="Active adhesion example">
2+
<!--
3+
Adding some fluid viscosity to prevent the hanging sphere from jiggling too much.
4+
-->
5+
<option viscosity="1"/>
6+
7+
<size memory="10M"/>
8+
9+
<visual>
10+
<headlight diffuse=".2 .2 .2"/>
11+
</visual>
12+
13+
<default>
14+
<joint damping=".3" axis="0 1 0"/>
15+
<geom type="box" friction=".5"/>
16+
<default class="wall">
17+
<geom rgba=".5 .5 .5 .4"/>
18+
</default>
19+
<default class="mechanical">
20+
<geom rgba=".5 .5 .8 1"/>
21+
<tendon rgba=".5 .5 .8 1"/>
22+
</default>
23+
<default class="active_adhesion">
24+
<!--
25+
Geoms in the active_adhesion class are "inflated" with a margin of 1cm, but contacts are
26+
activated only at a depth gap of 1cm, leading to a layer of inactive contacts at a 1cm
27+
distance from the surface. However the contacts can be used by the adhesion actuator.
28+
-->
29+
<geom rgba=".8 .5 .5 1" margin=".01" gap=".01"/>
30+
</default>
31+
<default class="object">
32+
<geom rgba=".5 .8 .5 1" density="100"/>
33+
</default>
34+
</default>
35+
36+
<worldbody>
37+
<light pos="0.4 -.15 .6" dir="-1 .5 -1" diffuse=".7 .7 .7"/>
38+
<light pos="-.4 -.15 .6" dir="1 .5 -1" diffuse=".7 .7 .7"/>
39+
40+
<body name="two crates">
41+
<joint name="conveyor" type="slide" damping="100" axis="1 0 0"/>
42+
<geom size=".2 .1 .01" pos="0 0 -.01"/>
43+
<geom size=".01 .08 .031" pos="-.19 0 .03" class="wall"/>
44+
<geom size=".01 .08 .031" pos="0 0 .03" class="wall"/>
45+
<geom size=".01 .08 .031" pos="0.19 0 .03" class="wall"/>
46+
<geom size="0.2 .01 .031" pos="0 -.09 .03" class="wall"/>
47+
<geom size="0.2 .01 .031" pos="0 0.09 .03" class="wall"/>
48+
</body>
49+
50+
<body name="arm1" pos="-.1 0 .3" childclass="mechanical">
51+
<joint name="arm1"/>
52+
<geom type="cylinder" size=".015 .01" zaxis="0 1 0"/>
53+
<geom type="capsule" size=".01" fromto="0 0 0 -.12 0 -.07"/>
54+
<body name="arm2" pos="-.12 0 -.07">
55+
<joint name="arm2"/>
56+
<geom type="cylinder" size=".015 .01" zaxis="0 1 0"/>
57+
<geom type="capsule" size=".01" fromto="0 0 0 .12 0 -.07"/>
58+
<body name="4boxes" pos=".12 0 -.08" childclass="active_adhesion">
59+
<site name="force_sensor" group="3"/>
60+
<joint name="arm3" damping=".01" pos="0 -.03 0"/>
61+
<geom size=".015 .015 .01" pos="0.015 0.015 0"/>
62+
<geom size=".015 .015 .01" pos="0.015 -.015 0"/>
63+
<geom size=".015 .015 .01" pos="-.015 0.015 0"/>
64+
<geom size=".015 .015 .01" pos="-.015 -.015 0"/>
65+
</body>
66+
</body>
67+
</body>
68+
69+
<body name="box" pos="-.1 0 .05">
70+
<freejoint/>
71+
<geom size=".05 .05 .05" class="object"/>
72+
</body>
73+
74+
<body name="winch" pos="-.01 0 .35" childclass="mechanical">
75+
<joint name="winch" damping="1"/>
76+
<geom type="cylinder" size=".015 .01" zaxis="0 1 0"/>
77+
<geom type="capsule" size=".01" fromto="0 0 0 .1 0 .05"/>
78+
<site name="anchor" pos=".1 0 .04"/>
79+
</body>
80+
<site name="pulley" pos=".1 0 .32"/>
81+
<site name="hook_left" pos=".08 0 .3"/>
82+
<site name="hook_right" pos=".12 0 .3"/>
83+
<body name="sphere" pos=".1 0 .2" childclass="active_adhesion">
84+
<freejoint/>
85+
<!--
86+
The composite balls in the crate have only 3 linear DoFs with condim=1, effectively
87+
frictionless point particles. In order to make them stick to the sphere we give the sphere
88+
priority 2, to force condim=3.
89+
90+
Also note the sphere has a margin+gap of 3cm as opposed to the 1cm of the arm box.
91+
-->
92+
<geom type="sphere" size=".03" priority="2" margin=".03" gap=".03"/>
93+
<site name="pin_left" pos="-.025 0 .025"/>
94+
<site name="pin_right" pos=".025 0 .025"/>
95+
</body>
96+
97+
<composite type="particle" count="4 4 4" spacing="0.025" offset=".11 .01 .1">
98+
<geom size=".012" rgba=".5 .8 .5 1" solref=".005 1"/>
99+
</composite>
100+
</worldbody>
101+
102+
<equality>
103+
<joint joint1="arm1" joint2="arm2" polycoef="0 -.5 0 0 0"/>
104+
<joint joint1="arm3" joint2="arm1"/>
105+
</equality>
106+
107+
<!--
108+
By using divisor=3 in the pullies we increase the distance by which the hanging sphere moves
109+
relative to the motion of the winch arm. One should imagine a double spindle with two radii that
110+
creates a ratio of 1.5 between the motion of tendon before the pullies and after the pullies.
111+
(1.5 rather than 3 because the tendon has 2 branches and the length is split between them)
112+
-->
113+
<tendon>
114+
<spatial range="0 .19" limited="true" solreflimit=".01 2" class="mechanical">
115+
<site site="anchor"/>
116+
<site site="pulley"/>
117+
<pulley divisor="3"/>
118+
<site site="pulley"/>
119+
<site site="hook_left"/>
120+
<site site="pin_left"/>
121+
<pulley divisor="3"/>
122+
<site site="pulley"/>
123+
<site site="hook_right"/>
124+
<site site="pin_right"/>
125+
</spatial>
126+
</tendon>
127+
128+
<actuator>
129+
<position name="conveyor" joint="conveyor" ctrlrange="-.2 .2" ctrllimited="true" kp="400"/>
130+
<position name="arm" joint="arm2" ctrlrange="-.8 1" ctrllimited="true" kp="10"/>
131+
<adhesion name="adhere_arm" body="4boxes" ctrlrange="0 1" gain="5"/>
132+
<position name="winch" joint="winch" ctrlrange="-.7 .5" ctrllimited="true" kp="10"/>
133+
<adhesion name="adhere_winch" body="sphere" ctrlrange="0 1" gain="5"/>
134+
</actuator>
135+
136+
<sensor>
137+
<force site="force_sensor"/>
138+
</sensor>
139+
</mujoco>

model/balloons/balloons.xml

Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
<mujoco>
2+
<option density="1.204" viscosity="1.8e-5" integrator="implicit"/>
3+
4+
<visual>
5+
<global elevation="-10"/>
6+
</visual>
7+
8+
<default>
9+
<tendon limited="true" width="0.003" rgba="1 1 1 1"/>
10+
<geom friction=".2"/>
11+
<default class="weight">
12+
<geom rgba=".8 .4 .8 1"/>
13+
<site rgba=".8 .4 .8 1"/>
14+
</default>
15+
<default class="balloon">
16+
<!--
17+
0.167 is the MKS density of helium at room temperature.
18+
Note this does not take into account the mass of the rubber,
19+
which is likely not insignificant.
20+
-->
21+
<geom density="0.167" fluidshape="ellipsoid"/>
22+
<default class="pink">
23+
<geom rgba="1 .6 .7 1"/>
24+
<site rgba="1 .6 .7 1"/>
25+
</default>
26+
<default class="blue">
27+
<geom rgba=".3 .7 .9 1"/>
28+
<site rgba=".3 .7 .9 1"/>
29+
</default>
30+
<default class="green">
31+
<geom rgba=".4 .9 .5 1"/>
32+
<site rgba=".4 .9 .5 1"/>
33+
</default>
34+
<default class="orange">
35+
<geom rgba="1 .4 0 1"/>
36+
<site rgba="1 .4 0 1"/>
37+
</default>
38+
</default>
39+
</default>
40+
41+
<asset>
42+
<texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb2="0 0 0" rgb1="1 1 1"/>
43+
<material name="grid" texture="grid" texrepeat="2 2" texuniform="true" reflectance=".6"/>
44+
</asset>
45+
46+
<worldbody>
47+
<geom name="ground" type="plane" size="5 5 .05" pos="0 0 -.5" material="grid"/>
48+
<geom name="ramp" type="box" size=".4 .2 .03" pos="0 0 -.4" euler="0 20 0" rgba="1 1 1 1"/>
49+
50+
<body name="weight" childclass="weight" pos=".3 0 .2">
51+
<freejoint/>
52+
<light pos="1 0 3" dir="-1 0 -3" mode="trackcom"/>
53+
<light pos="-1 0 3" dir="1 0 -3" mode="trackcom"/>
54+
<!-- The mass of the weight was chosen to be slightly bigger than the total buoyancy of the balloons. -->
55+
<geom name="weight" type="box" size=".015 .015 .015" mass=".0347"/>
56+
<site name="weight1" pos=" .013 .013 .013" size="0.005"/>
57+
<site name="weight2" pos="-.013 -.013 .013" size="0.005"/>
58+
</body>
59+
60+
<!-- The gravcomp value of 7.2 is the ratio of air and helium desities at room temperature. -->
61+
<body name="pink" gravcomp="7.2" pos="-.2 .1 .2" childclass="pink">
62+
<freejoint />
63+
<geom name="pink" type="ellipsoid" size=".11 .11 .15"/>
64+
<geom name="pink_knot" pos="0 0 -.15" size=".02"/>
65+
<site name="pink" pos="0 0 -.17" size="0.01"/>
66+
</body>
67+
68+
<body name="blue" gravcomp="7.2" pos=".1 .1 .2" childclass="blue">
69+
<freejoint />
70+
<geom name="blue" type="ellipsoid" size=".12 .12 .15"/>
71+
<geom name="blue_knot" pos="0 0 -.15" size=".02"/>
72+
<site name="blue" pos="0 0 -.17" size="0.01"/>
73+
</body>
74+
75+
<body name="green" gravcomp="7.2" pos=".1 -.1 .2" childclass="green">
76+
<freejoint />
77+
<geom name="green" type="ellipsoid" size=".12 .12 .14"/>
78+
<geom name="green_knot" pos="0 0 -.14" size=".02"/>
79+
<site name="green" pos="0 0 -.16" size="0.01"/>
80+
</body>
81+
82+
<body name="orange" gravcomp="7.2" pos="-.12 -.12 .2" childclass="orange">
83+
<freejoint />
84+
<geom name="orange" type="ellipsoid" size=".12 .12 .13"/>
85+
<geom name="orange_knot" pos="0 0 -.13" size=".02"/>
86+
<site name="orange" pos="0 0 -.15" size="0.01"/>
87+
</body>
88+
</worldbody>
89+
90+
<tendon>
91+
<spatial range="0 0.6">
92+
<site site="pink"/>
93+
<site site="weight1"/>
94+
</spatial>
95+
<spatial range="0 0.4">
96+
<site site="blue"/>
97+
<site site="weight1"/>
98+
</spatial>
99+
<spatial range="0 0.3">
100+
<site site="green"/>
101+
<site site="weight2"/>
102+
</spatial>
103+
<spatial range="0 0.5">
104+
<site site="orange"/>
105+
<site site="weight2"/>
106+
</spatial>
107+
</tendon>
108+
</mujoco>

model/car/car.xml

Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
<mujoco>
2+
<compiler autolimits="true"/>
3+
4+
<asset>
5+
<texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
6+
<material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".2"/>
7+
<mesh name="chasis" scale=".01 .006 .0015"
8+
vertex=" 9 2 0
9+
-10 10 10
10+
9 -2 0
11+
10 3 -10
12+
10 -3 -10
13+
-8 10 -10
14+
-10 -10 10
15+
-8 -10 -10
16+
-5 0 20"/>
17+
</asset>
18+
19+
<default>
20+
<joint damping=".03" actuatorfrcrange="-0.5 0.5"/>
21+
<default class="wheel">
22+
<geom type="cylinder" size=".03 .01" rgba=".5 .5 1 1"/>
23+
</default>
24+
<default class="decor">
25+
<site type="box" rgba=".5 1 .5 1"/>
26+
</default>
27+
</default>
28+
29+
<worldbody>
30+
<geom type="plane" size="3 3 .01" material="grid"/>
31+
<body name="car" pos="0 0 .03">
32+
<freejoint/>
33+
<light name="top light" pos="0 0 2" mode="trackcom" diffuse=".4 .4 .4"/>
34+
<geom name="chasis" type="mesh" mesh="chasis"/>
35+
<geom name="front wheel" pos=".08 0 -.015" type="sphere" size=".015" condim="1" priority="1"/>
36+
<light name="front light" pos=".1 0 .02" dir="2 0 -1" diffuse="1 1 1"/>
37+
<body name="left wheel" pos="-.07 .06 0" zaxis="0 1 0">
38+
<joint name="left"/>
39+
<geom class="wheel"/>
40+
<site class="decor" size=".006 .025 .012"/>
41+
<site class="decor" size=".025 .006 .012"/>
42+
</body>
43+
<body name="right wheel" pos="-.07 -.06 0" zaxis="0 1 0">
44+
<joint name="right"/>
45+
<geom class="wheel"/>
46+
<site class="decor" size=".006 .025 .012"/>
47+
<site class="decor" size=".025 .006 .012"/>
48+
</body>
49+
</body>
50+
</worldbody>
51+
52+
<tendon>
53+
<fixed name="forward">
54+
<joint joint="left" coef=".5"/>
55+
<joint joint="right" coef=".5"/>
56+
</fixed>
57+
<fixed name="turn">
58+
<joint joint="left" coef="-.5"/>
59+
<joint joint="right" coef=".5"/>
60+
</fixed>
61+
</tendon>
62+
63+
<actuator>
64+
<motor name="forward" tendon="forward" ctrlrange="-1 1"/>
65+
<motor name="turn" tendon="turn" ctrlrange="-1 1"/>
66+
</actuator>
67+
68+
<sensor>
69+
<jointactuatorfrc name="right" joint="right"/>
70+
<jointactuatorfrc name="left" joint="left"/>
71+
</sensor>
72+
</mujoco>

model/cards/assets/10_of_clubs.png

127 KB
125 KB
125 KB
126 KB

model/cards/assets/2_of_clubs.png

112 KB
111 KB

0 commit comments

Comments
 (0)