Skip to content

Commit f80782c

Browse files
Create simple_linkage.py
Kinematic Loop example
1 parent e65843c commit f80782c

File tree

1 file changed

+65
-0
lines changed

1 file changed

+65
-0
lines changed

examples/simple_linkage.py

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
import mujoco
2+
import mujoco_viewer
3+
4+
MODEL_XML = """
5+
<?xml version="1.0" ?>
6+
<mujoco>
7+
<option gravity="0 0 0" timestep="0.002" />
8+
<asset>
9+
<material name="blue_" rgba="0 0 1 1" />
10+
<material name="green" rgba="0 1 0 1" />
11+
<material name="red__" rgba="1 0 0 1" />
12+
<material name="white" rgba="1 1 1 1" />
13+
</asset>
14+
<worldbody>
15+
<geom type="plane" size="10 10 0.1" pos="0 0 -3" rgba=".9 0 0 1" />
16+
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1" />
17+
<body name="link_1" pos="0 0 0">
18+
<geom type="cylinder" size=".2 2" pos="0 0 2" euler="0 0 0" material="red__" mass="0.8" />
19+
<geom type="cylinder" size=".25 .25" pos="0 0 4" euler="0 90 0" material="red__" mass="0.1" />
20+
<geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="red__" mass="0.1" />
21+
<body name="link_2" pos="0.5 0 0" euler="0 0 0">
22+
<joint name="hinge_1" type="hinge" pos="0 0 0" axis="1 0 0" /> <!--limited="true" range="-30 30" -->
23+
<geom type="cylinder" size=".2 2" pos="0 2 0" euler="90 0 0" material="blue_" mass="0.8" />
24+
<geom type="cylinder" size=".25 .25" pos="0 4 0" euler="0 90 0" material="blue_" mass="0.1" />
25+
<geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="blue_" mass="0.1" />
26+
<body name="link_3" pos="-0.5 4 0" euler="0 0 0">
27+
<joint name="hinge_2" type="hinge" pos="0 0 0" axis="1 0 0" />
28+
<geom type="cylinder" size=".2 2" pos="0 0 2" euler="0 0 0" material="green" mass="0.8" />
29+
<geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="green" mass="0.1" />
30+
<geom type="cylinder" size=".25 .25" pos="0 0 4" euler="0 90 0" material="green" mass="0.1" />
31+
<body name="link_4" pos="0.5 0 4" euler="0 0 0">
32+
<joint name="hinge_3" type="hinge" pos="0 0 0" axis="1 0 0" />
33+
<geom type="cylinder" size=".2 2" pos="0 -2 0" euler="90 0 0" material="white" mass="0.8" />
34+
<geom type="cylinder" size=".25 .25" pos="0 0 0" euler="0 90 0" material="white" mass="0.1" />
35+
<geom type="cylinder" size=".25 .25" pos="0 -4 0" euler="0 90 0" material="white" mass="0.1" />
36+
</body>
37+
</body>
38+
</body>
39+
</body>
40+
</worldbody>
41+
<equality>
42+
<connect name="kinematic_link" active="true" body1="link_1" body2="link_4" anchor="0 0 4" />
43+
</equality>
44+
<actuator>
45+
<motor name="hinge_1" joint="hinge_1" forcelimited="true" forcerange="-1000 1000" /> <!-- gear="1" -->
46+
<position name="position_servo" joint="hinge_1" kp="100" />
47+
<velocity name="velocity_servo" joint="hinge_1" kv="100" />
48+
</actuator>
49+
</mujoco>
50+
"""
51+
52+
model = mujoco.MjModel.from_xml_string(MODEL_XML)
53+
data = mujoco.MjData(model)
54+
55+
# create the viewer object
56+
viewer = mujoco_viewer.MujocoViewer(model, data)
57+
58+
59+
# simulate and render
60+
for _ in range(100000):
61+
mujoco.mj_step(model, data)
62+
viewer.render()
63+
64+
# close
65+
viewer.close()

0 commit comments

Comments
 (0)