Skip to content

Commit c04abc7

Browse files
Format everything with black. (bdaiinstitute#161)
1 parent d1057e5 commit c04abc7

28 files changed

+437
-371
lines changed

.pre-commit-config.yaml

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
repos:
2+
# - repo: https://github.com/charliermarsh/ruff-pre-commit
3+
# # Ruff version.
4+
# rev: 'v0.1.0'
5+
# hooks:
6+
# - id: ruff
7+
# args: ['--fix', '--config', 'pyproject.toml']
8+
9+
- repo: https://github.com/psf/black
10+
rev: 'refs/tags/23.10.0:refs/tags/23.10.0'
11+
hooks:
12+
- id: black
13+
language_version: python3.10
14+
args: ['--config', 'pyproject.toml']
15+
verbose: true
16+
17+
- repo: https://github.com/pre-commit/pre-commit-hooks
18+
rev: v4.5.0
19+
hooks:
20+
- id: end-of-file-fixer
21+
- id: debug-statements # Ensure we don't commit `import pdb; pdb.set_trace()`
22+
exclude: |
23+
(?x)^(
24+
docker/ros/web/static/.*|
25+
)$
26+
- id: trailing-whitespace
27+
exclude: |
28+
(?x)^(
29+
docker/ros/web/static/.*|
30+
(.*/).*\.patch|
31+
)$
32+
# - repo: https://github.com/pre-commit/mirrors-mypy
33+
# rev: v1.6.1
34+
# hooks:
35+
# - id: mypy

docs/source/conf.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,6 @@
1111
# add these directories to sys.path here. If the directory is relative to the
1212
# documentation root, use os.path.abspath to make it absolute, like shown here.
1313
#
14-
import os
15-
import sys
1614

1715
# sys.path.insert(0, os.path.abspath('.'))
1816
# sys.path.insert(0, os.path.abspath('..'))
@@ -67,9 +65,11 @@
6765
# choose UTF-8 encoding to allow for Unicode characters, eg. ansitable
6866
# Python session setup, turn off color printing for SE3, set NumPy precision
6967
autorun_languages = {}
70-
autorun_languages['pycon_output_encoding'] = 'UTF-8'
71-
autorun_languages['pycon_input_encoding'] = 'UTF-8'
72-
autorun_languages['pycon_runfirst'] = """
68+
autorun_languages["pycon_output_encoding"] = "UTF-8"
69+
autorun_languages["pycon_input_encoding"] = "UTF-8"
70+
autorun_languages[
71+
"pycon_runfirst"
72+
] = """
7373
from spatialmath import SE3
7474
SE3._color = False
7575
import numpy as np

pyproject.toml

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ keywords = [
2828
"SO(2)", "SE(2)", "SO(3)", "SE(3)",
2929
"twist", "product of exponential", "translation", "orientation",
3030
"angle-axis", "Lie group", "skew symmetric matrix",
31-
"pose", "translation", "rotation matrix",
31+
"pose", "translation", "rotation matrix",
3232
"rigid body transform", "homogeneous transformation",
3333
"Euler angles", "roll-pitch-yaw angles",
3434
"quaternion", "unit-quaternion",
@@ -63,9 +63,9 @@ dev = [
6363

6464
docs = [
6565
"sphinx",
66-
"sphinx-rtd-theme",
67-
"sphinx-autorun",
68-
"sphinxcontrib-jsmath",
66+
"sphinx-rtd-theme",
67+
"sphinx-autorun",
68+
"sphinxcontrib-jsmath",
6969
"sphinx-favicon",
7070
"sphinx-autodoc-typehints",
7171
]
@@ -88,6 +88,7 @@ packages = [
8888
]
8989

9090
[tool.black]
91+
required-version = "23.10.0"
9192
line-length = 88
9293
target-version = ['py38']
9394
exclude = "camera_derivatives.py"

spatialmath/DualQuaternion.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -357,7 +357,6 @@ def SE3(self) -> SE3:
357357

358358

359359
if __name__ == "__main__": # pragma: no cover
360-
361360
from spatialmath import SE3, UnitDualQuaternion
362361

363362
print(UnitDualQuaternion(SE3()))

spatialmath/__init__.py

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,6 @@
1717
from spatialmath.DualQuaternion import DualQuaternion, UnitDualQuaternion
1818
from spatialmath.spline import BSplineSE3, InterpSplineSE3, SplineFit
1919

20-
# from spatialmath.Plucker import *
21-
# from spatialmath import base as smb
2220

2321
__all__ = [
2422
# pose
@@ -46,7 +44,7 @@
4644
"Ellipse",
4745
"BSplineSE3",
4846
"InterpSplineSE3",
49-
"SplineFit"
47+
"SplineFit",
5048
]
5149

5250
try:

spatialmath/base/animate.py

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -109,7 +109,9 @@ def __init__(
109109
if len(dim) == 2:
110110
dim = dim * 3
111111
elif len(dim) != 6:
112-
raise ValueError(f"dim must have 2 or 6 elements, got {dim}. See docstring for details.")
112+
raise ValueError(
113+
f"dim must have 2 or 6 elements, got {dim}. See docstring for details."
114+
)
113115
ax.set_xlim(dim[0:2])
114116
ax.set_ylim(dim[2:4])
115117
ax.set_zlim(dim[4:])
@@ -223,7 +225,7 @@ def update(frame, animation):
223225
else:
224226
# [unlikely] other types are converted to np array
225227
T = np.array(frame)
226-
228+
227229
if T.shape == (3, 3):
228230
T = smb.r2t(T)
229231

@@ -606,14 +608,14 @@ def trplot2(
606608
smb.trplot2(self.start, ax=self, block=False, **kwargs)
607609

608610
def run(
609-
self,
611+
self,
610612
movie: Optional[str] = None,
611613
axes: Optional[plt.Axes] = None,
612614
repeat: bool = False,
613615
interval: int = 50,
614616
nframes: int = 100,
615-
wait: bool = False,
616-
**kwargs
617+
wait: bool = False,
618+
**kwargs,
617619
):
618620
"""
619621
Run the animation
@@ -663,7 +665,6 @@ def update(frame, animation):
663665
animation._draw(T)
664666
self.count += 1 # say we're still running
665667

666-
667668
if movie is not None:
668669
repeat = False
669670

@@ -698,7 +699,9 @@ def update(frame, animation):
698699
print("overwriting movie", movie)
699700
else:
700701
print("creating movie", movie)
701-
FFwriter = animation.FFMpegWriter(fps=1000 / interval, extra_args=["-vcodec", "libx264"])
702+
FFwriter = animation.FFMpegWriter(
703+
fps=1000 / interval, extra_args=["-vcodec", "libx264"]
704+
)
702705
_ani.save(movie, writer=FFwriter)
703706

704707
if wait:
@@ -902,8 +905,6 @@ def set_ylabel(self, *args, **kwargs):
902905
# plotvol3(2)
903906
# tranimate(attitude())
904907

905-
from spatialmath import base
906-
907908
# T = smb.rpy2r(0.3, 0.4, 0.5)
908909
# # smb.tranimate(T, wait=True)
909910
# s = smb.tranimate(T, movie=True)

spatialmath/base/quaternions.py

Lines changed: 49 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -851,57 +851,74 @@ def qslerp(
851851
def _compute_cdf_sin_squared(theta: float):
852852
"""
853853
Computes the CDF for the distribution of angular magnitude for uniformly sampled rotations.
854-
854+
855855
:arg theta: angular magnitude
856856
:rtype: float
857857
:return: cdf of a given angular magnitude
858858
:rtype: float
859859
860-
Helper function for uniform sampling of rotations with constrained angular magnitude.
860+
Helper function for uniform sampling of rotations with constrained angular magnitude.
861861
This function returns the integral of the pdf of angular magnitudes (2/pi * sin^2(theta/2)).
862862
"""
863863
return (theta - np.sin(theta)) / np.pi
864864

865+
865866
@lru_cache(maxsize=1)
866-
def _generate_inv_cdf_sin_squared_interp(num_interpolation_points: int = 256) -> interpolate.interp1d:
867+
def _generate_inv_cdf_sin_squared_interp(
868+
num_interpolation_points: int = 256,
869+
) -> interpolate.interp1d:
867870
"""
868871
Computes an interpolation function for the inverse CDF of the distribution of angular magnitude.
869-
872+
870873
:arg num_interpolation_points: number of points to use in the interpolation function
871874
:rtype: int
872875
:return: interpolation function for the inverse cdf of a given angular magnitude
873876
:rtype: interpolate.interp1d
874877
875-
Helper function for uniform sampling of rotations with constrained angular magnitude.
876-
This function returns interpolation function for the inverse of the integral of the
878+
Helper function for uniform sampling of rotations with constrained angular magnitude.
879+
This function returns interpolation function for the inverse of the integral of the
877880
pdf of angular magnitudes (2/pi * sin^2(theta/2)), which is not analytically defined.
878881
"""
879882
cdf_sin_squared_interp_angles = np.linspace(0, np.pi, num_interpolation_points)
880-
cdf_sin_squared_interp_values = _compute_cdf_sin_squared(cdf_sin_squared_interp_angles)
881-
return interpolate.interp1d(cdf_sin_squared_interp_values, cdf_sin_squared_interp_angles)
883+
cdf_sin_squared_interp_values = _compute_cdf_sin_squared(
884+
cdf_sin_squared_interp_angles
885+
)
886+
return interpolate.interp1d(
887+
cdf_sin_squared_interp_values, cdf_sin_squared_interp_angles
888+
)
889+
882890

883-
def _compute_inv_cdf_sin_squared(x: ArrayLike, num_interpolation_points: int = 256) -> ArrayLike:
891+
def _compute_inv_cdf_sin_squared(
892+
x: ArrayLike, num_interpolation_points: int = 256
893+
) -> ArrayLike:
884894
"""
885895
Computes the inverse CDF of the distribution of angular magnitude.
886-
896+
887897
:arg x: value for cdf of angular magnitudes
888898
:rtype: ArrayLike
889899
:arg num_interpolation_points: number of points to use in the interpolation function
890900
:rtype: int
891901
:return: angular magnitude associate with cdf value
892902
:rtype: ArrayLike
893903
894-
Helper function for uniform sampling of rotations with constrained angular magnitude.
895-
This function returns the angle associated with the cdf value derived form integral of
904+
Helper function for uniform sampling of rotations with constrained angular magnitude.
905+
This function returns the angle associated with the cdf value derived form integral of
896906
the pdf of angular magnitudes (2/pi * sin^2(theta/2)), which is not analytically defined.
897907
"""
898-
inv_cdf_sin_squared_interp = _generate_inv_cdf_sin_squared_interp(num_interpolation_points)
908+
inv_cdf_sin_squared_interp = _generate_inv_cdf_sin_squared_interp(
909+
num_interpolation_points
910+
)
899911
return inv_cdf_sin_squared_interp(x)
900912

901-
def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interpolation_points: int = 256) -> UnitQuaternionArray:
913+
914+
def qrand(
915+
theta_range: Optional[ArrayLike2] = None,
916+
unit: str = "rad",
917+
num_interpolation_points: int = 256,
918+
) -> UnitQuaternionArray:
902919
"""
903920
Random unit-quaternion
904-
921+
905922
:arg theta_range: angular magnitude range [min,max], defaults to None.
906923
:type xrange: 2-element sequence, optional
907924
:arg unit: angular units: 'rad' [default], or 'deg'
@@ -913,7 +930,7 @@ def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interp
913930
:return: random unit-quaternion
914931
:rtype: ndarray(4)
915932
916-
Computes a uniformly distributed random unit-quaternion, with in a maximum
933+
Computes a uniformly distributed random unit-quaternion, with in a maximum
917934
angular magnitude, which can be considered equivalent to a random SO(3) rotation.
918935
919936
.. runblock:: pycon
@@ -924,24 +941,30 @@ def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interp
924941
if theta_range is not None:
925942
theta_range = getunit(theta_range, unit)
926943

927-
if(theta_range[0] < 0 or theta_range[1] > np.pi or theta_range[0] > theta_range[1]):
928-
ValueError('Invalid angular range. Must be within the range[0, pi].'
929-
+ f' Recieved {theta_range}.')
944+
if (
945+
theta_range[0] < 0
946+
or theta_range[1] > np.pi
947+
or theta_range[0] > theta_range[1]
948+
):
949+
ValueError(
950+
"Invalid angular range. Must be within the range[0, pi]."
951+
+ f" Recieved {theta_range}."
952+
)
953+
954+
# Sample axis and angle independently, respecting the CDF of the
955+
# angular magnitude under uniform sampling.
930956

931-
# Sample axis and angle independently, respecting the CDF of the
932-
# angular magnitude under uniform sampling.
933-
934-
# Sample angle using inverse transform sampling based on CDF
957+
# Sample angle using inverse transform sampling based on CDF
935958
# of the angular distribution (2/pi * sin^2(theta/2))
936959
theta = _compute_inv_cdf_sin_squared(
937960
np.random.uniform(
938-
low=_compute_cdf_sin_squared(theta_range[0]),
961+
low=_compute_cdf_sin_squared(theta_range[0]),
939962
high=_compute_cdf_sin_squared(theta_range[1]),
940963
),
941964
num_interpolation_points=num_interpolation_points,
942965
)
943966
# Sample axis uniformly using 3D normal distributed
944-
v = np.random.randn(3)
967+
v = np.random.randn(3)
945968
v /= np.linalg.norm(v)
946969

947970
return np.r_[math.cos(theta / 2), (math.sin(theta / 2) * v)]
@@ -953,7 +976,7 @@ def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interp
953976
math.sqrt(u[0]) * math.sin(2 * math.pi * u[2]),
954977
math.sqrt(u[0]) * math.cos(2 * math.pi * u[2]),
955978
]
956-
979+
957980

958981
def qmatrix(q: ArrayLike4) -> R4x4:
959982
"""

spatialmath/base/transforms2d.py

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -746,7 +746,7 @@ def trnorm2(T: SE2Array) -> SE2Array:
746746
b = unitvec(b)
747747
# fmt: off
748748
R = np.array([
749-
[ b[1], b[0]],
749+
[ b[1], b[0]],
750750
[-b[0], b[1]]
751751
])
752752
# fmt: on
@@ -810,7 +810,7 @@ def tradjoint2(T):
810810
(R, t) = smb.tr2rt(cast(SE3Array, T))
811811
# fmt: off
812812
return np.block([
813-
[R, np.c_[t[1], -t[0]].T],
813+
[R, np.c_[t[1], -t[0]].T],
814814
[0, 0, 1]
815815
]) # type: ignore
816816
# fmt: on
@@ -853,12 +853,16 @@ def tr2jac2(T: SE2Array) -> R3x3:
853853

854854

855855
@overload
856-
def trinterp2(start: Optional[SO2Array], end: SO2Array, s: float, shortest: bool = True) -> SO2Array:
856+
def trinterp2(
857+
start: Optional[SO2Array], end: SO2Array, s: float, shortest: bool = True
858+
) -> SO2Array:
857859
...
858860

859861

860862
@overload
861-
def trinterp2(start: Optional[SE2Array], end: SE2Array, s: float, shortest: bool = True) -> SE2Array:
863+
def trinterp2(
864+
start: Optional[SE2Array], end: SE2Array, s: float, shortest: bool = True
865+
) -> SE2Array:
862866
...
863867

864868

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy