Composing models and scenes¶
In this tutorial, we will learn how to compose fly models and simulation environments ("worlds") from individual components. We'll build a complete fly model with joints and actuators, place it in an environment with a ground plane, and visualize the result.
Key concepts:
- MJCF format: The model to be simulated is defined in MJCF (MuJoCo Modeling Format) and saved as an XML file. The full specification is available in MuJoCo's official XML reference.
- High-level composition API: Raw XML files are not the most human-readable or editable format. The
flygym.composemodule provides a cleaner interface to construct both fly models and environments.- Behind the scenes, MJCF models are edited using the dm_control PyMJCF module. If needed, you can always modify the underlying
dm_control.mjcf.RootElementobject directly.
- Behind the scenes, MJCF models are edited using the dm_control PyMJCF module. If needed, you can always modify the underlying
- Model description vs. instantiation: MJCF models—whether composed through
flygym.compose, configured through PyMJCF, or loaded from XML—are only descriptions of what the model should be, like a blueprint of a building. To instantiate the model for simulation, we must compile it into efficient data structures that MuJoCo can use. - Fly vs. World: A
Flyobject defines the body model of a fly; aWorldobject defines the environment (e.g., ground plane) and how flies attach to it (e.g., via free joints or tethers). Fly objects are added to World instances. During simulation, we simulate the World, which contains one or more flies.
Composing a Fly¶
Initializing body geometries¶
First, create an empty fly instance. This object contains all body segments and their 3D geometries, but no joints, actuators, or visual styling yet.
from flygym.compose.fly import Fly
fly = Fly()
Adding joint articulation¶
Now we'll add joints to the fly. A few important concepts to understand:
- Anatomical joints vs. joint DoFs: There is a distinction between anatomical joints (e.g., thorax-coxa connection) and joint degrees of freedom (DoFs) (e.g., thorax-coxa pitch rotation). An anatomical joint can have up to three rotational DoFs.
- Axis ordering: We must define the order in which rotational DoFs are chained at multi-DoF anatomical joints. This matters because 3D rotations do not commute.
- Selective articulation: The model doesn't need all biological joints. Removing articulations irrelevant to your behavior of interest improves numerical stability and speeds up simulation. In this example, we'll articulate all biological DoFs, but other presets are available.
- "Biological" means that not all anatomical joints have all three DoFs—this reflects real fly anatomy.
- Neutral pose: We can set a neutral pose for the joint's passive spring-damper properties. Note that this doesn't correspond to the zero position of joint DoFs! By definition, zero pose means all legs fully extended downward. The neutral pose simply defines the reference angles for computing the spring restoring force.
Let's proceed step by step. First, we'll create a Skeleton object that defines which anatomical joints exist and what DoFs they have:
from flygym.anatomy import AxisOrder, JointPreset, Skeleton
axis_order = AxisOrder.ROLL_PITCH_YAW
joint_preset = JointPreset.ALL_BIOLOGICAL
skeleton = Skeleton(joint_preset=joint_preset, axis_order=axis_order)
Defining a neutral pose¶
A predefined neutral pose is shipped with the FlyGym package:
from flygym.compose import KinematicPosePreset
neutral_pose = KinematicPosePreset.NEUTRAL
Again, axis ordering is important. The KinematicPosePreset internally allows the external callers to query joint angles in different axis orders. To demonstrate:
pose_ryp = neutral_pose.get_pose_by_axis_order(AxisOrder.ROLL_YAW_PITCH)
angles_ryp = pose_ryp.joint_angles_lookup_rad
pose_pry = neutral_pose.get_pose_by_axis_order(AxisOrder.PITCH_ROLL_YAW)
angles_pry = pose_pry.joint_angles_lookup_rad
print("Roll-yaw-pitch ordering:")
print(f" c_thorax-lf_coxa-roll: {angles_ryp.get("c_thorax-lf_coxa-roll", 0):.4f} rad")
print(f" c_thorax-lf_coxa-yaw: {angles_ryp.get("c_thorax-lf_coxa-yaw", 0):.4f} rad")
print(f" c_thorax-lf_coxa-pitch: {angles_ryp.get("c_thorax-lf_coxa-pitch", 0):.4f} rad")
print("\nPitch-roll-yaw ordering:")
print(f" c_thorax-lf_coxa-pitch: {angles_pry.get("c_thorax-lf_coxa-pitch", 0):.4f} rad")
print(f" c_thorax-lf_coxa-roll: {angles_pry.get("c_thorax-lf_coxa-roll", 0):.4f} rad")
print(f" c_thorax-lf_coxa-yaw: {angles_pry.get("c_thorax-lf_coxa-yaw", 0):.4f} rad")
Roll-yaw-pitch ordering: c_thorax-lf_coxa-roll: 0.3491 rad c_thorax-lf_coxa-yaw: 0.0000 rad c_thorax-lf_coxa-pitch: 0.4363 rad Pitch-roll-yaw ordering: c_thorax-lf_coxa-pitch: 0.4887 rad c_thorax-lf_coxa-roll: 0.4538 rad c_thorax-lf_coxa-yaw: -0.3142 rad
For the thorax-coxa joint (which has all three DoFs), the conversion between axis orders is exact. However, for rank-deficient joints (those that cannot rotate around all three axes), the effective 3D rotation must be approximated. This is handled automatically by KinematicPose.get_angles_lookup(), which runs an optimization to find the closest solution.
Now, we can add the joints based on the skeleton and the neutral pose (if we don't specify the neutral pose, all angles default to 0):
joints = fly.add_joints(skeleton, neutral_pose=neutral_pose)
print(f"{len(joints)} joint DoFs added to the fly model.")
126 joint DoFs added to the fly model.
Selecting actively controlled joint DoFs¶
So far, these joint DoFs are all passive—they can move subject to stiffness and damping, but they are not actively controlled (i.e., the "brain" cannot command the body to move specific joints).
To enable active control, we'll add actuators. Different actuator types are available:
- Position: Given a target angle, forces are automatically computed to approach that orientation
- Velocity: Similar, but the input is a target angular velocity
- Motor: User directly sets the torque as input
- Muscle: More nuanced and biologically realistic force generation
FlyGym includes a few presets for selecting which DoFs to actuate:
from flygym.anatomy import ActuatedDOFPreset
list(ActuatedDOFPreset)
[<ActuatedDOFPreset.ALL: 'all'>, <ActuatedDOFPreset.LEGS_ONLY: 'legs_only'>, <ActuatedDOFPreset.LEGS_ACTIVE_ONLY: 'legs_active_only'>]
Here, we'll add position actuators to actively control the fly's joints. While we articulated all biologically realistic DoFs, we'll only actuate leg DoFs that are actively controlled by muscles in real flies.
actuation_preset = ActuatedDOFPreset.LEGS_ACTIVE_ONLY
actuated_jointdofs = skeleton.get_actuated_dofs_from_preset(actuation_preset)
print(f"{len(actuated_jointdofs)} actuated DoFs selected based on '{actuation_preset.name}'.")
42 actuated DoFs selected based on 'LEGS_ACTIVE_ONLY'.
These are the following seven DoFs, repeated 6x for all legs:
for dof in actuated_jointdofs:
# Print left front leg DoFs only
if dof.child.pos == "lf":
print(dof.name)
c_thorax-lf_coxa-roll c_thorax-lf_coxa-pitch c_thorax-lf_coxa-yaw lf_coxa-lf_trochanterfemur-roll lf_coxa-lf_trochanterfemur-pitch lf_trochanterfemur-lf_tibia-pitch lf_tibia-lf_tarsus1-pitch
Side note: Naming conventions¶
FlyGym follows consistent semantic naming conventions:
- Body segments (body parts):
{pos}_{link}format{pos}: Position identifier—"c" (center), "lf"/"lm"/"lh" (left front/middle/hind), "rf"/"rm"/"rh" (right front/middle/hind), or "l"/"r" (left/right for non-leg parts like eyes){link}: Position-agnostic link name in the kinematic chain—"thorax", "eye", "wing", or for legs: "coxa", "trochanterfemur", "tibia", "tarsus1" through "tarsus5" (note: trochanter and femur are fused in flies)
- Anatomical joints:
{parent}-{child}format, where both are body segment names - Joint DoFs:
{anatomical_joint}-{axis}format, where axis is "pitch", "roll", or "yaw"
General rule: - separates different semantic objects, while _ separates descriptive parts within the same object. This enables easy parsing using string functions, e.g., parent, child, axis = dofname.split("-").
Adding actuators¶
Since position actuators take target angles as input, we can use the neutral pose defined earlier as the "neutral" actuator input.
Now let's add actuators to the model. We can tune the position gain: higher gains cause the actuator to apply greater forces to track the target angle.
gain = 50
actuators = fly.add_actuators(
actuated_jointdofs, actuator_type="position", kp=gain, neutral_input=neutral_pose
)
print(f"{len(actuators)} actuators added to the model.")
42 actuators added to the model.
Adding visuals for rendering¶
Now the final touches: we will add color and texture to the fly, and attach a tracking camera to it.
fly.colorize()
camera = fly.add_tracking_camera()
Exporting model to file(s)¶
Recall that the model so far is only a text-based description; it hasn't been instantiated yet. To demonstrate, let's export the fly model (including meshes—the 3D body geometries) to a folder for inspection:
fly.save_xml_with_assets("./demo_output/fly_model/") # specify a directory, not file
We can see some .stl mesh files:
!ls ./demo_output/fly_model/*.stl | head -n 5 # list first 5 only
./demo_output/fly_model/c_abdomen12-a8d3b2092c0571e951c358e8d9536526eeecfadb.stl ./demo_output/fly_model/c_abdomen12-d47a49030a20957f3951294ba54af2dcda12b4f0.stl ./demo_output/fly_model/c_abdomen12-e48c526400289d86e216836a7f5200ca16925152.stl ./demo_output/fly_model/c_abdomen3-1f0954c337602ed3433f170cfeeb165233459e93.stl ./demo_output/fly_model/c_abdomen3-7b9b9ea922c02eedf8f523d406c2800f4cd8392e.stl
... and the XML file:
!ls ./demo_output/fly_model/*.xml
./demo_output/fly_model/nmf.xml
Click open the XML file and see what's inside.
Compiling the model¶
Having fully specified the fly model, we can now compile it into an actual model object, along with an initialized data structure to serve as a container during simulation. These objects are of type mujoco.MjModel and mujoco.MjData—Python wrappers of corresponding structs in MuJoCo's C implementation. Detailed documentation is available in MuJoCo's API reference.
To compile the model:
mj_model, mj_data = fly.compile()
print("mj_model: type", type(mj_model))
print("mj_data: type", type(mj_data))
mj_model: type <class 'mujoco._structs.MjModel'> mj_data: type <class 'mujoco._structs.MjData'>
Let's preview the model by simulating a very short period of time. The preview_model() function is provided for exactly this:
from flygym.rendering import preview_model
preview_model(mj_model, mj_data, camera, show_in_notebook=True)
trackcam |
Two observations:
- Joint drift: Passive joints slowly drift from their initial angles due to gravity and finite joint stiffness.
- No environment: The fly is floating in empty space. We've only composed the fly model so far. In the next section, we'll create a World object and place the fly in it.
Composing a World¶
A World object defines the simulation environment and how flies are attached to it. Two World classes are provided with FlyGym:
FlatGroundWorld: A flat, infinite ground plane where flies can move freelyTetheredWorld: A world where the fly is tethered (fixed) in space
Custom worlds can be created by implementing concrete classes inheriting from the BaseWorld Abstract Base Class (ABC). Details can be found in the next tutorial.
For most scenarios, FlatGroundWorld is standard choice. As the name suggests, it consists of a fixed, massless ground plane. The fly can move freely over it, connected via a 6-DoF free joint that allows full translational and rotational freedom.
from flygym.compose import FlatGroundWorld
world = FlatGroundWorld()
Adding Fly to the World and enabling ground contact¶
When adding the fly to the world, we must specify its spawn position and orientation. Position is given in [x, y, z] format (in mm), and orientation is provided as a quaternion in [w, x, y, z] order. The representation of 3D rotations is (surprisingly) complex, but [1, 0, 0, 0] is the standard default for a fly standing upright and facing forward.
from flygym.utils.math import Rotation3D
spawn_pos = [0, 0, 0.7] # center of thorax is at 0.7 mm above the ground
spawn_rot = Rotation3D(format="quat", values=[1, 0, 0, 0]) # no rotation
In FlyGym's FlatGroundWorld, body parts that can collide with the ground must be explicitly defined. Disabling unnecessary contacts improves simulation speed and numerical stability. We'll make only the major body parts contactable: leg segments, thorax, abdomen, and head. FlyGym provides convenient presets for this:
from flygym.anatomy import ContactBodiesPreset
contact_preset = ContactBodiesPreset.LEGS_THORAX_ABDOMEN_HEAD
With these, let's add the fly to the world:
world.add_fly(fly, spawn_pos, spawn_rot, bodysegs_with_ground_contact=contact_preset)
Exporting and visualizing the world model¶
Let's export the MJCF model again, this time for the complete world (including the fly):
world.save_xml_with_assets("./demo_output/world_model/")
Inspect the XML file to verify that the fly is properly attached to the world via a free joint:
!ls ./demo_output/world_model/*.xml
./demo_output/world_model/flat_ground_world.xml
Notice in the XML file (excerpt shown below) how the fly is attached to the world via a <freejoint>, which allows 6 degrees of freedom (3 translational + 3 rotational):
<worldbody>
<geom name="ground_plane" ... />
<site name="nmf" pos="0 0 0.7" quat="1 0 0 0"/>
<body pos="0 0 0.7" quat="1 0 0 0" name="nmf/">
<freejoint name="nmf/nmf/"/> <!-- This connects the fly to the world -->
<body name="nmf/rootbody">
<body name="nmf/c_thorax" ...>
<geom name="nmf/c_thorax" ... />
<body name="nmf/c_head" ... >
...
As before, we can compile the model and simulate a short period of time:
mj_model, mj_data = world.compile()
preview_model(mj_model, mj_data, camera, show_in_notebook=True)
nmf/trackcam |
This time, the fly properly lands on the ground and interacts with it through contact forces.
Interactive viewer¶
For interactive exploration of the fly model, use scripts/launch_interactive_viewer.py to open the model in an interactive viewer.
If using uv for package management, run:
uv run mjpython scripts/launch_interactive_viewer.py