MuJoCo Document - THU-DA-Robotics/wiki GitHub Wiki
This page contains
- things not well described in the official document.
- things that are important but hard to notice in the official document.
- issues/problems we met (and solutions).
-
mjcf
andurdf
use different default values forjoint/axis
.mjcf
uses[0, 0, 1]
whileurdf
uses[1, 0, 0]
. - quaternions are in
w, x, y, z
order. - (Understanding xml kinematics) Take
body
as an example. Ifbody/pos
andbody/quat
form 4x4 transformationT1
, and the (composite) joint form 4x4 transformationT2
. Then the 4x4 transformation from child body to parent body isT1*T2
.
Set model.site_pos
instead of mjData.site_xpos
. mjData
is all about non persistent stuff and gets overwritten at every mj_step
. Ref
# in python script
viewer = mujoco.viewer.launch_passive(model, data)
viewer.cam.azimuth / distance / elevation / ... = ...
Changing the setting in the xml file seems not work.
In the xml file:
<visual>
<global offwidth="xxx" offheight="xxx"/>
</visual>
In python script:
renderer = mujoco.Renderer(model, <height>, <width>)
# for each frame
renderer.update_scene(data, camera=<camera_name>)
# --- rgb image -
rgb_image = renderer.render()
# --- depth image ---
renderer.enable_depth_rendering()
depth_image = renderer.render()
renderer.disable_depth_rendering()
# --- segmentation image ---
renderer.enable_segmentation_rendering()
seg_image = renderer.render()
renderer.disable_segmentation_rendering()
The camera intrinsic parameters can be calculated from the camera's fovy and image size. The camera extrinsic parameters can be calculated from the camera's position and quaternion. (Note: the image frame in Mujoco uses the definition of OpenGL, which is x-right, y-up, and z-out-of-image-plane.)
-
API
mj_applyFT
applies spatial force/torque to a specific body, and is the combination of multiplying force/torque bymj_jac
and settingmjData.qfrc_applied
with the results. Among the parameters, force[3], torque[3], point[3] are all in global corrdinates (NOTE: not relative to the link frame, although point is assumed to be fixed on that link). Do not call mj_applyFT multiple times without clearing mjData.qfrc_applied, since the applied force/torque would accumulate. (Reported by Yongpeng Jiang) -
The tag
body/euler
followsXYZ
intrinsic euler actually. (Reported by Yongpeng Jiang)
- You may encounter stack overflow when simulating too many bodies simultaneously. You can adjust the size of memory allocation to address this issue. Read more about
size/njmax
andsize/nstack
in theXML Reference
. (Reported by Yongpeng Jiang)
- Mujoco is not well suited for visualization (much worse than RViz). You can only use built-in types for visualization (i.e., contact points/forces, joints, frames and so on) and specify the hyper-parameters like sizes in the xml. You can not visualize anything not included in the xml (which you can visualize from topics in ROS ar run-time). (Reported by Yongpeng Jiang)
- There is no official ROS interface, but many folk versions exist. Among them, I recommend mujoco_ros_pkgs. You can try others such as shadow-robot version. I strongly recommend to hand craft your own for special purposes (i.e., ROS2), since many third party interfaces are still under construction, or not well documented.
- You might use Pytorch Kinematics to parse xml
- Not all XML tags are supported. For example,
mujocoinclude
,default
will be omitted or throw exceptions. (Reported by Yongpeng Jiang) - Only
body/quat
is supported for specifying orientation.body/euler
,body/axisangle
will be omitted and result in Identity rotmat. (Reported by Yongpeng Jiang)