Brief introduction to mujoco or gym modeling using xml
To build an environment that can be used for mujoco and gym, there are two main method. First you can build the model by writing a xml file, the second is building CAD model using 3D desigining software such as solidworks, then generate urdf file relying some extended tools of solidworks, last you can convert the urdf file to xml file by using related mujoco tools such as the following code(urdf method):
$./compile /path/to/model.urdf /path/to/model.xml
In this blog, i will take the first method. Firstly, you need prepare related stl file and texture file.
I want build my environment based on fetch env of gym, so I put my stl file under this path: "~/gym/gym/envs/robotics/assets/stls/fetch". I added chair related models such as "chair_seat.STL", and "chair_leg.STL". In path "~/gym/gym/envs/robotics/assets/textures", I added a png file named "light_wood.png". Final contents look like the following picture:
Then you can use these file in your xml description file, I added a xml file named "pick_assembly.xml" under path "~/gym/gym/envs/robotics/assets/fetch". Some key comment had been added in the description file.
<?xml version="1.0" encoding="utf-8"?>
<mujoco>
<compiler angle="radian" coordinate="local" meshdir="../stls/fetch" texturedir="../textures"></compiler><!--place you stl or texture png file in this path-->
<option timestep="0.002">
<flag warmstart="enable"></flag>
</option>
<include file="shared.xml"></include>
<!--add some assert -->
<asset>
<texture file="light-wood.png" type="cube" name="light-wood" />
<mesh file="chair_seat.STL" scale="0.001 0.001 0.001" name="chair_seat_mesh"/>
<mesh file="chair_leg.STL" scale="0.001 0.001 0.001" name="chair_leg_mesh"/>
<material name="MatLightWood" texture="light-wood" texrepeat="3 3" specular="0.4" shininess="0.1" />
</asset>
<worldbody>
<!--visulize x,y,and z axes-->
<site name="x_axes" pos="0.5 0 0" size="0.5 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="y_axes" pos="0 0.5 0" size="0.01 0.5 0.01" rgba="0 1 0 1" type="box"></site>
<site name="z_axes" pos="0 0 0.5" size="0.01 0.01 0.5" rgba="0 0 1 1" type="box"></site>
<!--load floor-->
<geom name="floor0" pos="0.8 0.2 0" size="1.2 1.4 1" type="plane" condim="3" material="floor_mat"></geom>
<body name="floor0" pos="0.8 0.2 0">
<site name="floor0x" pos="0.04 0 0" size="0.04 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="floor0y" pos="0 0.04 0" size="0.01 0.04 0.01" rgba="0 1 0 1" type="box"></site>
<site name="floor0z" pos="0 0 0.04" size="0.01 0.01 0.04" rgba="0 0 1 1" type="box"></site>
</body>
<!--load chair parts-->
<!--load seat-->
<body pos="0 0.8 0" name="chair_seat">
<joint name="chair_seat:joint" type="free" damping="0.01"></joint>
<geom mesh="chair_seat_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="MatLightWood"/>
<site name="chair_seat_x_axes" pos="0.1 0 0" size="0.1 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="chair_seat_y_axes" pos="0 0.1 0" size="0.01 0.1 0.01" rgba="0 1 0 1" type="box"></site>
<site name="chair_seat_z_axes" pos="0 0 0.1" size="0.01 0.01 0.1" rgba="0 0 1 1" type="box"></site>
</body>
<!--load leg0-->
<body pos="0 1.45 0" name="chair_leg0">
<joint name="chair_leg0:joint" type="free" damping="0.01"></joint>
<geom mesh="chair_leg_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="MatLightWood"/>
<site name="chair_leg0_x_axes" pos="0.1 0 0" size="0.1 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="chair_leg0_y_axes" pos="0 0.1 0" size="0.01 0.1 0.01" rgba="0 1 0 1" type="box"></site>
<site name="chair_leg0_z_axes" pos="0 0 0.1" size="0.01 0.01 0.1" rgba="0 0 1 1" type="box"></site>
</body>
<!--load leg1-->
<body pos="0.2 1.45 0" name="chair_leg1">
<joint name="chair_leg1:joint" type="free" damping="0.01"></joint>
<geom mesh="chair_leg_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="MatLightWood"/>
<site name="chair_leg1_x_axes" pos="0.1 0 0" size="0.1 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="chair_leg1_y_axes" pos="0 0.1 0" size="0.01 0.1 0.01" rgba="0 1 0 1" type="box"></site>
<site name="chair_leg1_z_axes" pos="0 0 0.1" size="0.01 0.01 0.1" rgba="0 0 1 1" type="box"></site>
</body>
<!--load leg2-->
<body pos="0.4 1.45 0" name="chair_leg2">
<joint name="chair_leg2:joint" type="free" damping="0.01"></joint>
<geom mesh="chair_leg_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="MatLightWood"/>
<site name="chair_leg2_x_axes" pos="0.1 0 0" size="0.1 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="chair_leg2_y_axes" pos="0 0.1 0" size="0.01 0.1 0.01" rgba="0 1 0 1" type="box"></site>
<site name="chair_leg2_z_axes" pos="0 0 0.1" size="0.01 0.01 0.1" rgba="0 0 1 1" type="box"></site>
</body>
<!--load leg3-->
<body pos="0.6 1.45 0" name="chair_leg3">
<joint name="chair_leg3:joint" type="free" damping="0.01"></joint>
<geom mesh="chair_leg_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="MatLightWood"/>
<site name="chair_leg3_x_axes" pos="0.1 0 0" size="0.1 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="chair_leg3_y_axes" pos="0 0.1 0" size="0.01 0.1 0.01" rgba="0 1 0 1" type="box"></site>
<site name="chair_leg3_z_axes" pos="0 0 0.1" size="0.01 0.01 0.1" rgba="0 0 1 1" type="box"></site>
</body>
<!--load fetch robot-->
<include file="robot.xml"></include>
<!--load table-->
<body pos="1.3 0.2 0.2" name="table0">
<geom size="0.5 0.7 0.2" type="box" mass="2000" material="table_mat" rgba="1 1 1 0.5"></geom>
<site name="table0_x_axes" pos="0.1 0 0" size="0.1 0.01 0.01" rgba="1 0 0 1" type="box"></site>
<site name="table0_y_axes" pos="0 0.1 0" size="0.01 0.1 0.01" rgba="0 1 0 1" type="box"></site>
<site name="table0_z_axes" pos="0 0 0.1" size="0.01 0.01 0.1" rgba="0 0 1 1" type="box"></site>
</body>
<!--load test box-->
<body name="object0" pos="0.025 -0.025 0.025">
<joint name="object0:joint" type="free" damping="0.01"></joint>
<geom size="0.025 0.025 0.025" type="box" condim="3" name="object0" material="block_mat" mass="2"></geom>
<site name="object0" pos="0 0 0" size="0.02 0.02 0.02" rgba="1 0 0 1" type="sphere"></site>
</body>
<light directional="true" ambient="0.2 0.2 0.2" diffuse="0.8 0.8 0.8" specular="0.3 0.3 0.3" castshadow="false" pos="0 0 4" dir="0 0 -1" name="light0"></light>
</worldbody>
<actuator>
<position ctrllimited="true" ctrlrange="0 0.2" joint="robot0:l_gripper_finger_joint" kp="30000" name="robot0:l_gripper_finger_joint" user="1"></position>
<position ctrllimited="true" ctrlrange="0 0.2" joint="robot0:r_gripper_finger_joint" kp="30000" name="robot0:r_gripper_finger_joint" user="1"></position>
</actuator>
</mujoco>
If you follow my steps, then you can test it in your terminal by using the following command:
cd ~/.mujoco/mojoco/bin
./simulate ~/your path/gym/gym/envs/robotics/assets/fetch/pick_assembly.xml
In my PC, this command is "./simulate /home/kai/GraphGuidedAssembly/gym/gym/envs/robotics/assets/fetch/pick_assembly.xml". Then you will get the following result:
In your simulation, it will be your stl model.
Then, let's made a short introduction to this xml file.
file named "shared.xml" included some common variables that will be used in this xml file such as "material="block_mat"" in "<!--load test box-->" part.
related part in shared.xml is as shown in the following:
Then I added some assets variables that will be ued in the following part. including " name="MatLightWood" ", " name="chair_seat_mesh" ". In this part, your xml file was loaded. But you must focuse the paramter of scale(<mesh file="chair_seat.STL" scale="0.001 0.001 0.001" name="chair_seat_mesh"/>), if you did not set this parameter, your model will looks huge or abnormal.
"<worldbody> ... </worldbody>" is the global coordinate system. I visulized it(x axes: red, y axes: green, z axes: blue) by using three site class of the kinematic trees of mujoco(mujoco kinematic tree). And coordinates defined in "<body> ... </body>" will be a local coordinate frame.
some key class of kinematic trees of mujoco was copied from the mojoco kinematic website:
Body
Bodies have mass and inertial properties but do not have any geometric properties. Instead geometric shapes (or geoms) are attached to the bodies. Each body has two coordinate frames: the frame used to define it as well as to position other elements relative to it, and an inertial frame centered at the body's center of mass and aligned with its principal axes of inertia. The body inertia matrix is therefore diagonal in this frame. At each time step MuJoCo computes the forward kinematics recursively, yielding all body positions and orientations in global Cartesian coordinates. This provides the basis for all subsequent computations.
Joint
Joints are defined within bodies. They create motion degrees of freedom (DOFs) between the body and its parent. In the absence of joints the body is welded to its parent. This is the opposite of gaming engines which use over-complete Cartesian coordinates, where joints remove DOFs instead of adding them. There are four types of joints: ball, slide, hinge, and a free "joint" which creates floating bodies. A single body can have multiple joints. In this way composite joints are created automatically, without having to define dummy bodies. The orientation components of ball and free joints are represented as unit quaternions, and all computations in MuJoCo respect the properties of quaternions.
Geom
Geoms are 3D shapes rigidly attached to the bodies. Multiple geoms can be attached to the same body. This is particularly useful in light of the fact that MuJoCo only supports convex geom-geom collisions, and the only way to create non-convex objects is to represent them as a union of convex geoms. Apart from collision detection and subsequent computation of contact forces, geoms are used for rendering, as well as automatic inference of body masses and inertias when the latter are omitted. MuJoCo supports several primitive geometric shapes: plane, sphere, capsule, ellipsoid, cylinder, box. A geom can also be a mesh or a height field; this is done by referencing the corresponding asset. Geoms have a number of material properties that affect the simulation and visualization.
Site
Sites are essentially light geoms. They represent locations of interest within the body frame. Sites do not participate in collision detection or automated computation of inertial properties, however they can be used to specify the spatial properties of other objects: sensors, tendon routing, slider-crank endpoints.
Light
Lights can be fixed to the world body or attached to moving bodies. The visualizer provides access to the full lighting model in OpenGL (fixed function) including ambient, diffuse and specular components, attenuation and cutoff, positional and directional lighting, fog. Lights, or rather the objects illuminated by them, can also cast shadows. However, similar to material reflections, each shadow-casting light adds one rendering pass so this feature should be used with caution. Documenting the lighting model in detail is beyond the scope of this chapter; see OpenGL documentation instead. Note that in addition to lights defined by the user in the kinematic tree, there is a default headlight that moves with the camera. Its properties are adjusted through the mjVisual options.
This blog is a basic modeling description, if there are some wrong points, your opinion would be welcomed!