├── README.md
├── assets
└── 2RRobot.jpg
├── MujocoModeling
├── terrain.png
├── MUJOCO_LOG.TXT
├── XMLReference.ipynb
├── MujocoPhysics.ipynb
└── xmlExamples.ipynb
└── MujocoControl
├── CartPoleControlMujoco.ipynb
└── MujocoControl.ipynb
/README.md:
--------------------------------------------------------------------------------
1 | # Mujoco Tutorial
2 |
--------------------------------------------------------------------------------
/assets/2RRobot.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/clearlab-sustech/MujocoTutorial/HEAD/assets/2RRobot.jpg
--------------------------------------------------------------------------------
/MujocoModeling/terrain.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/clearlab-sustech/MujocoTutorial/HEAD/MujocoModeling/terrain.png
--------------------------------------------------------------------------------
/MujocoModeling/MUJOCO_LOG.TXT:
--------------------------------------------------------------------------------
1 | Mon Sep 30 23:21:42 2024
2 | WARNING: Nan, Inf or huge value in QACC at DOF 0. The simulation is unstable. Time = 0.0260.
3 |
4 | Mon Sep 30 23:22:14 2024
5 | WARNING: Nan, Inf or huge value in QACC at DOF 0. The simulation is unstable. Time = 0.0360.
6 |
7 | Mon Sep 30 23:22:51 2024
8 | WARNING: Nan, Inf or huge value in QACC at DOF 0. The simulation is unstable. Time = 0.0160.
9 |
10 |
--------------------------------------------------------------------------------
/MujocoControl/CartPoleControlMujoco.ipynb:
--------------------------------------------------------------------------------
1 | {
2 | "cells": [
3 | {
4 | "cell_type": "markdown",
5 | "metadata": {},
6 | "source": [
7 | "# Example of cart pole simulation in Mujoco\n",
8 | "*****************************************************************\n",
9 | " Copyright © 2025 [Wei Zhang/CLEAR Lab]. All Rights Reserved.\n",
10 | "\n",
11 | "********************************************************************\n",
12 | "This tutorial introduces how to set up closed-loop control system for a simple cart pole systems in Mujoco. \n",
13 | "\n",
14 | "First, let's create the cart pole model"
15 | ]
16 | },
17 | {
18 | "cell_type": "code",
19 | "execution_count": null,
20 | "metadata": {},
21 | "outputs": [],
22 | "source": [
23 | "import mujoco\n",
24 | "import mediapy as media\n",
25 | "import numpy as np\n",
26 | "\n",
27 | "import mujoco.viewer as viewer\n",
28 | "modelxml = \"\"\"\n",
29 | "\n",
30 | " \n",
31 | " \n",
32 | " \n",
33 | " \n",
34 | " \n",
35 | " \n",
36 | " \n",
37 | " \n",
38 | " \n",
39 | " \n",
40 | " \n",
41 | " \n",
42 | " \n",
47 | " \n",
48 | " \n",
49 | " \n",
50 | " \n",
51 | " \n",
52 | " \n",
53 | " \n",
54 | " \n",
55 | " \n",
56 | " \n",
57 | " \n",
58 | " \n",
59 | " \n",
60 | " \n",
61 | " \n",
62 | " \n",
63 | " \n",
64 | " \n",
65 | " \n",
66 | " \n",
67 | " \n",
68 | " \n",
69 | " \n",
70 | " \n",
71 | " \n",
72 | "\n",
73 | "\"\"\"\n",
74 | "model = mujoco.MjModel.from_xml_string(modelxml)\n",
75 | "data = mujoco.MjData(model)\n"
76 | ]
77 | },
78 | {
79 | "cell_type": "markdown",
80 | "metadata": {},
81 | "source": [
82 | "## define controller"
83 | ]
84 | },
85 | {
86 | "cell_type": "code",
87 | "execution_count": 2,
88 | "metadata": {},
89 | "outputs": [],
90 | "source": [
91 | "# define customized controller which returns the feedback control action\n",
92 | "# you can implement your controller here \n",
93 | "def myControl(model, data):\n",
94 | " x = np.hstack((data.qpos,data.qvel))\n",
95 | " xref = np.array([0, np.pi, 0, 0])\n",
96 | " x_error = x-xref\n",
97 | " K = np.array([-0.5, 0.5, 0, 0])\n",
98 | " u = K@x_error\n",
99 | " data.ctrl = u\n",
100 | " return u\n",
101 | " "
102 | ]
103 | },
104 | {
105 | "cell_type": "markdown",
106 | "metadata": {},
107 | "source": [
108 | "## Simulate the closed-loop system"
109 | ]
110 | },
111 | {
112 | "cell_type": "code",
113 | "execution_count": 4,
114 | "metadata": {},
115 | "outputs": [],
116 | "source": [
117 | "import mujoco.viewer as viewer\n",
118 | "import time\n",
119 | "\n",
120 | "mujoco.mj_resetDataKeyframe(model, data, 0) # Reset the state to keyframe 0\n",
121 | "\n",
122 | "# \n",
123 | "with viewer.launch_passive(model, data) as viewer: \n",
124 | " # launch_passive means all the simulation should be done by the user \n",
125 | " \n",
126 | " start = time.time()\n",
127 | " while viewer.is_running() and time.time() - start < 10:\n",
128 | " step_start = time.time()\n",
129 | " data.ctrl = 0.2*myControl(model,data)\n",
130 | " mujoco.mj_step(model, data)\n",
131 | "\n",
132 | " # let viewer show updated info\n",
133 | " viewer.sync()\n",
134 | " \n",
135 | " # # make sure the while loop is called every sampling period \n",
136 | " # computation inside the loop may take some nontrivial time. \n",
137 | " time_until_next_step = model.opt.timestep - (time.time() - step_start)\n",
138 | " if time_until_next_step > 0:\n",
139 | " time.sleep(time_until_next_step)"
140 | ]
141 | }
142 | ],
143 | "metadata": {
144 | "kernelspec": {
145 | "display_name": "sp25",
146 | "language": "python",
147 | "name": "python3"
148 | },
149 | "language_info": {
150 | "codemirror_mode": {
151 | "name": "ipython",
152 | "version": 3
153 | },
154 | "file_extension": ".py",
155 | "mimetype": "text/x-python",
156 | "name": "python",
157 | "nbconvert_exporter": "python",
158 | "pygments_lexer": "ipython3",
159 | "version": "3.13.2"
160 | }
161 | },
162 | "nbformat": 4,
163 | "nbformat_minor": 2
164 | }
165 |
--------------------------------------------------------------------------------
/MujocoControl/MujocoControl.ipynb:
--------------------------------------------------------------------------------
1 | {
2 | "cells": [
3 | {
4 | "cell_type": "markdown",
5 | "metadata": {},
6 | "source": [
7 | "# Mujoco Control \n",
8 | "*****************************************************************\n",
9 | " Copyright © 2025 [Wei Zhang/CLEAR Lab]. All Rights Reserved.\n",
10 | "\n",
11 | "********************************************************************\n",
12 | "This tutorial introduces how to set up closed-loop control system for multi-body robotic systems in Mujoco. \n"
13 | ]
14 | },
15 | {
16 | "cell_type": "code",
17 | "execution_count": null,
18 | "metadata": {},
19 | "outputs": [],
20 | "source": [
21 | "import mujoco\n",
22 | "import mediapy as media\n",
23 | "import numpy as np\n",
24 | "\n",
25 | "import mujoco.viewer as viewer\n",
26 | "modelxml = \"\"\"\n",
27 | "\n",
28 | " \n",
29 | " \n",
30 | " \n",
31 | " \n",
32 | " \n",
33 | " \n",
34 | " \n",
35 | " \n",
36 | " \n",
37 | " \n",
38 | " \n",
39 | " \n",
40 | " \n",
45 | " \n",
46 | " \n",
47 | " \n",
48 | " \n",
49 | " \n",
50 | " \n",
51 | " \n",
52 | " \n",
53 | " \n",
54 | " \n",
55 | " \n",
56 | " \n",
57 | " \n",
58 | " \n",
59 | " \n",
60 | " \n",
61 | " \n",
62 | " \n",
63 | " \n",
64 | " \n",
65 | " \n",
66 | " \n",
67 | " \n",
68 | " \n",
69 | " \n",
70 | "\n",
71 | "\"\"\"\n",
72 | "model = mujoco.MjModel.from_xml_string(modelxml)\n",
73 | "data = mujoco.MjData(model)\n",
74 | "mujoco.mj_resetDataKeyframe(model, data, 0)\n",
75 | "viewer.launch(model,data)"
76 | ]
77 | },
78 | {
79 | "cell_type": "markdown",
80 | "metadata": {},
81 | "source": [
82 | "### Simulatioin of open-loop resposne \n",
83 | "now let's simulate the physics\n"
84 | ]
85 | },
86 | {
87 | "cell_type": "code",
88 | "execution_count": null,
89 | "metadata": {},
90 | "outputs": [],
91 | "source": [
92 | "duration = 3 # (seconds)\n",
93 | "framerate = 30 # (Hz)\n",
94 | "\n",
95 | "# Simulate and display video.\n",
96 | "frames = []\n",
97 | "mujoco.mj_resetDataKeyframe(model, data, 0) # Reset the state to keyframe 0\n",
98 | "with mujoco.Renderer(model) as renderer:\n",
99 | " while data.time < duration:\n",
100 | " mujoco.mj_step(model, data)\n",
101 | " if len(frames) < data.time * framerate:\n",
102 | " renderer.update_scene(data)\n",
103 | " pixels = renderer.render()\n",
104 | " frames.append(pixels)\n",
105 | "media.show_video(frames, fps=framerate, codec='gif')"
106 | ]
107 | },
108 | {
109 | "cell_type": "code",
110 | "execution_count": 3,
111 | "metadata": {},
112 | "outputs": [],
113 | "source": [
114 | "# define customized controller which returns the feedback control action\n",
115 | "# if we want to use control callback, we need to set data.ctrl, the returned value does not matter in this case\n",
116 | "def myControl(model, data):\n",
117 | " x = np.hstack((data.qpos,data.qvel))\n",
118 | " xref = np.array([0, np.pi, 0, 0])\n",
119 | " x_error = x-xref\n",
120 | " K = np.array([-0.5, 0.5, 0, 0])\n",
121 | " u = K@x_error\n",
122 | " data.ctrl = u\n",
123 | " return u\n",
124 | " "
125 | ]
126 | },
127 | {
128 | "cell_type": "code",
129 | "execution_count": 4,
130 | "metadata": {},
131 | "outputs": [
132 | {
133 | "ename": "",
134 | "evalue": "",
135 | "output_type": "error",
136 | "traceback": [
137 | "\u001b[1;31m在当前单元格或上一个单元格中执行代码时 Kernel 崩溃。\n",
138 | "\u001b[1;31m请查看单元格中的代码,以确定故障的可能原因。\n",
139 | "\u001b[1;31m单击此处了解详细信息。\n",
140 | "\u001b[1;31m有关更多详细信息,请查看 Jupyter log。"
141 | ]
142 | }
143 | ],
144 | "source": [
145 | "import mujoco.viewer as viewer\n",
146 | "import time\n",
147 | "\n",
148 | "mujoco.mj_resetDataKeyframe(model, data, 0) # Reset the state to keyframe 0\n",
149 | "\n",
150 | "# \n",
151 | "with viewer.launch_passive(model, data) as viewer: \n",
152 | " # launch_passive means all the simulation should be done by the user \n",
153 | " \n",
154 | " start = time.time()\n",
155 | " while viewer.is_running() and time.time() - start < 10:\n",
156 | " step_start = time.time()\n",
157 | " data.ctrl = 0.2*myControl(model,data)\n",
158 | " mujoco.mj_step(model, data)\n",
159 | "\n",
160 | " # let viewer show updated info\n",
161 | " viewer.sync()\n",
162 | " \n",
163 | " # # make sure the while loop is called every sampling period \n",
164 | " # computation inside the loop may take some nontrivial time. \n",
165 | " time_until_next_step = model.opt.timestep - (time.time() - step_start)\n",
166 | " if time_until_next_step > 0:\n",
167 | " time.sleep(time_until_next_step)"
168 | ]
169 | },
170 | {
171 | "cell_type": "markdown",
172 | "metadata": {},
173 | "source": [
174 | "### Simulation method 1: \n",
175 | "interactive simulation, the viewer can respond to user's input during the simulation"
176 | ]
177 | },
178 | {
179 | "cell_type": "code",
180 | "execution_count": 6,
181 | "metadata": {},
182 | "outputs": [],
183 | "source": [
184 | "# simulating the closed-loop system by using the control callback\n",
185 | "\n",
186 | "import mujoco.viewer as viewer\n",
187 | "mujoco.mj_resetDataKeyframe(model, data, 0) # Reset the state to keyframe 0\n",
188 | "mujoco.set_mjcb_control(myControl)\n",
189 | "viewer.launch(model,data)"
190 | ]
191 | },
192 | {
193 | "cell_type": "markdown",
194 | "metadata": {},
195 | "source": [
196 | "### Simuation method 2:\n",
197 | "Passive simulation, the user has the control over stepping the physics "
198 | ]
199 | },
200 | {
201 | "cell_type": "code",
202 | "execution_count": 8,
203 | "metadata": {},
204 | "outputs": [],
205 | "source": [
206 | "import mujoco.viewer as viewer\n",
207 | "import time\n",
208 | "\n",
209 | "mujoco.mj_resetDataKeyframe(model, data, 0) # Reset the state to keyframe 0\n",
210 | "with viewer.launch_passive(model,data) as viewer:\n",
211 | " while viewer.is_running() and data.time < 5:\n",
212 | " data.ctrl = 20*myControl(model,data) # apply control\n",
213 | " mujoco.mj_step(model, data) # step xdot= f(x,u)\n",
214 | " viewer.sync()\n",
215 | " time.sleep(model.opt.timestep) \n"
216 | ]
217 | }
218 | ],
219 | "metadata": {
220 | "kernelspec": {
221 | "display_name": "sp25",
222 | "language": "python",
223 | "name": "python3"
224 | },
225 | "language_info": {
226 | "codemirror_mode": {
227 | "name": "ipython",
228 | "version": 3
229 | },
230 | "file_extension": ".py",
231 | "mimetype": "text/x-python",
232 | "name": "python",
233 | "nbconvert_exporter": "python",
234 | "pygments_lexer": "ipython3",
235 | "version": "3.13.2"
236 | }
237 | },
238 | "nbformat": 4,
239 | "nbformat_minor": 2
240 | }
241 |
--------------------------------------------------------------------------------
/MujocoModeling/XMLReference.ipynb:
--------------------------------------------------------------------------------
1 | {
2 | "cells": [
3 | {
4 | "cell_type": "code",
5 | "execution_count": null,
6 | "metadata": {},
7 | "outputs": [],
8 | "source": []
9 | },
10 | {
11 | "cell_type": "markdown",
12 | "metadata": {},
13 | "source": [
14 | "# XML Summary\n",
15 | "This part summerizes key elements in a Mujoco XML model that is important for rigid-body robotic systems. Complete and detailed information can be found in the official website \n",
16 | "https://mujoco.readthedocs.io/en/latest/XMLreference.html\n",
17 | "\n",
18 | "\n",
19 | "\n",
20 | "## Frame orientation:\n",
21 | "\n",
22 | "The frame orientation is specified using at most one of these attributes. The quat attribute has a default value corresponding to the null rotation, while the others are initialized in the special undefined state. Thus if none of these attributes are specified by the user, the frame is not rotated.\n",
23 | "\n",
24 | "- quat: real(4), “1 0 0 0”\n",
25 | " If the quaternion is known, this is the preferred was to specify the frame orientation because it does not involve conversions. Instead it is normalized to unit length and copied into mjModel during compilation. When a model is saved as MJCF, all frame orientations are expressed as quaternions using this attribute.\n",
26 | "\n",
27 | "- axisangle: real(4), optional\n",
28 | " These are the quantities (x,y,z,a) mentioned above. The last number is the angle of rotation, in degrees or radians as specified by the angle attribute of compiler. The first three numbers determine a 3D vector which is the rotation axis. This vector is normalized to unit length during compilation, so the user can specify a vector of any non-zero length. Keep in mind that the rotation is right-handed; if the direction of the vector (x,y,z) is reversed this will result in the opposite rotation. Changing the sign of a can also be used to specify the opposite rotation.\n",
29 | "\n",
30 | "- euler: real(3), optional\n",
31 | " Rotation angles around three coordinate axes. The sequence of axes around which these rotations are applied is determined by the eulerseq attribute of compiler and is the same for the entire model.\n",
32 | "\n",
33 | "- xyaxes: real(6), optional\n",
34 | " The first 3 numbers are the X axis of the frame. The next 3 numbers are the Y axis of the frame, which is automatically made orthogonal to the X axis. The Z axis is then defined as the cross-product of the X and Y axes.\n",
35 | "\n",
36 | "- zaxis: real(3), optional\n",
37 | " The Z axis of the frame. The compiler finds the minimal rotation that maps the vector (0,0,1) into the vector specified here. This determines the X and Y axes of the frame implicitly. This is useful for geoms with rotational symmetry around the Z axis, as well as lights – which are oriented along the Z axis of their frame.\n"
38 | ]
39 | },
40 | {
41 | "cell_type": "markdown",
42 | "metadata": {},
43 | "source": [
44 | "## body\n",
45 | "- need to specify: name (optional)\n",
46 | "- pos, orientation (see frame orientation section) relative to parant coordinate system\n",
47 | "- and important sub-element (geom, inertia, joint, etc)\n",
48 | "\n",
49 | "### body/inertial:\n",
50 | "- This element specifies the mass and inertial properties of the body. If this element is not included in a given body, the inertial properties are inferred from the geoms attached to the body. When a compiled MJCF model is saved, the XML writer saves the inertial properties explicitly using this element, even if they were inferred from geoms. The inertial frame is such that its center coincides with the center of mass of the body, and its axes coincide with the principal axes of inertia of the body. Thus the inertia matrix is diagonal in this frame.\n",
51 | "- *pos*: position of inertial frame. \n",
52 | "- *orientation*: of the inertial frame\n",
53 | "- *mass*: positive number required\n",
54 | "- *diaginertia* (real(3)): diagonal entries of the inertial matrix;\n",
55 | "- *fullinertia*: real(6): Full inertia matrix M. Since M is 3-by-3 and symmetric, it is specified using only 6 numbers in the following order: M(1,1), M(2,2), M(3,3), M(1,2), M(1,3), M(2,3). \n",
56 | "\n",
57 | "### body/joint\n",
58 | "A joint creates motion degrees of freedom between the body where it is defined and the body’s parent. If no joints are defined, the body is welded to its parent. Joints cannot be defined in the world body. At runtime the positions and orientations of all joints defined in the model are stored in the vector mjData.qpos, in the order in which they appear in the kinematic tree. The linear and angular velocities are stored in the vector mjData.qvel. These two vectors have different dimensionality when free or ball joints are used, because such joints represent rotations as unit quaternions.\n",
59 | " - **name**, **class**: optional \n",
60 | " - **type**: \n",
61 | " - *free*: 6Dof joint. This joint type is only allowed in bodies that are children of the world body. Free joints do not have a position within the body frame. Instead the joint position is assumed to coincide with the center of the body frame. Thus at runtime the position and orientation data of the free joint correspond to the global position and orientation of the body frame. Free joints cannot have limits.\n",
62 | " - *slide*: a sliding or prismatic joint with one translational degree of freedom. Such joints are defined by a position and a sliding direction. For simulation purposes only the direction is needed; the joint position is used for rendering purposes.\n",
63 | " - *hinge*: 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. \n",
64 | " - **pos**: Position of the joint, specified in the frame of the body where the joint is defined. For free joints this attribute is ignored.\n",
65 | " - **axis**: This attribute specifies the axis of rotation for hinge joints and the direction of translation for slide joints.\n",
66 | "\n",
67 | "### body/geom\n",
68 | "- need to specify: name (optional), class (optional), pos, orientation (see frame orientation section), type, size (different meanings for different types), material (reference to materials defined in assets), rgba, among others. \n",
69 | " \n",
70 | "- **type**: (default: \"sphere\")\n",
71 | " - \"box\": The box type defines a box. Three size parameters are required, corresponding to the half-sizes of the box along the X, Y and Z axes of the geom’s frame. \n",
72 | " - \"cylinder\": defines a cylinder, which requires two size parameters: the radius and half-height of the cylinder. The cylinder is oriented along the Z axis of the geom’s frame. \n",
73 | " - \"mesh\": defines a mesh. The geom must reference the desired mesh asset with the mesh attribute. Note that mesh assets can also be referenced from other geom types, causing primitive shapes to be fitted; see below. The size is determined by the mesh asset and the geom size parameters are ignored.\n",
74 | "- **fromto**: This attribute can only be used with capsule, box, cylinder and ellipsoid geoms. It provides an alternative specification of the geom length as well as the frame position and orientation. The six numbers are the 3D coordinates of one point followed by the 3D coordinates of another point. \n",
75 | "- **pos**: (x,y,z) position \n",
76 | "- orietation related: see frame orietation section\n",
77 | "- **material**: \n",
78 | "- **rgba**: \n"
79 | ]
80 | },
81 | {
82 | "cell_type": "markdown",
83 | "metadata": {},
84 | "source": [
85 | "## asset\n",
86 | "Assets are not in themselves model elements. Model elements can reference them, in which case the asset somehow changes the properties of the referencing element. One asset can be referenced by multiple model elements. Since the sole purpose of including an asset is to reference it, and referencing can only be done by name, every asset has a name (which may be inferred from a file name when applicable).\n",
87 | "\n",
88 | "### asset/mesh\n",
89 | "MuJoCo works with triangulated meshes. They can be loaded from binary STL files, OBJ files or MSH files. \n",
90 | "\n",
91 | "### asset/material\n",
92 | "It can be referenced from skins, geoms, sites and tendons to set their appearance. Materials are useful for adjusting appearance properties beyond color."
93 | ]
94 | },
95 | {
96 | "cell_type": "markdown",
97 | "metadata": {},
98 | "source": [
99 | "## actuator\n",
100 | "MuJoCo provides a flexible actuator model. All actuators are single-input-single-output (SISO). \n",
101 | "- The input to actuator $i$ a scalar control $u_i$ specified by the user. \n",
102 | "- The output is a scalar force $p_i$, which is mapped to joint coordinates by a vector of moment arms determined by the transmission. \n",
103 | "- An actuator can also have activation state $w_i$ with its own dynamics\n",
104 | "- The control inputs for all actuators are stored in mjData.ctrl, the force outputs are stored in mjData.actuator_force, and the activation states (if any) are stored in mjData.act.\n",
105 | " \n",
106 | "### actuator/general:\n",
107 | "- joint/site: either specify a joint or a site for applying the force. \n",
108 | "- dyntype (\"none\"): internal dynamics type, including integrator, filter, filerexact, muscle, user... . The last case with \"user\" allows customize callback functions for actuator dynamics. \n",
109 | "- gaintype: The gain and bias together determine the output of the force generation mechanism, which is currently assumed to be affine. The general formula is: \n",
110 | " **scalar_force = gain_term * (act or ctrl) + bias_term**\n",
111 | "- ctrllimited: If true, the control input to this actuator is automatically clamped to ctrlrange at runtime\n",
112 | "- forcelimited: If true, the force output of this actuator is automatically clamped to forcerange at runtime\n",
113 | "\n",
114 | "### pre-defined actuator options: \n",
115 | "Below are actuator shortcuts discussed earlier. When a such shortcut is encountered, the parser creates a general actuator and sets its dynprm, gainprm and biasprm attributes to the internal defaults shown above, regardless of any default settings.\n",
116 | "\n",
117 | "- actuator/motor: \n",
118 | "\n",
119 | "| Attribute | Setting | Attribute | Setting |\n",
120 | "|-------------|---------------|-------------|---------------|\n",
121 | "| dyntype | none | gaintype | fixed |\n",
122 | "| dynprm | 1 0 0 | gainprm | 1 0 0 |\n",
123 | "| biastype | none | biasprm | 0 0 0 |\n",
124 | "\n",
125 | "- actuator/position:\n",
126 | " This element creates a position servo with an optional first-order filter. The underlying general attributes are set as follows: \n",
127 | "\n",
128 | "| Attribute | Setting | Attribute | Setting |\n",
129 | "|-------------|--------------------------|-------------|---------------------|\n",
130 | "| dyntype | none or filterexact | gaintype | fixed |\n",
131 | "| dynprm | timeconst 0 0 | gainprm | kp 0 0 |\n",
132 | "| biastype | affine | biasprm | 0 -kp -kv |\n",
133 | " \n",
134 | "- actuator/velocity\n",
135 | " This element creates a velocity servo. Note that in order create a PD controller, one has to define two actuators: a position servo and a velocity servo. This is because MuJoCo actuators are SISO while a PD controller takes two control inputs (reference position and reference velocity). When using this actuator, it is recommended to use the implicitfast or implicit integrators. The underlying general attributes are set as follows:\n",
136 | "\n",
137 | "| Attribute | Setting | Attribute | Setting |\n",
138 | "|-------------|---------------|-------------|-----------------|\n",
139 | "| dyntype | none | gaintype | fixed |\n",
140 | "| dynprm | 1 0 0 | gainprm | kv 0 0 |\n",
141 | "| biastype | affine | biasprm | 0 0 -kv |\n",
142 | "\n",
143 | "- actuator/damper\n",
144 | " "
145 | ]
146 | },
147 | {
148 | "cell_type": "markdown",
149 | "metadata": {},
150 | "source": [
151 | "## Sensor\n",
152 | "The outputs of all sensors are concatenated in the field mjData.sensordata which has size mjModel.nsensordata. This data is not used in any internal computations.\n",
153 | "\n",
154 | "- Sipmle example: \n",
155 | " > \n",
156 | " \n",
157 | " \n",
158 | " \n",
159 | "- other attributes:\n",
160 | " - **force**: 3-axis force. The sensor outputs three numbers, which are the interaction force between a child and a parent body, expressed in the site frame defining the sensor. The convention is that the site is attached to the child body, and the force points from the child towards the parent.\n",
161 | " - note that *site* sub-element is required. \n",
162 | " - **torque**: a 3-axis torque similar to force\n",
163 | " - "
164 | ]
165 | },
166 | {
167 | "cell_type": "markdown",
168 | "metadata": {},
169 | "source": []
170 | }
171 | ],
172 | "metadata": {
173 | "language_info": {
174 | "name": "python"
175 | }
176 | },
177 | "nbformat": 4,
178 | "nbformat_minor": 2
179 | }
180 |
--------------------------------------------------------------------------------
/MujocoModeling/MujocoPhysics.ipynb:
--------------------------------------------------------------------------------
1 | {
2 | "cells": [
3 | {
4 | "cell_type": "markdown",
5 | "metadata": {},
6 | "source": [
7 | "# Tutorial for Robotic Modeling using Mujoco \n",
8 | "*****************************************************************\n",
9 | " Copyright © 2025 [Wei Zhang/CLEAR Lab]. All Rights Reserved.\n",
10 | "\n",
11 | "********************************************************************\n",
12 | "\n",
13 | "This tutorial covers the basics of the physics modeling with Mujoco. We will primarily focus on rigid-body systems that are prevalent in most robotic applications. \n",
14 | "\n",
15 | "## Principles of Physics Modeling\n",
16 | "In order to simulate a physical system, we typically need to tell the simulator three things:\n",
17 | "1. **System models**, often described as ODE/PDE or just functions. Often times, it is hard to derive analytically the system (differential) equations. Therefore, the most important functionality of a simulator is to allow the user to easily specify physical properties and automatically translate these properties into (differential) equations. For rigid body robotic systems, we need to tell the simulator:\n",
18 | " - **Muti-body system**: articulated rigid body system consists of multiple rigid bodies connected through joints. We need to define each body and describe its physical properties (e.g. pos, orientation, inertia matrix, etc), and how it is connected to adjacent bodies (through joints) \n",
19 | " - **Environment/interaction**: gravity direction, ground, table, obstacle, wall, person, other robots, etc. How the robot interacts with the environments depends on many physical properties that can be modified, including friction, contact, collision mechanisms, \n",
20 | " - **Actuators/sensors**: robot's motion is completely determined by each joint's motion. Joint's motion is determined by sensing and actuation strategies. The simulation is about the closed-loop behavior of the robot's motion and its interaction with the environment. \n",
21 | "2. **Physics Engine**: This part determines how to solve the (differential) equations associated with the specified robot-environment physical system. Parameters that can be modified include simulation time step, integrator (Euler, RK4, implicit, implicitfast), tolerance (to terminate iterative solver), constraint solver (PGS, CG, Newton), number of iterations (for constraint solver), etc. For Mujoco xml, these parameters are mostly specified through the \\