Skip to content

Commit e68b68a

Browse files
committed
Remove unused imports and fix f-strings
1 parent 376e3f8 commit e68b68a

25 files changed

+139
-156
lines changed

docs/conf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@
5959
templates_path = ["_templates"]
6060
exclude_patterns = []
6161

62-
html_title = f"adam"
62+
html_title = "adam"
6363

6464

6565
# -- Options for HTML output -------------------------------------------------

examples/mpc-ik.ipynb

Lines changed: 104 additions & 97 deletions
Original file line numberDiff line numberDiff line change
@@ -66,20 +66,17 @@
6666
"import mediapy as media\n",
6767
"from adam.casadi import KinDynComputations\n",
6868
"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"
7370
]
7471
},
7572
{
7673
"cell_type": "markdown",
77-
"source": [
78-
"## Import the panda scene in mujoco"
79-
],
8074
"metadata": {
8175
"id": "2zw4FO-IGxdR"
82-
}
76+
},
77+
"source": [
78+
"## Import the panda scene in mujoco"
79+
]
8380
},
8481
{
8582
"cell_type": "code",
@@ -90,22 +87,22 @@
9087
"outputs": [],
9188
"source": [
9289
"# 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\")"
9491
]
9592
},
9693
{
9794
"cell_type": "markdown",
95+
"metadata": {
96+
"id": "CZMO7PsmKUB6"
97+
},
9898
"source": [
9999
"## Import urdf in adam\n",
100100
"\n",
101101
"Set the commanded joint list and impor the urdf in adam.\n",
102102
"\n",
103103
"For now I have to use a separate urdf for adam.\n",
104104
"An importer for a mujoco model could be an idea for the future!"
105-
],
106-
"metadata": {
107-
"id": "CZMO7PsmKUB6"
108-
}
105+
]
109106
},
110107
{
111108
"cell_type": "code",
@@ -115,19 +112,28 @@
115112
},
116113
"outputs": [],
117114
"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",
119125
"\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)"
121127
]
122128
},
123129
{
124130
"cell_type": "markdown",
125-
"source": [
126-
"## A wrapper interface with mujoco"
127-
],
128131
"metadata": {
129132
"id": "g5LX5kQAKwaM"
130-
}
133+
},
134+
"source": [
135+
"## A wrapper interface with mujoco"
136+
]
131137
},
132138
{
133139
"cell_type": "code",
@@ -138,50 +144,51 @@
138144
"outputs": [],
139145
"source": [
140146
"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",
146157
"\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",
151161
"\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",
155167
"\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",
161171
"\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",
165176
"\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",
170177
"\n",
171-
"wrapper = MujocoWrapper(model)\n"
178+
"wrapper = MujocoWrapper(model)"
172179
]
173180
},
174181
{
175182
"cell_type": "markdown",
183+
"metadata": {
184+
"id": "wuY9hqdlD3Vo"
185+
},
176186
"source": [
177187
"# Model Inverse Kinematics as an MPC\n",
178188
"\n",
179189
"An MPC is maybe not the best way to solve an IK problem.\n",
180190
"I just want to show how to use the casadi interface."
181-
],
182-
"metadata": {
183-
"id": "wuY9hqdlD3Vo"
184-
}
191+
]
185192
},
186193
{
187194
"cell_type": "code",
@@ -197,13 +204,13 @@
197204
"# casadi opti stack\n",
198205
"opti = cs.Opti()\n",
199206
"\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",
202209
"\n",
203210
"# joints variables\n",
204-
"q = opti.variable(8, N+1)\n",
211+
"q = opti.variable(8, N + 1)\n",
205212
"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",
207214
"\n",
208215
"# set the desidered end-effector position as a parameter\n",
209216
"# it will be set later when the mpc is solved at each iteration\n",
@@ -217,7 +224,7 @@
217224
"\n",
218225
"for i in range(N):\n",
219226
" # 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",
221228
" # bounds on the joint velocities\n",
222229
" opti.subject_to(opti.bounded(-5, q_dot[:, i], 5))\n",
223230
" # running cost\n",
@@ -232,13 +239,16 @@
232239
"opti.minimize(target_cost + velocities_cost)\n",
233240
"\n",
234241
"# 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",
236243
"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)"
238245
]
239246
},
240247
{
241248
"cell_type": "markdown",
249+
"metadata": {
250+
"id": "Hf-Uq8PWFy6v"
251+
},
242252
"source": [
243253
"# Simulation loop\n",
244254
"\n",
@@ -247,10 +257,7 @@
247257
"\n",
248258
"On the notebook it is a bit slow.\n",
249259
"To run it real time set OMP_NUM_THREADS=1 on your laptop!"
250-
],
251-
"metadata": {
252-
"id": "Hf-Uq8PWFy6v"
253-
}
260+
]
254261
},
255262
{
256263
"cell_type": "code",
@@ -275,45 +282,49 @@
275282
"mujoco.mj_resetData(wrapper.model, wrapper.data)\n",
276283
"i = 0\n",
277284
"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",
311318
"\n",
312-
"media.show_video(frames, fps=framerate)\n"
319+
"media.show_video(frames, fps=framerate)"
313320
]
314321
}
315322
],
316323
"metadata": {
324+
"colab": {
325+
"include_colab_link": true,
326+
"provenance": []
327+
},
317328
"kernelspec": {
318329
"display_name": "adam_env",
319330
"language": "python",
@@ -330,10 +341,6 @@
330341
"nbconvert_exporter": "python",
331342
"pygments_lexer": "ipython3",
332343
"version": "3.10.11"
333-
},
334-
"colab": {
335-
"provenance": [],
336-
"include_colab_link": true
337344
}
338345
},
339346
"nbformat": 4,

src/adam/casadi/computations.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,10 @@
22
# This software may be modified and distributed under the terms of the
33
# GNU Lesser General Public License v2.1 or any later version.
44

5+
from typing import Union
6+
57
import casadi as cs
68
import numpy as np
7-
from typing import Union
89

910
from adam.casadi.casadi_like import SpatialMath
1011
from adam.core import RBDAlgorithms

src/adam/model/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
from .abc_factories import Joint, Link, ModelFactory, Inertial, Pose
1+
from .abc_factories import Inertial, Joint, Link, ModelFactory, Pose
22
from .model import Model
33
from .std_factories.std_joint import StdJoint
44
from .std_factories.std_link import StdLink

src/adam/model/conversions/idyntree.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
1+
from typing import List
2+
13
import idyntree.bindings
24
import numpy as np
35
import urdf_parser_py.urdf
4-
from typing import List
5-
66

7+
from adam.model.abc_factories import Joint, Link
78
from adam.model.model import Model
8-
from adam.model.abc_factories import Link, Joint
99

1010

1111
def to_idyntree_solid_shape(

src/adam/model/std_factories/std_link.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
import urdf_parser_py.urdf
33

44
from adam.core.spatial_math import SpatialMath
5-
from adam.model import Link, Inertial, Pose
5+
from adam.model import Inertial, Link, Pose
66

77

88
class StdLink(Link):

src/adam/model/std_factories/std_model.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,8 @@
1+
import os
12
import pathlib
2-
from typing import List
33
import xml.etree.ElementTree as ET
4-
import os
4+
from typing import List
5+
56
import urdf_parser_py.urdf
67

78
from adam.core.spatial_math import SpatialMath

0 commit comments

Comments
 (0)