|
66 | 66 | "import mediapy as media\n",
|
67 | 67 | "from adam.casadi import KinDynComputations\n",
|
68 | 68 | "import numpy as np\n",
|
69 |
| - "import casadi as cs\n", |
70 |
| - "import distutils.util\n", |
71 |
| - "import os\n", |
72 |
| - "import subprocess" |
| 69 | + "import casadi as cs" |
73 | 70 | ]
|
74 | 71 | },
|
75 | 72 | {
|
76 | 73 | "cell_type": "markdown",
|
77 |
| - "source": [ |
78 |
| - "## Import the panda scene in mujoco" |
79 |
| - ], |
80 | 74 | "metadata": {
|
81 | 75 | "id": "2zw4FO-IGxdR"
|
82 |
| - } |
| 76 | + }, |
| 77 | + "source": [ |
| 78 | + "## Import the panda scene in mujoco" |
| 79 | + ] |
83 | 80 | },
|
84 | 81 | {
|
85 | 82 | "cell_type": "code",
|
|
90 | 87 | "outputs": [],
|
91 | 88 | "source": [
|
92 | 89 | "# load scene from xml\n",
|
93 |
| - "model = mujoco.MjModel.from_xml_path(\"mujoco_menagerie/franka_emika_panda/scene.xml\")\n" |
| 90 | + "model = mujoco.MjModel.from_xml_path(\"mujoco_menagerie/franka_emika_panda/scene.xml\")" |
94 | 91 | ]
|
95 | 92 | },
|
96 | 93 | {
|
97 | 94 | "cell_type": "markdown",
|
| 95 | + "metadata": { |
| 96 | + "id": "CZMO7PsmKUB6" |
| 97 | + }, |
98 | 98 | "source": [
|
99 | 99 | "## Import urdf in adam\n",
|
100 | 100 | "\n",
|
101 | 101 | "Set the commanded joint list and impor the urdf in adam.\n",
|
102 | 102 | "\n",
|
103 | 103 | "For now I have to use a separate urdf for adam.\n",
|
104 | 104 | "An importer for a mujoco model could be an idea for the future!"
|
105 |
| - ], |
106 |
| - "metadata": { |
107 |
| - "id": "CZMO7PsmKUB6" |
108 |
| - } |
| 105 | + ] |
109 | 106 | },
|
110 | 107 | {
|
111 | 108 | "cell_type": "code",
|
|
115 | 112 | },
|
116 | 113 | "outputs": [],
|
117 | 114 | "source": [
|
118 |
| - "joints_name_list = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7', 'panda_joint8']\n", |
| 115 | + "joints_name_list = [\n", |
| 116 | + " \"panda_joint1\",\n", |
| 117 | + " \"panda_joint2\",\n", |
| 118 | + " \"panda_joint3\",\n", |
| 119 | + " \"panda_joint4\",\n", |
| 120 | + " \"panda_joint5\",\n", |
| 121 | + " \"panda_joint6\",\n", |
| 122 | + " \"panda_joint7\",\n", |
| 123 | + " \"panda_joint8\",\n", |
| 124 | + "]\n", |
119 | 125 | "\n",
|
120 |
| - "kindyn = KinDynComputations(urdfstring=\"panda.urdf\", joints_name_list=joints_name_list)\n" |
| 126 | + "kindyn = KinDynComputations(urdfstring=\"panda.urdf\", joints_name_list=joints_name_list)" |
121 | 127 | ]
|
122 | 128 | },
|
123 | 129 | {
|
124 | 130 | "cell_type": "markdown",
|
125 |
| - "source": [ |
126 |
| - "## A wrapper interface with mujoco" |
127 |
| - ], |
128 | 131 | "metadata": {
|
129 | 132 | "id": "g5LX5kQAKwaM"
|
130 |
| - } |
| 133 | + }, |
| 134 | + "source": [ |
| 135 | + "## A wrapper interface with mujoco" |
| 136 | + ] |
131 | 137 | },
|
132 | 138 | {
|
133 | 139 | "cell_type": "code",
|
|
138 | 144 | "outputs": [],
|
139 | 145 | "source": [
|
140 | 146 | "class MujocoWrapper:\n",
|
141 |
| - " # a simple wrapper to use mujoco as a simulator\n", |
142 |
| - " def __init__(self, model, joints_list=None):\n", |
143 |
| - " self.model = model\n", |
144 |
| - " self.data = mujoco.MjData(model)\n", |
145 |
| - " self.renderer = mujoco.Renderer(self.model)\n", |
| 147 | + " # a simple wrapper to use mujoco as a simulator\n", |
| 148 | + " def __init__(self, model, joints_list=None):\n", |
| 149 | + " self.model = model\n", |
| 150 | + " self.data = mujoco.MjData(model)\n", |
| 151 | + " self.renderer = mujoco.Renderer(self.model)\n", |
| 152 | + "\n", |
| 153 | + " def set_qpos(self, qpos):\n", |
| 154 | + " # set the joint positions\n", |
| 155 | + " self.data.qpos[:] = qpos\n", |
| 156 | + " mujoco.mj_forward(self.model, self.data)\n", |
146 | 157 | "\n",
|
147 |
| - " def set_qpos(self, qpos):\n", |
148 |
| - " # set the joint positions\n", |
149 |
| - " self.data.qpos[:] = qpos\n", |
150 |
| - " mujoco.mj_forward(self.model, self.data)\n", |
| 158 | + " def get_qpos(self):\n", |
| 159 | + " # get the joint positions\n", |
| 160 | + " return self.data.qpos[:]\n", |
151 | 161 | "\n",
|
152 |
| - " def get_qpos(self):\n", |
153 |
| - " # get the joint positions\n", |
154 |
| - " return self.data.qpos[:]\n", |
| 162 | + " def render(self):\n", |
| 163 | + " # render the scene and return the frame\n", |
| 164 | + " mujoco.mj_forward(self.model, self.data)\n", |
| 165 | + " self.renderer.update_scene(self.data)\n", |
| 166 | + " return self.renderer.render()\n", |
155 | 167 | "\n",
|
156 |
| - " def render(self):\n", |
157 |
| - " # render the scene and return the frame\n", |
158 |
| - " mujoco.mj_forward(self.model, self.data)\n", |
159 |
| - " self.renderer.update_scene(self.data)\n", |
160 |
| - " return self.renderer.render()\n", |
| 168 | + " def step(self):\n", |
| 169 | + " # step the simulation\n", |
| 170 | + " mujoco.mj_step(self.model, self.data)\n", |
161 | 171 | "\n",
|
162 |
| - " def step(self):\n", |
163 |
| - " # step the simulation\n", |
164 |
| - " mujoco.mj_step(self.model, self.data)\n", |
| 172 | + " def set_qvel(self, qvel):\n", |
| 173 | + " # set the joint velocities\n", |
| 174 | + " self.data.qvel[:] = qvel\n", |
| 175 | + " mujoco.mj_forward(self.model, self.data)\n", |
165 | 176 | "\n",
|
166 |
| - " def set_qvel(self, qvel):\n", |
167 |
| - " # set the joint velocities\n", |
168 |
| - " self.data.qvel[:] = qvel\n", |
169 |
| - " mujoco.mj_forward(self.model, self.data)\n", |
170 | 177 | "\n",
|
171 |
| - "wrapper = MujocoWrapper(model)\n" |
| 178 | + "wrapper = MujocoWrapper(model)" |
172 | 179 | ]
|
173 | 180 | },
|
174 | 181 | {
|
175 | 182 | "cell_type": "markdown",
|
| 183 | + "metadata": { |
| 184 | + "id": "wuY9hqdlD3Vo" |
| 185 | + }, |
176 | 186 | "source": [
|
177 | 187 | "# Model Inverse Kinematics as an MPC\n",
|
178 | 188 | "\n",
|
179 | 189 | "An MPC is maybe not the best way to solve an IK problem.\n",
|
180 | 190 | "I just want to show how to use the casadi interface."
|
181 |
| - ], |
182 |
| - "metadata": { |
183 |
| - "id": "wuY9hqdlD3Vo" |
184 |
| - } |
| 191 | + ] |
185 | 192 | },
|
186 | 193 | {
|
187 | 194 | "cell_type": "code",
|
|
197 | 204 | "# casadi opti stack\n",
|
198 | 205 | "opti = cs.Opti()\n",
|
199 | 206 | "\n",
|
200 |
| - "N = 10 # number of control intervals\n", |
201 |
| - "dt = 0.05 # time step\n", |
| 207 | + "N = 10 # number of control intervals\n", |
| 208 | + "dt = 0.05 # time step\n", |
202 | 209 | "\n",
|
203 | 210 | "# joints variables\n",
|
204 |
| - "q = opti.variable(8, N+1)\n", |
| 211 | + "q = opti.variable(8, N + 1)\n", |
205 | 212 | "q_dot = opti.variable(8, N)\n",
|
206 |
| - "w_H_b = np.eye(4) # base of the manipulator as identity matrix\n", |
| 213 | + "w_H_b = np.eye(4) # base of the manipulator as identity matrix\n", |
207 | 214 | "\n",
|
208 | 215 | "# set the desidered end-effector position as a parameter\n",
|
209 | 216 | "# it will be set later when the mpc is solved at each iteration\n",
|
|
217 | 224 | "\n",
|
218 | 225 | "for i in range(N):\n",
|
219 | 226 | " # integration - forward euler\n",
|
220 |
| - " opti.subject_to(q[:, i+1] == q[:, i] + q_dot[:, i] * dt)\n", |
| 227 | + " opti.subject_to(q[:, i + 1] == q[:, i] + q_dot[:, i] * dt)\n", |
221 | 228 | " # bounds on the joint velocities\n",
|
222 | 229 | " opti.subject_to(opti.bounded(-5, q_dot[:, i], 5))\n",
|
223 | 230 | " # running cost\n",
|
|
232 | 239 | "opti.minimize(target_cost + velocities_cost)\n",
|
233 | 240 | "\n",
|
234 | 241 | "# set the solver\n",
|
235 |
| - "p_opts = {\"expand\": True, 'ipopt.print_level': 0, 'print_time': 0, 'ipopt.sb': 'yes'}\n", |
| 242 | + "p_opts = {\"expand\": True, \"ipopt.print_level\": 0, \"print_time\": 0, \"ipopt.sb\": \"yes\"}\n", |
236 | 243 | "s_opts = {\"max_iter\": 100, \"print_level\": 0}\n",
|
237 |
| - "opti.solver(\"ipopt\", p_opts, s_opts)\n" |
| 244 | + "opti.solver(\"ipopt\", p_opts, s_opts)" |
238 | 245 | ]
|
239 | 246 | },
|
240 | 247 | {
|
241 | 248 | "cell_type": "markdown",
|
| 249 | + "metadata": { |
| 250 | + "id": "Hf-Uq8PWFy6v" |
| 251 | + }, |
242 | 252 | "source": [
|
243 | 253 | "# Simulation loop\n",
|
244 | 254 | "\n",
|
|
247 | 257 | "\n",
|
248 | 258 | "On the notebook it is a bit slow.\n",
|
249 | 259 | "To run it real time set OMP_NUM_THREADS=1 on your laptop!"
|
250 |
| - ], |
251 |
| - "metadata": { |
252 |
| - "id": "Hf-Uq8PWFy6v" |
253 |
| - } |
| 260 | + ] |
254 | 261 | },
|
255 | 262 | {
|
256 | 263 | "cell_type": "code",
|
|
275 | 282 | "mujoco.mj_resetData(wrapper.model, wrapper.data)\n",
|
276 | 283 | "i = 0\n",
|
277 | 284 | "while wrapper.data.time < duration:\n",
|
278 |
| - " wrapper.step()\n", |
279 |
| - " if len(frames) < wrapper.data.time * framerate:\n", |
280 |
| - " # you do not need to set the desired ee position every time step\n", |
281 |
| - " # you can set it only when you want to change it\n", |
282 |
| - " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
283 |
| - " q0_numeric = wrapper.get_qpos()\n", |
284 |
| - " # remove the last joint since they are not controlled\n", |
285 |
| - " q0_numeric = q0_numeric[:-1]\n", |
286 |
| - " # set the initial condition\n", |
287 |
| - " opti.set_value(q0, q0_numeric)\n", |
288 |
| - " sol = opti.solve()\n", |
289 |
| - " # take the q_dot solution at the first time step and extend with the last joint to 0\n", |
290 |
| - " sol_q_dot = sol.value(q_dot)[:, 0]\n", |
291 |
| - " sol_q_dot = np.concatenate((sol_q_dot, np.zeros(1)))\n", |
292 |
| - " wrapper.set_qvel(sol_q_dot)\n", |
293 |
| - " pixels = wrapper.render()\n", |
294 |
| - " frames.append(pixels)\n", |
295 |
| - " # set the solution as the initial condition for the next time step\n", |
296 |
| - " opti.set_initial(q, sol.value(q))\n", |
297 |
| - " opti.set_initial(q_dot, sol.value(q_dot))\n", |
298 |
| - " i += 1\n", |
299 |
| - " if wrapper.data.time > 2:\n", |
300 |
| - " # change the desired ee position\n", |
301 |
| - " des_ee_pos_numeric = np.array([2.0, 0.0, 0.2])\n", |
302 |
| - " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
303 |
| - " if wrapper.data.time > 4:\n", |
304 |
| - " # change the desired ee position\n", |
305 |
| - " des_ee_pos_numeric = np.array([0.0, 0.5, 0.4])\n", |
306 |
| - " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
307 |
| - " if wrapper.data.time > 6:\n", |
308 |
| - " # change the desired ee position\n", |
309 |
| - " des_ee_pos_numeric = np.array([0.0, -0.6, 0.6])\n", |
310 |
| - " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
| 285 | + " wrapper.step()\n", |
| 286 | + " if len(frames) < wrapper.data.time * framerate:\n", |
| 287 | + " # you do not need to set the desired ee position every time step\n", |
| 288 | + " # you can set it only when you want to change it\n", |
| 289 | + " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
| 290 | + " q0_numeric = wrapper.get_qpos()\n", |
| 291 | + " # remove the last joint since they are not controlled\n", |
| 292 | + " q0_numeric = q0_numeric[:-1]\n", |
| 293 | + " # set the initial condition\n", |
| 294 | + " opti.set_value(q0, q0_numeric)\n", |
| 295 | + " sol = opti.solve()\n", |
| 296 | + " # take the q_dot solution at the first time step and extend with the last joint to 0\n", |
| 297 | + " sol_q_dot = sol.value(q_dot)[:, 0]\n", |
| 298 | + " sol_q_dot = np.concatenate((sol_q_dot, np.zeros(1)))\n", |
| 299 | + " wrapper.set_qvel(sol_q_dot)\n", |
| 300 | + " pixels = wrapper.render()\n", |
| 301 | + " frames.append(pixels)\n", |
| 302 | + " # set the solution as the initial condition for the next time step\n", |
| 303 | + " opti.set_initial(q, sol.value(q))\n", |
| 304 | + " opti.set_initial(q_dot, sol.value(q_dot))\n", |
| 305 | + " i += 1\n", |
| 306 | + " if wrapper.data.time > 2:\n", |
| 307 | + " # change the desired ee position\n", |
| 308 | + " des_ee_pos_numeric = np.array([2.0, 0.0, 0.2])\n", |
| 309 | + " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
| 310 | + " if wrapper.data.time > 4:\n", |
| 311 | + " # change the desired ee position\n", |
| 312 | + " des_ee_pos_numeric = np.array([0.0, 0.5, 0.4])\n", |
| 313 | + " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
| 314 | + " if wrapper.data.time > 6:\n", |
| 315 | + " # change the desired ee position\n", |
| 316 | + " des_ee_pos_numeric = np.array([0.0, -0.6, 0.6])\n", |
| 317 | + " opti.set_value(des_ee_pos, des_ee_pos_numeric)\n", |
311 | 318 | "\n",
|
312 |
| - "media.show_video(frames, fps=framerate)\n" |
| 319 | + "media.show_video(frames, fps=framerate)" |
313 | 320 | ]
|
314 | 321 | }
|
315 | 322 | ],
|
316 | 323 | "metadata": {
|
| 324 | + "colab": { |
| 325 | + "include_colab_link": true, |
| 326 | + "provenance": [] |
| 327 | + }, |
317 | 328 | "kernelspec": {
|
318 | 329 | "display_name": "adam_env",
|
319 | 330 | "language": "python",
|
|
330 | 341 | "nbconvert_exporter": "python",
|
331 | 342 | "pygments_lexer": "ipython3",
|
332 | 343 | "version": "3.10.11"
|
333 |
| - }, |
334 |
| - "colab": { |
335 |
| - "provenance": [], |
336 |
| - "include_colab_link": true |
337 | 344 | }
|
338 | 345 | },
|
339 | 346 | "nbformat": 4,
|
|
0 commit comments