Skip to content

Commit 4badd5e

Browse files
authored
Merge branch 'devel' into passivity_based_rnea_dev
2 parents 9701062 + 7d55bf0 commit 4badd5e

File tree

122 files changed

+760
-525
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

122 files changed

+760
-525
lines changed

.github/workflows/scripts/get_label.js

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ module.exports = async ({github, context, core}) => {
3434
' -DBUILD_PYTHON_BINDINGS_WITH_BOOST_MPFR_SUPPORT=ON',
3535
' -DINSTALL_DOCUMENTATION=ON',
3636
' -DGENERATE_PYTHON_STUBS=ON',
37-
' -DBUILD_WITH_ACCELERATE_SUPPORT=ON'
37+
' -DBUILD_WITH_ACCELERATE_SUPPORT=OFF'
3838
],
3939
build_collision: ' -DBUILD_WITH_COLLISION_SUPPORT=ON',
4040
build_casadi: ' -DBUILD_WITH_CASADI_SUPPORT=ON',

CHANGELOG.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,11 +9,17 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).
99
### Added
1010

1111
- Default visualizer can be changed with `PINOCCHIO_VIEWER` environment variable ([#2419](https://github.com/stack-of-tasks/pinocchio/pull/2419))
12+
- Add more Python and C++ examples related to inverse kinematics with 3d tasks ([#2428](https://github.com/stack-of-tasks/pinocchio/pull/2428))
1213

1314
### Fixed
1415
- Fix linkage of Boost.Serialization on Windows ([#2400](https://github.com/stack-of-tasks/pinocchio/pull/2400))
1516
- Fix mjcf parser appending of inertias at root joint ([#2403](https://github.com/stack-of-tasks/pinocchio/pull/2403))
1617
- Fix unit tests with GCC 13.3 ([#2406](https://github.com/stack-of-tasks/pinocchio/pull/2416)
18+
- Fix class abtract error for Rviz viewer ([#2425](https://github.com/stack-of-tasks/pinocchio/pull/2425))
19+
20+
### Changed
21+
22+
- Modernize python code base with ruff ([#2418](https://github.com/stack-of-tasks/pinocchio/pull/2418))
1723

1824
## [3.2.0] - 2024-08-27
1925

bindings/python/pinocchio/deprecated.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,5 @@
22
# Copyright (c) 2018-2023 CNRS INRIA
33
#
44

5-
## In this file, are reported some deprecated functions that are still maintained until the next important future releases ##
6-
7-
from __future__ import print_function
5+
## In this file, are reported some deprecated functions
6+
# that are still maintained until the next important future releases

bindings/python/pinocchio/deprecation.py

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,7 @@ def decorator(func):
2020

2121
@functools.wraps(func)
2222
def wrapper(*args, **kwargs):
23-
message = "Call to deprecated function {}. {}".format(
24-
func.__name__, instructions
25-
)
23+
message = f"Call to deprecated function {func.__name__}. {instructions}"
2624

2725
warnings.warn(message, category=DeprecatedWarning, stacklevel=2)
2826

bindings/python/pinocchio/derivative/dcrba.py

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -2,19 +2,14 @@
22
# Copyright (c) 2016 CNRS
33
#
44

5-
from __future__ import print_function
65

6+
import lambdas
77
import numpy as np
88
import pinocchio as pin
9-
from numpy.linalg import norm
10-
from pinocchio.robot_wrapper import RobotWrapper
11-
from pinocchio.utils import rand
12-
13-
import lambdas
149
from lambdas import (
1510
FCross,
16-
Mcross,
1711
MCross,
12+
Mcross,
1813
adj,
1914
adjdual,
2015
ancestors,
@@ -23,6 +18,9 @@
2318
quad,
2419
td,
2520
)
21+
from numpy.linalg import norm
22+
from pinocchio.robot_wrapper import RobotWrapper
23+
from pinocchio.utils import rand
2624

2725

2826
def hessian(robot, q, crossterms=False):
@@ -111,9 +109,12 @@ def __call__(self):
111109
T_jSd = np.array(H[:, d, j0:j1]) # this is 0 is d<=j
112110

113111
"""
114-
assert( norm(T_iSd)<1e-6 or not joint_diff<i ) # d<i => TiSd=0
115-
assert( norm(T_jSd)<1e-6 or not joint_diff<j ) # d<j => TjSd=0
116-
assert( norm(T_jSd)<1e-6 or not norm(T_iSd)<1e-6 ) # TiSd=0 => TjSd=0
112+
# d<i => TiSd=0
113+
assert( norm(T_iSd)<1e-6 or not joint_diff<i )
114+
# d<j => TjSd=0
115+
assert( norm(T_jSd)<1e-6 or not joint_diff<j )
116+
# TiSd=0 => TjSd=0
117+
assert( norm(T_jSd)<1e-6 or not norm(T_iSd)<1e-6 )
117118
assert( norm(T_iSd)>1e-6 )
118119
"""
119120

@@ -123,7 +124,8 @@ def __call__(self):
123124
if j < joint_diff:
124125
dM[i0:i1, j0:j1, d] += Si.T * Yd * T_jSd
125126

126-
# Make dM triangular by copying strict-upper triangle to lower one.
127+
# Make dM triangular by copying strict-upper triangle to lower
128+
# one.
127129
if i != j:
128130
dM[j0:j1, i0:i1, d] = dM[i0:i1, j0:j1, d].T
129131
else:
@@ -203,7 +205,8 @@ def __call__(self, q):
203205
H[:, k0:k1, j0:j1], YJ[:, i0:i1], [0, 0]
204206
)
205207

206-
# Fill the border elements of levels below k Q[kk,k,:] and Q[kk,:,k] with kk<k
208+
# Fill the border elements of levels below k
209+
# Q[kk,k,:] and Q[kk,:,k] with kk<k
207210
for kk in ancestors(k)[:-1]:
208211
kk0, kk1 = iv(kk)[0], iv(kk)[-1] + 1
209212
_Skk = J[:, kk0:kk1]
@@ -377,7 +380,7 @@ def adjf(f):
377380
Tkf = Yci * (-MCross(Sk, a[lk]) + MCross(MCross(Sk, v[lk]), v[lk]))
378381

379382
# Tk Si' fs = Tk Si' Ycrb[i] ai + Si' Ys (vs-vi) x (Sk x vlk)
380-
# = "" + Si' Ys vs x (Sk x vlk) - Si' Ys vi x (Sk x vlk)
383+
# = "" + Si' Ys vs x (Sk x vlk) - Si' Ys vi x (Sk x vlk) # noqa E501
381384
Tkf += Yvx[i] * MCross(Sk, v[lk])
382385

383386
R[i0:i1, k0:k1] = Si.T * Tkf

bindings/python/pinocchio/derivative/lambdas.py

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
# ruff: noqa: E731
55

66
import numpy as np
7-
from pinocchio import Motion, Force, skew
7+
from pinocchio import Force, Motion, skew
88
from pinocchio.utils import zero
99

1010

@@ -25,16 +25,13 @@ def jFromIdx(idxv, robot):
2525
robot.model.joints[i].idx_v + robot.model.joints[i].nv,
2626
)
2727
)
28-
ancestors = (
29-
lambda j, robot, res=[]: res
28+
ancestors = lambda j, robot, res=[]: (
29+
res
3030
if j == 0
3131
else ancestors(
3232
robot.model.parents[j],
3333
robot,
34-
[
35-
j,
36-
]
37-
+ res,
34+
[j, *res],
3835
)
3936
)
4037

@@ -53,12 +50,13 @@ def __contains__(self, anc):
5350
dec = self.robot.model.parents[dec]
5451

5552

56-
# descendants = lambda root,robot: filter( lambda i: root in ancestorOf(i,robot), range(root,robot.model.njoints) )
53+
# descendants = lambda root,robot: filter(
54+
# lambda i: root in ancestorOf(i,robot), range(root,robot.model.njoints) )
5755
descendants = lambda root, robot: robot.model.subtrees[root]
5856

5957

6058
def setRobotArgs(robot):
61-
ancestors.__defaults__ = (robot,) + ancestors.__defaults__
59+
ancestors.__defaults__ = (robot, *ancestors.__defaults__)
6260
descendants.__defaults__ = (robot,)
6361
# ancestorsOf.__init__.__defaults__ = (robot,)
6462
iv.__defaults__ = (robot,)
@@ -91,7 +89,7 @@ def setRobotArgs(robot):
9189

9290

9391
def np_prettyprint(sarg="{: 0.5f}", eps=5e-7):
94-
mformat = (
95-
lambda x, sarg=sarg, eps=eps: sarg.format(x) if abs(x) > eps else " 0. "
92+
mformat = lambda x, sarg=sarg, eps=eps: (
93+
sarg.format(x) if abs(x) > eps else " 0. "
9694
)
9795
np.set_printoptions(formatter={"float": mformat})

bindings/python/pinocchio/derivative/xm.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,11 @@
44

55
import numpy as np
66
import pinocchio as pin
7+
from dcrba import DCRBA, DRNEA, Coriolis
78
from numpy.linalg import norm
89
from pinocchio.robot_wrapper import RobotWrapper
910
from pinocchio.utils import rand
1011

11-
from dcrba import DCRBA, DRNEA, Coriolis
12-
1312
np.random.seed(0)
1413

1514
robot = RobotWrapper(

bindings/python/pinocchio/robot_wrapper.py

Lines changed: 21 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
)
1313

1414

15-
class RobotWrapper(object):
15+
class RobotWrapper:
1616
@staticmethod
1717
def BuildFromURDF(
1818
filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None
@@ -160,13 +160,16 @@ def centroidalMomentum(self, q, v):
160160

161161
def centroidalMap(self, q):
162162
"""
163-
Computes the centroidal momentum matrix which maps from the joint velocity vector to the centroidal momentum expressed around the center of mass.
163+
Computes the centroidal momentum matrix which maps from the joint velocity
164+
vector to the centroidal momentum expressed around the center of mass.
164165
"""
165166
return pin.computeCentroidalMap(self.model, self.data, q)
166167

167168
def centroidal(self, q, v):
168169
"""
169-
Computes all the quantities related to the centroidal dynamics (hg, Ag and Ig), corresponding to the centroidal momentum, the centroidal map and the centroidal rigid inertia.
170+
Computes all the quantities related to the centroidal dynamics (hg, Ag and Ig),
171+
corresponding to the centroidal momentum, the centroidal map and the centroidal
172+
rigid inertia.
170173
"""
171174
pin.ccrba(self.model, self.data, q, v)
172175
return (self.data.hg, self.data.Ag, self.data.Ig)
@@ -350,15 +353,16 @@ def buildReducedRobot(self, list_of_joints_to_lock, reference_configuration=None
350353

351354
def getFrameJacobian(self, frame_id, rf_frame=pin.ReferenceFrame.LOCAL):
352355
"""
353-
It computes the Jacobian of frame given by its id (frame_id) either expressed in the
354-
local coordinate frame or in the world coordinate frame.
356+
It computes the Jacobian of frame given by its id (frame_id) either expressed in
357+
the local coordinate frame or in the world coordinate frame.
355358
"""
356359
return pin.getFrameJacobian(self.model, self.data, frame_id, rf_frame)
357360

358361
def computeFrameJacobian(self, q, frame_id):
359362
"""
360363
Similar to getFrameJacobian but does not need pin.computeJointJacobians and
361-
pin.updateFramePlacements to update internal value of self.data related to frames.
364+
pin.updateFramePlacements to update internal value of self.data related to
365+
frames.
362366
"""
363367
return pin.computeFrameJacobian(self.model, self.data, q, frame_id)
364368

@@ -396,8 +400,10 @@ def viewer(self):
396400
return self.viz.viewer
397401

398402
def setVisualizer(self, visualizer, init=True, copy_models=False):
399-
"""Set the visualizer. If init is True, the visualizer is initialized with this wrapper's models.
400-
If copy_models is also True, the models are copied. Otherwise, they are simply kept as a reference.
403+
"""
404+
Set the visualizer. If init is True, the visualizer is initialized with this
405+
wrapper's models. If copy_models is also True, the models are copied.
406+
Otherwise, they are simply kept as a reference.
401407
"""
402408
if init:
403409
visualizer.__init__(
@@ -406,7 +412,10 @@ def setVisualizer(self, visualizer, init=True, copy_models=False):
406412
self.viz = visualizer
407413

408414
def getViewerNodeName(self, geometry_object, geometry_type):
409-
"""For each geometry object, returns the corresponding name of the node in the display."""
415+
"""
416+
For each geometry object, returns the corresponding name of the node in the
417+
display.
418+
"""
410419
return self.viz.getViewerNodeName(geometry_object, geometry_type)
411420

412421
def initViewer(self, share_data=True, *args, **kwargs):
@@ -437,7 +446,9 @@ def loadViewerModel(self, *args, **kwargs):
437446
self.viz.loadViewerModel(*args, **kwargs)
438447

439448
def display(self, q):
440-
"""Display the robot at configuration q in the viewer by placing all the bodies."""
449+
"""
450+
Display the robot at configuration q in the viewer by placing all the bodies.
451+
"""
441452
self.viz.display(q)
442453

443454
def displayCollisions(self, visibility):

bindings/python/pinocchio/romeo_wrapper.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,9 @@ def __init__(self, filename, package_dirs=None, verbose=False):
6868

6969
for op, name in self.opCorrespondances.items():
7070
self.__dict__[op] = self.index(name)
71-
# self.__dict__['_M'+op] = types.MethodType(lambda s, q: s.position(q,idx),self)
71+
# self.__dict__["_M" + op] = types.MethodType(
72+
# lambda s, q: s.position(q, idx), self
73+
# )
7274

7375
# --- SHORTCUTS ---
7476
def Mrh(self, q):

bindings/python/pinocchio/shortcuts.py

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,15 @@
1+
# ruff: noqa: E501
12
#
23
# Copyright (c) 2018-2020 CNRS INRIA
34
#
45

56
## In this file, some shortcuts are provided ##
67

7-
from . import pinocchio_pywrap_default as pin
8-
from . import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
98
from typing import Tuple
109

10+
from . import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
11+
from . import pinocchio_pywrap_default as pin
12+
1113
nle = pin.nonLinearEffects
1214

1315

@@ -77,8 +79,10 @@ def buildModelsFromUrdf(
7779

7880

7981
def createDatas(*models):
80-
"""Call createData() on each Model or GeometryModel in input and return the results in a tuple.
81-
If one of the models is None, the corresponding data object in the result is also None.
82+
"""
83+
Call createData() on each Model or GeometryModel in input and return the results in
84+
a tuple. If one of the models is None, the corresponding data object in the result
85+
is also None.
8286
"""
8387
return tuple([None if model is None else model.createData() for model in models])
8488

@@ -120,7 +124,8 @@ def buildModelsFromSdf(
120124
)
121125
if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
122126
print(
123-
"Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
127+
"Info: MeshLoader is ignored. "
128+
"The HPP-FCL Python bindings have not been installed."
124129
)
125130
if package_dirs is None:
126131
package_dirs = []
@@ -173,7 +178,8 @@ def buildModelsFromMJCF(
173178
)
174179
if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
175180
print(
176-
"Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
181+
"Info: MeshLoader is ignored. "
182+
"The HPP-FCL Python bindings have not been installed."
177183
)
178184

179185
lst = [model]

bindings/python/pinocchio/utils.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ def mprint(M, name="ans", eps=1e-15):
7676
cmin = i * 6
7777
cmax = (i + 1) * 6
7878
cmax = ncol if ncol < cmax else cmax
79-
print("Columns %s through %s" % (cmin, cmax - 1))
79+
print(f"Columns {cmin} through {cmax - 1}")
8080
print()
8181
for r in range(M.shape[0]):
8282
sys.stdout.write(" ")

0 commit comments

Comments
 (0)