Generating MuJoCo XML models - AIMotionLab-SZTAKI/AIMotionLab-Virtual GitHub Wiki

The main sections of this page:

MuJoCo XML basics: Gives a short overview about the XML structure of MuJoCo models.

Organizing the XML generator code into a class: Gives an overview on how the xml.etree.ElementTree package works, and how to create a class that allows easy XML file generation with MuJoCo specific examples.

EXAMPLE #1: Creating the model of the Fleet1Tenth car by hand: Walks you through some very simple general examples on how to create valid MuJoCo models, and a more complex example that shows how to build a model for the Fleet1Tenth car.

EXAMPLE #2: Creating the model of an actuated MovingObject: demonstrates how to build a simple actuated vehicle from zero, with a corresponding Python class.

SceneXmlGenerator Tutorial: A tutorial on how to use the SceneXmlGenerator class.

MuJoCo XML basics

There's a great introductory level Python tutorial here.

Building a simple scene with some objects

Two boxes in a scene

<mujoco model="Example">

  <compiler angle="radian"/>
  <visual>
    <quality shadowsize="4096"/>
  </visual>

  <asset>
    <texture type="skybox" builtin="gradient" rgb1=".3 .5 .7" rgb2="0 0 0" width="512" height="512"/>
    <texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .1 .1" rgb2=".2 .2 .2"/>
    <material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".05"/>
  </asset>

  <worldbody>
    <geom size="20 20 .05" type="plane" material="grid" condim="3"/>

    <light dir="0 -0.3 -1" diffuse=".9 .9 .9" specular="0.6 0.9 0.6" pos="1 1 15" cutoff="70"/>
    <light dir="-.2 1 -.4" diffuse=".9 .9 .9" specular="0.6 0.9 0.6" pos="2 -5 6" cutoff="70"/>
    
    <geom name="redBox" type="box" size="0.5 0.5 0.5" pos="1 1 1" rgba="0.9 0.1 0.1 1.0" euler="0.78 0 0.78" />l
    <geom name="blueBox" type="box" size="0.5 0.3 0.5" pos="1 -1.5 1" rgba="0.1 0.1 0.9 1.0" />

  </worldbody>

</mujoco>

The scene defined in the XML above contains a plane with the checkerboard pattern, two light sources, a skybox, and two boxes (3D rectangular shapes). The worldbody is the toplevel layer of the kinematic tree. It corresponds to the origin of the world frame, within which the rest of the kinematic tree is defined.

To see what it looks like, copy-paste the code into a text editor and save it as an .xml file. Run the script: scripts/load_and_display_scene.py. Press 'l' on the keyboard, and when the pop-up window appears, navigate to the xml file you just saved and open it. If everything goes well, this should appear in the window:

Screenshot 2023-05-12 115020

As can be seen, the red box is rotated and the blue one is aligned with the world coordinate system because the blue box does not have a rotation specified, and all unspecified attributes have a default value (0, 0, 0 in this case). The true size of the boxes is twice the values specified in the xml as those are half the side lengths. A 3D object is defined as a geom. It can be one of MuJoCo's built in shapes like box, sphere, cylinder, etc., or it can be a triangle mesh in *.stl or *.obj format. If a geom is defined straight in the worldbody elemet, it is a static object. Therefore, geoms are usually not used by themselves, but are attached to a body element, so that they can move around, have joints etc. For a body to be able to move, it needs to have at least one joint. The joint types are: free, ball, slide and hinge.

A free joint gives a body 6 degrees of freedom (it makes the object float). This joint type is only allowed in bodies that are direct children of the worldbody. The ball type creates a ball joint with three rotational degrees of freedom. The rotation is represented as a unit quaternion. The slide type creates a sliding or prismatic joint with one translational degree of freedom. The hinge type creates a hinge joint with one rotational degree of freedom. The rotation takes place around a specified axis through a specified position. This is the most common type of joint and is therefore the default. Most models contain only hinge and free joints.

A body element that has a joint

<mujoco model="Example">

  <compiler angle="radian"/>
  <visual>
    <quality shadowsize="4096"/>
  </visual>

  <asset>
    <texture type="skybox" builtin="gradient" rgb1=".3 .5 .7" rgb2="0 0 0" width="512" height="512"/>
    <texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .1 .1" rgb2=".2 .2 .2"/>
    <material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".05"/>
  </asset>

  <worldbody>
    <geom size="20 20 .05" type="plane" material="grid" condim="3"/>

    <light dir="0 -0.3 -1" diffuse=".9 .9 .9" specular="0.6 0.9 0.6" pos="1 1 15" cutoff="70"/>
    <light dir="-.2 1 -.4" diffuse=".9 .9 .9" specular="0.6 0.9 0.6" pos="2 -5 6" cutoff="70"/>
    
    <body name="pendulum" pos="0.0 0.0 1.2">
      <geom name="blueBox" type="box" size="0.5 0.3 0.5" pos="0 0 0" rgba="0.1 0.1 0.9 1.0" />
      <body pos="0.55 0.5 0.0">
        <geom name="arm" type="box" size="0.05 0.5 0.05" rgba="0.6 0.0 0.6 1.0" />
        <joint name="arm" type="hinge" axis="1 0 0" pos="0.0 -0.5 0.0" />
      </body>
    </body>

  </worldbody>

</mujoco>

If this xml is compiled and displayed, this should be seen:

joint

The blue box geom is now part of the body element called pendulum. Inside it, there's another body element that contains a geom and a joint called arm. The joint is placed at one of the endpoints of the magenta geom. Therefore, the arm starts a pendulum motion due to gravity. The joint is a hinge type that can rotate about the x axis.

Including another MJCF model

Multiple XML files can be used to build a single MJCF model. An XML file can be included in another by the following syntax:

<include file="scene_base.xml" />

This way, all the materials, textures, meshes, objects and other elements that can be reused can be stored in a separate file. In the case of this project, there is a base XML file (xml_models/scene.xml) that contains the AIMotionLab 3D model and a number of meshes, textures and materials. This file can be included in all the other generated XML files and it usually is.

It contains the following objects:

tut01

Organizing the XML generator code into a class

As mentioned in the overview, the user can create XML files by hand which is fine if the same model needs to be used many times with minor modifications at most. However, when a simulation requires a complex model that needs to be changed according between runs, it is much more convenient to generate a new model programmatically every time before the simulation is run. This is doable because generating an XML file only takes a moment with the xml.etree.ElementTree package and if done correctly, it only requires a few lines of Python code.

In this section, the concept of creating an MJCF model as an XML file will be discussed.

1. Create a class that initializes the xml.etree.ElementTree package in its constructor

Store a reference to every subelement that might be needed later. These are asset, worldbody, contact, actuator and sensor. Textures, materials, meshes etc. can be added in the asset element. Bodies, geoms can be added to the worldbody element. Friction between objects can be specified in the contact element. In the actuator element, actuators can be attached to objects. And finally, various sensors can be attached to objects in the sensor element.

import xml.etree.ElementTree as ET

class XmlGenerator:

    def __init__(self, base_scene_filename):

        self.base_scene_filename = base_scene_filename
        
        self.root = ET.Element("mujoco")
        
        ET.SubElement(self.root, "include", file=base_scene_filename)

        self.asset = ET.SubElement(self.root, "asset")
        self.worldbody = ET.SubElement(self.root, "worldbody")
        self.contact = ET.SubElement(self.root, "contact")
        self.actuator = ET.SubElement(self.root, "actuator")
        self.sensor = ET.SubElement(self.root, "sensor")

This way, there's a reference to each subelement for later use.

2. Create a method within the class that saves the XML tree to a file

    def save_xml(self, file_name):
        
        tree = ET.ElementTree(self.root)
        tree.write(file_name)
        print()
        print("[XmlGenerator] Scene xml file saved at: " + os.path.normpath(file_name))

After an instance of the class is initialized, the tree can already be saved to see what a template XML file looks like:

import XmlGenerator # from wherever it is
xml_generator = XmlGenerator("base_scene.xml")
xml_generator.save_xml("empty.xml")

And the generated empty.xml looks like this:

<mujoco>
    <include file="base_scene.xml" />
    <asset />
    <worldbody />
    <contact />
    <actuator />
    <sensor />
</mujoco>

Asset, worldbody, contact, actuator and sensor are the subelements where other elements will be placed later. As can be seen, there's also an include subelement, where other XML files can be linked to the file that's to be generated. The included file must be a valid XML file and can contain predefined assets, settings, objects, etc. The file location is relative to the directory of the main MJCF file. So the base_scene.xml file should be in the same directory as the generated empty.xml. If the file is not in the same directory, it should be prefixed with a relative path.

3. Writing methods within the class to generate particular objects

As a very simple example, here is a method that creates a "ball":

    def add_ball(self, pos, size, color, name):

        body = ET.SubElement(self.worldbody, "body", name=name, pos=pos)

        ET.SubElement(body, "geom", type="sphere", size=size, rgba=color)
        ET.SubElement(body, "joint", type="free", name=name)

The method creates a body subelement in the worldbody element, plus a sphere type geom and a free joint within this body.

Here is a simple script that uses the new method:

import XmlGenerator

xml_generator = XmlGenerator("base_scene.xml")

xml_generator.add_ball("0 0 1", "0.1", "0.3 0.4 0.5 1.0", "labda00")

xml_generator.save_xml("ball.xml")

And the ball.xml file that's been generated:

<mujoco>
    <include file="base_scene.xml" />
    <asset />
    <worldbody>
        <body name="labda00" pos="0 0 1">
            <geom type="sphere" size="0.1" rgba="0.3 0.4 0.5 1.0" />
            <joint type="free" name="labda00" />
        </body>
    </worldbody>
    <contact />
    <actuator />
    <sensor />
</mujoco>

In the framework, the SceneXmlGenerator class follows this concept. To create more complex MuJoCo objects, the same rules can be followed.

Creating the model of the Fleet1Tenth car by hand

In this section, the components and the structure of the virtual Fleet1Tenth model are discussed.

A 3D mesh is not available for the car, so it is constructed out of MuJoCo's built in shapes. It needs a cylinder for each wheel, and some rectangular boxes for the chassis. The main body has a free joint to be able to move around in the world, an "inertial" property in which its mass and inertia can be specified and a "site" which will later be needed to attach sensors to the object. As a first step, the wheels are added:

<body name="Fleet1Tenth_0" pos="0 0 .052388" quat="1 0 0 0">
    <inertial pos="0 0 0" diaginertia=".05 .05 .08" mass="3.0" />
    <joint name="Fleet1Tenth_0" type="free" />
    <site name="Fleet1Tenth_0_cog" pos="0 0 0" />

    <body name="Fleet1Tenth_0_wheelfl" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelfl" type="cylinder" size=".052388 .022225"
            pos="0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
    <body name="Fleet1Tenth_0_wheelrl" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelrl" type="cylinder" size=".052388 .022225"
            pos="-0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
    <body name="Fleet1Tenth_0_wheelfr" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelfr" type="cylinder" size=".052388 .022225"
            pos="0.16113 -.122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
    <body name="Fleet1Tenth_0_wheelrr" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelrr" type="cylinder" size=".052388 .022225"
            pos="-0.16113 -.122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
</body>

In this XML snippet, the main body of the car contains 4 bodies, each of which contain a cylinder type geom. The material of the wheel is defined in the "scene_base.xml" base XML file, so for this snippet to compile, the base XML needs to be included as discussed in the previous section. If displayed, it'd look like this, where the tiny sphere in the middle is the visual representation of the site:


Next, let's add two rectangle boxes that represent the chassis. These do not need to be inside a separate body, since they do not move with respect to the car's coordinate frame:

<body name="Fleet1Tenth_0" pos="0 0 .052388" quat="1 0 0 0">
    <inertial pos="0 0 0" diaginertia=".05 .05 .08" mass="3.0" />
    <joint name="Fleet1Tenth_0" type="free" />
    <geom name="Fleet1Tenth_0_chassis_b" type="box" size=".10113 .1016 .02"
        pos="-.06 0 0" rgba="0.85 0.2 0.2 1.0" />
    <geom name="Fleet1Tenth_0_chassis_f" type="box" size=".06 .07 .02" pos=".10113 0 0"
        rgba="0.85 0.2 0.2 1.0" />
    <body name="Fleet1Tenth_0_wheelfl" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelfl" type="cylinder" size=".052388 .022225"
            pos="0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
    <body name="Fleet1Tenth_0_wheelrl" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelrl" type="cylinder" size=".052388 .022225"
            pos="-0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
    <body name="Fleet1Tenth_0_wheelfr" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelfr" type="cylinder" size=".052388 .022225"
            pos="0.16113 -.122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
    <body name="Fleet1Tenth_0_wheelrr" quat="1 0 0 0">
        <geom name="Fleet1Tenth_0_wheelrr" type="cylinder" size=".052388 .022225"
            pos="-0.16113 -.122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
    </body>
</body>

The model with the "chassis":

Adding joints to the model

For the wheels to be able to spin, a y-axis hinge joint needs to be added to each. The front wheels also get a hinge joint on the vertical axis (z) to make steering possible. The XML code of the front left wheel:

<body name="Fleet1Tenth_0_wheelfl" >
    <joint name="Fleet1Tenth_0_wheelfl_steer" type="hinge" pos="0.16113 .10016 0"
        limited="true" frictionloss="0.2" damping="0.2" armature="0.001"
        range="-0.6 0.6" axis="0 0 1" />
    <joint name="Fleet1Tenth_0_wheelfl" type="hinge" pos="0.16113 .122385 0"
        axis="0 1 0" frictionloss="0.01" damping="0.00001" armature="0.05"
        limited="false" />
    <geom name="Fleet1Tenth_0_wheelfl" type="cylinder" size=".052388 .022225"
        pos="0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
</body>

A joint element can have attributes such as frictionloss, damping and armature. The frictionloss attribute means friction loss due to dry friction. This value is the same for all degrees of freedom created by this joint. Damping is simply a force linear in velocity and is applied in all degrees of freedom. Armature is the rotor inertia which is added to the diagonal of the inertia matrix in generalized coordinates. The XML reference of the MuJoCo documentation provides more details.

The joint responsible for rolling is at the same position as the geom (the position of the geom specifies the position of the center of it). The steer joint is a bit shifted to the inside because the real wheel rotates about a vertical axis at inner side of the wheel.

Adding actuators to the model

Right now the car can roll if it is pushed but it's not capable of moving on its own. Therefore, actuators need to be added to the joints. Since the Fleet1Tenth car is a four-wheel drive car, it is modeled with an actuator at each wheel. The actuators that simulate the engine are four motor type MuJoCo actuators whose control input is a torque value. Each actuators input will be the same, as the torque is the same on each wheel because of the differential drive.

For steering, a position type actuator is added to each front wheel steer joint. The control input of these actuators is an angle in radians that determines how much the wheel should be tilted.

To add actuators, the element of the XML tree needs to be used. Here, all the actuators can be specified, no matter which pbject they are attached to. In the case of the Fleet1Tenth the joint attribute of the specific actuator determines which joint the actuator acts on. The actuators of the Fleet1Tenth can be seen below:

<actuator>
    <motor name="Fleet1Tenth_0_wheelfl_actr" joint="Fleet1Tenth_0_wheelfl" />
    <motor name="Fleet1Tenth_0_wheelfr_actr" joint="Fleet1Tenth_0_wheelfr" />
    <motor name="Fleet1Tenth_0_wheelrl_actr" joint="Fleet1Tenth_0_wheelrl" />
    <motor name="Fleet1Tenth_0_wheelrr_actr" joint="Fleet1Tenth_0_wheelrr" />
    <position forcelimited="true" forcerange="-5 5" name="Fleet1Tenth_0_wheelfl_actr_steer"
        joint="Fleet1Tenth_0_wheelfl_steer" kp="15" />
    <position forcelimited="true" forcerange="-5 5" name="Fleet1Tenth_0_wheelfr_actr_steer"
        joint="Fleet1Tenth_0_wheelfr_steer" kp="15" />
</actuator>

Adding sensors to the model

MuJoCo provides sensor modeling capabilities. There is a whole range of sensors that can be checked out in the MuJoCo documentation. These include accelerometer, gyroscope, velocimeter, magnetometer, position etc.. The Fleet1Tenth needs a gyroscope, a velocimeter, a position and an orientation sensor. The first two sensors are attached to a site which has to be specified inside the 3D object itself. The framepos and framequat sensors are also attached to the site, but they can also be attached to bodies, xbodies, geoms or camera. In case of the Fleet1Tenth the site is at the origin of its coordinate frame.

The sensors need to be added in the element of the XML tree.

<sensor>
    <gyro site="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_gyro" />
    <velocimeter site="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_velocimeter" />
    <framepos objtype="site" objname="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_posimeter" />
    <framequat objtype="site" objname="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_orimeter" />
</sensor>

Defining friction between two specific objects

The MuJoCo grouping element contact serves the purpose to create predefined geom pairs that will be checked for collision. Unlike dynamically generated pairs whose properties are inferred from the corresponding geom properties, the pairs created here specify all their properties explicitly or through defaults, and the properties of the individual geoms are not used. Anisotropic friction can only be created with this element.

For the Fleet1Tenth car, contact pairs are defined between wheel and floor.

<contact>
    <pair geom1="Fleet1Tenth_0_wheelfl" geom2="roundabout" condim="6"
         friction="2.5 2.5 .009 .0001 .0001" />
    <pair geom1="Fleet1Tenth_0_wheelfr" geom2="roundabout" condim="6"
        friction="2.5 2.5 .009 .0001 .0001" />
    <pair geom1="Fleet1Tenth_0_wheelrl" geom2="roundabout" condim="6"
        friction="2.5 2.5 .009 .0001 .0001" />
    <pair geom1="Fleet1Tenth_0_wheelrr" geom2="roundabout" condim="6"
        friction="2.5 2.5 .009 .0001 .0001" />
</contact>

The roundabout represents the floor, because even though it has a 3m x 3m texture, it is an infinite plane for collision detection purposes (as stated in the MuJoCo docs) and this is the topmost plane in the scene.

condim="6" means that the contact can oppose motion in all relative degrees of freedom between the two geoms. In particular it adds rolling friction, which can be used for example to stop a ball from rolling indefinitely on a plane. It can also be used to model rolling friction between tires and a road, and in general to stabilize contacts.

The final Fleet1Tenth model

A scene containing one single Fleet1Tenth car:

<mujoco>
    <include file="scene_base.xml" />
    <worldbody>
        <body name="Fleet1Tenth_0" pos="0 0 .052388" quat="1 0 0 0">
            <inertial pos="0 0 0" diaginertia=".05 .05 .08" mass="3.0" />
            <joint name="Fleet1Tenth_0" type="free" />
            <site name="Fleet1Tenth_0_cog" pos="0 0 0" />
            <geom name="Fleet1Tenth_0_chassis_b" type="box" size=".10113 .1016 .02"
                pos="-.06 0 0" rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_chassis_f" type="box" size=".06 .07 .02" pos=".10113 0 0"
                rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_front" type="box" size=".052388 .02 .02" pos=".2135 0 0"
                rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_back" type="box" size=".052388 .02 .02" pos="-.2135 0 0"
                rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_front_bumper" type="box" size=".005 .09 .02"
                pos=".265888 0 0.02" rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_back_bumper" type="box" size=".005 .08 .02"
                pos="-.265888 0 0.02" rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_number" type="cylinder" size=".01984 .03" pos=".12 0 .05"
                rgba="0.1 0.1 0.1 1.0" />
            <geom name="Fleet1Tenth_0_camera" type="box" size=".012 .06 0.02" pos=".18 0 .08" />
            <geom name="Fleet1Tenth_0_camera_holder" type="box" size=".012 .008 .02"
                pos=".18 0 .04" />
            <geom name="Fleet1Tenth_0_circuits" type="box" size=".08 .06 .03" pos="-.05 0 .05"
                rgba="0.85 0.2 0.2 1.0" />
            <geom name="Fleet1Tenth_0_antennal" type="box" size=".007 .004 .06"
                pos="-.16 -.01 .105" euler="0.2 0 0" rgba=".1 .1 .1 1.0" />
            <geom name="Fleet1Tenth_0_antennar" type="box" size=".007 .004 .06"
                pos="-.16 .01 .105" euler="-0.2 0 0" rgba=".1 .1 .1 1.0" />
            <geom name="Fleet1Tenth_0_antenna_holder" type="box" size=".008 .008 .02"
                pos="-.16 0 .04" rgba=".1 .1 .1 1.0" />
            <body name="Fleet1Tenth_0_wheelfl">
                <joint name="Fleet1Tenth_0_wheelfl_steer" type="hinge" pos="0.16113 .10016 0"
                    limited="true" frictionloss="0.2" damping="0.2" armature="0.001"
                    range="-0.6 0.6" axis="0 0 1" />
                <joint name="Fleet1Tenth_0_wheelfl" type="hinge" pos="0.16113 .122385 0"
                    axis="0 1 0" frictionloss="0.01" damping="0.00001" armature="0.05"
                    limited="false" />
                <geom name="Fleet1Tenth_0_wheelfl" type="cylinder" size=".052388 .022225"
                    pos="0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
            </body>
            <body name="Fleet1Tenth_0_wheelrl">
                <joint name="Fleet1Tenth_0_wheelrl" type="hinge" pos="-0.16113 .122385 0"
                    axis="0 1 0" frictionloss="0.01" damping="0.00001" armature="0.05"
                    limited="false" />
                <geom name="Fleet1Tenth_0_wheelrl" type="cylinder" size=".052388 .022225"
                    pos="-0.16113 .122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
            </body>
            <body name="Fleet1Tenth_0_wheelfr">
                <joint name="Fleet1Tenth_0_wheelfr_steer" type="hinge" pos="0.16113 -.10016 0"
                    limited="true" frictionloss="0.2" damping="0.2" armature="0.001"
                    range="-0.6 0.6" axis="0 0 1" />
                <joint name="Fleet1Tenth_0_wheelfr" type="hinge" pos="0.16113 -.122385 0"
                    axis="0 1 0" frictionloss="0.01" damping="0.00001" armature="0.05"
                    limited="false" />
                <geom name="Fleet1Tenth_0_wheelfr" type="cylinder" size=".052388 .022225"
                    pos="0.16113 -.122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
            </body>
            <body name="Fleet1Tenth_0_wheelrr">
                <joint name="Fleet1Tenth_0_wheelrr" type="hinge" pos="-0.16113 -.122385 0"
                    axis="0 1 0" frictionloss="0.01" damping="0.00001" armature="0.05"
                    limited="false" />
                <geom name="Fleet1Tenth_0_wheelrr" type="cylinder" size=".052388 .022225"
                    pos="-0.16113 -.122385 0" mass="0.1" material="material_check" euler="1.571 0 0" />
            </body>
        </body>
    </worldbody>
    <contact>
        <pair geom1="Fleet1Tenth_0_wheelfl" geom2="roundabout" condim="6"
            friction="2.5 2.5 .009 .0001 .0001" />
        <pair geom1="Fleet1Tenth_0_wheelfr" geom2="roundabout" condim="6"
            friction="2.5 2.5 .009 .0001 .0001" />
        <pair geom1="Fleet1Tenth_0_wheelrl" geom2="roundabout" condim="6"
            friction="2.5 2.5 .009 .0001 .0001" />
        <pair geom1="Fleet1Tenth_0_wheelrr" geom2="roundabout" condim="6"
            friction="2.5 2.5 .009 .0001 .0001" />
    </contact>
    <actuator>
        <motor name="Fleet1Tenth_0_wheelfl_actr" joint="Fleet1Tenth_0_wheelfl" />
        <motor name="Fleet1Tenth_0_wheelfr_actr" joint="Fleet1Tenth_0_wheelfr" />
        <motor name="Fleet1Tenth_0_wheelrl_actr" joint="Fleet1Tenth_0_wheelrl" />
        <motor name="Fleet1Tenth_0_wheelrr_actr" joint="Fleet1Tenth_0_wheelrr" />
        <position forcelimited="true" forcerange="-5 5" name="Fleet1Tenth_0_wheelfl_actr_steer"
            joint="Fleet1Tenth_0_wheelfl_steer" kp="15" />
        <position forcelimited="true" forcerange="-5 5" name="Fleet1Tenth_0_wheelfr_actr_steer"
            joint="Fleet1Tenth_0_wheelfr_steer" kp="15" />
    </actuator>
    <sensor>
        <gyro site="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_gyro" />
        <velocimeter site="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_velocimeter" />
        <framepos objtype="site" objname="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_posimeter" />
        <framequat objtype="site" objname="Fleet1Tenth_0_cog" name="Fleet1Tenth_0_orimeter" />
    </sensor>
</mujoco>

Several more geoms were added to the model to imitate the parts of the car. Visual representation:

tut02

Creating the model of an actuated MovingObject

As an example, let's create a new type of controlled object from scratch that fits in the Mujoco-Simulator framework.

The steps are the following:

- naming convention for main body and free joint: ClassName_index

- create an XML model following the naming convention

- create the corresponding python class for the object

- test with the ActiveSimulator class

The example object will have two wheels and a crossbar. Let's call the object bicycle. Each wheel will have a hinge type joint so that they can roll; and the bicycle will also have an actuator on the rear wheel, and a velocimeter sensor.

Naming convention

This is the way the global parsing function creates Python instances for every object in the model. When a new class is created, it is very important to go to file classes/object_parser.py and import the new class at the top of the file!

  • top-level body name: Bicycle_n
  • free joint name: Bicycle_n
  • actuator name: Bicycle_n_actr
  • velocimeter sensor name: Bicycle_n_velocimeter

These will be important when the corresponding Python class is referencing the joints, actuators and sensors.

XML model

Next, let's build it in an XML file. The object's top-level body will contain an inertia definition, a free joint, a site for attaching the sensors, a geom for the crossbar, and two more bodies for the wheels. The wheel bodies each will contain a hinge type joint and a cylinder type geom.

<mujoco>
    <include file="scene_base.xml" />

    <worldbody>

        <body name="Bicycle_0" pos="0 0 0.06">

            <inertial pos="0 0 0" diaginertia=".01 .01 .01" mass="1.0" />
            <joint type="free" name="Bicycle_0" />
            <site name="Bicycle_0_cog" pos="0 0 0" />

            <geom name="Bicycle_0_crossbar" type="box" size="0.06 0.015 0.02" pos="0. 0. 0."
                rgba="0.2 0.2 0.8 1.0" />

            <body name="Bicycle_0_wheelf">
                <joint name="Bicycle_0_wheelf" type="hinge" pos="0.1 0 0"
                    axis="0 1 0" frictionloss="0.001" damping="0.00001" armature="0.01" />

                <geom name="Bicycle_0_wheelf" type="cylinder" size="0.04 0.015" pos="0.1 0 0"
                    euler="1.571 0 0" material="material_check" />
            </body>

            <body name="Bicycle_0_wheelr">
                <joint name="Bicycle_0_wheelr" type="hinge" pos="-0.1 0 0"
                    axis="0 1 0" frictionloss="0.001" damping="0.00001" armature="0.01" />

                <geom name="Bicycle_0_wheelr" type="cylinder" size="0.04 0.015" pos="-0.1 0 0"
                    euler="1.571 0 0" material="material_check" />
            </body>
        </body>

    </worldbody>

    <actuator>
        <motor name="Bicycle_0_actr" joint="Bicycle_0_wheelr" />
    </actuator>

    <sensor>
        <velocimeter site="Bicycle_0_cog" name="Bicycle_0_velocimeter" />
    </sensor>

</mujoco>

The model looks like this:

tut07

Corresponding Python class

Let's write a class that digs out the actuator and the sensor from the model in its constructor.

import mujoco
from aiml_virtual.object.moving_object import MovingObject

class Bicycle(MovingObject):

    def __init__(self, model: mujoco.MjModel, data: mujoco.MjData, name_in_xml):
        
        super().__init__(model, name_in_xml)

        self.actr = data.actuator(name_in_xml + "_actr")
        self.ctrl = self.actr.ctrl
        self.sensor_velocimeter = data.sensor(name_in_xml + "_velocimeter").data
    
    def update(self, i, control_step):
        
        if self.controllers is not None:
            ctrl = self.controllers[0].compute_control(i)

            self.ctrl[0] = ctrl

Bicycle is a subclass of MovingObject.

The constructor receives the entire mjModel and mjData of the model when the parser method calls it. It looks for and saves a reference of its actuator and sensor in the model so that when its update method is called, it can compute its new control based on the sensor data. Instances of subclasses of MovingObject should not be created by the user, they should be created by the parser method (classes.object_parser.parseMovingObjects) that is called by the ActiveSimulator instance.

The update method serves as a simple example to show that the developer can write whatever they want in it. This is the method that the ActiveSimulator calls at every control timestep. The MovingObject base class contains the declaration of self.controllers. It'll be clear later in this tutorial why it calls the first element of the self.controllers list.

A dummy bicycle controller

Let's create a dummy controller to show how the components fit together.

from aiml_virtual.controller import ControllerBase

class BicycleController(ControllerBase):

    def __init__(self):
        pass
    
    def compute_control(self, i):
        
        return 0.1

The compute_control method always returns 0.1 which will be the control input of the rear wheel actuator which is a motor type actuator whose control input is a torque value.

Test the model with the ActiveSimulator class

The following script assumes that the XML snippet was saved in this repository as bicycle.xml and the Bicycle and BicycleController classes were saved as bicycle.py.

import os
from aiml_virtual.simulator import ActiveSimulator
from aiml_virtual.object.bicycle import BicycleController
from aiml_virtual.object import parseMovingObjects

abs_path = os.path.dirname(os.path.abspath(__file__))
xml_path = os.path.join(abs_path, "..", "xml_models")

xml_filename = "bicycle.xml"

virt_parsers = [parseMovingObjects]

simulator = ActiveSimulator(os.path.join(xml_path, xml_filename), None, 0.01, 0.02, virt_parsers, None, False)

bicycle0 = simulator.get_MovingObject_by_name_in_xml("Bicycle_0")

bicycle0_controller = BicycleController()

bicycle0.set_controllers([bicycle0_controller])

while not simulator.glfw_window_should_close():
    simulator.update()

simulator.close()

The script creates a one-element list out of the parseMovingObject function and initializes the simulator with the XML file name and the parser. Then it grabs the Bicycle instance that the parser method created, initializes and assignes the controller to it, and starts the simulation. A MovingObject can have multiple controllers and can decide for itself when to use which. In this case, the bicycle only has one controller which is what its update method assumed earlier.

As expected, because of the constant torque control input, the bicycle starts accelerating:

tut08

Generate the XML code by Python code

If the XML needs to be generated automatically, the SceneXmlGenerator class can be used. For every new object, the class can be extended with a method that generates the new object type.

The constructor of the class initializes the xml.etree.ElementTree module that will generate the XML. Let's also add a counter variable to the constructor to keep record of how many bicycles have been added to the model:

    def __init__(self, base_scene_filename):

        self.root = ET.Element("mujoco")
        ET.SubElement(self.root, "include", file=base_scene_filename)
        self.worldbody = ET.SubElement(self.root, "worldbody")
        self.contact = ET.SubElement(self.root, "contact")
        self.actuator = ET.SubElement(self.root, "actuator")
        self.sensor = ET.SubElement(self.root, "sensor")

        self._bicycle_cntr = 0

Next, let's create the method that adds the necessary XML elements to the tree:

    def add_bicycle(self, pos, quat, color):

        name = "Bicycle_" + str(self._bicycle_counter)
        self._bicycle_counter += 1

        site_name = name + "_cog"

        bicycle = ET.SubElement(self.worldbody, "body", name=name, pos=pos, quat=quat)

        ET.SubElement(bicycle, "inertial", pos="0 0 0", diaginertia=".01 .01 .01", mass="1.0")
        ET.SubElement(bicycle, "joint", name = name, type="free")
        ET.SubElement(bicycle, "site", name=site_name, pos="0 0 0")

        ET.SubElement(bicycle, "geom", name=name + "_crossbar", type="box", size=".06 .015 .02", pos="0 0 0", rgba=color)

        front_wheel_name = name + "_wheelf"
        wheelf = ET.SubElement(bicycle, "body", name=front_wheel_name)

        ET.SubElement(wheelf, "joint", name=front_wheel_name, type="hinge", pos="0.1 0 0",
                      axis="0 1 0", frictionloss="0.001", damping="0.00001", armature="0.01")
        ET.SubElement(wheelf, "geom", name=front_wheel_name, type="cylinder", size="0.04 0.015",
                      pos="0.1 0 0", euler="1.571 0 0", material="material_check")

        rear_wheel_name = name + "_wheelr"
        wheelr = ET.SubElement(bicycle, "body", name=rear_wheel_name)

        ET.SubElement(wheelr, "joint", name=rear_wheel_name, type="hinge", pos="-0.1 0 0",
                      axis="0 1 0", frictionloss="0.001", damping="0.00001", armature="0.01")
        ET.SubElement(wheelr, "geom", name=rear_wheel_name, type="cylinder", size="0.04 0.015",
                      pos="-0.1 0 0", euler="1.571 0 0", material="material_check")
        
        ET.SubElement(self.actuator, "motor", name=name + "_actr", joint=rear_wheel_name)
        ET.SubElement(self.sensor, "velocimeter", site=site_name, name=name + "_velocimeter")

This is how to use it in a script:

from aiml_virtual.simulator import ActiveSimulator
from aiml_virtual.xml_generator import SceneXmlGenerator
from aiml_virtual.object import parseMocapObjects, parseMovingObjects
import os

abs_path = os.path.dirname(os.path.abspath(__file__))
xml_path = os.path.join(abs_path, "..", "xml_models")
xml_base_filename = "scene_base.xml"
save_filename = "built_scene.xml"

scene_generator = SceneXmlGenerator(xml_base_filename)
scene_generator.add_bicycle("0 0 0", ".7 0 0 .7", "0.1 0.7 0.7 1.0")
scene_generator.save_xml(os.path.join(xml_path,save_filename))

mocap_parsers = [parseMocapObjects]
virtual_parsers = [parseMovingObjects]
simulator = ActiveSimulator(os.path.join(xml_path, save_filename), None, 0.01, 0.02, 
                            virtual_parsers, mocap_parsers, False)

while not simulator.glfw_window_should_close():
    simulator.update()

simulator.close()

This adds a bicycle to the model, that has a turquoise colored crossbar:

turquoise_bicycle

And the generated XML is the following:

<mujoco>
    <include file="scene_base.xml" />
    <worldbody>
        <body name="Bicycle_0" pos="0 0 0" quat=".7 0 0 .7">
            <inertial pos="0 0 0" diaginertia=".01 .01 .01" mass="1.0" />
            <joint name="Bicycle_0" type="free" />
            <site name="Bicycle_0_cog" pos="0 0 0" />
            <geom name="Bicycle_0_crossbar" type="box" size=".06 .015 .02" pos="0 0 0"
                rgba="0.1 0.7 0.7 1.0" />
            <body name="Bicycle_0_wheelf">
                <joint name="Bicycle_0_wheelf" type="hinge" pos="0.1 0 0" axis="0 1 0"
                    frictionloss="0.001" damping="0.00001" armature="0.01" />
                <geom name="Bicycle_0_wheelf" type="cylinder" size="0.04 0.015" pos="0.1 0 0"
                    euler="1.571 0 0" material="material_check" />
            </body>
            <body name="Bicycle_0_wheelr">
                <joint name="Bicycle_0_wheelr" type="hinge" pos="-0.1 0 0" axis="0 1 0"
                    frictionloss="0.001" damping="0.00001" armature="0.01" />
                <geom name="Bicycle_0_wheelr" type="cylinder" size="0.04 0.015" pos="-0.1 0 0"
                    euler="1.571 0 0" material="material_check" />
            </body>
        </body>
    </worldbody>
    <contact />
    <actuator>
        <motor name="Bicycle_0_actr" joint="Bicycle_0_wheelr" />
    </actuator>
    <sensor>
        <velocimeter site="Bicycle_0_cog" name="Bicycle_0_velocimeter" />
    </sensor>
</mujoco>

SceneXmlGenerator Tutorial

SceneXmlGenerator can be found in the aiml_virtual.xml_generator package which corresponds to the xml_generator directory in the aiml_virtual directory in this repository. The purpose of this class is to provide a way to programmatically generate MuJoCo MJCF models as an XML file using a set of predefined models. They are defined in the class's methods themselves which generate parts of the XML file based on the provided inputs. These models include:

  • Miniature buildings used at AIMotionLab:

    • Hospital
    • SZTAKI building
    • Post office
    • Airport
    • Parking lot
    • Obstacle poles
    • Landing zones
  • Vehicles:

    • Controlled
      • Quadcopters:
        • Crazyflie
        • Bumblebee
        • Bumblebee that has a hook hanging with 1 or 2 degrees of freedom
      • Cars:
        • Fleet1Tenth (with or without a 95cm rod sticking out of it vertically)
        • Fleet1Tenth with a trailer
    • Mocap:
      • Quadcopters:
        • Crazyflie
        • Bumblebee
        • Bumblebee with a mocap hook
      • Cars:
        • Fleet1Tenth (with or without a 95cm rod sticking out of it vertically)
        • Fleet1Tenth with a trailer
  • Simulated or mocap payloads for the bumblebee to carry:

    • Rectangular box shape
    • Teardrop shape

Usage

from aiml_virtual.xml_generator import SceneXmlGenerator

The constructor of SceneXmlGenerator expects an xml file name. This file can contain default classes, meshes, textures, materials and static objects that have a fixed position throughout the simulation. In our case, this file is xml_models/scene.xml that contains drone- and building meshes, carpet textures etc. Initially, scene.xml is displayed when scripts/load_and_display_scene.py is run. SceneXmlGenerator will "include" this file in the generated XML file as described in MuJoCo XML basics.

Initializing SceneXmlGenerator:

import os

abs_path = os.path.dirname(os.path.abspath(__file__))
xml_path = os.path.join(abs_path, "..", "xml_models")
xml_base_filename = "scene_base.xml"
save_filename = "built_scene.xml"

scene_generator = SceneXmlGenerator(xml_base_filename)

To add buildings to the model:

# the inputs must be strings in a format that MuJoCo expects
# the first is position and second is quaternion

scene_generator.add_hospital("1 1 0", "1 0 0 0")
scene_generator.add_sztaki("0 0 0", "1 0 0 0")
scene_generator.add_post_office("0 1 0", "1 0 0 0")
scene_generator.add_airport("1 0 0", "1 0 0 0")
scene_generator.add_pole("0.4 0.4 0", "1 0 0 0")

To add drones to the model:

from aiml_virtual.object.drone import DRONE_TYPES

position = "-1 1 0"
orientation = "1 0 0 0" # as quaternion
color = "0.2 0.2 0.85 1.0"

# this will be a simulated (not a mocap), blue crazyflie drone
drone0_name = scene_generator.add_drone(position, orientation, color, DRONE_TYPES.CRAZYFLIE)

position = "1 0 1"
orientation = "1 0 0 0"
color = "0.2 0.85 0.2 1.0"

# this will be a simulated (not a mocap), green bumblebee drone with a hook
drone1_name = scene_generator.add_drone(position, orientation, color, DRONE_TYPES.BUMBLEBEE_HOOKED)


position = "0 1 1"
orientation = "1 0 0 0"
color = "0.85 0.2 0.2 1.0"

# this will be a mocap, red bumblebee drone without a hook
drone2_name = scene_generator.add_mocap_drone(position, orientation, color, DRONE_TYPES.BUMBLEBEE)

To add a payload to the model:

from aiml_virtual.object.payload import PAYLOAD_TYPES

# arguments are position, size, mass, quaternion and color
scene_generator.add_payload("0 -1 0", ".1 .1 .1", ".15", "1 0 0 0", "0.1 0.1 0.9 1.0", PAYLOAD_TYPES.Box)

To save the xml to hard disk:

save_filename = "built_scene.xml"

# saving the scene as xml so that the simulator can load it
scene_generator.save_xml(os.path.join(xml_path, save_filename))

If the model is displayed, it looks like this:

tut06

And the generated XML file:

<mujoco>
    <include file="scene_base.xml" />
    <worldbody>
        <body name="hospital" pos="1 1 0" quat="1 0 0 0">
            <geom name="hospital" type="box" pos="0 0 0.445" size="0.1275 0.13 0.445"
                material="mat-hospital" />
        </body>
        <body name="sztaki" pos="0 0 0" quat="1 0 0 0">
            <geom name="sztaki" type="box" pos="0 0 0.0925" size="0.105 0.105 0.0925"
                rgba="0.8 0.8 0.8 1.0" material="mat-sztaki" />
        </body>
        <body name="post_office" pos="0 1 0" quat="1 0 0 0">
            <geom name="post_office" type="box" pos="0 0 0.205" size="0.1275 0.1275 0.205"
                material="mat-post_office" />
        </body>
        <geom name="airport" pos="1 0 0" quat="1 0 0 0" size="0.105 0.105 .05" type="plane"
            material="mat-airport" />
        <body name="pole_0" pos="0.4 0.4 0" quat="1 0 0 0">
            <geom class="pole_top" />
            <geom class="pole_bottom1" />
            <geom class="pole_bottom2" />
        </body>
        <body name="Drone_crazyflie_0" pos="-1 1 0" quat="1 0 0 0">
            <inertial pos="0 0 0" diaginertia="1.4e-5 1.4e-5 2.17e-5" mass="0.028" />
            <joint name="Drone_crazyflie_0" type="free" />
            <geom name="Drone_crazyflie_0_body" type="mesh" mesh="drone_body"
                rgba="0.2 0.2 0.85 1.0" />
            <geom name="Drone_crazyflie_0_4_motormounts" type="mesh" mesh="drone_4_motormounts"
                rgba="0.2 0.2 0.85 1.0" />
            <geom name="Drone_crazyflie_0_4_motors" type="mesh" mesh="drone_4_motors"
                rgba="0.2 0.2 0.85 1.0" />
            <site name="Drone_crazyflie_0_cog" pos="0 0 0" />
            <body name="Drone_crazyflie_0_prop1">
                <joint name="Drone_crazyflie_0_prop1" axis="0 0 1" pos="0.047 -0.047 0.032" />
                <geom name="Drone_crazyflie_0_prop1" type="mesh" mesh="drone_ccw_prop"
                    mass="0.00001" pos="0.047 -0.047 0.032" rgba="0.1 0.1 0.1 1.0"
                    euler="0 0 -0.785" />
            </body>
            <body name="Drone_crazyflie_0_prop2">
                <joint name="Drone_crazyflie_0_prop2" axis="0 0 1" pos="-0.047 -0.047 0.032" />
                <geom name="Drone_crazyflie_0_prop2" type="mesh" mesh="drone_cw_prop" mass="0.00001"
                    pos="-0.047 -0.047 0.032" rgba="0.1 0.1 0.1 1.0" euler="0 0 -0.785" />
            </body>
            <body name="Drone_crazyflie_0_prop3">
                <joint name="Drone_crazyflie_0_prop3" axis="0 0 1" pos="-0.047 0.047 0.032" />
                <geom name="Drone_crazyflie_0_prop3" type="mesh" mesh="drone_ccw_prop"
                    mass="0.00001" pos="-0.047 0.047 0.032" rgba="0.1 0.1 0.1 1.0" euler="0 0 0.785" />
            </body>
            <body name="Drone_crazyflie_0_prop4">
                <joint name="Drone_crazyflie_0_prop4" axis="0 0 1" pos="0.047 0.047 0.032" />
                <geom name="Drone_crazyflie_0_prop4" type="mesh" mesh="drone_cw_prop" mass="0.00001"
                    pos="0.047 0.047 0.032" rgba="0.1 0.1 0.1 1.0" euler="0 0 0.785" />
            </body>
        </body>
        <body name="DroneHooked_bumblebee_0" pos="1 0 1" quat="1 0 0 0">
            <inertial pos="0 0 0" diaginertia="1.5e-3 1.45e-3 2.66e-3" mass="0.605" />
            <joint name="DroneHooked_bumblebee_0" type="free" />
            <geom name="DroneHooked_bumblebee_0_body" pos="0.0132 0 0" type="mesh"
                quat="-0.7071067811865475 -0.0 0.0 0.7071067811865476" mesh="drone_body_large"
                rgba="0.2 0.85 0.2 1.0" />
            <site name="DroneHooked_bumblebee_0_cog" pos="0 0 0" />
            <body name="DroneHooked_bumblebee_0_rod" pos="0 0 0">
                <geom type="cylinder" fromto="0 0 0  0 0 -0.4" size="0.005" mass="0.00" />
                <site name="DroneHooked_bumblebee_0_rod_end" pos="0 0 -0.4" type="sphere"
                    size="0.002" />
                <joint name="DroneHooked_bumblebee_0_hook_y" axis="0 1 0" pos="0 0 0"
                    damping="0.001" />
                <body name="DroneHooked_bumblebee_0_hook" pos="0 0 -0.4" euler="0 3.141592 -1.57">
                    <geom type="capsule" pos="0 0.01299 0.0475" euler="-1.0472 0 0"
                        size="0.005 0.018" mass="0.0001" />
                    <geom type="capsule" pos="0 0 0.02" size="0.005 0.02" mass="0.01" />
                    <geom type="capsule" pos="0 0.02598 0.07" euler="0 0 0" size="0.005 0.018"
                        mass="0.0001" />
                    <geom type="capsule" pos="0 0.01299 0.0925" euler="1.0472 0 0"
                        size="0.005 0.018" mass="0.0001" />
                    <geom type="capsule" pos="0 -0.01299 0.0925" euler="2.0944 0 0"
                        size="0.005 0.018" mass="0.0001" />
                </body>
            </body>
            <body name="DroneHooked_bumblebee_0_prop1">
                <joint name="DroneHooked_bumblebee_0_prop1" axis="0 0 1" pos="0.091 -0.087 0.036" />
                <geom name="DroneHooked_bumblebee_0_prop1" type="mesh" mesh="drone_ccw_prop_large"
                    mass="0.00001" pos="0.091 -0.087 0.036" rgba="0.1 0.02 0.5 1.0" />
            </body>
            <site name="DroneHooked_bumblebee_0_prop1" pos="0.091 -0.087 0.036" />
            <body name="DroneHooked_bumblebee_0_prop2">
                <joint name="DroneHooked_bumblebee_0_prop2" axis="0 0 1" pos="-0.074 -0.087 0.036" />
                <geom name="DroneHooked_bumblebee_0_prop2" type="mesh" mesh="drone_cw_prop_large"
                    mass="0.00001" pos="-0.074 -0.087 0.036" rgba="0.1 0.02 0.5 1.0" />
            </body>
            <site name="DroneHooked_bumblebee_0_prop2" pos="-0.074 -0.087 0.036" />
            <body name="DroneHooked_bumblebee_0_prop3">
                <joint name="DroneHooked_bumblebee_0_prop3" axis="0 0 1" pos="-0.074 0.087 0.036" />
                <geom name="DroneHooked_bumblebee_0_prop3" type="mesh" mesh="drone_ccw_prop_large"
                    mass="0.00001" pos="-0.074 0.087 0.036" rgba="0.1 0.02 0.5 1.0" />
            </body>
            <site name="DroneHooked_bumblebee_0_prop3" pos="-0.074 0.087 0.036" />
            <body name="DroneHooked_bumblebee_0_prop4">
                <joint name="DroneHooked_bumblebee_0_prop4" axis="0 0 1" pos="0.091 0.087 0.036" />
                <geom name="DroneHooked_bumblebee_0_prop4" type="mesh" mesh="drone_cw_prop_large"
                    mass="0.00001" pos="0.091 0.087 0.036" rgba="0.1 0.02 0.5 1.0" />
            </body>
            <site name="DroneHooked_bumblebee_0_prop4" pos="0.091 0.087 0.036" />
        </body>
        <body name="DroneMocap_bumblebee_0" pos="0 1 1" quat="1 0 0 0" mocap="true">
            <geom name="DroneMocap_bumblebee_0_body" pos="0.0132 0 0" type="mesh"
                quat="-0.7071067811865475 -0.0 0.0 0.7071067811865476" mesh="drone_body_large"
                rgba="0.85 0.2 0.2 1.0" />
            <geom type="box" size="0.0475 0.025 0.025" pos="0.01 0 -0.02" rgba="0.85 0.2 0.2 1.0" />
            <body name="DroneMocap_bumblebee_0_prop1">
                <joint name="DroneMocap_bumblebee_0_prop1" axis="0 0 1" pos="-0.074 0.087 0.036" />
                <geom name="DroneMocap_bumblebee_0_prop1" type="mesh" mesh="drone_ccw_prop_large"
                    pos="-0.074 0.087 0.036" rgba="0.1 0.1 0.1 1.0" />
            </body>
            <body name="DroneMocap_bumblebee_0_prop2">
                <joint name="DroneMocap_bumblebee_0_prop2" axis="0 0 1" pos="0.091 -0.087 0.036" />
                <geom name="DroneMocap_bumblebee_0_prop2" type="mesh" mesh="drone_ccw_prop_large"
                    pos="0.091 -0.087 0.036" rgba="0.1 0.1 0.1 1.0" />
            </body>
            <body name="DroneMocap_bumblebee_0_prop3">
                <joint name="DroneMocap_bumblebee_0_prop3" axis="0 0 1" pos="0.091 0.087 0.036" />
                <geom name="DroneMocap_bumblebee_0_prop3" type="mesh" mesh="drone_cw_prop_large"
                    pos="0.091 0.087 0.036" rgba="0.1 0.1 0.1 1.0" />
            </body>
            <body name="DroneMocap_bumblebee_0_prop4">
                <joint name="DroneMocap_bumblebee_0_prop4" axis="0 0 1" pos="-0.074 -0.087 0.036" />
                <geom name="DroneMocap_bumblebee_0_prop4" type="mesh" mesh="drone_cw_prop_large"
                    pos="-0.074 -0.087 0.036" rgba="0.1 0.1 0.1 1.0" />
            </body>
        </body>
        <body name="Payload_0" pos="0 -1 0" quat="1 0 0 0">
            <geom name="Payload_0" type="box" size=".1 .1 .1" pos="0 0 .1" mass=".15"
                rgba="0.1 0.1 0.9 1.0" />
            <joint name="Payload_0" type="free" />
            <body name="Payload_0_hook" pos="0 0 0.2" euler="0 0 3">
                <geom type="capsule" pos="0 0 0.02" size="0.002 0.02" mass="0.0001" />
                <geom type="capsule" pos="0 0.01173 0.04565" euler="-1.12200 0 0"
                    size="0.004 0.01562" mass="0.0001" />
                <geom type="capsule" pos="0 0.01061 0.04439" euler="-1.17810 0 0"
                    size="0.004 0.01378" mass="0.0001" />
                <geom type="capsule" pos="0 0.02561 0.05939" euler="-0.39270 0 0"
                    size="0.004 0.01378" mass="0.0001" />
                <geom type="capsule" pos="0 0.02561 0.08061" euler="0.39270 0 0"
                    size="0.004 0.01378" mass="0.0001" />
                <geom type="capsule" pos="0 0.01061 0.09561" euler="1.17810 0 0"
                    size="0.004 0.01378" mass="0.0001" />
                <geom type="capsule" pos="0 -0.01061 0.09561" euler="1.96350 0 0"
                    size="0.004 0.01378" mass="0.0001" />
                <geom type="capsule" pos="0 -0.02561 0.08061" euler="2.74889 0 0"
                    size="0.004 0.01378" mass="0.0001" />
            </body>
        </body>
    </worldbody>
    <contact />
    <actuator>
        <general joint="Drone_crazyflie_0_prop1" name="Drone_crazyflie_0_actr1"
            gear=" 0 0 1 0 0 0.02514" ctrllimited="true" ctrlrange="0 0.16" />
        <general joint="Drone_crazyflie_0_prop2" name="Drone_crazyflie_0_actr2"
            gear=" 0 0 1 0 0 -0.02514" ctrllimited="true" ctrlrange="0 0.16" />
        <general joint="Drone_crazyflie_0_prop3" name="Drone_crazyflie_0_actr3"
            gear=" 0 0 1 0 0 0.02514" ctrllimited="true" ctrlrange="0 0.16" />
        <general joint="Drone_crazyflie_0_prop4" name="Drone_crazyflie_0_actr4"
            gear=" 0 0 1 0 0 -0.02514" ctrllimited="true" ctrlrange="0 0.16" />
        <general site="DroneHooked_bumblebee_0_prop1" name="DroneHooked_bumblebee_0_actr1"
            gear=" 0 0 1 0 0 0.5954" ctrllimited="true" ctrlrange="0 15" />
        <general site="DroneHooked_bumblebee_0_prop2" name="DroneHooked_bumblebee_0_actr2"
            gear=" 0 0 1 0 0 -0.5954" ctrllimited="true" ctrlrange="0 15" />
        <general site="DroneHooked_bumblebee_0_prop3" name="DroneHooked_bumblebee_0_actr3"
            gear=" 0 0 1 0 0 0.5954" ctrllimited="true" ctrlrange="0 15" />
        <general site="DroneHooked_bumblebee_0_prop4" name="DroneHooked_bumblebee_0_actr4"
            gear=" 0 0 1 0 0 -0.5954" ctrllimited="true" ctrlrange="0 15" />
    </actuator>
    <sensor>
        <gyro site="Drone_crazyflie_0_cog" name="Drone_crazyflie_0_gyro" />
        <velocimeter site="Drone_crazyflie_0_cog" name="Drone_crazyflie_0_velocimeter" />
        <accelerometer site="Drone_crazyflie_0_cog" name="Drone_crazyflie_0_accelerometer" />
        <framepos objtype="site" objname="Drone_crazyflie_0_cog" name="Drone_crazyflie_0_posimeter" />
        <framequat objtype="site" objname="Drone_crazyflie_0_cog" name="Drone_crazyflie_0_orimeter" />
        <frameangacc objtype="site" objname="Drone_crazyflie_0_cog"
            name="Drone_crazyflie_0_ang_accelerometer" />
        <jointvel joint="DroneHooked_bumblebee_0_hook_y"
            name="DroneHooked_bumblebee_0_hook_jointvel_y" />
        <jointpos joint="DroneHooked_bumblebee_0_hook_y"
            name="DroneHooked_bumblebee_0_hook_jointpos_y" />
        <framepos objtype="site" objname="DroneHooked_bumblebee_0_rod_end"
            name="DroneHooked_bumblebee_0_hook_pos" />
        <framelinvel objtype="site" objname="DroneHooked_bumblebee_0_rod_end"
            name="DroneHooked_bumblebee_0_hook_vel" />
        <framequat objtype="site" objname="DroneHooked_bumblebee_0_rod_end"
            name="DroneHooked_bumblebee_0_hook_quat" />
        <frameangvel objtype="site" objname="DroneHooked_bumblebee_0_rod_end"
            name="DroneHooked_bumblebee_0_hook_angvel" />
        <gyro noise="0.0027" site="DroneHooked_bumblebee_0_cog" name="DroneHooked_bumblebee_0_gyro" />
        <velocimeter noise="0.00078" site="DroneHooked_bumblebee_0_cog"
            name="DroneHooked_bumblebee_0_velocimeter" />
        <accelerometer site="DroneHooked_bumblebee_0_cog"
            name="DroneHooked_bumblebee_0_accelerometer" />
        <framepos noise="0.00014" objtype="site" objname="DroneHooked_bumblebee_0_cog"
            name="DroneHooked_bumblebee_0_posimeter" />
        <framequat noise="0.00026" objtype="site" objname="DroneHooked_bumblebee_0_cog"
            name="DroneHooked_bumblebee_0_orimeter" />
        <frameangacc objtype="site" objname="DroneHooked_bumblebee_0_cog"
            name="DroneHooked_bumblebee_0_ang_accelerometer" />
        <framepos objtype="body" objname="Payload_0" name="Payload_0_posimeter" />
        <framequat objtype="body" objname="Payload_0" name="Payload_0_orimeter" />
    </sensor>
</mujoco>
⚠️ **GitHub.com Fallback** ⚠️