-
Notifications
You must be signed in to change notification settings - Fork 1
Pendulum Example (Draft)
Create a simple pendulum to understand the units and a practical working control example of the implementation
From the official documentation on units:
In MuJoCo basic physical units are undefined. The user may interpret the system of units as they choose, as long as it is consistent. To understand this, consider an example: the dynamics of a 1 Meter spaceship that weighs 1 Kg and has a 1 Newton thruster are the same as those of a 1 cm spaceship that weighs 1 gram and has a 1 dyn thruster.
Here we use the MKS system: meter, newton-meter, θ° in degrees, seconds
A simple pendulum with a mass with a single-cylinder at its end
basic pendulum.xml
<mujoco>
<option gravity="0 0 0" timestep="0.002" />
<asset>
<material name="blue" rgba="0 0 1 1" />
<material name="red" rgba="1 0 0 1" />
</asset>
<worldbody>
<geom type="plane" size="10 10 0.1" pos="0 0 -3" rgba=".3 .3 .3 1" />
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1" />
<body name="link_1" pos="0 0 0" euler="90 0 0">
<joint name="hinge_1" type="hinge" pos="0 0 0" axis="1 0 0" />
<geom name="connecting_link" type="cylinder" size=".1 2" pos="0 0 2" euler="0 0 0" material="red" />
<geom name="end_mass" type="sphere" size=".25" pos="0 0 4" euler="0 0 0" material="blue" />
</body>
</worldbody>
</mujoco>
example script.py
import mujoco
import mujoco_viewer
model = mujoco.MjModel.from_xml_path("path_to.xml")
data = mujoco.MjData(model)
# create the viewer object
viewer = mujoco_viewer.MujocoViewer(model, data)
# simulate and render
for _ in range(100000):
mujoco.mj_step(model, data)
print(data.qpos)
viewer.render()
# close
viewer.close()
The script loads the following:
In the above image, the created pendulum has this center of mass [M]:
from the documentation about geoms:
This is because only the geoms were used to (automatically) infer the inertial properties of the body. If we happen to know the latter, we can of course specify them directly. But it is often more convenient to let the model compiler infer this body properties from the geoms attached to it, using the assumption of uniform density (geom density can be specified in the XML; the default is the density of water).
from the documentation about body:
This element creates a geom, and attaches it rigidly to the body within which the geom is defined. Multiple geoms can be attached to the same body. At runtime they determine the appearance and collision properties of the body. At compile time they can also determine the inertial properties of the body, depending on the presence of the inertial element and the setting of the inertiafromgeom attribute of compiler. This is done by summing the masses and inertias of all geoms attached to the body with geom group in the range specified by the inertiagrouprange attribute of compiler. The geom masses and inertias are computed using the geom shape, a specified density or a geom mass which implies a density, and the assumption of uniform density. Geoms are not strictly required for physics simulation. One can create and simulate a model that only has bodies and joints. Such a model can even be visualized, using equivalent inertia boxes to represent bodies. Only contact forces would be missing from such a simulation. We do not recommend using such models, but knowing that this is possible helps clarify the role of bodies and geoms in MuJoCo.
Inertial properties are computed from geoms at runtime, all we need to do is give it mass(assuming uniform density). We add mass properties to the pendulum. connecting_link mass = 0 and end_mass mass=1
<body name="link_1" pos="0 0 0" euler="90 0 0">
<joint name="hinge_1" type="hinge" pos="0 0 0" axis="1 0 0" />
<geom name="connecting_link" type="cylinder" size=".1 2" pos="0 0 2" euler="0 0 0" material="red" mass="0"/>
<geom name="end_mass" type="sphere" size=".25" pos="0 0 4" euler="0 0 0" material="blue" mass="1"/>
</body>
The COM shifts:
This can be used further for meshes effectively as long as they have a uniform density. If densities are different, either put in the inertial elements in the boy tags:
<body>
<inertial ... />
</body>
...or combine multiple meshes that have a uniform density as a composite (rather tedious).
The next step towards control is specifying the actuator capabilities at the joints. We insert this into <mujoco></mujoco>
:
<actuator>
<motor name="hinge_1_actuator" joint="hinge_1" forcelimited="true" forcerange="-0.5 0.5" />
</actuator>
For forcelimited
and forcerange
:
forcelimited: [false, true], “false”: If true, the force output of this actuator is automatically clamped to forcerange at runtime. If false, force output clamping is disabled.
forcerange: real(2), “0 0” Range for clamping the force output. The compiler expects the first value to be no greater than the second value.
forcerange
limits the torque applied to the joint, this can be accessed by data.qfrc_applied
:
Let us replicate the following situation:
The system is in static equilibrium and there is only a positive torque being applied to the joint irrespective of the position. If the arm is below the position, the torque acts as a restoring force, but if the arm is above the horizontal, the torque acts to destabilize the arm by accelerating it:
Change the force range in xml file to:
forcerange="-39.24 39.24"
And add this to the simulation loop
data.qfrc_applied[0] = -10.0 # from -forcerange to +forcerange
The output will be similar to this: (The below image is running at 8x real-time speed to show the oscillations)
The motion of the pendulum as the torque of 10Nm is applied and it stays oscillates in the equilibrium position. If we make data.qfrc_applied[0] = -39.24
, the pendulum will stay in the horizontal position until we disturb it or the solver pushes it to instability over time. The gif below shows the instability due to angular velocity and stability due to restoring force just below horizontal.