
import mujoco
import mujoco.viewer
import time
# Load a model from a file (won't do this here to avoid external file calls)
# model = mujoco.MjModel.from_xml_path('path/to/your/model.xml')
# Create a simple pendulum model
model = mujoco.MjModel.from_xml_string("""
<mujoco>
<worldbody>
<light name="light1" pos="0.3 0.3 1"/>
<geom name="ground" type="plane" pos=" 0 0 -1.2" size="2 2 0.1" rgba="0.5 0.5 0.5 1"/>
<body name="pendulum" pos="0 0 0">
<joint name="pivot" type="hinge" pos="0 0 0" axis="0 1 0" damping="0.1"/>
<geom name="rod" type="capsule" fromto="0 0 0 0 0 0.6" size="0.05" rgba="0.5 0.5 0.5 1"/>
<geom name="mass" type="sphere" pos="0 0 0.6" size="0.07" rgba="0.8 0.2 0.2 1"/>
</body>
</worldbody>
</mujoco>
""")
data = mujoco.MjData(model)
data.qpos[0]=0.01
# Create a viewer
viewer = mujoco.viewer.launch(model, data,
show_left_ui=False,
show_right_ui=False,
)
Run python3 code/basic_mujoco.py
import mujoco
import mujoco.viewer
import time
# Load a model from a file (won't do this here to avoid external file calls)
# model = mujoco.MjModel.from_xml_path('path/to/your/model.xml')
# Create a simple pendulum model
model = mujoco.MjModel.from_xml_string("""
<mujoco>
<worldbody>
<light name="light1" pos="0.3 0.3 1"/>
<geom name="ground" type="plane" pos=" 0 0 -1.2" size="2 2 0.1" rgba="0.5 0.5 0.5 1"/>
<body name="pendulum" pos="0 0 0">
<joint name="pivot" type="hinge" pos="0 0 0" axis="0 1 0" damping="0.1"/>
<geom name="rod" type="capsule" fromto="0 0 0 0 0 0.6" size="0.05" rgba="0.5 0.5 0.5 1"/>
<geom name="mass" type="sphere" pos="0 0 0.6" size="0.07" rgba="0.8 0.2 0.2 1"/>
</body>
</worldbody>
</mujoco>
""")
data = mujoco.MjData(model)
data.qpos[0]=0.01
# Create a viewer
viewer = mujoco.viewer.launch(model, data,
show_left_ui=False,
show_right_ui=False,
)import mujoco
import mujoco.viewer
import time
# Load a model from a file (won't do this here to avoid external file calls)
# model = mujoco.MjModel.from_xml_path('path/to/your/model.xml')
# Create a simple pendulum model
model = mujoco.MjModel.from_xml_string("""
<mujoco>
<worldbody>
<light name="light1" pos="0.3 0.3 1"/>
<geom name="ground" type="plane" pos=" 0 0 -1.2" size="2 2 0.1" rgba="0.5 0.5 0.5 1"/>
<body name="pendulum" pos="0 0 0">
<joint name="pivot" type="hinge" pos="0 0 0" axis="0 1 0" damping="0.1"/>
<geom name="rod" type="capsule" fromto="0 0 0 0 0 0.6" size="0.05" rgba="0.5 0.5 0.5 1"/>
<geom name="mass" type="sphere" pos="0 0 0.6" size="0.07" rgba="0.8 0.2 0.2 1"/>
</body>
</worldbody>
</mujoco>
""")
data = mujoco.MjData(model)
data.qpos[0]=0.01
# Create a viewer
viewer = mujoco.viewer.launch(model, data,
show_left_ui=False,
show_right_ui=False,
)code/basic_mujoco.py
import mujoco
import mujoco.viewer
import time
# Load a model from a file (won't do this here to avoid external file calls)
model = mujoco.MjModel.from_xml_path('../models/simple_pendulum_act.xml')
data = mujoco.MjData(model)
data.qpos[0]=0.01
# Create a viewer
viewer = mujoco.viewer.launch(model, data,
show_left_ui=False,
show_right_ui=False,
)code/mujoco_load_xml.py
and then drag and drop xml files from models/
<mujoco>
<option gravity="0 0 -9.81"/>
<worldbody>
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
<body pos="0 0 1">
<joint type="free"/>
<geom type="box" size=".1 .2 .3" rgba="0 .9 0 1"/>
</body>
</worldbody>
</mujoco><mujoco>
<option gravity="0 0 -9.81"/>
<worldbody>
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
<body pos="0 0 1">
<joint type="free"/>
<geom type="box" size=".1 .2 .3" rgba="0 .9 0 1"/>
</body>
<body pos="0.1 0 1.5" euler="0 90 0">
<joint type="free"/>
<geom type="box" size=".1 .2 .3" rgba="0 0 0.9 1"/>
</body>
<body pos="0.1 0 2.0">
<joint type="free"/>
<geom type="sphere" size=".1" rgba="0.9 0.9 0 1"/>
</body>
</worldbody>
</mujoco>
import mujoco
import mujoco.viewer
import time
# Load a model from a file (won't do this here to avoid external file calls)
model = mujoco.MjModel.from_xml_path('../models/simple_pendulum_act.xml')
dt: float = 0.002
model.opt.timestep = dt
data = mujoco.MjData(model)
data.qpos[0]=0.01
# Create a viewer
viewer = mujoco.viewer.launch_passive(model, data,
show_left_ui=False,
show_right_ui=False,
)
try:
while viewer.is_running():
step_start = time.time()
# Step the simulation
data.ctrl[0] = -100*data.qpos[0] - 20*data.qvel[0]
print(data.qpos[0])
mujoco.mj_step(model, data)
# Update the viewer
viewer.sync()
# Add a small delay to control frame rate
time_until_next_step = dt - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step)
except KeyboardInterrupt:
print("Viewer closed by user")
finally:
viewer.close()code/mujoco_load_xml_control.py
Robot Modeling and Control • ME 676 Home