From ca3d1b25c67003d6b681329cfdf686a1f553ebc2 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Fri, 20 Sep 2024 10:31:38 +0200 Subject: [PATCH 01/62] Fix latexpdf build --- doc/source/index.rst | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/doc/source/index.rst b/doc/source/index.rst index c578b484d..67d64d1af 100644 --- a/doc/source/index.rst +++ b/doc/source/index.rst @@ -58,7 +58,5 @@ If you use pytransform3d for a scientific publication, I would appreciate citation of the following paper: Fabisch, A. (2019). pytransform3d: 3D Transformations for Python. -Journal of Open Source Software, 4(33), 1159, |DOI|_ - -.. |DOI| image:: http://joss.theoj.org/papers/10.21105/joss.01159/status.svg -.. _DOI: https://doi.org/10.21105/joss.01159 +Journal of Open Source Software, 4(33), 1159, +https://doi.org/10.21105/joss.01159 From 32b43059fc7528e6b1ed3d3f54e0a0db73f85660 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Fri, 20 Sep 2024 10:33:48 +0200 Subject: [PATCH 02/62] Define author --- doc/source/conf.py | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/source/conf.py b/doc/source/conf.py index ac5e8a402..111e280f2 100644 --- a/doc/source/conf.py +++ b/doc/source/conf.py @@ -52,6 +52,7 @@ language = 'en' today_fmt = '%B %d, %Y' add_function_parentheses = True +author = "Alexander Fabisch" show_authors = True pygments_style = 'sphinx' html_logo = "_static/logo.png" From 8c74192cd34d9a07ec2439cd9dd462346e96a5ab Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 21 Sep 2024 16:40:32 +0200 Subject: [PATCH 03/62] Fix typo in Euler angle section and clean up ex. --- doc/source/user_guide/euler_angles.rst | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/doc/source/user_guide/euler_angles.rst b/doc/source/user_guide/euler_angles.rst index 6d47867bb..4881a61fb 100644 --- a/doc/source/user_guide/euler_angles.rst +++ b/doc/source/user_guide/euler_angles.rst @@ -10,14 +10,12 @@ conventions that could be used. Furthermore, you have to find out whether degrees or radians are used to express the angles (we will only use radians in pytransform3d). -------- -Example -------- +.. figure:: ../_auto_examples/plots/images/sphx_glr_plot_euler_angles_001.png + :target: ../_auto_examples/plots/plot_euler_angles.html + :align: center -Here we rotate about the extrinsic (fixed) x-axis, y-axis, and z-axis by -90 degrees. - -.. plot:: ../../examples/plots/plot_euler_angles.py + Here we rotate about the extrinsic (fixed) x-axis, y-axis, and z-axis by + 90 degrees. -------------- 24 Conventions @@ -44,7 +42,7 @@ rotation matrices). Range of Angles --------------- -Euler angles rotate about three basis vectors with by the angles +Euler angles rotate about three basis vectors by the angles :math:`\alpha`, :math:`\beta`, and :math:`\gamma`. If we want to find the Euler angles that correspond to one rotation matrix :math:`R`, there is an infinite number of solutions because we can always add or subtract From 5b57e3936eb862d33d30b712f1c4d6760a9df613 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 21 Sep 2024 16:41:01 +0200 Subject: [PATCH 04/62] Fix grammar in modeling section --- doc/source/user_guide/transformation_modeling.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/user_guide/transformation_modeling.rst b/doc/source/user_guide/transformation_modeling.rst index 8832360a4..44cadc545 100644 --- a/doc/source/user_guide/transformation_modeling.rst +++ b/doc/source/user_guide/transformation_modeling.rst @@ -4,7 +4,7 @@ Modeling Transformations With many transformations it is not easy to keep track of the right sequence. Here are some simple tricks that you can use to keep track of transformations -and make to always concatenate them in the correct way. +and concatenate them in the correct way. .. image:: ../_static/transformation_modeling.png :alt: Three frames From 9e89c623978627fe0a80ee4e516885634ad242a5 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 21 Sep 2024 16:43:29 +0200 Subject: [PATCH 05/62] Review section about time series transform manager --- .../user_guide/transformation_over_time.rst | 24 ++++++++++--------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/doc/source/user_guide/transformation_over_time.rst b/doc/source/user_guide/transformation_over_time.rst index f587bfce5..37628e5bd 100644 --- a/doc/source/user_guide/transformation_over_time.rst +++ b/doc/source/user_guide/transformation_over_time.rst @@ -3,27 +3,27 @@ Graphs of Time-Dependent Transformations ======================================== In applications, where the transformations between coordinate frames are -dynamic (i.e. changing over time), consider using +dynamic (i.e., changing over time), consider using :class:`~pytransform3d.transform_manager.TemporalTransformManager`. In contrast to the :class:`~pytransform3d.transform_manager.TransformManager`, which deals with static transfomations, it provides an interface for the logic needed to interpolate between transformation samples available over time. -We can visualize the lifetime of two dynamic transformations (i.e. 3 coordinate -systems) in the figure below. Each circle represents a sample (measurement) -holding the transformation from the parent to the child frame. +We can visualize the lifetime of two dynamic transformations (i.e., 3 +coordinate systems) in the figure below. Each circle represents a sample +(measurement) holding the transformation from the parent to the child frame. .. figure:: ../_static/tf-trafo-over-time.png :width: 60% :align: center -A common use-case is to transform points originating from system A to system B -at a specific point in time (i.e. :math:`t_q`, where :math:`q` refers to query) -Imagine two moving robots A & B reporting their observations between each -other. +A common use case is to transform points originating from system A to system B +at a specific point in time (i.e., :math:`t_q`, where :math:`q` refers to +query). Imagine two moving robots A & B reporting their observations between +each other. -------------------------------------- -Preparing the transformation sequences +Preparing the Transformation Sequences -------------------------------------- First, you need to prepare the transfomation sequences using the @@ -48,7 +48,7 @@ Next, you need to pass the transformations to an instance of :lines: 58-61 ------------------------------------ -Transform between coordinate systems +Transform Between Coordinate Systems ------------------------------------ Finally, you can transform between coordinate systems at a particular time @@ -61,4 +61,6 @@ Finally, you can transform between coordinate systems at a particular time The coordinates of A's origin (blue diamond) transformed to B are visualized in the plot below: -.. plot:: ../../examples/plots/plot_interpolation_for_transform_manager.py +.. figure:: ../_auto_examples/plots/images/sphx_glr_plot_interpolation_for_transform_manager_001.png + :target: ../_auto_examples/plots/plot_interpolation_for_transform_manager.html + :align: center From be5efdb8b5730dae98c5818b8ff4c87c9ca4af47 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 21 Sep 2024 16:50:08 +0200 Subject: [PATCH 06/62] Link examples --- doc/source/user_guide/rotations.rst | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 0e2da5cb3..c387b046e 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -202,7 +202,10 @@ This will be done, for instance, to obtain rotation matrices from Euler angles Axis-Angle ---------- -.. plot:: ../../examples/plots/plot_axis_angle.py +.. figure:: ../_auto_examples/plots/images/sphx_glr_plot_axis_angle_001.png + :target: ../_auto_examples/plots/plot_axis_angle.html + :width: 50% + :align: center Each rotation can be represented by a single rotation about one axis. The axis can be represented as a three-dimensional unit vector and the angle @@ -402,7 +405,10 @@ information. Rotors ------ -.. plot:: ../../examples/plots/plot_bivector.py +.. figure:: ../_auto_examples/plots/images/sphx_glr_plot_bivector_001.png + :target: ../_auto_examples/plots/plot_bivector.html + :width: 70% + :align: center Rotors and quaternions are very similar concepts in 3D. However, rotors are more general as they can be extended to more dimensions [3]_ [4]_. From 25525969161506dc1be206157f2a44c09754fc6d Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 21 Sep 2024 16:51:47 +0200 Subject: [PATCH 07/62] Link example --- doc/source/user_guide/transformations.rst | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index 8eaa73006..d695605a0 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -134,7 +134,10 @@ quaternion and typically we use the variable name pq. Screw Parameters ---------------- -.. plot:: ../../examples/plots/plot_screw.py +.. figure:: ../_auto_examples/plots/images/sphx_glr_plot_screw_001.png + :target: ../_auto_examples/plots/plot_screw.html + :width: 70% + :align: center Just like any rotation can be expressed as a rotation by an angle about a 3D unit vector, any transformation (rotation and translation) can be expressed From 44bf5cbbfdd070f5df5baba518dc02cd99658e67 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 22 Sep 2024 09:12:22 +0200 Subject: [PATCH 08/62] Document iterative Gaussian estimation --- pytransform3d/uncertainty.py | 23 +++++++++++++++++++++-- 1 file changed, 21 insertions(+), 2 deletions(-) diff --git a/pytransform3d/uncertainty.py b/pytransform3d/uncertainty.py index ff00f88c0..09e383625 100644 --- a/pytransform3d/uncertainty.py +++ b/pytransform3d/uncertainty.py @@ -14,10 +14,25 @@ def estimate_gaussian_transform_from_samples(samples): - """Estimate Gaussian distribution over transformations from samples. + r"""Estimate Gaussian distribution over transformations from samples. - Uses iterative approximation of mean described by Eade [1]_ and computes + Uses iterative computation of mean described by Eade [1]_ and computes covariance in exponential coordinate space (using an unbiased estimator). + The derivation of the procedure is presented by Pennec [2]_. + + 1. For a set of transformations :math:`\{T_1, \ldots, T_N\}`, we initialize + the estimated mean :math:`\overline{T}_0 \leftarrow T_1`. + 2. For a fixed number of steps, in each iteration :math:`k` we improve the + estimation of the mean by + + a. Computing the distance of each sample to the current estimate of the + mean in exponential coordinates + :math:`V_{i,k} \leftarrow T_i \cdot \overline{T}_k^{-1}`. + b. Updating the estimate of the mean + :math:`\overline{T}_{k+1} \leftarrow Exp(\frac{1}{N}\sum_i V_{i,k}) \cdot \overline{T}_k`. + + 3. Estimate the covariance in the space of exponential coordinates with + :math:`\Sigma \leftarrow \frac{1}{N - 1} \sum_i \left[ V_{i,k} \cdot V_{i,k}^T \right]` Parameters ---------- @@ -36,6 +51,10 @@ def estimate_gaussian_transform_from_samples(samples): ---------- .. [1] Eade, E. (2017). Lie Groups for 2D and 3D Transformations. https://ethaneade.com/lie.pdf + + .. [2] Pennec, X. (2006). Intrinsic Statistics on Riemannian Manifolds: + Basic Tools for Geometric Measurements. J Math Imaging Vis 25, 127-154. + https://doi.org/10.1007/s10851-006-6228-4 """ assert len(samples) > 0 mean = samples[0] From f455741204d66122210969940998295f678ed189 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Thu, 26 Sep 2024 14:13:36 +0200 Subject: [PATCH 09/62] Fix broken link --- doc/source/user_guide/rotations.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index c387b046e..ce795127e 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -504,7 +504,7 @@ References https://arxiv.org/pdf/1801.07478.pdf .. [2] Gehring, C., Bellicoso, C. D., Bloesch, M., Sommer, H., Fankhauser, P., Hutter, M., Siegwart, R. (2024). Kindr cheat sheet. - https://docs.leggedrobotics.com/kindr/cheatsheet_latest.pdf + https://github.com/ANYbotics/kindr/blob/master/doc/cheatsheet/cheatsheet_latest.pdf .. [3] ten Bosch, M. (2020). Let's remove Quaternions from every 3D Engine. https://marctenbosch.com/quaternions/ .. [4] Doran, C. (2015). Applications of Geometric Algebra. From f39589ed0d7919327a7290f24f681a92ba2a8d87 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Fri, 27 Sep 2024 13:54:14 +0200 Subject: [PATCH 10/62] Link tf paper --- pytransform3d/transform_manager/_transform_manager.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/pytransform3d/transform_manager/_transform_manager.py b/pytransform3d/transform_manager/_transform_manager.py index 8a8b4e83c..94dc7bd02 100644 --- a/pytransform3d/transform_manager/_transform_manager.py +++ b/pytransform3d/transform_manager/_transform_manager.py @@ -14,8 +14,8 @@ class TransformManager(TransformGraphBase): """Manage transformations between frames. - This is a simplified version of `ROS tf `_ that - ignores the temporal aspect. A user can register transformations. The + This is a simplified version of `ROS tf `_ [1]_ + that ignores the temporal aspect. A user can register transformations. The shortest path between all frames will be computed internally which enables us to provide transforms for any connected frames. @@ -52,6 +52,12 @@ class TransformManager(TransformGraphBase): check : bool, optional (default: True) Check if transformation matrices are valid and requested nodes exist, which might significantly slow down some operations. + + References + ---------- + .. [1] Foote, T. (2013). tf: The transform library. In IEEE Conference on + Technologies for Practical Robot Applications (TePRA), Woburn, MA, USA, + pp. 1-6, doi: 10.1109/TePRA.2013.6556373. """ def __init__(self, strict_check=True, check=True): super(TransformManager, self).__init__(strict_check, check) From 634aa80596caf43bc6aae8a93b12d935b336bb1b Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Fri, 27 Sep 2024 13:58:33 +0200 Subject: [PATCH 11/62] Link docstring to user guide --- doc/source/user_guide/transformation_over_time.rst | 2 ++ pytransform3d/transform_manager/_temporal_transform_manager.py | 2 ++ 2 files changed, 4 insertions(+) diff --git a/doc/source/user_guide/transformation_over_time.rst b/doc/source/user_guide/transformation_over_time.rst index 37628e5bd..32a59d770 100644 --- a/doc/source/user_guide/transformation_over_time.rst +++ b/doc/source/user_guide/transformation_over_time.rst @@ -1,3 +1,5 @@ +.. _transformations_over_time: + ======================================== Graphs of Time-Dependent Transformations ======================================== diff --git a/pytransform3d/transform_manager/_temporal_transform_manager.py b/pytransform3d/transform_manager/_temporal_transform_manager.py index c4f7091da..bb1c36c7e 100644 --- a/pytransform3d/transform_manager/_temporal_transform_manager.py +++ b/pytransform3d/transform_manager/_temporal_transform_manager.py @@ -132,6 +132,8 @@ def _interpolate_pq_using_sclerp(self, query_time): class TemporalTransformManager(TransformGraphBase): """Manage time-varying transformations. + See :ref:`transformations_over_time` for more information. + Parameters ---------- strict_check : bool, optional (default: True) From eeb3135245f6f5364248542ba95233b6204cc61c Mon Sep 17 00:00:00 2001 From: David Wendorff <42057206+savidini@users.noreply.github.com> Date: Fri, 27 Sep 2024 15:59:27 +0200 Subject: [PATCH 12/62] adapted logos improved for dark mode --- doc/source/_static/logo.png | Bin 8257 -> 8061 bytes doc/source/_static/logo.svg | 333 ++---------------------------------- 2 files changed, 14 insertions(+), 319 deletions(-) diff --git a/doc/source/_static/logo.png b/doc/source/_static/logo.png index dc1b3279313cf1533db7e91a7b1d92cc62f75195..12cff75bbec3016bf60c29ef72a5772dc7e81598 100644 GIT binary patch delta 8036 zcmV-qADiI8K>a?DUVjQnL_t(|ob8=?cvaQ4z<=xJW}X-W382g>3ZmtKAbo|_K3laS zTG2XIZJnoJZJ+IX59y?>R&Xw;6>(@42hduFYSmh2MXgpr0)!y}0tAwfk=(o9AM4!Q zb5HI~ZUP~}p5OQ7%Q^S#z0W?=I%}_CA5m3&e0+Soyng?c{eN%1@5P2?|5#De-F*pk zcL#iYe0nAsS$RKA&CI&2yZZsYpz`tYiNj}0=H>)b0_SCRp%R zq=*!U!%Cn0Y=82y(|;-=-6|`5LFLmXA~FZ~7`PF*61W@qqFX!V(;-A8Q$!|+$fY9k zJWv6glBj%czusr1r3U**Acd^VH2U?<8CuXc_r!hI97&Zew=+?6j4 zA~F;>9yko>4}^ftzz4uHs=8w@?&}EP5nvRM;@Rw72Y=wX+pkO?JgCog!L&4*YZ^%l z1}W&9$LbAR=ZMHM?WQmRUr_nPMMNe8{|7V!e*iuL1_Iv&hIU`i_D@7)An+UDEE11o z>P2K8@N-pd+zY#{0OmQ%Q-QPFtI(@Y)+rh3sRyLz^`fC{E5Tq2y>he2&PpFYpl{A} z;BR}OUw<9OANu(uVjdvC&8m8ls@|=tbATg&^Sife`xhcI4tN(hhqj-&OyH-$vm%nY zr~6gaGF4rustbXulBu)&vq7gp3c>VTnwy(RNfEL$)99U-O(>jp+Mf2Qv+Q>om58Kc z7yJrfvZ~g0bCstoxs7sCBS7w zh1fSRZT7mo*oW$53SIu|=_v($QyDvE2ijCeZG9L`v&=C($y{guA zXMer~906nlm&6fLEvV|BfCa9f@`2G^+_yNSY;uH>gA!fW@_pYQV}BD=?wq4d-PVgQ zHwOa+&hkEfn|~=e8Z&A?okZDtJ?m+EzkfUJ5qbB=2q?S z#6#N0wfusrcGxB)B1d61v0>OV@&WJ{%%+TXh|~9^h9!>8Wh!tgaJZ`er}Mi2XJ8(e z;lKvqVpaVxK|4nSrvX!dLhR~o1ApED?o-uwS3PtuLQ7>j!TFW^9+FHnaWli$RG z8edDYEdeHD=WB|pPIPUXg?Y+G0p-Bus`|F4elK7KcHLf5)mxn3hXX&x?0-jtflA;r z;2u?dDNa8I0sjq5z+%X1faSm+RQ1JVjwMN^Isco1pC?;ML{fkYfNO|v*IJF;>q+2M zqI-x&HT|+BIkoAv(*wvc3df`fV}OmAJC!N37Y_<+_;)IDnjq1d!eOW!mKv06Cl)Wd zacEiguOEBt)DV((5-HpY41d5K#44fXNXql9TK)o~_&!fkh%R5;)XVYq*G9h#4KzfgB(gbLk!ld=oevySWB9bv8rG18^Tv?-rQw8R$Jh zA~GIxFHehe{suYwxX|&?%#Blj67X$cywjIKamo|}HxU~xJOHy7eSZ)5hlrf4s$0Ev zU2O~p7GpM%cYzn2;~j{dkK=*w0Kazreio;V0^lguPuU`JBX(YcSe#D=aH*x{teha^Z@6JMiJK-MPL#@;7bn_hoTfWUY~XJHRL zk^d8m7mXK@mk_B@xL;Ivs7P;tL$I4D2xN)K&r1i_eSOO8`+rV(^OmKLQZn;>&<|Yg zL0GS5^wRiVkHL@C1HXb+hn6EB59M2ejHMVJ7%J5HG~z#lQ8(cszE8_VT8 z2NOgQvVfm>nhIg(*Ij=I_Anog38yo>Le&W^`4jL}=Xl-}k+W2FnWz2Jfa8FEKwg~V zxQRvTIS5ahh=?4A#WB?Z4`70P1g3RGu7Bg@meiNa^Fw7`oUufgrAS}NF_W~H1MRtg6#YQfAPwkX)!wCQCB`ZScAKN339Hh zxi_=&4}bXDD|4nbv+ATP5pIoc;&etVZ97nK{RzEk3T_1&(BL>mJ-$Xneu>>o)tHtv z%qhJB@ZRJV5%s=hw<3SRE*RL2`4jBoK7l3I9)W2a0*q4C5?9?O?4cf|s$0C>bpj(_ z#N5vS&#LMPi4IRh76GpF#j}_;aFwe5!&7!DuzwUAIz>1(-cUnC7GvoVD^>O2Huir2 zW}y9V_jz*i&#uJI@dWIAfC>Izc$%qG)!SWlbAh+9A!`XRK2Z>^h-6^`^+@NZ2H@+7 zvOt42^e>w1qQNp91^}6W(V!VG7CAorwwE2H^O%hSMT) zD)4(^ZD41r>Laboes}@o-)nxW4cKXZ7qf6QouInu*`y9`Z=h7 z7ir7i)%RZ!*`DZcV)6aIim6llz`3f5zJGsVs;-)`PFKxP`#b5r_S({t6Hm9YCteqC zJLckz=%J6b+n&|A!BwXLdl--Ll)1#&-rMtg6L3R2?f=Zvez1+Q#l#N!UjZ`PD1WS{ z{DL@TQn9;Afv1x=A0Gl2wXyvg*ZwM!Xm63L{P&V5KiWC3kveOE^aN%9*Hvz}bARoQ z_mnx;**+*v{jIM0A>gDWucKnar!(6qf2pVZ`AOc7Q=R){8zvClZ8SOe#1DXsHrg2L zs(V?I`<>|7*BSB4y>|hWD15B&XN8*-zN>J6!ocH`*;iNmwG5@+UvS}WEZ)OV?tW+9 z_gmhai8yd$_WvokYz=BgyRR(R4S&p!{vQ4guTF2<%NUkfKqVpWXm7tAz#Ybr4lGoU z!BlOiG=tWWw?6{zYNvhoTPYpW{u1GB|8iAL7+tTbFJPKLgd^h=8$eW}8{-Tk+Tu}c z+Lk>=L=M7|Y{4EJuZG(SRs8}>a*i+*dobhSK3_rLVO5QJqpRuzzzMkT-G399I@54cY((TxZ)NBD-ir;< zw>V{!;e+;zKx^k<&oHKYwPg5|{xUw@oB!j1B3%SUwXV{TY;ZY{G_0XZAuk z4)it-TDCVQllQtY;tD}keSca#o-kFtO;tCv)wrszB{mSXFj3h!efg}dwjJD#hrV&P zyJO2n0C$K;Mx1g0sOpXC@s8~QKOj1^`c#vTV!z+BJ}W`FWUt+`sv6Jz?*6UKbFDUP zb5F6-Uin&VY!o5c$poJU3RU$4RsFH5&QaB~Fq6iEu5t$hFFLa>xPLhX(~iJG7@CsY zZ<1(j>p;&IA=PamL0&->c>{&A@(x&&Y$IXOS6r)kM_u`_89`0pL=D~&IG02;>vw@> z!g^=2`|SjEz`8wcL_~5#msF?aT|$JSolOdhG6knPXL=l| zxNCV3u`j|d$Si3lPFMonEv&riYNrI%VRM(H5q0g>zJGqh8L^UHWnOeyFK*R9iv9rQ zDMl=9(;l=habkm(V=n4m!1cgL$FA^#s>UF*}->HMJ;Vf93$lD zCqKr#9Dg8;qvYhTwQPHJdJy3}VmyT1ixc1S1krSa`&4zVs`lt4T~*z!s((?{bFpC8 zuVCQ@FX9RE#8N``gi6o)$PU(bYXfz}+N}QFaStioiOJiEH3b~rfi{!0ow_xu2t7|w zMKr1o&E%&RMGb(cCp{)wXkm0Ed_~LRpk6b8Qh!D*eWxS)>|&;2xpH7v$s6?8<5AU+ zsxDX6TU7N}%$D|?tH@z{@(CozUgXw*M>}aW$#zi zC7F|o7hM72S1|RnTEcSt+qa$Rbvef}e1GXDScW4& z3QAv61IeZUfF+qm7z{ipBFBlyX(IBdh_sq!h1juqu9Fzs9^M%c=84EO{|CU z4`QE(O4N_Zn4k&)Kh!qn5r6meB~5I8sibi1Z*H$xGUvK~g5_jr<$-gC+ohOO<4FA*)Ka-N6`a$cf`ipXy;C)Vr0F~mOaagVQ{pfa^} zM7l=$*liPSid*}iRQ$jL2*x&^`}-=R_^n!(ZmX> z*^3v0o^2brTz^H2Kqg=h{1Bq5bQSQHs6LX}Yv><462;ES6Nix!SObL6;AloYo^+}X zfQX!f-Ei(V!e-!`s`{x@=0&2(!OcW-@q)w#7Vc8jxGr8tbD4|HZq_n?{KaUsH+N*)o806Fdx80Do6wH*vMoZkAK$K+Hb4kk)px zdMpSx;$8ayxJgx8O|>H;&tnt8;o1+_O&vM*OyIlD(4!S%b7K7xo6{=dT-b$8rBjF5 zq*9&p@w<3J*=c7PQA4}CFWzexQq|F(x`$w2@{QyiHV}tQep+wH4i+5a(^b!{BC|}y3UE6GWdw%MZLnol-(cS zboQPlCzj0o0>U3Ma#^RoyecB8nBW|OU66li7k&TCdFzhFE^4`|CX-0K&k>Okn8sA- z`~|TW$|~S(XV!v!(T{$ZmNyc6ne4}8dQy&yj6h|pWGV8J)~_3QUic6K)5aF~XM25M?**s)^=6%`efm6fq(%^FHd zN``>oXejx#p^+Lv(Pcb#p)$&_D1tj(%R zP}K(PA?wko>S|&mn!BqX+t@c=y!{Ht2Wh+npgJBV%TEb~b5gX@tXJ z!r?H%V31%iNNQ>-X=!Psr>B#enwrwo)HDM#&hIl~jp=A)z3a^UYd)TW@GnL`)$Yd- ze0+Smp1C5y=D+=ILb$vf5g{`(lcJ)cR^>#5P;Q9EoW_ZJ5-i*q_WgJL!r@C$y?=S1 z@7Kr2rxmw|e4_x~lf{cCZNBItcE0u+)z#IMmX^}o+#K^)KCGPblgp`{R(k?d`MV60 zN&BjwUO^Qx9(GNn_2;J)f*j1qBmdkb?fdxnB*pC_gYOo3tQWkP3FDiAn&xI!+cTK!R zFnj~buj78#&&S87%b6>ZbBD)z#G0)KF7X z!>0#*N;o@g5~2|EsegqOj^YBwu}Th;*)mEx6O@}2u>wiRb7H$XI=4{!tbaaf3c_KG zT(-|$n?64O?#vYl^o0`!!MrpWu9(}g4vSUTi3NFW22wx&oZO?2X4kG=?AWn`ty{NJ zp%oU^oQegkq+$UpIY4jn*}(5u&3Q6HuGZE1^4{*hcZSc1MwL2c_I(MXXgkcB6AwUn z1ktNtkMqlXe0(~FqnT+aV1V}>zmjQod#IiTqt?T3Cvsaie(klbz_J4*8gOJgTMW)tb zTGS4rT2z_+Rt8-9{;E~aWDFQEq^hcFQgwB8sJ6ED?Z*2XH<8O(3}8Nm^dT1u2hPN_ zs|-xL>IDqsWLEQEGEU}G!Hv2(`FO5G$h1oz%c)DNAFC2RO^~Zx+g?`ThM>xdH*Yzo zEMW^?UY#CfaQ+TrXMZ<%k*2ioFy^tYp7Ywr=ii>WBEbQ0RvO%x4g(?|46MVVqpPrd zs0!@U&lM2f4G*P2@dj1zgorW7MN&u~?xu(t^u+{K3Kr1RL{tiH!^B<*>)6a}RY2P*mvfuPHnPFSfEkw#T53)eON?EM87Ciy9(S$`>%?4A!g3UoKf^K7hI z(195ee0+R5$?YOXWx}1AaAYJ2wH_Pld9|o=pvH3jE-iCXZIVTlS1R;sTby)R!- z`S|R=EVR7W%QN5?>5v^6fkm{aDq3q%wXiV^7jN=>b-J_2WpXA1nNK18$iuX&0H$3< zT#J$M<|d$oO1AK0RRxTa<|C0GvTHTIDa%U%yS#dcVhDqZNUW8c3?N$ zp8>Nwt3@S3&Xz(3atB46On+LmD?!j^jn3r}iG$bxl=3c{n62xyT_>9_sC<0(GvSlt+nG_3?SgREiKz_t0;mapCU z`?ziTg38Bd|KP9p6rY`+leM^J=^Jc)?6nwUxqn-W+JtFR^%lo@NxACt-O*pUR8FOU zJ1C?eGL>XnW*T`pc~oz&rm4EAMFsq3=@`NvseZ9`%eU8W+5UpJt$jaxf{%|+hk5#r zD~fWmGHy*t36L{m3ZX-XvIFz}Z^BGIYq99^b)faIFcZdimyiO`yL1U_7|TkQuo0++ zrhl3ywr}4~zoLE&J7^fvM>slvBq#PgoWl9)z*eSCb9M*8Gu zKb)2t>>XC9ZD=C>q$yOa+`#tcP>U9|1!#cv0zW8^Gar3-po_Hvm?am~FF=n__N7%O>{jX)LDRMs%~;}8P^ zdE{niP}nbzF(ZnYICj{nV-Fr2BdB~Em5)yk=Jor3G$uPI>)ntBvNx1hux;lqc7Ima zQMId{E#=#J`Pp}9G%f0avN#_H>1l|F@Iy|ffI9;PGGIZ|+4N7(B{i5rARsh1huF4b z7ytOEWb12huRU_r#*G`nANu+D^jKbiX<2)|OGewTf+(HB?sDva_b1 zn!1LDP)6ZX5{B&lAE1Dc4j*L z`{ePBNr&_gAoq&Mw^dbrLFMDqLun|gne*94+eUn{vhDbz+2PCACQ}!c~D-jtdYHQGe-2v%^ul1H(hh&S0{{~ zQdp3GDR8GRsC;~SD4%{&ar>g@mjB|@Pe1+A&N?#3W>hG3{$j!s&O2{<#<)TK`+{$y m^6~N65AeNyK0ZD@p8p5ouSbS75tu0e0000L_t(|ob8=?cobE-xZl&=>1-q+tg;1E7Fk3XkOB1yjtnZu zqJrzFqcSk!0yr11Gx}4wjH9Bm2%`h)4?%8!a6$L>+!xEM(gd}7kd%Dj3 z>kdT1&K2M%>b)Bj@RejEP&iS@dSXfvzDzw%w0DliObUiA|ig9U0Ol(|3 zR|Q)`SHQx;qH&VB`xDl$eY2sf0a${{!onf|uBr<14{hU2pN;Qs;l0ds*vKukkc$|8I!Dk|8%eLIU6FJ|o6 zv9xU2l6mvy1udU<=m%^@18hHOQST zZGjO$U!WzRfo$M=;C&#ot}c|7mBrOpU(K#vyK3l}Tz@WCz+((o6}hRO6XSGJRaB1C z;h9HmrURWBkeL1ht)3xTHr19%PC0<;E31N|DVT4yYYz)av?ASy_i zN?_@cBS&2A+qXaE3&zLCGilN!0Cw-*&D^6rY!v!4u_ql332?e z^=H2L{C_hp`>)GSxn3uOC8#WdF$ZZMF9DNG-~SC53zRoRrOr@NfcFsLABrg8o`C}g z=6(PD_q1%;@{}%`kdVNH2@?R&TC-%y5{@4~9`cxPzDTEYQ#+361gfg4u-g^!u}+c` z<9U0{T1!wxKn(DEr1J~{iW{^xXD5AuE8U;p^MBjt0vd;N&6&d!c!kvaz#`x);3#k& za3`V*i~&ebPj5DP@?@4TUtVVwP)d=IkWj0j`umDreDhUjF6?m}T~R`DX&T4!%1O^Y zNUw|QtU3{MrU|M?5xq$=GEFXR*y^0M+++H@t-)$>_HY?+0ue}S{Pyif1lb1Q-#{$D z%72wBnKNe&ty{M~o%JLs$wqc=EE_+o1kM2p5S64RDJk)^*2T=3rVzaX5mEpdi2lT) z?ipqJe4@c>adyxO=mPu?HHDO!FAx_HK$P8Ew{ETHs@0@T8xcxgboF-Iwx?HUnmN-1 zRgvj)MuXMj?4}dY!L%LR;l?5yE(5B7aDTieU&SOP%F7!<4X9231AT57&SXJV*kH9d zyXkHEY#^P?;^gTA{0j)J91@OUYS*1RcdoBGg}{H2qG=3*>P*v7nVmnZk-mOt(a;q* z%XmD3vQD50K(AiC=+&!N#24GPZ5y9{`YCB?Y1nKw`u6S1s8ORxNJt3t41t7F!+#1X z2q38XO?kbIQbvbw=iK?V`TK!WmUee3*F=RH44jAN5H`KKvQq#3`}ubt^OV!6*F@uT zw8gHPqHNw7n_)kWE-$BR|4gN(*U&BL1H;du%Fza;VljwA87HvWim?@>s&hA$1*m&P znD=Nytb;cq{y&$wzgNI5z#oBgfq!(wlK5Sa^9%%TcAu+_`@DI;H^5@x^Dyhv2N(xj z>pqu9;0{C#1s4F#5H02pz*=Ax;mvH6`~Jov_u2-CLq_U!;A=!_yCuZ=PF3&M3>X6p z1G*wQnsUU#wFR*venj}Kzc1eB^=rHal&gWMKo8{p{tSHRcWfLm9Qo}JAb)xy+;y7f zK3^wfroIpH7kh`A&mh@d{u1DPH+2vLwtZG}0N>kVz|>6h{|dVM7hoFce%pfFro|6oaNNX=iBTc|#dD zDNGMe(F?75MLE>8i>EApx_?u8{NGlsy3vJlj=|16pf%cbbISD{%KibV-+c&tYOaJn zJT8{nuBNk)2GkkoX*%pYU;>bUm~|77(dbcR`SM$&k@rW;7XUfc zwTFekA574S8#KJL17G=J^0yZ`?Yn2+zk z(H7_q+=K|Q(TK1KMmu0B@EgR-c|DMYbjpj64tq5+!u$J1c}NES%e1W!r_VUV^b_s= z{69#?H{%2zao5#`2-syv3%?K%HiLjEz_&=u;FkgF&=>LC?gLzm_#k=k41A9v&XXS6 zBkkiu#Ip7)_woIJcz<`9*WCYmxy!ZnyKWC)BqDfj1w4aeH{b(Apqc3kT#pFen>h6u zzCwg8x7>2eH)F<(3CkJa;K763dh4xx`K9+!Mny&Wc%o-!W-@Z*NNl#+H9hB@7fVg8 ziU_K6&rJz%#Oc9N99?>c4O<_Lz7a@rf1dU})emVrqwv+KUF`ldQw%(abm}V+0d)>Fc>-S{fX8`}^8Hx1Z|bleK0V_%6^ko7|>Mwb$JCX|c_ z|MQT>{tPvT!1EEoF_4;W9r1`G=iRuM9&QwYh3|cS+s)neyBzTk8ix#aW*!D!M}%d6 z;A2EszUo)*N`gNx+;yB8;Cs(+H_3fJDR_mHhk=N`$bads?_Oj;9)sI0zPZ!m-8Zde3RoILV z+?!e}<9{-xZEG|vj8Ez~bJO%Id^*UlA6V92J1YMQ>Q2+?zKlys8N6xw6;=A@(GQ~V zMm{QTR-Hp<;nD|3Bvauy29%*4y;axM`;kU@9%3fH66tUNdyrAvOg1pvv~5Ei?5=We z=O82cQeZW(3mIXrbC>M~{A@bD01?KW2^@oUF@LZTnau%wf;6^Z`~#S1+I}AqdQ%Y} z8Z*B_gkC$-cjJJ!0-SfY`yAOwM+!DiZ;ANr%)wW8(h?C!g~+V+M)&s`neCa;z{{rX zC}b&j8M3_Vfh>sw;Xr059%oVm5fbkPDgQDs-n2au5ilE(W#qYd2aDeV|1p(qh72qo zfq$|SnH4PsW+2bXLr+9-dR)OZ;wtbk@J}Ql+dP{+AJ~LfkZSiib_cnSP+aUj|48IF zoEuJt&n;WFFm&ipN=r*wzI-`1-gslsvKu#Uga^y6er3kH z_c!zVz5waep_pnqe-*wn5`TV&@1lQeE#(Ixo!L`9n5%N8dw;+gs~`VCI$$t9{`%rPVmE)aL(`@9N(`~AvX<*sMn0LO3fJKq0TGq?Md)xcju zlph^ISu-7xc9@MU7tQA=2R7e(@4cTD6&2}Vq^GCr=FOXHKtJ@*LqW@#Nli`FF)=aK z*P1zVX25cA{Qd<{Iti(LZXkPky?p^b1 zedkgdAQp4Zz?iHlr z<@<+C z9Uz?0nxptW(-x+4_~ZY)HbRZI@gX9tQUe@sUgCZq;8-&&@eRk?i|FTq@h&1{J@gJ% z(2q-y+51-DMPNGc|B=DQ2@HJcrI#-2(xnTZeHM7!nKWq246uH$aSC`@64w)Vu4Hw zP|m{wWSLVJ+=f>VbO;eb;oxtA8W*HoxWC*P9Oe)%A@Xg#U-Zf_b(g_LuqrvPyF=*%Mth^9zjA7<-_3#yWL(b zB-gE5hc>zSe1Gx97uBDWlLL39x}oue&w#(6Qh1y%B69k33$^O?eYD+KZ3|W1-b+U- zj~*wQim03YkJr1$bV6|%GCOHZ#3EM5BS=RdhWIC4gV%h1E#WVD>WfW?pH#5fVoOBO zzKG1Wrq;nV6~42eNCos^zwK~cr_XjWJ9g|?tt&1mDSzSEF;RtStw~Eut1ehoRUgq! z{xN?3-!%;W)76s_R6VD!bRx43fa1@ezRfqTNh`1AOlyC0H`w)fG;gcUYyBHsDg6~$MomM!yN?Awv_aU2c(sp0ETX|&1mY2QhKWJ;hl?Fw2h~t|u|W98zGVk2 z^$Vn3yMK1o9+yg~YTb}hikKMh>fa;4!lj}joC%=6P-=J~1vLeg=T0I@jGT~P+_w5$ ziW)xrs@vP!5l28!^wz1@4fgEQ9}jV$xC4wkS+{>*{OJ9g|KBO|2@XfYHS=J~bjP7K#pi`{f&o(&kHH-hp;nKKdvZ zTyTNU&M{-g5FPFH>3#OuXE|^nw5wlEP7e3qAId4;pGLm)Q-)UuW7ySGZY6n8225Sr zAEi8v>j8|zA&4odlO!#hzjyK6lN=)9m&$*Pc#x< z^C!Q0g=*mb*AKTop~@@7zbc$%S8Kd)ISwWq%-66HdbYR=-`P+%#08=@#v{+qKmweD z<-V`W=M`yNi8NPRpt@~Fj2a6F9wuZa8n@Huwbx!7Fcz;}yLSBH58inC;(y{|h7TW3 zdV1i*8W|ZGj2JP3`1p9bckf>PeQ=AR#@CkS*=|HuKdp3iCsS}kd_l=~1Ewyy4zy3_ z8#Hxgti%Bto&G1;JbVPufGMvnL2*Zb zVh5ErzA}_5P@VxAH(~uIL})EvVeJrSNdV3g(V+2~4CF@8)m_drtE)tGGk**4S_W;1V)-RxuozF^ z*ucJsn?+mX8Fw`8`x3FnX1nX}2~zhEh2*ko>b|FY@wV{_W_F|cfcFMQ2=aKS}%`n+G#~3UhI0$$bWOO+x7!4w4ygH8APvsbDWmYtsO(5=W3ZP(IuIYKsrb%fHUf9yby##F4ZqZVJ_BiR zF^KN!NhFt*XIY((G-`8Q;*d`DPJnvcgV!~pz)lQN`379fH!4hg`0hTu-Ji;y5=|GL=m z{T-4K%b|Il(i92J@%-Kuc-=CZAkSPOF?~Z3;hBwh>259`k5})Pgv_@5{RYY4Trt*hv)7% zrGJ-x>eMkmgYmuUvhJpnJVg|;>`Fm|!;jS8n|q@WfzTY8we1OAyus**Wan&)SGk^t zSS-IHaCU+Epb0W)^g=p!5h4t>B08I2>dPXUBW^F9kU?J~gWVQnl~8Sx3s+E?Iez>& z`}glBKR=(Cm>9Zu?@qI3;l@crdU`rrwts9PE-ntkFeoc4qo}BeM zEG+69qpFIm4?o1n$UrGYY-}uT+t$pKpp?Ru;9|?}Ef~h>efRI_f3Kfm+>6%Fo%ZWm zSXk8H(8i6dzW8EtpLl|-i4)2HRs2j0d)bLfAwB{oZrI2B0P$Y9O1(oZ)D@JVH9uMMio$0RmGm? zo}(Z=owBkr%F4t|tMQU6q)IKkJ`r?aM8H?mf(LK_ApctaKr6&LgU>eUn$7E)MP zNKsJ{MMXvI?6wml-Vh1V1~?yFeOQ%(v0m!$pW)Lpqly|d^_B2# zo3)_#jZ8ta9Hl2K)d&KIEG&LOl=?Obq?qulfq1^EB4Wu1TtJ8b% zF7c*Mw^86tQ(L8M7ZCVOwzZ;v9<>mq2BGyzY&bF0eZUIUdEFPa9&BM@Q74q==kx6o zPjFz-B2-x!8u7p_Mt^2f$MMdl(t)^k?O62Ui~M%vNV2oD*}i={hGEdBPaj&hZq2f9 zmoeq@DdaWHlXwRw;@TR8xVbg~n!=jQHEfu?fhoV4!XtM-LVVn*zZ60ZnY6M=iL>-V zEw5}hzqV+jRy^g*&$yd_EvW@}{L!t8CVz&L9uTd^+1Xn;7jzfUm7qT0NWsDgG9*}7{GvG(L6!B@SA2EfeH4H9 z9SR8pC`Fcf{ACzIPW*E_oc@vkp)Uoanu5IqP(nh#;# zE#yoJA$JZ_hLT_y<>x7*QwnedC)qnDWUK za+>Cdf`8qKnCVSdl;S)PwXr5{BER4y>~uDh5%dp3zDIg1KLW_~93ue+Z$xoad}hkJIVQ0OWx zlC#)dsT|-i42U1V?0aW(Y5z-WJ-;QWEG!xswSNh!qO>%&OrA{6yYFJx+Gpb8nMLK{ zoke8=N$uM+YtbTpbImpNS#RFl`X{D60M6%ER+uwlbh>hf0dIB*nfhiu%|`!;4h zIE!;yofGujmY}k*Xk>&ERD0IE&i3C;#9mrjz0C9Iu084?vo0#%W@GGKck#sY&y$!G z>3^#iPmb)uZ0>vKK33yCtYBEY1MR zOA0x%?S1Ta8%;)Ef~#jIjw9CpOeFl}0ODPKNGWcZFoAz>+r|}FU)^AJ9@lRiJN~$X zak1kh4n8V;6moQOXPOD~#oZq1p9a~28*XcE1;%x~k3yVfh#!s86$UlNsc5?Gi zkeypdp2JQ_&rTdbmU%~%V(f$oe1EiK2ZMk6+lH=k4aW5w$IeMRxheK0nOzk?QC<=4 zx4UR2ZEr3e$J7VZCoAC`(XTSTtfv@{e+C&&L?pIh3Bwq0C$kW#(}( zBbVa#E!YdhrlhcZ!vlT<& cE?L0;0cpjAwsDP;Pyhe`07*qoM6N<$f{LaG3jhEB diff --git a/doc/source/_static/logo.svg b/doc/source/_static/logo.svg index d21a54221..bf878599d 100644 --- a/doc/source/_static/logo.svg +++ b/doc/source/_static/logo.svg @@ -8,8 +8,8 @@ version="1.1" id="svg8" sodipodi:docname="logo.svg" - inkscape:version="1.1.2 (0a00cf5339, 2022-02-04)" - inkscape:export-filename="/home/afabisch/logo.png" + inkscape:version="1.3.2 (091e20e, 2023-11-25, custom)" + inkscape:export-filename="logo.svg" inkscape:export-xdpi="96" inkscape:export-ydpi="96" xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" @@ -30,21 +30,23 @@ inkscape:pageopacity="0.0" inkscape:pageshadow="2" inkscape:zoom="2.8" - inkscape:cx="152.67857" - inkscape:cy="16.071428" + inkscape:cx="152.32143" + inkscape:cy="16.25" inkscape:document-units="mm" inkscape:current-layer="layer1" showgrid="false" - inkscape:window-width="1920" - inkscape:window-height="1051" - inkscape:window-x="1920" - inkscape:window-y="0" + inkscape:window-width="2560" + inkscape:window-height="1369" + inkscape:window-x="4472" + inkscape:window-y="-8" inkscape:window-maximized="1" fit-margin-top="0" fit-margin-left="0" fit-margin-right="0" fit-margin-bottom="0" - inkscape:pagecheckerboard="0" /> + inkscape:pagecheckerboard="0" + inkscape:showpageshadow="2" + inkscape:deskcolor="#d1d1d1" /> @@ -65,318 +67,11 @@ width="18.115763" height="15.67791" preserveAspectRatio="none" - xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAa8AAAF1CAIAAADQrPIfAAAACXBIWXMAAA7EAAAOxAGVKw4bAAAg -AElEQVR4nO29edhsV13n+1tr7V3DO573DDkEEgkhEQG9PAx5vEijdvcTAW1onECDNj7c2+o1HQMi -jXBtujsdEjgBAqgo0iheBQRazIWGQMABh+5WEdDkomEIMTmcnJMzvlMNe1jr/rH23rX2tGpXvXtX -vcP381Qqdeqtt96q96361Pe3fmutzZRSBAAABx4+7wcAAAC7AtgQAACIYEMAANDAhmBX8MCnbv/e -654070cBDjSwIdgVDLzgGU95/LwfBTjQwIZg/tx313/2/fDIocXjR1bm/VjAwQU2BPNnodMaDL2F -Tuuqxx2d92MBBxfYEMyZ//n+1ymiIJQt13ncZYcQD8G8gA3BnDlyaCkMZSilK8Ta6qIQeE2C+YBX -Hpgnf/TeVzuCh6GUUgnBlrrtK46vIR6CuQAbgnnymKOrRESMSak45922e3hlcd4PChxQYEMwN/7f -X/l3bddRirhwpFKcsVbLWV7qLHbbiIdg9sCGYG48/vIjnDOpZBAESinGWcsRC53W4VXEQzAHYEMw -N7odl4ikVJ7nKyLGmOOIbttdWerM+6GBgwhsCObD33zolx3BiUhKFYQhKcWIhOCtlrPYba8udVEs -gxkDG4L5sNhpMcaUUrqFohQxxgTnLcfptlsrS915P0Bw4IANwRz4n+9/neMIIpKKHMeRUilSjJHg -zHVEp+0sdluO4IiHYJbAhmAOLHbbgnMiUko5jquUIkWMiHPuOLzlOt1Oa3kR8RDMFNgQzJo//53X -tlyHMVJEukJW+ngUjHHGBOeuIzotd3GhRUSIh2BmwIZg1iwttqPld0pJpfT0GiLFiBhnQnDXEe2W -s9BuddruvB8sOEDAhmCm/PFv/WLbdThjRKQDoe/7KrpMOhs6jmi5otN2F7ttQjwEswI2BDNlZbHj -CC1DkkoJIXw/iA7cyBhjxDlzBHcdp91yusiGYIbAhmB23PObr2q3XB71T0gp1Wq1gzCMZEjEGONc -x0Pech3EQzBLYEMwO1aXF1yHM86ISHdQ2u22lFJR0kdhnHEhuCOEHj3U61UAmAGwIZgRn/z1mzst -h/PEhaRICSGkVKSi2+hKWUTFsmi5Tqfl6iUriIegaWBDMCPWVhZcR8QyJKUUI6Yn2cTBkBgxzohz -LoTupTjtltPttOb6wMFBATYEs+Cud97YablCcBZ3kxURFyLwg8iFRKSFmAwdGvFQfxXxEDQKbAhm -wdFDS64reNRMJj1Q2Gq1PN9T+t9EuqnM9BxswRzBHcF1PGy3nHk+enAwgA1B4/z+HT/d7bTESIZa -h9TpdD3PJ70ubzR0yDhnSbHsRvUy4iFoHNgQNM7lxw65jhCcU2xDRYpIdbtd3/dHdbLuoiTxkHNH -6Kk2ot1yWGJSAJoBNgSN0+3o9gkbdZMVEbF2ux0EYbIQhYiImBai4FzHQ1eIzOghAA0BG4Jm+ZPf -+sWW6wiRrpKV4kJwLkIZxi5UjBGjaM4h0/NsOBdOtFAvGTpEsQwaAjYEzdLttByhy9+RDomo5bak -klJqFyajhsSIuPYhZ1xwh3M3Gj0UDg61DJoELy/QIJ/9r69uu47go/6JirIhxYOGUk831DpkUVuZ -okYKZ0JEU21c9FJAw8CGoEEWui3H4ZyngqFOg4tLi8Ph0GyhEGkdRkbUsw6FGC3Ua7lixo8fHChg -Q9AUn/7NV0XBkKdkSETEaHFxaTj0lDn3Wm/cQIwRS4plEU21ieJhy8XoIWgK2BA0xWK37ThpF1JU -Jwsu2MLCcDjU+7yOSmVK4mFSLHOH62zIEQ9Bo8CGoBE++es3t91YhpSsTdbjhuS6LWq1fN+nUQNF -w1iyJCWJh0ax7LpOstIZ8RDUC2wIGmF5IWmfmNFQaSN2ul1izPcDpVI6jF1otJU545w7ul4WvOWI -pFgGoF5gQ1A/H/+1m1otV4h8lRypb2lpicIwDENdIccN5eickZkNdWeZOYI7jtBr9ZI7RDwENQIb -gvpZWexEE67ZqEwmigYNGWNLqyvkeaEMSZGxSJlFZyxeoscjIfI4G7qCuw4mHoJGwKsK1Mxd77yx -3Yqq5NTUmlh6XAhaWZWDoZQySYZJPGSjYUNKimWh2ynxPg6uUSwjHoK6gA1BzawudfUeDTydC+Ml -eeS6Li0vD/p9pQ8BoL+kYdFylKSXkhFisrHNzJ8W2P/AhqBO/tvbfjYJhpkyORk07HQ61Or2BwMZ -zzXM9FGSGdiRCpn2YLQuJdkFNvkexENQC7AhqJO11UVXt0/yS5Nj5y0tLRM5g+GQ0rkwMSeLfDja -CjuZexjVy4I7iIegbmBDUCcdMxiaZbKeaahbKIdWicgbDhURjSZex50UHSnNKYdJsSz03EPdWU6O -NwVAPcCGoDY+855fMIIhEaV1SIqIhBC0tkYU+L4/WpVnDBvq/4/mYOtgmOx4mGRDgak2oGZgQ1Ab -nbbrCL3hv453oy+peJNXx3Vp9TD5Qz8ICu5Cz7GJsmE0B5vpSTaM6S1tzI1tZvTEwMEANgT18Ol3 -v6rlCiFYvkw2Bw07nQ7RIer3wiCMNsFWqRsk36d9mi6WYxVy7jjCEamJh4iHYIfAhqAeuh0jGDJG -mUnXeoSQ0dLSEtES9XqhDNOejBkNGxpjiHG9zJN5Nhy9FFAzsCGogbt/4+bEhXGdbH49GjRkjC+t -HiLq0HYvmnodfSmzdQOR0U7hUcnMU81lwYXDHSHMFIp4CHYCbAhqoNuOjn2i+ycF3RNFRCQ4p8OH -iXg/mnqdDYZJpGQjIWq/Eksq5bi57HDhOByr9EBd4JUEauATf3ZvepJhdqsG3UVxXZdWjxLJfr8f -Tb2Ohw5jola0ro8pM3QYJURuHiTALJZ/8oXPnt1zBvsO2BDUwFve98vm8pPMoY8T17U7HaKjRN5g -EO3zmrkBUTL3evR/Ntq+wVilJ7gQTDdSOI9exm/9nXsbfqJgP4Ot4kAtqKf98I8Qdb7yiQ/lpkRH -u1szRouLi0SHic553lBPu1bGjYjMXWxG+zdwIlOIIrs0RbgOf/j0woyeKNi/wIagFqJmyLf+wMuI -+Nfvfr95bXQoFMaXV1eJBNH2aNfr7GGiiBk9lHiJnq6RyUyI0dxDwe5/kBF1ZvdEwf4FNgS1kJLa -E1/wk/rKr33y9yje/V8IQYcPExHRlh8EKufBEaNtbEZL9KJuSryJwz3/wyPabvAJgYMHbAhqoVht -13z/y4gUUUgkicLX/NTNJ377e2hzKwzD5JuKwqGxJIWIMZJSvuP3jhL1iXpEPaJh2U8EYGqY7SMa -gGow9idER4i6RA6RiIf+krmEkQ2Jgvg8IPKNk2echsZpEJ/6sQr7RNtEPaItol7+kSh1avZPH+wP -0FMGtZDbqLDS7SveRuWuxEc4qB/YENSCRU8wF9gbwIagFnKr66a/n4r3D8mCmoENQS3IZu62LskC -MB7YENSC3EF2m9R38CNoBNgQ1ILOhkUb0jQChAjqBzYEtVC0kfWOKPSdKmk0A1ADsCGoAaVetBv0 -hMmGYCfAhmC3kbfq/D0LDgKwIaiLGkcMy8rk2n8QACNgQ9AEtdsK+gONAxuCutj5mrmJvhd+BDUD -G4JdS16vqJFBg8CGoEYs8RAWA7sd2BDURRM18thZhwDUBmwImmOitXpYnwfmDGwI6qJiZJs62UF/ -oFlgQ1AXhYOGYxU20bavFW8PwDTAhqAh6tVWRrVwIqgf2BDURRP6s3wJQgQ1AxuCGsH0abCHgQ1B -XdSyjhhbNoC5ARuCeoG8wF4FNgR1UfseNoXt6eQc2gU1AxuCuphCT2PX8FmECEDNwIZg94MkCGYB -bAjqAs4CexvYENTFLMtYmBfUD2wI6mI2C0UgQdAUsCGoi7K8VvvBUiBE0AiwIWiCSfduqHhX8CBo -ENgQ1MXODTiR+GBGUDOwIagLlSuWaxRWjWETgGJgQ1AXTRgK063B7IANQV1M3eXAQVHArgA2BHUh -Z+spOBHUDGwI6qLpqlZhkg1oFNgQ1MUOJxtiJg2YM7AhqItaKuXp7AlADcCGoC6kcXknjRT7Ll7o -ooCmgA1BXcyyiwIhgvqBDUFd+ETUTHaD+8AsgA1BPSj1g5krav8J9vtU6lTdPxEcLGBDUCO1L8Vr -dFMcAFLAhmBvgbV6oClgQ1Aj9Q4aQnlgpsCGYJbUvpYZgNqADUGNZA52jOYy2EvAhqBemmslYwI2 -aBbYENSIRVJVtu2q4jh4EDQFbAh2IVAemAOwIagRWAzsYWBDUC/5Qb26DphX130CUAxsCGqkuT0K -Ve4cgJqBDcGuYuzsHKgQNAVsCGqkcDYMFV2ueG+WfwJQM7AhqJGGDiIKD4JZABuC2mlaXvAjaATY -ENTITo6MDMGBOQMbghppOrUhFYIGgQ1Bc1SJhGU3s98VnAjqBzYENdJ0MJzBTwEHF9gQ1IgyTpN+ -Y+E/IT4wO2BDUCMNdUXgRDALYEOwy8kYFovzQFPAhqBGcFwUsIeBDUGNzEaFsCRoBNgQ1MgOy1i7 -ASFB0CywIaiRWpyF4wGA+QAbghppemYMEiJoENgQ1Ijc8aIRBEMwN5x5PwCwn6h9h2rMpwGzA9kQ -1IgsunKHLitb7AxAzcCGoEaaG9fDiCFoHNgQ1EhhNqwXaBE0BWwIaiScdteGDGXDhfAgaBDYENSI -P6sfBC2C+oENQW0o9SOWL9Z0fdmPPjXR7QHIAxuCemloWR5htg1oGtgQ1E7TezdAiKARYENQL7Uc -Vz5/h5aD1gNQD7AhaIKdjAbCdGA+wIagXipGQigP7DpgQ1A7MzikMmQK6gc2BPUy3bGSq/SLYUDQ -LLAhmBmTDhrmeyYQImgQ2BDUS0OzAuFB0DiwIaidnQvRPjKIcUPQCLAhqJeJtloYK7W8+OBB0BSw -IagX2ArsVWBDUDsVhTjFIVOgWtAgsCGolxnsrQAngkaADUFz1KUthUk2YAbAhqBeUM+CvQpsCOpl -bIgbq0vEQDAfYEOwyzHliA1fQYPAhqBept6IEBu7gjkDG4J6aXrcEH4ETQEbgnqpxVYZpaIzA2YB -bAjqpdBcO6yXp743ACYANgT10ugxAOBB0CCwIWiCJnaoRkMZNAtsCOpFTigs2A3sFmBDUC87GTQs -/MYa7xAAG7AhqJfpVDV2tBEGBI0DG4J6aW7EkDDVBjQKbAjqpTlbISeCZoENQb3I9HjfFBNrIDsw -H2BDUC+ypvuBE8GsgQ1BvWgb7rAdPPVuYABMD2wI6iXc2XKUsu8qPOo8AHUCG4I6UeqHmrhX47zw -h55q4IeCAwdsCGqnrp0XUBeDmQIbgiaYQmRYhgzmDGwIaqfe/bsyt0dgBE0BGwIAABFsCBogP5t6 -hxNrJroTAKYENgRNsPNBQKzDA7MGNgS1U3Fl3nTDiwiJoClgQzAbammtwIOgQWBDUDs7dxbKZDAH -YEPQBE0UyFPcAwATABuC2mno0HeYng2aBTYEu4GdT8EBYKfAhqB2lHGq694AaBzYEMyXKUwHOYJG -gA1B7dQy6bqJOwfABmwIakdNOEWm8DZTL+8DYEpgQ9AQtcwZLDyAFLQIGgE2BLVTl61gPTBTYENQ -O/mqdoc7XWPqNZgFsCGonbIaufqkQugPzAHYEMySHY4hYtwQNAhsCGqnif36YUDQOLAhqJ1GzQUt -gqaADUHtNC0sCBE0AmwIaqdw9vVODiiK4UIwC2BDUDtVDDid4CBE0CCwIaiduqJcYTCEEEFTwIag -dnYyYRCyA3MDNgS1Iyf/FkgQzB/YENTJz/zMz9Qx2bBsV5viuz169OjOfhwARLAhqJFXv/rVx44d -i7Ph1DsV5q8fX3dDiGDnwIagHl7/+tevrq4uLi4SnYmv23nro9I9tFotghDBjmFKYcgG7Iibb755 -bW2t3W47juM4Duf8la/8TqIukUPEiVhc5EqikCggCol84+QRDYk8ogHRkGgQn/pEvfi0TbRNtEW0 -SbRl/vQnP/nQYDDo9/u+7+trzp07N49fA9jzOPN+AGBv85rXvObYsWOmCjmfruCosuFNwdBhq9VS -MUEQENHRo0chRDAFqJTB9PzSL/3S4cOHFxYWOp1Ou91utVqu67qu+5733Ff5APMVtzXM/5OI6DnP -uVr/xFar1W63ExGjagZTABuCKXnta1+7trbW7Xa1BxMV6pD4vvf9XdMP4Prrv91xHDdGP4bkqxAi -mBTYEEzJkSNHut1up9PRHnTSCCF+93e/WNOPKkiFL3rRdUKI5MclQnRdt6YfCg4csCGYhhMnTuhU -6BokHkx4//u/WOvhoqKy+iUvea5Wof4ppoVd10W9DKYDPWUwMW9605sWFxe1CrWPOOcsxrxl0t+4 -4YanEYVEkiiIT0lD2YvbykOjp9yPe8r9uKG8TbT5ilc8w/d93/eDIPA8z/d9z2A4HA4Gg8FgMBwO -k8eAjgqoCGwIJuOWW245dOiQLpCTDMgMkltqD+oLUkql1A03PGWcDfUkm35+hs1NN12rJRgEgW+Q -saEWYr/fl3K0QBBCBFXADBswGSsrK1qFSaFqCYaUduIHPvBlbUYp5ctfPiS6yvqjnvyGN5zU+gvD -MAgCXoTIoetlMx4CUAVkQzABd9xxx/Lysq6RtQ21khIV6vNEf2QEw+SCNAjDMLmQJ/FghkyxnCTE -YYyulxEPwUQgG4IJWFhYSDrI+WCYZMNMKuScawlyzqWU5u11x0MppS8rg+T2hZGwSk40bQjAWNBT -BlW58847dYFsNo4TB2ktZs4TCq80TZqxatldJV8qvLeME80Hj/4yGAuyIahKp9MxU6FpQIprZDKK -ZXMQJkl5+WyolNLn5jX6ZvnvKvSg+U9T0EKIMAzn8rsCexFkQ1CJO++8MzOjsFBGmbiXuWYsFW+c -uVlhQtSYTwHxENhBNgSVSDonZaVuckvGmA56STZkRoOluhkrajEv0DIbAmAHLxcwnhMnTujZhUkp -aqbCneiM0n6kSaTJjWFEVj62aD4RxENgAdkQjKfb7WYK5IyP8t+i46F5gcWZ0e5E2nF+zKRXDB2C -isCGYDz5FXhlZbKJrpRNJzKWnd/KrHmw7EuWb8lrETYEFUGlDMZw2223JcOFeQ/mrUSTyIvSQsxQ -9qW8hS1OzHwvimVQBmwIxrCwsJAsRs7kwfxlKpFX4fVkzYaZGxRq1H5NoQ0BKAOVMhiDDoasqGGi -b5DJaMlAYULSYrb7LvNzC+8//9XCa2BDMAWwIRhDYsO8xSrqRn+7lFIftyRh7PdmbpD/cWXZkNKh -EovxQRVgQzCG/FSVQiuR0TYxZxoKIfQW2b7vb25uZvbamoIyh2YeoeWWABQCG4Ix8Hjh3dgwmE9h -jLGlpaVrr712bW2NiO69995Tp05N1+S1l8aW70I2BBVBFwXYeOMb37iT0TfHcY4dO6ZVSERXXXVV -u92e7q7yRpvacWgrg0JgQ2DDcaLqoYoQzW0Nk+9aWFhI/tntds37MW9ZqLbMlclmX1UfPQCTABsC -G4m8EgfllUe5HWuSy1LKjY2N5PrTp0/7vp+RWv6C/frC29hvBkAVMG4IbGy/9rWMqEXkEnEiQXTF -Jz9ZuCmDxlSYUioIgnPnzrVaraNHj166dOmhhx4aDod5hWW+K+9Ki3zN2xcaVil1/pnnaaAPr0K0 -TtSv8TcE9g+wISjlzYytEblEgogTcSJG9Mj3fz8jetynP52Pjck/zWy4tbX14IMPPvzww77v9/v9 -IAgyykvOy0YGzRsUhsrMjc0LJ//lyeggVC5Ri6hN1CHaInaMqbPIkiAFbAgKuI2xDtEikYhVyOIT -ETGiU897niK68jOf0bc3Z9hoEnNJKfv9vr4QhmH+NlSSDS2uzCiv8J9ffv6Xo6PyOfHJTTmRPYHR -OqkLcCKIgA1BilsYWyRaInLSkTDxoEYr5KHrr/+Wz3zGrJrzVkqcmL+y8JaZ66nIfWXfmDyML73w -SxQQCUOFGSG2iDpEC8SuZLQNJwIidFGAyQnGVok68UChUxQMKVahIlJED15/fZmYqkBF6S/vOxqn -P/Oav/7Bv6Y2jU4dog5Rl2iBaIFIy36FaJVojegyomPEjmOeNkA2BEREdDtjHaIFIifOgzyXBzUq -bUNF9PXrr7/6nnuir1rNNYUoJ+Uvf/QvKSQK4ueQlPoiPpXkRHY1o0sIiQca2PCgcytjC+nSmMUl -Q96DZEgwOUmir37f913z6U9TrTYsLK4Lb5bc8nM/9jmSsQdD47zQhokTW3GKXCD2LYy24MQDCmx4 -cPkPjK0SrRQNEebrxrwKZfr8H5/3vG+9+26qVYgT8dkbPkshkYx1rk9BWoWCyC8Jia7hxMsZDeHE -AwfGDQ8ob2bsCFGXqJ0eIiwUYqK/wlMYn/9/L3hBoad0divMepkvSQPL9+av/NTLPlWQ+5x4BDSp -iPUwYuFg4jLRCtEhosNEx4kOEzuCwcSDBbLhgeONjOm3vxPHJlbeNR4bCWVGlFJSeU/Z1FyZH8vI -iNK8Qyll6mkwIyGG6ahYpXA2Z+E8ntEmQuJBAdt7HCD+E2PLRK0KpXHZEKHK6U+lE6IketrHPqbS -xXKhvxLCMNTn5oUwDIMgSC7oy0GM7/vm+cd+4mPZxxSms2vmFMTnAZEfn/tEHpFPNIxPfaJ+vHxl -ACfuf2DDg8IJxtrxwhIRB6aKQ4SFkdBSNT/zrrvs2dD0YEaIJhkhmiQq/MOf+EPbQwytTjRPvnHy -YiEOKFrSt0V0ibB8ZX+DSnn/cztj3fTCkjIPUkkerO7BMK6Xy0pdMx4WRsV8RWyHePwQkwJZ5qrm -TGvFPIn0yYmTs1Mw4MiuYrSBkLhvQTbcz/wXxhbTpXFm9ow+LxsirBgJw/S5vvDsj3zEEg+nqJT1 -P3UkTLLhR1/+0cnkbT7KTEgMywtnLw6JunDeIOrBifsQZMN9y1sYW83tuVDYL6ZxebBMhZky1PRM -Ph6OzXpVkmA2GJLhdfOh5xNivsGSOeUbLMJorTjpnLhN7DKmHoUQ9xXIhvuQNzPWMYYIyzxI1gnV -U0TCzOmff+ADO8+Gmf6JOW740Z/6aMHToPRzKOx8lz10s7ti5kQvN5jYNwYTERL3C8iG+4o3xgtL -8kOEFg9Szh5VImGmNM5bReYm0+SFmDRSMv/MXF8o0NGTYXEeNOHG0yscTCzMiUHJqGLhFJw2URf7 -PuwfkA33Cf+BsUPxEKFj9SBViIRjh93sqTDJWC943/vK2sqm7+w9ZXOGTTJu+NGXf5So3PFU8sTy -z6rwyWRCYr7j7KU7znoWjgcn7m2QDfcDJxg7lvbg2K4xpUUxNhKGOXuERjAMSkyiNzS0F8uJCu3X -Z0rpKAwm0Y/iC/mQSHFOLBtMlEXztIPyYcRMVDQ3kT3MIMS9C2y4t7nNWFgydjtCS9fYEgkLPVjY -mM2HKn2wUGUsO7FUvplgaMmMYRimvKbSQiTjGnt3hRvPLb92JUh3VyyFs7l8Bfs+7FlQKe9V/nN6 -YYk5oZpKusZUIsEyFeY9OLY0zk9q/tF3vSs/6zBTLFeplM3+ycf/zcez08fLdh8znzMZT9v+nMtC -r71wzixfwb4Pew1kwz3JHYwdLhkinKhrbKog33QtLI1l2oBl42yJNMxiubBStmfAQj9GeY1yS6wz -ZbJ5jb7M03IsrJ1lUU7MxENeVDi7ucL5KFPnIMQ9A2y4x3hTvLAkvzF1YbekSiQ0L5d5sKw0LlOh -n7OhpVgutKE5wyZzDYXx0zAnlJuw3AXzS+bvxTKYOOm0xEz5jOUrew3YcM9wK2N636nptiO0tEpU -uQfLSmNLdWyu5giIMgfJS8rkwm5JRnzJ5czGDdExT5QR9zJVsyUkJuSX9JnjiaHVifklfaIoJLai -fcPY4xj14cTdDmy4N3grY4eMIcK8B5P+KpXPMLG0jC0ezM88KVOhn7OhX2RDS1t57KDhyIYqVpJK -V808Lb6ykJjprlD8XWZbRsY2LHRiWCTHfEJ0sXxlz4Auym7nRLywpHD2TKZrTEV5cOzsmXzPpCwV -mjZMVvf6Jd0F3WC4m+iuW24hop3bUE82/Nzff45uMz4ZRPr3kvmgKGsqlf2mqnSUChNy/lfgpWcm -JstXcNjS3Qqy4e7ltpIjllTsGleZPTNRaWzplpilsWcIQTM2HpbZMD/p2vd9IiKPSBI58bMyQ6Iq -EmI+LWa6K5mcWNZdsYREkW6wWFawdIldwbDvwy4ENtyNvIGxQ0Qr6T0XCj1I5UOEE0VCS8PE3i3J -l8bahjJ+eB983euU5xFRRoj5eGjPhn7M077laX83+DtyYyEqQ4XCqJrzrRVKO7FwbHFsd6WscDaX -9FU5ItU2seOMfDhxFwEb7jruYOxYtT0XqKhrXD0ShiU2rD6XMONBrcIg/Qi9WIU0rljWCdHcyMsM -hsm553nUI2obz0SHxIwTy0IipT9VqndXMlO1807MhMSxR6TC8pVdBmy4i7i98p4LVC0SlqkwP63a -nE5YOJGwrHGc2eQl/7YeDofRAy4XYr5SLguGkQ23jEfpGkJMcmJGiGZOzBfOZSEx011R6XhY1mDJ -LOnzSwpncxNZ7PuwO0AXZVdwS7ywpHA7QjJyDBkX7HVxdQ+W9QYSA+Ybx2MjoeYFr3gF55yIGGOq -5GApdhsmkTBRoed5w+Hw/A3naSE+AF4SuApbK/np6YWN5rLB18IPGftYQ77ZlP/oKNxEFstX5gqy -4fx5C2OHi4YIC0cJydoLtUTCvActDZOgSIWFHiyLhJrt7W0hBGOMsdHzKIuHeRsWqjAIAiKi00SH -iRaJgqKq2WytqHTVnEzBsYfEwu5KUmgXjiSaOTEs2vfBLJxFbhNZXTgfYeo8hDgfYMN58ubcwpIy -D1qCSz4MqsoelCV50NI4DtLdksJISESnlCKi5z//+a7rOo7DGNMhkeKSubCznJlunZTJXszoF/Jh -RUTspxitEC0QhUTtuHDON1hMIVLRJ4x9JJEZv/qywUR9fTJtmxlVszkzsWyqtjCa7TAAACAASURB -VOFEHLZ0XqBSng+3MrZUbc8FslZv+QJOFXlwbGls75aUNY7LXjqn0i+q5z73ua1WSwjBOU9CYr65 -nLehGQmTezt37px55+wlLAqJXaJ27JRkhK6wcM6HO8r93u2Fc9l4RNm0xLGFc2ZjbV0447ClswU2 -nANvY6yd23MhmRmSYaL3o7J6sEppXLFxHJY8tVPWl9OznvUsx3ESJ5pjiGZD2YyEYRj9qIwEM4xC -YicWopt2Is+NREw6T5tyv/0qg4mWMYj8J0zRJrI4bOnMgA1nyh3phSXCOnuG0mNWspoK7R4sLI0L -uyWWxnEZdhVmuPrqqx0nGqhJhDhae0dE4wyYgb2E0RrRkhESXcOJYxeu1N5dsTuxcPmKGRKHxvIV -7PswE2DDGaFnz7SKhggzoWTsEKH9DVhYsVliykSN4+ki4SwZhcS24cSMEKuERMr9SagoJFoGbgv7 -94UhcWzh3CPaIOz70DSwYeO8gbE1onb5nguFQaR6JLQkEktpPEXjuIzdo0IN+1FGh8eFRJ7+UMrP -cZ+ok1VlMLHMiclvv6xwzmwiG8CJTQEbNstbcgfznLprnEkeFT0oiwxYqEI/F1OSpLL7I2Ee9nJj -JLEsJHLj0ym/DtweEmkSIVqcWDhCYRlMxL4PjQEbNsWbcqVxxa4xFUlwbCQMre+4nTSOy9jNKtSM -QmIn7q6Yk7SdIiFOFxKp/G9W+Kca68TMJ5IXT9VOBhM3CctXagc2rJ9bGFspWlgyXdd4bCS0DBHK -dKvE4sHC0liWPMHd70GTbEhM5veJXOFcKMTpQmKVj6/CrlbZX8UrmYWDw5bWB2xYM2/NlcbVu8am -AQvH5S0etDRMxk6r9ouq4zL2lgo1UUjMz0l0S1orTXRXVMlfbqwTCwvnZDBxi+gShFgPsGFtnGCs -S9Qq33OhStfY/iayeNDSMJl0LuH+iIR5UiGxcE7i2NXNOwyJlsFE80L+D1ZYOGc2kcVhS3cMbFgD -b8wtLKnYNab0+6VKJLR4MJ8wLCrMe9Dfd5EwD/sRRkcmX7hiD4nmL6YwJFb8cDP/ipnZT2WFs5cr -nLHvww6ADXfKnbmFJVN0jQvfL6rEg2NL40IJ5nNGpjTer5Ewz/iQaF+4Yndi5g9M5Z910zmxrHA2 -l6/gsKVTARtOz1uMhSX22TM0YSQsG2WqWBqP7ZbkU2EZ+0+FGvYjFeYkFq5utkzByYREqtAaS/7S -hWPAZX/RssLZXL6CfR8mBzachtsZW8wtLLHskDLpmJKq5kFZ9H6ZqHF8oCJhHvZvKsxJrCUkUvmf -vKwEKPuUq1g461k4WL4yCbDhZLyBscPlC0ssXWMqyQf24qnQg5Z3ir1xnHn7BOVP8yCoUDMKiVXm -JJatbjb/8KxaSJxoMNES+zNL+oaxE/vGYCKWr1QDNpyAt5YfzHOirvGkHrQPEU7XOC77qx8cD5pk -Q2LZZtpVFvPlsbwaxr4OLE7Uf+zMUsr8xtrY96EysGEl3lx5zwUaVyFNHQkL3xdB7t1R5sFg3P6s -dFBVqGE/nG43t429qauHRKrgRPvHYzJWUtY1s4wN2/fC2SQcttQObDiG/8LYSro0ZuXdEnskzAyg -W1Q4UWlcqMKyxjEioZ1USGwZhXN+4Up+dXO+u5In/yFZ5cVheSnYC+fC5Ss4bGkJsKGNt1Xec4Em -iYRVCiO7B/NvhEy/Md8wQSSsSDYkVpmTOHVIpPJXSf4lUvayKBsfsSxfwb4PRcCGxdwRLywxt2Wt -pWts9+BEpbG9cZyUxoiEU1AcEqssXCmcgpOnLCRW766MdWLZXjjJLBzs+5AGNsxyW7ywpPBgnhW7 -xhNFwrwHp+uWFDaOw/JnChXaYT881ZzEKborVaqJwtdN5rWSf3FYCucB0TbRJpavjIANU7ydsbZ1 -zwX7ugP7B3xZ6VPmQZl+kU/ROC4DHqwO+0nrnEQn3VqxrG7eeXdFlbx0ypw4tnA2l6/gsKWwYcJb -yxeWFM6eoUkiYdmweMWBwoqNYzMEIBLWCPshRkdmEhJp8tZb4cBK5hVjKZyH2PdhBGxIb0ovLNlJ -17hszKfwQ33sEKG9W1LWMEEkbIhsSCyck1jlKFQ7DIn2wcS8EwsLZ8vylQN82NKDbsN3VN5zgcpV -mM+DmVesSktwbGlc1i0Z2zhGJGyUKCTqdnOVhSuZ1kqj3ZVCJxaGxHzhnEzVjmfhHMzDlh5cG74t -VxpP3TWu8kIt82BZJMx/roc5D2bmEpYBD9ZLaUgsnJO4w5BI1k9d80J+8EVfKJuFYN8L50Du+3AQ -bXjCurDE4kGaMBJaeiZVSuPCrnFh41iWP1mosAlSIdEyJzEvxPz8m3q7K/nXWf61pV9e+SV9+SNS -HbB9Hw6WDW/NLSwp9KC57n7sEKFlgNvSMykU4ti5hNiMa1eRComWOYmWo1DZhUjlhXOVF5+9K2cv -nDPLVw7Gvg8HyIZ3li8s2XnX2D6SU7FhMnYuYaY6RiScO+wHJ283TzoFh8oT4qSDiRYn5gtnczDx -YOz7cCBs+BZjYUn1PReo2suvugctpbFdhYiEuxz2E4xWJ9lM23KAgSkK5/xr0T6YmC+c85+6mb1w -9JK+/b7vwz634e1FC0umWGs8XSTMezD/ggysKiz0ICLhLmQOIZHSr8sqg4n2l2BZTswvX9mnhy3d -zzZ8R9HCkhq7xpaxmolK40zXuHBOtY/9WfcC7Ccm3Ex78pDI9Ht2usK5uhMza90ze+HownnfLV/Z -nzbUs2fKDuZZvWtsGa0u/Oi1vORkzoCWIcLCxrHl7wQV7h5GITG/mXbh/JvJp+AwYkRU7MTCEqai -E8uGafL7PiRL+vbX8pX9ZsM35xaWVNlzgSYcpFaVPVj2GTxWhdiMa0+TDYljF65YtsApetUyxoiI -FClZkhPHDmyXvUbHFs755Sv7Zd+HfWXDd5YvLDFnz5CRsyoOERaqMO/BsaVxlcYxIuH+gL2Y0dFJ -NtO2r27OOTESIhFJa04sq2gsL9n8a9SyF06yfGXvH7Z0n9jwzsp7LlDlrvHYVolloLDw1TVp4xiR -cB+QColj5ySWVc3WkBgVzlJNmRPLapmKhbO5F84eX76y5214R9HCkrq6xnYPViyN7d2SssYxIuG+ -gb04124u20y77AAD40KidqKSSkpZ52Bi5oVrL5wHe37fhz1sw1sZWy1aWFLWNc5Ux7VEQkuPrmwo -ZmzjOCx/yvDg3oW9bNycxCoLV8pCIiPOOGNMjyRmnShzl8e+rPONv+TcvqSvH8/C2YPLV/aqDd9u -PZjn1F3jKiosG28pHIwuU2HZJjSIhPuYgpBYcU5i5ZDIOddTcGQoiwtny2Bi4aCPLA+J+cI5vxfO -nhLi3rPhW60LS2rpGtuLiSql8dhuSX5GFyLhAYG9bPLNtC3zb9KveC1EzjgRyVBKmXNilfGgzAe+ -/mfZZIixe+HsneUre8mGtzO2XL6wxLKiaeeRMO/BiqVxxcaxBahw/8H+NaOj0y5cqTAFh3MuuGCc -KalkKMMwTBXLFbsr9hd6UuyM3QtHF8574bCle8aG78wtLKkye4Z2HAktHsy/TuzdksKGCSLhgSUb -EivOSaw2BYcxJoQQXDDGwjAMg1CGuQZLYSKo7kTLzMTCwcRdf9jSPWDDt8WlcX6j9bLZMzR519he -LhQOFE4UCTMNE/v+rAQVHgyikDjRZtqFrZVMIogvc8YdxxFCKKmCIAiDUElFkoiMN0OhEO2DiRYn -ZgaAhunBxN192NJdbcMTxsISJ/3pSEXVsaVVYv8sVCUetJTG5kCKXYWFDRNEQpBQGhJFeeE8SUh0 -HMdxHM54GIaBHzvR8t6wpAOLEwvHxfN74fR2774Pu9eGv2JdWGLpGk8UCc0/fTjur28vjfMFclnj -2AJUeDBJhcT8nMSKC1fKnMhIcOG6ruu4Sinf9wMvCMNw4u6K3YmWwjm/fKW3G5ev7EYbvt26sGTq -rvHYVknZX3yi0jjMedD8mJTlzxoeBOyGSeYkFs7TptLCmXHmOm6r1XKEEwbhcDgM/KBgMHGi7spY -J1qW9O2+fR92lw3fkl5YInKff3ks1XFhXWxXoWWIUKb/3GUfh5aGiQWoEGjYiyq3mysehSoTEoVo -t9rtVpsx5g294WAYBMH4WThlNVTFkJhvsJjLV7Z2y/KV3WLDWxk7lFtYUm/XuLoHLaVxWXVs9yAi -IZiI6UNiZli9KCRyzl3X7Xa6bssNg3DQHwyHwzAYNwvHMr4+XeHsZQtnCufsxF1hw3ekF5aYkZBy -n3CmCmuJhPm/qaU0tnRLMi01REKwEyYIiZn3TJXuCiNHOJ1OZ6G7IIQYDoa9Xs8bemNm4Uw6mJh/ -q2RGjvJ74cx134f52/BTv/HKdttd3+xt3fyuwiHC/ASaiSLh2NGPsr+mzP1Z7SpEJAS1w26oY+FK -iRM5561Wa3FxsdvpSim3t7f7233f90eFs7S+ryZ1or1wHtJTzl6+vtn3g/DM+Y15/LLnbcNPvOvn -u+2W6wpHcM7ZgzfcXuZBmrZrbPkwy/8Fy1KhfVr1RJtxEVQIJmEUEi2baVdc3ZwvnBk5wllYWFhe -Xm65reFguLGxMegPgiAoKJyrjDoVvpcy75+iwvl7zz5pqzfc3O5f3OgR0VyEOE8b3vXOG5cW2i3X -cYQQnHHOGGMP/tgbqbGJhJYh4IrVcVnHzIz/ll8oPAimIxsSp1u4Uh4S2+328vLyyvIKEW1ubG5s -bAwHw2zhXGUQytKILC+cf/DRp/eH/nZ/uNUbbmz1N7cHNA8hzs2GHzzx04cPLXZajiOEEJzrDYkY -Y0TfeOmt5i2ni4SWP1OV0tjSLQlLJtAgEoJGYS9kdGzCzbQzq5vtIdFxlhaX1g6tLSwsDAfDixcv -bm5u+p6vwmmnauedWBQSf+rsdw2GwWDo9Qbedt/b3B5c2uwNhj7NXIjOLH+Yyepyt+UIkVMhMXrC -h3/5Gy+JhFhliLDwj6KqedASCe3dkvycakRC0Cjq44qI2I/H7eYwbjdLIic+F0QqPtenzC4P6V5K -9KplRIoCP9jY2BgOh2uH1g4fPnzF0hUb6xvnz5/vbfcCP0i98Vj8HmPx5fxIpYyv50RhfIHHb6e4 -+XPT+r8YuoFSpJSSSkmpQimDUPpBGIaWgfdGmE82/Niv/rvFrq6RueBc18hElBzpgRQ98NJbaapI -mPwzTF9Z3YNVGseIhGBesBfm2s2Fm2mXLVzJrGzNFM6MXMddWlo6duzYodVDnuedO3vuwvkLg8FA -hnKng4nJhYAopF969AV+EAz90POCgecPhn5v4PX63mZvsL7VvzTzAcQ52PDDb/3ZtZWFdrpGpkiF -0aeVflAPvPRWSySs8lfIx3ZLaTy2W1LYMEEkBHNhFBIrzkkcO5JoXOCcdzqdI4ePHD9+vNPprF9a -P3P6zKX1S/7QL13jXDaYWPL2u+Xsv/aD0PdDzw88Pxh6wcDz+0O/N/C2e0NdL2/1hjRDIc6hUl5Z -6rRc4QguBOMso0KiWIVKqcI8aB/DreLBslRYsXEcxN2S0Po0oULQKOqDKhUS9WvXjV/xunYWcbGc -XFAlQqRU4Syl7PV6vu9v97Yvv/zyy45ddvjw4dOnT585fWZrcysIgtS7kRvlc2HtnFTNSe3MyXVE -6unoU3QkAyWlCkPpB3Lo2efs1smss+F//7WfX+y2Wq4jBBfRYCEzVKhGKlSkSH39x2+r+Ak01oOF -qTDI2bBK4xiREOwe2I+Pm5NoTtIuXN2c765QdFmHxGPHjl15xZWrq6vr6+sPP/Tw2UfPDvqDnUzV -vvPMS4Mw1OODvh96QeD54dALhnG9vN33tnqD9c3+uUtbSqnZxMOZ2vAP3v5zh5a6rZbjOmLUOSlX -ob7wtZfdPml1XDZEaC+N8yqcdDMuggrBPGD/itGxyReu2OdpGxccx1ldXb3yiiuvvPJKzvmpb556 -6KGHLl646HvpwjlTwZW8Ud/16MvCUAahDAIZhOFIiF4w9IPBcFQvb2wPLm32ZjaAONNKeXmhHU20 -ZgUqpCIVKqJr3v/6+19229SRsJbGcVIdW4AHwbxQ/z1uN5shMSmcnfhdIdIls8q1VlRx4RwEwYUL -F/q9/qX1S0984hOvfdy1l19++QNff+DkyZObm5vRGmcy7jZpVZslMyeS9N4zLw+F1MeANobHop8e -Fcu6xSxVGNXL4XZvOINf4+xs+Mlfv3mh03KE4HET2RwrjH8RKRUSEWOMiIUVVFixNLZUx/aGCSIh -2OWoD6ooJC4SBUQd4+3hGMHNnH+Tn4JD8WU1CipEpEj1+r2TJ09ubmxeddVV115x7XXXXvfYxz32 -q1/96pnTZwoKZyoeTBSCM2KMJBGxAh9S8v6PRg+lDMLQ98PjR1aajoczqpTveueNK0vdtus4Djdn -1MRfV0rFKozOiEgfMpuFYRiG4T+8/EShCsPc5bGpsGxataVxbAEeBLsN9mNGu7niwhXLAQbSg4mM -sU6n85jHPObbvu3brnKvGtDgK2e/8rWvfi0qnJVK1cvpIf8PnPm3+kB+oZRhKPXUwlG9HOj+cjj0 -/IEXDAbedlIvb/TOXtykhuvlGWXDpYV2yxFC8HgBHuk2clwcGypUSmkRMq6IwjAMgjAM5RP/6y/c -/3++raIHLaWxvTrON46l9XlBhWAXon5fsR+IRxKDuGqWRu2cpML8PG1edI/GRGBFqt/vP/zww+vr -6+euPvftj/32Zx979uOPPf6+r9/3T//0T1ubW2EQZm1IRIo+fPZnJFfEOGOSGGfx/OLkgvkMiKL5 -2Mqoly9t9hr6jWlmYcNPvfuVC52WbiJzPl6FnHPGuVIU+EEQBPrDRCkVlnswHwbluDxYZS6hBXgQ -7GbUJxSZIVG/+qssXMlPwUkwCucgCC5evHjvffeeO3fuO77jO57MnnzFE6/4h6v+4b577zt9+vSg -P0h1V4hIkeCcMcWkYkSMVEhaA4zFP4OlqkVKzCCVklIGofSCZuvlxivlj//qTcuLndaoRiaLCokx -zjnjQkrp+74fhDKUUuljZCsl1Zd/7p3TNUwCqwon2oyLoEKwdxiFRHu72b66uXDVCulxQLGysnLN -Ndc86/JnXUlXnqEzXzj/hfv/8f6LFy76vp/k0LvO3JhkvWQFnp5UGNXLoQyCUA8RekEYzcdO9Zf7 -Fzd6j57fDMKmtvxqNhu+/83/9jFHV1wn6SOTEYoLVCiEwzkPwtDz/CQVmr/B5xL98eSlcZUJNAEi -IdiPFIdEs7tiBkORrpqpaAzR7DsrCsPw0qVL9/79vY8++ujTn/b0Z9AzXnTkRV9+zpc//7XPP/jg -g9tb27q7wjlTiphkkitS0aRtpkMRM36Obiekujekono5Wr989sJmQwmxWRseW1uKOyd6zQlLZtNk -2iaMc8dxGWOe78cq1B6U2oP6/NQ7fi64+V07mUtor44RCcG+JDWSON3ClcIpOBS9mQfDwcmTJ9fX -109ec/K7Hvtd19F1115z7V898a++9MUvnTl95g/+6acVU4qY4ooUMUWMOGMqGkBkujcTnWUiaGKK -KFGG0vebGkBssFL+xLt+XtfIQvDR7MLRTJpEhcS5cF1XEQ2Hnud5QRhKnQpjCcrIitHle1/97hrn -EmLnBXBwYD9WeTNty8KVksKZMdZqtY4fP/6Mpz/jOfSco3T0frr/e97dH0WfWGwyPYcm6TInJbMf -jOrloef3B35v4G31Bhvbg4vr22cubPYHXu3xsKls+JG3/ezRtWVtQrsKHcd1W60wDAeDwdDzwzA0 -PBgHw7QQg0lK4ypzaBAJwQFB/b5i38/osrjdbIZEx2iq5HMilUy+MdKiUmroDU9+8+Sl9UsPXfPQ -d1/x3c+kZzL6W2KKEVNMKcUUkeIssmMcFBlTUZ0cZcToR6SaKmTEw0A+4vm118tN2XBtZbHlCsOF -RJRSoVRKf5K03Jbn+71e3/P9OBSmDJhJiFKqJ9/2ii+9/rfGziWs0jhGJAQHDfVJRUTspYxW40na -Ey1cKZyCQ6PCWYZyY2PjvnvvO3PmzAv+Nr/ihEgPGUpi3KyaiTEVazYaPmSpb4wiVChVEEo/CB69 -sFnvb6YRG37qN165tNDWMhypUKVUqFeDC8ft9we9Xs8PAillGG1fYQgxJceRGYPJVWh6MBi3ZT9B -hWBfoz4Uh8TFeE5ixYUrND4kkiLP9x555BFijJSKfKgDYhISOSlFpBgjxfRtSLFornE0ilg4hKi1 -EITh0A/qjYf1jxv+4TtvPLK62I6KZJ5ToZKKhBALi4uM8a2t7V6/HwSBfoahab34cijTNoyF+MVb -ftc0YFnjOD+nGpEQgIQoJOYXroiiHR+qHGAgduI9j76K4onU+ppo4Z1ebKaUIkpmjKj0tJtADyNm -BhCHfm/o9/rDze3h+lbv/KXtU2cvDYZ+XUKsPxseWuq6etlJrEKzQlaKWq3W4tJSGMp1fXQuXR1L -FY58lw+JUSrU1+shRL+8cVw4h6bKZlwEFYIDhvqQYi8wRhKThStOegpO4cIVKpqkTdH1SqlRyUuK -VFI0M0bR1ziR4sQUScWIdItZMUYsjMYPo8HE0b0Q6f6y0vOxg5OnL9b1q6g5G97zm69aWui4rhB8 -NFgYzbpUShHrdDpLyyv9/mB9fX0wHIahoT8VOzHuMWUiYZiOh0rKvznx4YqN4wCREAArqZA46Wba -uZD4qUdfmTdkQhISKe6mmtOK4zyUajH7QbQBop6PvdUbrm/1L65vnz638eiFjVriYZ3Z8OO/etPa -yoLjcGH0TaJOkFKM2PLy8uLi0qX1jfX1dc/3R+ILR/oLozxoxMOMB42RRL+oLi5rmCASAmAhFRLt -cxLNSdpUHBLjmMWIFQbH5D9FjJEahUTGiDHOmApHg4g0asUa9y+lkqH0g3BYU3+5ThuuLHXdeB9X -oliFUkmlOBdra2utdufs2bMbm1tBPKUwlEqG0edA/nwUFdP1cnLhaTe9+H/9yl1jPRhaHzY8CIBG -3R23m1eIFidZuJJe3fyJsz+vp1tHq01iI2a0yIgUY0xR3F0hFf836jKzeOJNdCHuXStSiqSSoZR+ -EPaHNRwwoDYb/tF7X73YbTsiWopMNFKh47iXXXZcSnnq1CO9Xk8vPk6WKEYTLyMtmiExsV4qJ47M -qJSUyrNuQoNICMCkqA8p9nxGx6dduMJJyshimaUrKhcVjZAYMQqJ0cybRIbRZMTU3g56hkkovTo2 -QKxn3PDuX795dXmh5QrBOUVN5EiFnU738ssfu7G5efr0GT1QGI48aF7Wk9F1MEwGCuNRRTMb5prL -f/HeuxEJAagd9pJ0u7nawpW7zt2ozRUvuKN436pkFXIUFFOTCaP/JUtWRiOJoZTSWKaStJj7A683 -0Eej75+7tPXNMxfPnN/RAGI92XB5UXdOMiqklZXVyy9/7DdPPXL23Dnf98NwtMtjpMX4n5momFKh -OYCYmY8tlVRyWNQ4tgMVAjAW9WEjJI5duCKiYcQwlIyxONYpfZkYY0rFS9KS9vCogo7q32h0MLpG -xiExTKYhGhARMaYUSUWyjnq5Bhv+6W+/ZqHbEpzrYKxVqBRddtnxI0eOfPVrX19fX9deNzyYnKeF -mI6HqZCYjodhtE4vKpbNVIhICEBdqE8pSkKifeGKrpRfTcH/LRmjZD1u7C4VzaeOJDbazMqsoKM5 -2rEjuZ6ozRRjKtRbQBuHVGLJNjCklFKBlL4fXH7s0CNnL033ZHdaKd/znl9YXeq4juCMJSokYlc9 -4WouxP33f6XX72sPmjYMslrUbeUoLWb6KsVTEY2QqKT64z/4c0RCAJqDPd9oN7fjedpOep42p9+7 -8H+wWFuJDXlKi5S0iOPa2aigs8VzVDhLSSqegReGoyMH6D0QtwfeVm9wabN/7uLmydMXv/HNc9PV -yzvKhn9w5//12MsOOSKlQi6cpz7128+eO/fAA98Yen6yL0UYhnp+ecqGxjCitV6OLyhz9HAkxAF2 -XgCgSVIhcSHeSTu3mbbvh2x0cODYg6lrzKJXB0YV171EZIwpRnOviYg4J6V0U0UxRowTY4wbKZER -KUVSyiCQ/eGUE252ZMPjR1ZariN4pMJQqk678x3PeOaX773v9JkzQRAGodTHkA4D7cQwWXOTToip -bJidfpgfNMw1UqBCAGaA+rBiz8u1m1txvXwreTeNbMg5xRfMtJj8M61FFh8WgEXzcpLimSnGGOm5 -N9EtjftJYiYRkR46C4Lt/jRHHJ2+Uv6T3/rF5cWOEJwR6TVza2uHr3nqU//6L/7HxuZWEIb6UFjR -eWjYMFc4m00VmVzINlJSI4aZbCil+vyf/l3+QcKDADQB+1FGh7ILV95+6aWR6TiLjoHEGTdsaHw1 -9iOnbJA0A192nmK8cUO8qDnqMvvhwPP78QKVsxc3H37k4r1fPTlpPJwyG3781246fmRlpMJQXfWE -Jxw6dPjPPvvHA8/XK2kiFQahn3gwNmNyMITM0KE57aYgHiplajFjw/yDhAoBaAj1EcW+j9FjUiGx -P/R5pD+u3Zf5ZyLHAkUaWS/+fxwDjS6LXrHMjZDI4//xWKJKqTCUg8kXqExpw2Nry64jGDE9Nfq6 -//3ZJx9++M//4i+9IPCDMAhCP5DRBTMeBjKMc2KRELPjhvk1y9nRQ2Mmtvnw4EEAmkbdo0iHxNVo -W7Be34sMyLlIPJhck/gx5croMCGFomTJBZXs/6rjo4qnZWe0GxlRKRUEctJ6eRob/vn/89rFblur -UEq67kUv/sIn7z5/4aIf6ONdBbrdM3JiSohRNkxGD4umH2Yn2eTmY5tbOURaTB4eVAjAzDBD4sZ2 -X3Cu93jWm1jlzyNRRteYZoyOMBz5kRdU1vEQYSRG3Z9hTLHkZrE9iUgq8oLg6iuOPXDybMXnMrEN -7/nNVx05tMQZk0oSE8/64Rd/7v0fHAw8zw+8IPD80PdDPwg8Q4hmQjRaOLQUBgAABCtJREFUzPqf -mfnYo/mG1sXLGTnKUCqCBwGYB0lIvDDcFoLr/fyEYEJwLUfBeXQN54JznlxIRBkdbN0UJU9SZGJJ -sz+TbBWW+FDfRkSSZYyRlHLoTbAj7MQ2PLy6KASXUi4sLD3pyU/5o/f97tAPhl7g+ckp9ILQ95OE -mIuH8TBivq2cK5lVeiTRaLAYc3R0MDwDFQIwP9RH1HOefk2n7bZdx3WF6wjXEY4QjsMdIRzBheBO -7MfkgmFMlngz0aUQWpG5OCkzDWXdexFJzOTR9qpMStUbeBWfwmQ95b/6wOvbbVdKec21T3ro4ZPf -fOTMcOgPvWDgB57nD73A80PPD0wbRkIMw3jCTXlnuciMgfElfWMiaujY0gCA2vlnz7i223bbLaeV -WFIIxxlZ0tFxUisyOU9cmVwenUeK1HJkjHMez7Ah0kde9oNwMAy2+oMLl7YfOn3hr+/9xt/c9+DY -hzpBNvyz3/n3K0vdMJTPfMmP/+lv//Z23xsMvf7QH3r+wIsO9BfZ0A/8IPT8pFiORgz90dzDMLFh -PIxoKDKI5poTxAfAHucvvvDV/JXf/cxv7XZanbbTcp2W67R0kHR0ouSO1qXg0bnQ12hXiqwuYz/y -uPHiMBElSsH1oZmCQF5xfO3kmTG7ZE9gw5VFrcIb73nPm3t9rzfwegNvMPD7nj8Y+hkbahUa7ZQw -CEPfnIEYB0Y/kH4QSKkgPgAOCH/2t1/JX/m91z1podvqtt12y225TssVLddxHRG5Ms6VsTcLpCni -Gplz5roOj0zKGWfXP/spYx9V1Ur5i//tDVKqw0ePf/kfv7K5PdjqD7f7Xq8/7A/9gT5FlbIeQwz9 -IBaizolRuzn0/CAIQogPAFCFf/mdT15caC90Wp222245bdfRRXdKl65wHXOwUpfejDGmlPKDcKs3 -fOTs+v/6+wc+8unPW35WJRt+/kO/TESXNvuXNnqXNnsb2/3N7eF2f6gTohbi0IuEmDhx4Pk1Hs4K -AAA03/ddT11Z6ix2I0t2226n7bZbbqfltFtuuxUb0xGOIzhjUqnewPvmmYsf/ewXPvf5gliqGW/D -P3zHz13z+Md+4+SZM+c3zl/curCxvbHVj+Jhz+sNhr2B1+t72/3hNx+dciMdAADYIS/83qetrSws -L3aWFztL3fZCt73YbS10Wt1Oq9NyHcH9MDx5+uJ/etfHyiJalWz4wLv/43/8xslzp85eevTC5vlL -2xc3tr/20KO1PxkAAKiXG37gOy8/unrs8PLRQ0trKwsL3fa5i5s/+br3Ft54jA1vf+UPve7tH23m -cQIAwKz5ge/+3372pd/zwht/Jf+lmo+nDAAAexQ+7wcAAAC7AtgQAACIYEMAANDAhgAAQAQbAgCA -BjYEAAAi2BAAADSwIQAAEMGGAACggQ0BAIAINgQAAM3/DwVXEvzRPjD5AAAAAElFTkSuQmCC -" + xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAa8AAAF1CAYAAABfzmVIAAAABHNCSVQICAgIfAhkiAAAIABJREFU eJztvXm0LFld5/uNIacz3HOHulUUFG0hFAo0rx4g3U2j0sMqEVpxQEBAxUW38ppZsEEcWsaCKqGU 1sambZReAirQgKVQTM1rUHk2zhaizPWqiqp7645nzCGG3X9E7MgdO3dE7Mj55Pl+1ooTkXky82TG yYxvfn/7u38BEEIIIYQQQgghhBBCCCGEEEIIIQV89bYbxRO+7aFi0c+DkFXDXfQTIGSV6Q1CPPrh 37Top0HIykHxImRG3P7BV4sgiHDq+DquPLlJ90XIFKF4ETIj1tpN9PoDrLWbuPYBVyz66RCyUlC8 CJkBn33XzwgBIIxiNBs+HnDlcbovQqYIxYuQGXDq+AaiKEYUx2h4Hk5srcPz+HEjZFrw00TIlPnk f3uZ8D0XURQjjgU8z8FGp4VrrjpB90XIlKB4ETJl7nfFVrLhOIhjAdd10Wk1cPLY+mKfGCErBMWL kCnyof/0AtFq+BACcD0fsRBwHQfNpo/NjTbWOy26L0KmAMWLkCnyTVefgus6iEWMMAwhhIDjOmj6 HtbaTZzcovsiZBpQvAiZIp12AwAQxwKDQQABwHEc+L6HTquBYxvtxT5BQlYEihchU+Jzv/tzwk8T hXEsEEYRIAQcAJ7notn0sd5pYWujw9IhIRNC8SJkSqy3m3AcB0KILKyRbDrwXBdN30en1cSxjc6i nyohhx6KFyFT4LPv+hnh+x4AIBaA7/uJeEHAcQDPddDwPbRbPtY7TfieS/dFyARQvAiZAuudFjw3 +TgJIeD7jcSBCcAB4LoufN9Fs+Gj025ic53ui5BJoHgRMiGfeecrRLPhw3EAAWRlQyEEBAA4Dty0 dNjwPbSbDayvNQGA7ouQMaF4ETIhG+utYesnIRALkcXkgSSw4bgOPC8Rr1bTx1qriXarscinTcih huJFyAT8z3e8XLQaPlzHAQCIxGohCILUhSW3k87L9z00Gx7arQbWOy0AdF+EjAPFi5AJOLbehu+5 SLULsRDwPA9BIJ0XAMeB4wCu68D3XDR8H62mjw6dFyFjQ/EiZEw+9vaXilazATcLaiTjXc1mC2EU Za7LQRKXd13pvpLgBt0XIeND8SJkTLY219DwXThuaruQzOtqtVqI4xgCInNfjuPAdVx4ngvf87Kx L9mRgxBSD4oXIWPw4be9WLSbPlzXRSZdAhBIyoZxnMTkJbJs6GWlQy9xX80GZFcOui9C7KF4ETIG J46toeF7cDPXlZQMHThZXH7ougAHDlwnme/leTK4kY59tZsLehWEHF4oXoTU5INvfb5oNxvwPBeO kjIUAFzPQ5iGNVQb5TjauJfmviR0X4TYQfEipCZXHN9Ao5G4LmW0Kw1rNDEIBolwZZVDB47jpONe DjwvKR36npu5r1bTX9TLIeRQQvEipAa/c/NPiE67Cc9zs7ldABKhEkC73cFgEAAi6WuYH/dKnJda Omxk5UO6L0LqQPEipAZXnz6Ohu8lfQwV8UqKhAKdTieZoKzJj+MkE5UdpVWU78nYfJI8dFQxJISU QvEipAaddpIOdB0nnzJMO2u0Wi2EYZTrrpHgZALmuW7mvhqeZxz7IoSUQ/EixJJPvePlotnw06DG 8Ho53uV6HlzXQxRHinKJNG2IpNOGmyye68B3XXj+sGWUOu7F0iEh5VC8CLGk026mraCcfIkvlZlm o4lYxOl5vJRfAEAqYG5aNnRdB67nwk87zTdSAZNzvggh5fCTQogFn/iNl4lWw09KfrmxLum8oIx3 xek8r6F8OVniEMPQRtppXsbmGwxuEGINxYsQC9Y6Tfi+m8TjDSlDAFjfWEe/3x8JawBInFc610ud 7+V5+ZZRzYY3l9dDyGGH4kVIBR99+0uHrst1Rsa7AAAOsL6+gX5/kLkuFQep+4KTKx16WWx+6L6a DY59EVIFxYuQCtY7rdR1uaNx9rSTvOd6cNbWUueVFhNFfp7X0H2ppcNk3CtxXi7dFyGWULwIKeHD b3uxaDV8+NJ1Qe1lKMe8gEajCTSbCIIg+d3IIznZqVHUbhtuOu6llg4bDT/XM5Hui5BRKF6ElLC5 1kob8LpZ4GKIyBSs3ekAjpOehBIj6uUkypXN9coSh6kD82X50HPRTOd9EUKKoXgRUsCtv/ZC0Uwb 8OpjXcDQdQHAxsYGEEWIogh6UN5R1g505yVTh2m/Q9/L2kap0H0RkofiRUgBx9bbaSuoVHBgHu9y HAcbW8eAwSCdoAytr6EzXDlKqyh3KGCu4rwaaXSec74IKYafDkIMfPCtzxet9ESRbioyuZShok2u 5wHHthD3+ukZlJH9UnVfquvKyoeukjrM+h0Ox75U6L4IGULxIsTA1kYna8DrZv2dVJLxLiGARqMB bG6i1+1CxOn18jYS6brkphbaUAVM7ThPCDFD8SJE431veV7OdZlKhup4V7vdBpoddHs9xMpJKPM2 ycn6G0IXLkeK1rDjhnqyShW6L0ISKF6EaJzYWkej4SmTkvWJycgp08bGJgAfvX5/2G5Dm9+lbjqO uuRTh7nyYerACCGjULwI0WjrrksvGcr5XTKscXwLADDo91NhEzD5L/lYI3O91NKhJ+d9ydShm5vz RQhJoHgRovDx//pTIu+6gNEBr2HR0PM84MQJAGHalHcoW/qQl9zKTVaWrks9z5fqvDzG5gkxQfEi RKHdasD3EvGSY13G+V3p/GS/0QC2TgJBH0EYFj+wTMs7yKcNs0a9bipgqfPSOs4TQvJQvAhJ+eh/ ealoNjx4nlNYMtTHu9rtNoDjQPcAURgNz6osRm+rPpQUxdHSoSJcbjpp2Rud80X3RY46FC9CUjpt zXU5MtiuoIx3wUk7a2ADODhIJiiPhuSHZE7OyTkwvXzoqpF5l8ENQkxQvAgB8JFff7Fo+F7SCsoZ TkoeCWso412O42Jj6ziANrB/MJygnN3GIGFZ+VB1XrKE6I4mDz0Xnp+Mfekd7em+yFGG4kUIgE6r mbWCkkGNwphGKhme6wInTwJw0c0mKJtdl+rhnJyAJa7LcZC6r7RsqCQPfdeD77tsF0WIAj8NhAD4 8GduTxvwlpcMh2XDtLPG1hUAYnS73eEEZWXca4iT/ZSlQ5jGvTIH5ubHvwylwx/93sfNZF8Qchig eBEC4M3v/PmsFZST2q7RkmFej1rtNoArAAzQ6w1PQmm6LQBlhrK6qUTmcxOWh2dZTjrOe+ncs+FH 9i3//fZpvXxCDh08aRAhAACB65/6QwDa+NKHf2+0lWF6G3mGZMcB1tfXAZwEcB6DQT87c7LQ7gFA byyfimMakwdGBMwzdt1IJi3fdWZtFjuAkEMFxYsQAGrI4qH/5tkAXHz1tneP/FaqkeO42NzaAuAB 2M+fQVmYcxSOMtkrmUMGrWyIEQeWzfvyHHzxDgdAe+qvnJDDCMWLEACmmMWDn/Sj2e++8pF3Dce7 kHbWOHky/f0egjBMy4YV5DrL51tFSRFzlGa9H//sAMD+NF4gISsFxYsQAAUzszIe8uRnp7eJAMQA IvyHH38Jbv6tJwC7e4iiKPcw5nleefcFxX3FcYy3vusKAF0AB+nSr3xehBxV2PGTEADApwRwCkAH yXc6D0OPpM7bGooXECrrEECgLQNt6WtLT1m6GApXF4nbOgCwl66LuJefYXIkYdqQEABDhzOu06l7 P2OsY0rPhZDVh+JFCAA7oaCYELIsULwIAVDYzmmqjz/O36dgEmKC4kUIgGQca97MWjAJWV0oXoQA SMRrms5nUlGiqBFSBsWLEABD51XSEX7uLMNzIGQ5oXgRAiCJus+LMlHShZMCRogJihchAIDvcw6f UHCOFzm6ULwImRtF4njYRJOQxUPxIiRjHmNdVSXDeT4XQg4vFC9CCpmneFCoCKkDxYuQjFm1ZZrk 8ShqhJigeBGyEIqEkuVCQmygeBGSw8Z9UVwIWTQUL0Iy5l0urDPfixCiQvEipJJJ2kaxTRQhs4Di RUjGOG5nmg6JQkWILRQvQjLKxrvqCMskJ6Yc5/6EHD0oXoSUMi8hMQknRYyQIihehGTMW6hsbkMB I8QExYuQHJxQTMhhgOJFSMYsewuyKS8h04TiRcgIFBRClh2KFyEZ8+wqX5ZoVNcUUkJMULwIyZiG UNRpK2UjYIQQExQvQhYOHRYhdaF4EZJBESHksEDxIiRj2Up2FFNCiqB4EZKxLN0tKFiEVEHxIiSj yunMK4k4j79FyOGG4kVIIZM26B3nb1C0CLGB4kVIxqzEahKBopgRYoLiRUiGgLl0OA8BmYfLI2R1 oHgRkjFvsVi2dCMhhweKFyEZ0wxMVN2/KhhCQSOkDIoXIRkxlk80lu35ELIcULwIyVh0GU93XBQu QoqgeBGSMYs5XozCEzILKF6EZMyybDgt8SOEABQvQhRi7fK0Qxu2p0BhYIOQKihehGQsW2BjmZ4L IcsFxYuQjCBdz9v5UKQIqQvFi5CMH3RGr5u3iNn+vXsNz5WQowPFi5Ac82wFtcgO9oQcbihehCwd i55vRsjyQ/EiJMe8xrsoTIRMAsWLkLGZZy9EQogKxYuQHGrJbhHlO4oYITZQvAgZYVEJQ05UJsQW ihchOWwEo+7pTuqKEEWLkCooXoTMFQoTIdOA4kVIDooLIYcBihchIxSNN01b2CY52zIhRxuKFyE5 FnX+LT20QeEipAyKFyFzoU70nsJFSBUUL0JylEXX9dtN+ndsriOEmKB4EZJj3gLC+VyEjAPFixAj ixYUihohZVC8CMkxyXiUSXAoQITMAooXITkW7XgW/fcJORxQvAippK7bqrqP7d+giBFSBMWLkByL dl2mbUKIDsWLkBxCWyZ9rLLrKFCEjAvFi5AciwhcUMQIqQvFi5CFYhJLtogipAqKFyE55pX2ozAR MgkUL0JyLItwUdwIKYPiRUiOWZTsbMWKgkWILRQvQnLMUkSmMfeLEAJQvAjRWHSUnQ6MEBsoXoTk iDGbbhd0XYRME3/RT4CQ5WKeZzRmJJ6QcaHzIiRHXPK7WYhMVd9EQogJihchORY15sSxLkLqQPEi JEeZ85oXFDJCqqB4EZIjwvQa85qoGueiaBFiA8WLkBzBop+AAoWMkCIoXoTkeJpTfZsqUZn091Xc a/EcCVltKF6EjLCI1lCmNSGkCIoXIUYW3aCXAkZIGRQvQkYoaxE1bVEpc10UMEKKoHgRUsi0x64o RoRMC4oXISOM47YoTITME4oXIUYWKUaznGdGyGpA8SJkhGl0lVfFx/a+FCtCbKF4ETIWk453FQUz KGCE2EDxImSERcy3omgRUgeKFyFGZiVgtmNZHPMipAyKFyEjTNI0t47gFAkURYuQKihehIxA8SBk 2aF4EWJkHAGbVPRYKiTEFooXISMsQ4NcihghZVC8CKlk1kKiOy4KFyFVULwIGYHlO0KWHYoXISPU cUF1hI7uipBpQfEiZKHogrYM422ELD8UL0JGmOa5tXjCSUJmAcWLkBEWPeZFUSOkCooXISPMUjxM wrhosSTk8EHxImSEMjGZRflwmn+HkKMBxYuQEWwShtN8vEkem5CjCcWLkELmfUZjJg0JsYXiRcgI MSYTEIoPIbOG4kXICNMe7yp7rHn8LUJWD4oXISNMSzjqjJ1RrAipA8WLkBEWNdal/m1CSBkUL0JG WJR40IkRYgvFi5AR1MDGuAlA0+0pSIRMC4oXISPEM358ihghk0LxImQEKV6zSARO8xQrhBxdKF6E jBBh+l02qh7H1O+QEFIExYuQEZ7qzPfv1RlXu3fOz42Q5YTiRYiRWTfSZXmQkEmgeBFSyDQEhv0K CZkFFC9CjMzr1Cem+9OVEVIFxYsQQsihg+JFiJGiScaziMdP8tiEHE0oXoQUMqvxKraBImRSKF6E GBmnPdS0xsnowgipguJFSG1mGeagaBFiA8WLECOzEhGWDAmZBhQvQgqZd6lwGo9LyNGA4kWIkTri Mes+h4QQHYoXITNjVrF6QgjFixAjQltm/XcIIXWgeBEydaYhRhQ0QsqgeBFiZJYTk+f9twlZPShe hBjRy3nTPEXKNFtPEXI0oXgRUsos52UVidgs/hYhqwXFixAjsxYPihMhk0DxIsRIURlvFmdM5gRl QupC8SLESFW5cNw5XBQqQqYBxYuQsZnFGBjHvAixgeJFiJF5TFDW/x4hxBaKFyFGFikmFDJCqqB4 EWJk0QKy6L9PyHJD8SLESNkk5UmFpegszRQsQmyheBFipK5YTUuAKGCE2EDxIsTIrN1QmeuigBFS BcWLECPTnpNFQSJkmlC8CDEST+ExKFiEzAqKFyEaP/mTPylmN8erqtt8+d88deoUFZEQULwIyfGy l71MnD59GkPnNc3zcBX9vl55kgJGCMWLkIxXvepVYmtrC+vr6wDOKr+ZVZii/uM2m00AFDBCnEU/ AUIWzYtf/GJx4sQJtFot+L4P3/fhui5e+tJ/CqADwEfyPc/BsLQXA4gAhOk60JYBgH667qXbPWXp AjhQlv102QOwm67zPOxhx9Hr9dDtdhEEQXb9hQsX+DkmRw5/0U+AkEXy0z/902Jra2tEuFx3WkWJ uh3pi8e9ms0mhBDZEoYhgMSFUcDIUYNlQ3JkeeUrXylOnjyJtbU1tNtttFotNJtNNBoNNBoN/MZv fB71Jiirl8cZ/yq+z+Mf/83Z82o2m2i1WjmBZRmRHDUoXuRI8opXvEKcOHECnU4nEy1VuKQLe+c7 /2bRTxU33PCP4ft+9tykgMnxLwkFjBwlKF7kSHLq1Cl0Oh202+1MtKRgqYvnefjt3/6rGT+bYs15 ylMeC8/zcs9JFbBGozHj50bIckLxIkeOm266SUjHpboZVcA8z8st7373X2G2LZzUNlHJ9tOf/h2Z cMnnoYtro9Fg+ZAcSTjIS44Ub3zjG8X6+nomXFIUXNeF4zjZoqMGJZ71rOuRJAxjJGlDuahJQ7n0 lUVNGsq0YRfDpOE+gF0897mPRhAECIIAYRhiMBggCAIMBoPc0u/30ev10Ov10O/3c8+XAQ6y6vAN To4Mr3nNa8Tx48ezUqHqrFTh0sVLipbcjuM4FbGHw168ZFy+i6Ko/ItedF0mWGEYZgImF5N4SQHr druI43xLKwoYWWUYlSdHhmPHjmXCpZbibFyXXKvb73nPFzIxi+MYz3lOH8C1ls/mYfiP//HuTKii KEIYhllM37TopUy1lNhoNEbcFyGrDL+ZkSPBzTffLDY3N7NyoRQvKQyqcMm1KlRyLV2Xui3FSy5R FOW2ixZVtEyLqXSoOjDpvNTyId0XOSrQeZEjwdraWi5VWOS6VOdlclyu62aC5bou4jgeub8MUAgh ssvqmJl+/zK3VdeJ6eJFyKrCtCFZeW655RYhS4V6klAVASlkprW6lP1OF0OTOFb9DfU2ZX/HJGI6 TB+SVYXOi6w87XZ7xHHpYgUg57rU0qF0XRLVMRU5LyFEttavl/cpepwy0dKv0wXY8zxEUTS/nUvI gqDzIivNLbfcIkzzt8oEweSeTNfXWca5r+k+NuVEHbovsorQeZGVRg1oVJX4VBzHyVyT6rz0UMe4 YjaOkJWVIMvEi5BVhO90srLcdNNNQs7nUktsprGraS7AqKjJ60y/q+PAbMfIdOi+yKpB50VWlk6n YywVmkShCOm+9G3VmdmKmH552q5MXTjuRVYdihdZWYraP1WVDHVk2VAXMb2kKLF1WlW3sXmMIiGj eJFVh2VDspK84Q1vEOo4V9m4EVBc5htHUPTbFFF1myJxtRExEywdklWC4kVWkrW1tVzfQpPTKros t02MI0pl4mIrhLbX2zhJQlYBlg3JSiJdl0m4igREvayOb6moCURbUTJR9veLbld2PcWLHDUoXmQl UcWrSFzGOdDLx4zjGGEYjvy+zuOZblv0nKqcl/p48jrTeBwhqwLFi6wkRbHxMnEA8uEMfX6X53nZ 2ZeDIMDu7q7xVCTToEoETa/L5n6ErAoUL7KSqC2f6risIsfiOA42NjZw3XXX4cSJEwCA22+/Hffc c8/Ukn22JUKbx6HzIqsOAxtk5Xj9618vpj324/s+Tp8+nQkXAFx77bVotVpT+xtFYjNNEWLikKwK FC+ycvj+sKBQV8D0c3ipj7O2tpa7rtPpjDy+fr8y4TH9Tj1tCiGkGIoXWTlUQVFFoEiY5HVlwhPH MXZ2dnK/P3PmDIIgMApO0bbt78tub3sfQlYZjnmRlWP/la+EA6AJoIHkG5oH4JqPfKS02a5EFxYh BMIwxPnz59FsNnHFFVfg8uXLuPPOO9Hv9wuFxfQ4RSJnI6j6/cvEUgiBC4+5APQAHADYB7ANoFu8 3wg5TFC8yErxJkC0kIiWh0S4XAAOgHuf/GQ4AB7wsY8VujP1Ot157e3t4Y477sBdd92FIAjQ7XYR hqFRmExnYTb9DdNty1yc6b769t3/+m5ggGRpIFHxFoA2gD0AHgTOg7FEcqiheJGV4A2AaCM5TnsY CpejLEjX9zzxiRAAHviJT2T316PyElVM4jhGt9vNtqMoKry9/li6MNmInEmYyq77wnd/AQiQLL6y NDAqYhsQ2AZwiSJGDicUL3KoeQ0g1pEcm32Mui1VtCRSIu684Qb8o098YqSMWCQOqogV/a7sfqbf q5fLflf2eADw19/710CY7gDfsKgC1kQiYGsA1iGwD4oYOXQwsEEOLTcBYgvJcViOb6kCprsuYChc Il3uuOGGSoGouwDFjqqOkyorI6rL537gc4mjUpd2unSQiFQiVMAGgGMAtgCcAHAlgNMArsRobZKQ JYbOixw6bkxLhFKsXOTdFgCjjZCCpW4LAF+94QZ888c/PrydpZhMQ+AmXf7kaX8CREhcl9wJat3U U5YqJ7YOgcugCyOHAooXOTS8DhBrMDssWUIoEi25Ni0xgC9/13fhIR/7WHK7OYhXWemx7D7q/T79 w59OnrwUrUhbl4mXKmJyLKyFxKFtQGAPFDGy1FC8yNLz82l5sInica2io2yRcMWG9T888Yl46G23 Jbefg4BNsnzyWZ9MRCrGUL3lIl2Ypy0Byl1YA3kRa0GgD4oYWUo45kWWmjcB4hSSoRsZgbcVMFWo ypZIWf/dk55k5ZjKnJPpNtI16e6p7PGKfvfRZ3+02En5GA4AqmVBOQ5WNh62iWQ87DiAkwCuStcn OR5Glg86L7KUvF4rEUojYYq+S4RhXeW29O0YyLrE24iTLizjlAPLBE7/W3Ecj+4IB3kHFmHUjdUt JZqi9bugCyNLA9+IZKn4RUBson6JsGpcyyRa+uVI2b7+1luNpcMyUVGXKIqytb4dRRHCMMxty8ty OwxDBEEwsr71R241v4gIo3bStITKOkRSSpTrAMnE5gBAX1m66SK7dPRAESMLh29AsjTcpHXHkAZD n7OlUyZcRW7Lpoz4mA99yNp56aJlEjB9MQmYvqjC9cEf+aDdC4tgJ2L6EmjLAEMB62HYamoPwGWA XTrIImHZkCycGwHRQV60TBONTZQ5rXFFKzv2V4xrmdxXmRsrKgvaLnCVF6aWCuVaLyOawhz6ooc6 1FKi3C4aP1uHwA7owshC4JuOLIzXpt0x9BKhKfou11XjWuO4LV20ImX7ce97n5X7mkbZUF4n3Zbq vD7wnA9MptL6izO5MLldVkocYOjCZClxB4kjo4iROULnRRbCLwFChuKKxrVM6UG5tjmGVwmXqbqm H9+L3Fcd51TXYRldF5BXcv2FFzmwolCHaSkKdahurIH8/DDpxPYB+BA4RwEj84FvNDJX3qR0xyhq oDvuRONpuC3T8i/f856ZOS9TUEMf8/rAj3+geEeo27G2XTYeVvTC9UCH7sQGMI+HdZEfD6MLIzOG zovMBRl917u+100Rym39OF3XbZlKhEXH8aI4fJGAqaGNsiBH1SJvl0O6LtPOUsfE5G2LxsPKnFho uM6mzZSc4NwBG/6SmcM3FpkpPw+I4xiOa6m9CMftjlE0zGM75GPruFQT8qR3vrMycaiLkm3aUI/K q2NeH3hO6rqqlN20o2xUvWyHmFxYUSpROjE1lSij9QNQxMjUofMiM+OmtESoi1adFKG6PY7b0se1 TIIVY3icLjpuy3N32ZYOVeGy/b2pxJi5LNVNQdkucmHA0IlVjYfFKJ7cbGr4W5RKNPVLlCfABAQF jEwTiheZOm+AuYGuzTm2bFKENm6rTLTKQndFhiOKouR5VbR9snVeNs4siqJR0dHFSo1h1g10uNpO KurQESrX1yklmrp0sOEvmRJ8E5Gp8WqMdsfQJxoDo2+6MuEqcltFwlUkWnVKhEVzeJ/2treVtnTS S4d1y4Z6UOMPfuwPzLO0i3Zk0U6EtiNtd2KVNbUtJZq6dLDhL5kQOi8yFW4uKBFOK0WoH2OLQnRl JUL1clWZ0HRs1kuHdROHtosUtczpwLATi0qG+vXyshrmqAp06GEOUzmx6NxhplKiyYXtAXAhcIEC RsaD4kUm4o0YdscoOotxWSCjrtvSL1eJVlWJsEq41JS4Kl42pcMy8dKj8qbrESk7Qp+9rWMqJZpu o+90m/GwSeeGmUqKaimRXTrIGFC8yFi8DubuGNNOERYJV5loVZUIbcqEepOJEEAYhtZtosrGtUyC ZWrOizDdsaqAqUJW14WpFLWa0sfEItiJWFGrKdMkZ/0Mzh0AHQh0QREj1lC8SG3ejKSBrjquVSRa alAOKBauKrdVJwJflvquEq7AsM4ErEC8bBKHdca7cuIlxcpTtuWOlWJSFOLQt/V/il5GlI+jh0Pk zq4SMT3QoQpakQNTy4ns0kFqwDcJsUZG39VzbNmmCOX2OG7LJk1Y5bh08VLb+QUYFTBT/uA2AB96 7WuT1zIj8ZJzvD79t58GbkT+G4Jqb9Uyomk8TP9H1Pln1E3FlNnaoh07wOj8MLVLxzbowkgpdF6k Ehl9L2qgO06KsG70fZISoU0gQy8RDpA/1krquK8q8SqamBwE6V8cpC+MmKbRAAAgAElEQVTQV3aO 7sL0MmJZKdE2Vm8b6LBxYbrw2nbqSM7yLNjwlxRB8SKF/AKG3TH0BrplogVUj2tN4rZsQhm2gYyi EqEUr1h5Tb/zqldBDAbJ66o4C7I+8djGeQVBkC3X/6Pr8Te9v0l2vBQwgbxwyX+I/CcUhTn0f1LV GFmdQEdVKVFvNWUT6FBbTe0DaEAgAEWM5KB4ESMy+l63gS5QnCIc122ZRKvKcdnM2zKJlhSu0PC6 BopwybVN6VA6MP00KLrrUteDwSApobW0nSFdmEnEqlwYMPqNY9xAh2mCc5GImVyYl+7sqknO7NJB CqB4kRw3YrwGukB9t1UlXPrQikmwYpTP2apKEpqapatDQyr9fn/4Wi0ErKhsWOW6MvHa016c6sLk zvOUtS5guhMrKiVWuTBToEMPd9iEOkytplQBK2ozpZ8Akw1/CRjYICmvwbA7Rtk5toD8l3Zo27bl wXFFqyojoIpVUZKwjtuSPOm5z4XrJmrgOM6IeJkEzEa8VLelCtdgMEC/38eFZ10A1pAcuFvIu5Ky MEfRLPGyJGLVIGXZtxDbGm9Rcqbo20TZCTDZpeNIQ+dF8EtaidAmRahiE1yzcVtFomUTyhhppAs7 0apyW5L9/X14ngfHceA4+T1R5b6KxKtMuMIwldIzAE4CWE9fQFEZUQ9zCOU6U6ze1oWVBTrUUmTZ WJjuxOQ/xzQOppcSPZhPgClLiQ4ELlLAjiIUryPMm2DujlElWjZf0Itclk3y2sZx1QlkmMa3Bsp1 ZdybvvzLly+LRqMB3/fhOE7mwoBhCbEsdWiakKyWDKVoyXG1jPelu/85EDiGxIVFSERMlhKLQh26 gAHF30Bsx8LU8TOb8TD5e3XCs7xNqFxfNtm5aG6YFLENCOyCLuyIwX/2EeR1gNhA/Qa6gF1Fqaiq pF+OCi7Xmbc1SZKwym3da9gF3/7t3y6azSY8z4PrujkXVpQ8LBIv3W2pXLhwYXT3Pw0ic2EdJAIm D+LqWFFZKbHIJUnGLSVW1YSr5obVKSWazuIsS4k9UMSOCPwnHzHegmF3DL2Brpq6NjHJ8Uu9XCZa dUuE4yQJo4p9ZBItE495zGOE7/s5EdPHwPSkoe625KlWgALBMqG6sDaGAiYttCpiahpxmpOb1W31 n153PMymBlz0DaTsBJjneWxbdfgPPiKo0XcpWtJtVaUIgdHhjhj1hctWtMpKhGWBDJskYRW2wmXi QQ96kPD9YSVeFbBc26cUa7Ey8TQInACwgbwLU8McdbtzzDPQYStiZV06dBcmT70iu3Sw4e9Kw3/s iqNG36sa6KpvhjrjWrbHqrIKks0X8UmShNNyW0uH6sLkxF7dheljSHVcmL5t48JsBj3LIqVlLqxO KfEAiYCx4e9Kwn/oivILgDiB5FhW1UC37Av2uG7L5su2TYlwGknCKg6tcEl+KB0Ls3VheimxyIXB sJaM68LKxsOqREz951eVEk0nwAxBEVsh+I9cQfTo+yxShFUJQtvjk+lYVZYk1I9dZUnClXVbRfyY NhZW5cJUEXMMa6C8lKi7MLkeR8BsRKysVmwzHsaGvysF/4krxBsLSoTjpAjV7aLy4LiiZRM4mzRJ WMXKCZdEdWFtDAMd+sRmU6BDnYs1DRembtetMdt8u6maCyGXHvLjYbsAu3QcfvjPWwFeA4hjKO6O Ma0UYR23ZTOuFWM0jGEjWmUlwrhiX62saOmYXJg6T0oVMFXEygRsWi6s7refshRP1ZtDLyXq0foB KGKHFP7TDjlvLigRjpsi1MWqbMzdRrRsQhl1Jhyrpy2h26pAurCieWHqm6ZsXti8Ah36G8vmG9A4 pUR1PGwPwGVQwA4h/IcdUm5C0h3DpoFu3RSh7bHFRrRsQhmTztui26pAd2Fl88Lq9EichQuzGQ/T t4veQGWlRNMJMPdAETtE8B91yHg9zN0xxkkRqtvjui0b0Sr6smwjXEWiJZcqjrxwSZ4KgVOYvDuH rQtTBUxetkkC2X5L0t9cpvkUVaVEXcTY8PdQwX/QIeIWmLtjTCNFWHb8MB1LooLLVSXCMsEq+tJs KhHSbY1JHRdm253DVsRMb0Cg+pvTtESsqpSod+m4wPfQMsN/ziFAjb7XaaALTOa2qoYhxikR1glk FDmuKihcFTwV9eaFlfVItInVm1yYXNsmhNQ3Y9nAatWbraqUqHfpYMPfpYX/lCXmRkCsw9wdw6ZR +KTDDeplW9EyHUfqBDLKSoR0W1PmR1FvXtgsXZi6XWfQ1RTqKBKxcUqJMlrPLh1LB/8ZS8gvAOIk qrtj2KQI1W3Tl1rbKk2ZaNkcN2yThKZjSmixzyhcY6K6sLrzwqp6JOr/EQf1Xdgk42E2lt/Uakqe AFPv0rGT3pYithTwn7BkqNH3onGtSVKEk4qW7bjWtJKE+rFOh6I1JUwurOqszXVbTBVh8+at86a1 ETH5hjT1Fys6izMb/i4V/AcsCW/CeA10AfsKzDTdVtnxwTRmbpMkDGF/kkiAwjV1fhCjiUQpYuq8 sHFcGFBPxGy/fak17qoUkc3Aq23X+t10TRFbGNzxC+a1SLpj6CVC/TgAlIuWXNuOf9sI1yQlwjLh qkoS0m0tGN2FqYnEsu4cRT0SiwIdRRR9C6v7hrZ549qWEsu6dASgiC0A7vAF8haM10AXGN9t1a26 2IpW0bHAFPQqCmXQbS0RJhdWd17YNF2Yul23lFD1Rq6qadt06WDD37nDnb0AbsawO4Z+YshZpght RWuSEqFtklAtEdJtLTFlLqxud46yWH0RVS5s3EBHHRGr6lqvRuvZ8HducCfPkTdg2B3D1EB3khTh JG6rSLSmFcgoSxJGFvuNwrVgfhDTmRc2jUBH3TJD2Zve9CYvekPblBJ7SMRrF+zSMQe4c+fELyPp jmHTQNe2OYHtF9CqakqVaKmXi5zWOEnCKihaS8aPwG5emFpOqNMjcVaBDv0DoL/xq0SsTilR79Jx ke/hWcEdO2P06HvdBrpyexy3VTWOPc741jhJQv0LK93WIeYH0rGwZXBhcj1JQqmsPm56s9uUEvUu HWz4OxO4Q2fEGzHaHWPaKcKqcn/ZF84641q2gYyqUAbd1gphcmFl88Jsu3PM0oXZjocViVhZKdGm S0cPFLEpwh05A34F4zXQBaqFq8hpmT6XAqOCVadEWBXIqJMkpNtaQaQLk4nEut05TGGORQY6ykSs zIUVlRLVCc5qtP483+fTgDtxiqjRd/XzOs0UYd3PYpVoVbmtoi+dclsXLdO8rSooWoecKhdWNi9s Fi5M3a6TZCqqp8vtqmitbdd6NvydCtx5U+Am2HXHsBEtuR7XbdkEM+qWCMtShGVJwthi31G4VgTd hdnMCysSsKJI/bwCHUUfmqIPifygFLWa0kuJUsTY8HciuNMm4HUwd8coEy0Ho2EMua76rNmMP9sE M8oErM68LZ62hIyguzCbeWF6iWISFwZUlxLrfqBsU0y2pURTl44QFLGacGeNyS2o7o4xqxShbdl+ nFBGnXlbpjIh3RbB92PyROKksXqg2oFNOh5mI2JFpUR9PIwNf2vDHVWTX0K+O8a4DXTlus5nalzR sikR2goX3Rax5tkQ2ML4Z20uGg+DYV3EuB+2OuNhRaXEom98pq71stUUG/5awx1kyY0o7o4xjV6E 03JbRaJV9FkzCVZRBaRItOi2SCHL6sLkdTGKhaxqPMz2g1XlxIq6dAxAESuBO8YCGX03dceYR4rQ phw/SYnQlCIsm2wsP3Ohxb6jaBEAiQub5KzNU3BhDhwIIaZXShxXxEwNPk1d62UpkV06jHCnlCCj 702Uj2uNmyK0GTuuCkJVfYbUyyGqP1e2SUJ17K4IChfJobqworM2l0XqpxCrd9IblIpYWQlkHBGr qsMXNfxVW02xS8cI3BkG3gRzd4y6DXTletwvefplW9Gq+hJYR7h42hIydUwurE53DptO9SXvQMdJ fykAEVc4sTqDzlUfwjqlxKIuHWz4m8GdoPFWVHfH0KPvQN6JjDOuVSZcRaJVp0RYN0lIt0VmyvdB 4AqMf9Zm2x6JBe/GTMAAILZ0YlVlEZsPZtGH0KZrvRqtv8DP2ZHfARI1+j6PFGGdMIbN+FbZ52TS JCHdFpkZugurMy+sqoxo6cKyUmIspufEqsoh45QS9a71R7xLx5F94ZKbUdwdY9YpQlvRGqdEaBvI qEoS0m2RmfN9MCcSq87abEpOjRHocBwnEzERC8RxPJ/xMNMH1LaUqHbpOKINf4/cC5a8DhBbKO6O UZUiNJUJZ+m2bIJNVSX2OknCyGIfUrTIVHkW7OeF1e3OUeXCHMB13KScmI6FGUUsLrhc54NclKRS 17atpmQpcTe97RESsSPzQlV+WSsRlk0nMWFTJiz7glbnvV70fi8bD64SrqoO8HRbZGEUubBx5oWN 6cJc181i9XEUl5cSbcbDyur9crvMhRWVEou61h8RATsSL1LyZth1x5hlitC2ylC3RFgnkFE01YRu iywNz8LkZ222idQb3s1SwFzHBQDEUYw4LhCxumMCpm+l8rqqOHCdrvVHoEvHSr84yY2A2ER1d4yq nVE2rjWp2yoSrXFKhOMkCW2gcJG58hQkicRpdeeoGat3XRee68Fx07GwKEYURaOlw3ECHbYfcLV0 UqdrvSwlBlhZEVvJF6Uio+82DXShbOtjWnI9bbdlI1pF72/bQEZZKINuiyw9Jhc2zrywMWL1juPA 87xExBwHURQhCiPEkWE8bJxAh42I2cwPKxsP28ZKCtjKvSDJW5QSYdFZyKui73J7khShbfWgbHxr ErdlCmXYniQSoHCRJUG6sEnO2lwW5jB9g1Uuu44L3/fheR5ELBCGIaIwSkqJcXo7kyMzHQRsx8Ns RMxU/1cb/qqtpvaxUiK2Mi9EchPy3THUQIb88gUUlwltwhi2X7JMwhUVXC563+qlcFvhKgtl0G2R Q0uVC9PP2jxlF+b7Pnzfh+u4iKIIYaCImM1BwuYbrY2IlQ1kF3Wtl9H6FWn4e+hfgMp/gl13DJsU 4SRuS3+P6oI1jRJhUamwKkloA4WLLDW6CyuaFzZOd44qEXMAz/XQaDTQ8BsQQiAIAoSDMBkPmzTQ YStiNqXEoi4dB1iJLh2H+slL9Oj7PFKEdcIYVe/LSUqEclsXLf2LmKxslEHRIoeKZ2L8eWFlk5uB 0QOG9slwXAcNv4Fmswnf8xGFEfr9PsIgLB4PmyTQUUfEbFpNrUDD30P5pCW/hNHuGB6Kp3iYsCkT lpUHbYXLZlxLvayXCm3j76YvXzZQuMih5HvHTCTatpiCYY3hZc/z0Gq20Gq24DgOBv0B+r0+wjCs F62vKteM48KKQh16l449HMouHYfqyUpeB4jjMHfHmFeKcFzRsikRVpUJbUWLboscGabpwkyD4yUu zHVdNBoNdNodNJoNRGGEXreHfr+PKIzyglUV6KgaKJ9WKdHUtX4nvf8hEbFD8SRVfgWj3TF0twXD GrBPEU7DbRW932xKhDaBDFPYiG6LHGnGdWGmg0jdQIcD+J6PdruNtc4aPM9Dv9fHwcEBBv2BfbR+ 0vGwogOHaSyhqGv9IWn4u/RPUOW2X3+JaLUa2N49wN5L3lY6rlUUf5/EbdUpU1e9z/TLRU6rrBpA t0WIgWcaEonT6s5RIWKu66LZbGJ9fR2ddgdxHGN/fx/d/S6CIMiXEnVHNs3xsHFKiX3g4eeuxvZu F0EY4b6Lu0t9nFjqJ6fyh//5RaLTaqLR8OB7LlzXwR3PemOlaAHTSxHafCEqel9VOS7bCceTnLYE oHCRI4LqwmzO2jxOj8SiUmLqwtbW1rC5uYlmo4l+r4+dnR30uj2EYVhcSqw7NlF2kDEdVEpKif/i 3Ldg76CP3f0uLu0cAMBSC9jSPjGVD771+WJjrYVmw4fvefBcB66bnMbgjh9+A4DFzNmyGVcdp0xY FSDS3b9aDi2CokWOJCYXNq3uHBYurNVqYXNzE8c2jwEAdnd2sbOzg36vby4l1h2vsEmCWZQSf+C+ R6HbD7Df7WPvoI+dvS5293sAllfAlvJJqbznpp8QJ4+vo91MhSt1XW52Dh7g6894/cj9puW2bN4z dUuENoGMCOXxd7otQiz5HgicxmRnbTb1SLR1Yb6PjfUNnDh+Amtra+j3+rh06RJ2d3cRDAKIyJBK rDseViViJS7sx8/9c/T6IXr9AQ56A+x3B9jd7+Hy7gF6/WQEfRkFzF/0E6hia7ODpu8l/cUMwgUH eNB7fx5ff/pQwOqOa5W9N/TLNqJl47ZsAxlFk43ptgix5A/Tz8EPY5hIjDBMJMZIjoRy7SH5gMm1 XEyNfQ3BjezDmW6HQZi4rX4fJ46fwMmTJ3HNxjXY2d7BhQsXcLB/gDAIRw9QDoYHIUe5XDQWFyu/ d9PXKLfl5VC57AEv2v5X6DdCCIHkFDBCII4FojhGGMUIwghRZDOSPn+W+uD2+7/6ArHekeVCF57r ZuVCAHC0KOHXUgc2DbelXqcL1iSiVTdJSLdFyBT5HpgTiWVnba7qzmHqOWcqJTpAw29gY2MDp0+f xvGt4xgMBjh/7jwuXriIXq+XlBJnMR6mbqcHnp+570kIwhD9IMJgEKI3CNDrBzjoDXDQHWD3oIft vS4uL+n411I9GZXfe/PzxIlja2gZyoWAFK7h1xyRqtXXnvF6K7dV931Q5M5tSoR1AhlloQy6LUKm hOrCxpkXVmcsTNt2XRftdhunTp7CVVddhXa7je3L2zh75iwub19G0A+qeyVWjYdVHKhee+77EIQR giDCIAgxCEL0UwHrpgK2f9DPyod7B30AyyVgS1s2PLbRRjNNFnpeIlqjwpUghUsIUeq06iYIbd8L VY5rnCShXA/S29pA4SLEkt+FM+LC5Ie0geGHXZYTZQnR1bbVcqJJwICRUmIcxzg4OEAQBNg/2MfV V1+NK09fiZMnT+LMmTM4e+Ys9nb3klSifvCSf1MvIZrKiWoZUS0nukDD90Z2SfanBJLzl6VLFMUI whj9ge0M0vmwlAe7P/i1F4n1ThPNhg/Pc+GlpcJkAYZPW+SFSwACAl995o1jfVmpI1pljiuEWbzq JgnptgiZAz9sSCQWzQvTJzaX9UgsCnRgeFm6sNOnT+OB1zwQW1tb2N7exl133oVz951Dr9ub+gTn Xz77DIRRlI1pBUGEQRhiEEToD0L0lfLhfneAvYMetne7OH95D0KIpXFfS/EkVN7/y/9eHN/ooNn0 0fC9fEDDQrjk9lee/caJy4RV41q2JcIi4Zr0tCUAhYuQqfBv0kTipN05bCc3a9u+72NrawsPvOaB eOADHwjXdXHPN+7BnXfeiUsXLyWpRL2UaCorVRzg3nbfsxFFSRgjDGOEUZQXsEGIfhCi18+XD3fS 8uEyjX8tXdlwc601nIjsFAsXSoRLAHjIu38WX3z2jVN1W7NMEqplQhsoWoRMkQ8riUTdhamlRFlG lKVEvYSolxFlmEOW+iRaKTEMQ1y8eBHdgy4ub1/Ggx/8YFz3gOtw9dVX42tf/Rruvvtu7O7uDnsl QvubasJRLyG6yXXvOPscRF6MNKeN3CFVIvVRYJhAjAWirHwYYT8d/1o0SyVeH37bi4WciOwqyUJ9 jGu4g0eFC0CaRnQQoZ5wjVMitCkT2oYy6LYIWTC/CydzYetIPqRt5A8UUsCkaOiRelXAgOIxMOW7 eLISOOgeJEK1s4trr70W111zHR573WNx/wfcH1/+8pdx9szZ4lIilMc1jId5ngsHDpxU/XIipiDS H8kxVRn7ilOnFkS48uSmWLT7WpqD4Aff+nxxbKODVsOH77uJeJmEKy0XZsIlRCpeye0cxwEcB1EU IYoi/P1zbi4VLj0GX7dEWFUmtE0S2kDRImSOPENLJI7TnaOsjGgqJaaXHcdBu93G/e53P3zrt34r rm1cix56+NK5L+ErX/7KsJQoxGj50DDY/56zP4EojjMRiqI4m8uVKx+GMn0YJWNfgxC93gD7avlw 5wDnLu0CWGz5cDRysiD+3VO//dWJcHnKfC5g+P0AMApXmjB0HAeu62bCFaaT60485Z/h/K3/n1G0 dKdVVQqsWoqEST8nnHpuOLotQpaUv8NrcBVenSv96S5HXevbOmWfYMPvwjDE3t4ezp8/j57fw5Wb V+Kh6w/F6QeeRuzF6PWTPolCiFJhfO+55yWb0gykDR7kPFnHQTZ3Vt4uu77g5QkB9AYB9ruD15S8 qpmyFGXD2/7LS4SaLNSFK9lhxcLlui4c14UQyWz2MAyzbxlCCGM5sKhUaOO4ipxW3XlbNlC0CFkg H0k/f6oLkx/+ut05imL1KlopMQxDXLp0Cbd//nacP38ej3zkI/Ew52G45sHX4O+v/Xt8/vbP48yZ M+h1e6OBjvRxPNeF4wg4sUj/ZHJMTJUsZw/0p6SOfQmBtANH4tgGYYQrT2Jh5cOFO69bf/WFYr3T QsNXy4WAjXDBceB5HlzPhxACQRAgCCPEUYxYJOIVC4GTT/6nOPvh/10pVHUdV1nEXXdZ6kK3Rcgh Q3dhQLkTs5njYuvEBBBGIXZ3d3H27FlsN7dxxeYVeIT7CFxzv2vgnHDQ7XYxGAwQizj3GB869wKp UanbkkMryFrsSTcGzXEhG7YxkbzAbi9Ap9149SIc2EKd17ve9O/EWqeJhq+mCwGbUmEiXD5c10UY RRgMgpzjioVIJtqlA47fAeBTsIvA10kTVsXfdVGzgaJFyBJS5sL0QIfuujztsh7m0MfA9HSiAKIo wuXLl3H7396O++67D4+6/lF4NB6Np5x6Cr7w+C/gz7/y57jjjjuwv7efBTpc14EQgBM7iN3URiEG 4MKRCutoT0XmDEYCJenxV+t9eO7i7kICHAt1Xs972ne+utNqoNFIx7lS9R/uM3M4w3FdNBpNuK6L IAwV4ZKiFWeiJde73/1YnPnon1mFLsrcV9m4VpnjotsiZEWo68Jg2DZddiquT38XRslY2L1n7sW5 xjlsbW7helyP605eh+aDmuh2u+j3+/j9e56PrDAo3ZcjLyvjX8p1Q7eV3lO6tJGnMtyKY7GQ8a+F HSj/8D+/SGyut7MuGrn5XLkovCpcgOt6aDQaEAD6/QEGgwHCKEIsHZciWLI+K5TLt7/87XOZt8VG uoQcAZ5hmBdmc9Zmm+4cumJoRwjHcdBsNnHVVVfh0Y96NB6Px+MKXIEv4ot4wtu7+S/+cjqR/IKv ReDVFGKYTWJO04dpAlF23+j2ksnLewc97Oz3cGl7H2cv7qLbG8w1fbiQsuF73/I8sdZpoeEPHZeN cPl+A41mE1EUodfroT8IEEWRJlqK6zIIWIjxS4R1I/BK9bkUChchh5Tfg4MnQeBKJN051BKOOrFZ DXEU9UkEyuP0WilRCIH+oI+7v3E3Lm9fxp0PuRPfec134jF4DBz8BeAIOHAgHAEhkiKhcB1ADr1A AI5IHZlMLA7dl6M8h5EQB5TTp6S9D+8dBHMtHy5EvE4cW0ezMewU7ygDg7pwxUJk3zCajSYGQYCD gy4GQYAoigvFyuTA4ljgYTc+F3/9s79Za95W3SQh3RYhR4jb0s/x09OxMDmxeZLuHC7KUUqMcRRj Z2cHn7/98zh79iye9Bfy9+bDi+sAIgYcV2pXmkZMRWyomfJnPpEo/7A0FlEs0vGvEPdd3K3cXdNi 7uJ126+/RLSbPhqel0Y4FeESo8IlG1d6fgPdbi/pxhyGiOM4GeOKDW5rRNDyYlY1vmUjXLpohUjG tmxCRgCFi5CV472KC5PdOVoYrzsHUMuFQQCDYIB77703sUxCDPVLOKMuzE2zG8KBAwFH3h4il0rM 5oCNlC6H4iWPuWEUoR+EAOYTn5/rAfQDb32+OLW1jpYc53LdAuESiAXgeR7W1tfhOC729vZx0O0i DMNsZ0W6OCmXo9ggXoqA/dVrf9sY1ChLEpbF4+m2CCEZ0oUVdedQu9TbdOdQt2HYTvn4fT8FIP0S LYZfpUX6I+tGlA7FqKnsYR/DOCsHhnIczDT+1Q9w0A9w0O1jd7+P7b0DXLi8j3vOXUavH8x8/Guu zuv4RicZ59KEC3JnKq6r2WxifWMDURRje2cHvW4PoSwTpo0ih6JU5MKGjkv+XqT3kb0Ey1o7lUXg 6562BKBwEXJkeC8cfLc2FibLiPrE5qJIfVms3oSDYbcNGS1MQwTDKmLitKTPcgGItHwYCyd5Uo5S RoyUoqGSBpfXSZGMRXI8TiYvh7j7zKUp7MRy5iZeH3v7S0Wr2YCfnuZEFS4hhsov4KDdaWNj8xi6 3R62t7fR6/fT8S1FqIQiYkpaxuS2IoP7euQrno4/u/m9YyUJVTGzgaJFyBHko9pYmKk7h1pONAU5 TN05TONhDvDRsy9NtkX2w3QziGw6UlpKTK9LSo1uWkJUyohZeMMZ6qc2ezn1H1n3+cEgAmZcPpyL eN36qy8Ua+0mfN+FJ2d4A5mNjVPxcuBgc3MT6+sbuLy9g+3t7SSYoQpUlBeqKHNamvsyiZY2Fqa6 qbpJQrotQogVuguzPWuzLmBAqQsTWZkwPzdLx8n9EOkYWd6FJYKVOLBICpcyBpYdw7W/H8cCcTp5 OT3z8swEbC7idWyjg0bDTwIariZcqRNyXQ8nTpxAs9XGuXPnsLO7lzTXjeOhMEVxJmRF65wbM5QP 1e3rX/T9+NNf/VAt0eJkY0JIbVQXdgxJoGPc7hyqC0uXD597cRLGyLwUoCqY6WCUuTABJdABCCFd mMinEB0o4oXhkj6e7IOYZA4SAev2bfsK1Wfm4vXJ//Yy0Wr6Sfsnd7gLVeHy/QauvPIqxHGMe+65 FwcHBwjTlv3SbeUm0mVCprswVZxGnVhOzNLtAex7FtJtEUIm4r1w8EQIXIV6LkyfE6aVEeN4KC56 EDHxV2Y3lndhQ3IuLIvSp+NfWU9EOfKVjz1mc2qjGIMgwiAIZ8FP5aEAAAnVSURBVOK+ZipeH3nb i0Wn1cz6FkrUjhftdgdXX31/7Ozu4syZs9n4VpQTLf2ynA0uXZc6vqWMjenOyzD29eh/+yT88Ttu o9sihMyHj6XHiacZEolFsXpVsLz85Q/d9wLEiNNIeyoyYpjXSERGcWPpakTgHBnESBxc5sJkR/rU fbkRFPFClg1xDMf4MIpnVj6cqXhtrrezvoVyTw2FCzh2bAtXX31/fOOee3Hu/HkEQYAoyp8sLRMy 5TqTGxsRLn38yzR5ORWzPoqThLZQuAghtXif5sLqdOeQAgYgiuK0lCcyoZKX4ThJAMMZpgOlqOll xaz8p/SXldfHiguLpPsyLMmdnLR8CMRK+XDaE5hnJl7/72/+tGg203EuZ9g5I4mrA1deeRVOnTqF L3/lq9je3s76aeVFS10bBMzgvkZcmMF9RWJ4ri9ZOtQdF90WIWTm6C7MtjuHdGEvB8KfixNHZAhV OOlYlnLGk9w2MFpWVF2YvIErHAgh3ZdAlD6+my7Z34X62MkxNoxjBEGIvYO+OHN+e2rHy5kceD/2 X39KbG200fA9uI6TEy7AwbUP+ma4nocvfvFLycTjaNgQUhWt0ChkImsLJR2ZKchROhdMc2EiFvjU //gjui1CyOJ4opZIbGE4udnH6ORmF3jXxX+bCZUuXu6IkGE4ZiWvB7IIPKRg6Ue1NHqf9TSMkc2X lcfjMEomMScpwxC9foD9tHnv5d0uzl/axd1nLuHr3zg/tcnLU3de77/l/xGbay343qhwuZ6PRzzi H+Pc+fP42te+njbWjRXXFWUzukfESxsHsysfKtsi7750AeuBjXQJIQvENBYm54QVnLU5CCI4ripc imiNXK8KmerKhmVFiSN/ZvXE4e9dFxDCzVxY8rdSwXSHjy/vLtLyYRjGMn04lfGvqYvXVaeOJac5 cYfCFcUC7VYbj3z0Y/CF2z+PM2fPIgyjVLSSdRTG2WW1LcmoAxt1Xsa5X0XjXYbQRhwLChchZDl4 Hxx8V0EiUZ3c/Hpg8KK8eLkulG3dkanXGYQsSxHmQx6OImKOSIRRhjmy+2mPn+uLCCRdOGKBQRhi v9ufyvjXVMXrU+94uWi3GlkkXgrXiRMn8ZBHPAKf++PPJvO3oghhGOfXkSZeBaVEPcQRq9vG0Mbo WJfJeX3bv7gef/6//qbwtVG0CCFz4+Pp8eaHIHAcxu4cv/KTz0A/CDLRcJ309FKpmKnilW2rQuc4 cFyYXZu8TnlKTu5nIlwCTuq63Nz4V24sLL2/ABDFSfeN3f3exO5rauJ166+9UKyvteB5bpJOEQJR JHDtgx6E48dP4jOf/BR6gyBr8JgJVxghUEVLETMpVqMCZo7RF7qvrLdhsXgl43FmKFyEkIXwfji4 AQL3w4gL6/aDTIzc9LyIrusYr1MFrVDYNOc0FDXFXaWNErMOh6kjczUXlt1XEUs4qaGJYvSmEJ+f mnidPrGJhu/BgZNNEH7sP3sc7r7rLvzRH/8JBmGYiFYYIQjj4bbuvsJ07EtzXSYHVjiB2XbsS5u0 rEPRIoQsnE8oLmwL2elWDrqDoVi5LjxVtNTrVVEbETl36MZKBM5Rt+Us6GxeWOrCMtdmElIpfklq MQzjicuHUxGvz/z3V4hmw8+EK46Bxz7l+/GXH7kNFy5eSlIoQZQJ2IiIjQjY0HmpY1/Fc7/McXnz 5GW9ae9QyFQoXISQpUJzYTv7XXium53U13PL15nAZdfrYiZ/r4iaLmRaCMSRE5QhS4lIhU4MBc/N CyGQzAEbhCG2d7vi6984P9axdmLx+tjbXyrW2k24TiJccDx821O/H59+9++g1xtgEIQYhCEGQSJg QRhioAmY7sDyCUR5nWnycn6el13fw4JuHGnZkKJFCFlaFBd2sb8Pz3Phpyf29TwHnudmgua57vD6 dNtVt1WB84bClhe4ofC5jpMTNz0oonbbSBya6uSSx/UyIUsSiP1BiP1uf6zy4cTidXJrHZ7nIo5j rK1t4Fse9nD8z3f+NvrpCcsGgbokJzMLAtWBFbgvZRysKHFoLiFKUSqYE6bfNxqWDO+jcBFCDgPv h/PV//ucaLcaaDV8NBoeGn6y+J4H309EzffcVOCGoqZu58XOyYmeKnSeJ4WtwL3FpqShDH54OXcn 7+vAQRwLHPQG+NT//ofau2Cig/WfvvtVotVqII5jPOS6b8Gdd92Nb9x7Fv1+kExUC0IMBkEqYlHq wvLilQlYFCnxeYvUYYmYhdpt5H0BzPzsnoQQsmge/6iHiE6rgVbTR1MVN8+D7+fFzZfuTQqbulZF Tr2cWw+FTQqa47iJG3OGh1uRGoggjNDrh9jr9nDx8j7uPHMRn7v96/jzv/v/ax2bx3Zen37nfxCt VgNRFOMxT38m/tdv/Rb2uwP0+gN0+wH6gwC9QXq66EEwFK9UuAaBWjocjnUFuXlfUU68huNgmrCF wxneAAWKEHK0+ZO/+krhMfA7Hn2d6LSbaLcSYWs2fDSla/Olg0vFzU8Fzs8Lne+7WcnSKHSKqGWx edeB73hDB5feznEchGGMe89ti2/cd9n62D22eB1b76TC9QJ8/DduwkF3gINesvR6AbqDAL3Ugeni JYUrH96IUgHS5n8priwJeISIY0GBIoSQMfijv/xy4bHzCd/2ULHWaSJxbY1U3LzEvfneUOQUJzcU vWLB85Ryoes6aDR8uJkYJuNnNzzu4Xjn73/W+nWMJQB/+b5fEHEscPKKq/CFf/gSdvd72Ov2sd8d 4KDbR7efCFevH6CXlQ3DrHwYhIqASSeWJRITkQvDiAJFCCFLwr/6J98q1tdaWGs30U5Lkq2Gn5Um R4Su4aHh6+NxskSZjI0JIRCEEfYO+rj33Db+9G+/hvd//C+sjvu1xeHPfvfnBABc3u3i8s4BLu8e YGe/i939Pva7/cyBSQFLyofSgQ1FrJc6MwoUIYQcbm543MPFsY021jtDceu0GqnINdBu+mg1U8Fr DkuVftq8PRZJcOMbZy/hA5/8S3zmL4rdoaSWcHzgV/69eMg33R9fv/sszl7YwYVLe7i4s4+dve7Q fR0McNDrJyXE7gD73T7uOTe9NviEEEIOD9/zhP9LnDi2hs31NjbX29jotLDWaWG908Rau4lOu4l2 swHfcxFEEe4+cwmvftutlcamlqgI8VXx9l/8RXz97vO459xl3HdxFxcu7+PSzj6+etc5ChQhhBBr nvnkfyKuvmILp09u4orjGzhxbA1rnRbOX9rFj/3sb05HU258yQ8UN/8jhBBCpsSTv+OR4tZfeyE1 hxBCCCGEEEIIIYQQQgghhBBCCCGEEEIIIYQQQgghhBBCCCGEEEIIIYQQQgghhBBCCCEz4/8Ad9wQ YnOoIrsAAAAASUVORK5CYII= " id="image847" x="133.74034" - y="54.445656" /> + y="54.445656" + inkscape:label="image847" /> Date: Fri, 27 Sep 2024 16:00:30 +0200 Subject: [PATCH 13/62] Update README.md changed logo link to be relative and markdown --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 034c94c98..445d662d9 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ - +![pytransform3d logo](/doc/source/_static/logo.png) [![CircleCI](https://dl.circleci.com/status-badge/img/gh/dfki-ric/pytransform3d/tree/main.svg?style=svg)](https://dl.circleci.com/status-badge/redirect/gh/dfki-ric/pytransform3d/tree/main) [![codecov](https://codecov.io/gh/dfki-ric/pytransform3d/branch/main/graph/badge.svg?token=jB10RM3Ujj)](https://codecov.io/gh/dfki-ric/pytransform3d) From 3a0e34139a43811ae3c940097037af204d9c74ef Mon Sep 17 00:00:00 2001 From: David Wendorff Date: Fri, 27 Sep 2024 17:09:19 +0200 Subject: [PATCH 14/62] Revert "Update README.md" This reverts commit 9571615ab7bd5368db696ff3305a3bedf9161c9f. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 445d662d9..034c94c98 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -![pytransform3d logo](/doc/source/_static/logo.png) + [![CircleCI](https://dl.circleci.com/status-badge/img/gh/dfki-ric/pytransform3d/tree/main.svg?style=svg)](https://dl.circleci.com/status-badge/redirect/gh/dfki-ric/pytransform3d/tree/main) [![codecov](https://codecov.io/gh/dfki-ric/pytransform3d/branch/main/graph/badge.svg?token=jB10RM3Ujj)](https://codecov.io/gh/dfki-ric/pytransform3d) From 23fa4ea6bb05ebc6034f70851cbc64f3d681ca33 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 28 Sep 2024 17:24:58 +0200 Subject: [PATCH 15/62] Review UrdfTransformManager docstring --- pytransform3d/urdf.py | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/pytransform3d/urdf.py b/pytransform3d/urdf.py index d6ddbf237..1f7e285b8 100644 --- a/pytransform3d/urdf.py +++ b/pytransform3d/urdf.py @@ -16,10 +16,11 @@ class UrdfTransformManager(TransformManager): """Transformation manager that can load URDF files. - URDF is the `Unified Robot Description Format `_. - URDF allows to define joints between links that can be rotated about one - axis. This transformation manager allows to set the joint angles after - joints have been added or loaded from an URDF. + The Unified Robot Description Format (URDF) [1]_ is the most common format + to describe kinematic and dynamic properties of robots [2]_. This + transformation manager allows to set the joint configurations of a robot + loaded from a URDF file and provides an interface to its geometric and + visual representation. .. warning:: @@ -39,6 +40,14 @@ class UrdfTransformManager(TransformManager): check : bool, optional (default: True) Check if transformation matrices are valid and requested nodes exist, which might significantly slow down some operations. + + References + ---------- + .. [1] ROS Wiki: urdf, http://wiki.ros.org/urdf + + .. [2] Tola, D., Corke, P. (2023). Understanding URDF: A Dataset and + Analysis. In IEEE Robotics and Automation Letters 9(5), pp. 4479-4486, + doi: 10.1109/LRA.2024.3381482. https://arxiv.org/abs/2308.00514 """ def __init__(self, strict_check=True, check=True): super(UrdfTransformManager, self).__init__(strict_check, check) From 544944ed025974f7dded5ca17bb3775cba99da7a Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 28 Sep 2024 17:25:16 +0200 Subject: [PATCH 16/62] Explain PPOE step by step --- .../vis_probabilistic_robot_kinematics.py | 74 +++++++++++++++++-- 1 file changed, 66 insertions(+), 8 deletions(-) diff --git a/examples/visualizations/vis_probabilistic_robot_kinematics.py b/examples/visualizations/vis_probabilistic_robot_kinematics.py index e38441a2c..5a13c68d8 100644 --- a/examples/visualizations/vis_probabilistic_robot_kinematics.py +++ b/examples/visualizations/vis_probabilistic_robot_kinematics.py @@ -6,13 +6,6 @@ We compute the probabilistic forward kinematics of a robot with flexible links or joints and visualize the projected equiprobably ellipsoid of the end-effector's pose distribution. - -The end-effector's pose distribution is computed based on the probabilistic -product of exponentials (PPOE): - -Meyer, Strobl, Triebel: The Probabilistic Robot Kinematics Model and its -Application to Sensor Fusion, -https://elib.dlr.de/191928/1/202212_ELIB_PAPER_VERSION_with_copyright.pdf """ import os import numpy as np @@ -25,6 +18,32 @@ import pytransform3d.visualizer as pv +# %% +# Probabilistic Robot Kinematics +# ------------------------------ +# +# The end-effector's pose distribution is computed based on the Probabilistic +# Product of Exponentials PPOE [1]_. +# +# Our ProbabilisticRobotKinematics class is a subclass of +# :class:`~pytransform3d.urdf.UrdfTransformManager`, which loads a description +# of a robot from the URDF format. +# +# The complicated part of this example is the conversion of kinematics +# parameters from URDF data to screw axes that are needed for the product +# of exponentials formulation of forward kinematics. +# +# Once we have this information, the implementation of the probabilistic +# product of exponentials is straightforward: +# +# 1. We multiply the screw axis of each joint with the corresponding joint +# angle to obtain the exponential coordinates of each relative joint +# displacement. +# 2. We concatenate the relative joint displacements and the base pose to +# obtain the end-effector's pose. This is the original product of +# exponentials. +# 3. The PPOE modifies the original product of exponentials by transforming +# and concatenating the covariances of each transformation. class ProbabilisticRobotKinematics(UrdfTransformManager): """Probabilistic robot kinematics. @@ -150,8 +169,14 @@ def probabilistic_forward_kinematics(self, thetas, covs): return T, cov +# %% +# Mesh Visualization +# ------------------ +# To visualize the 6D covariance in the tangent space of SO(3), we project its +# equiprobable hyper-ellipsoid to 3D and represent it as a mesh. We can then +# visualize the mesh with this class. class Surface(pv.Artist): - """Surface. + """Surface to be visualized with Open3D. Parameters ---------- @@ -213,6 +238,8 @@ def geometries(self): return [self.mesh] +# %% +# Then we define a callback to animate the visualization. def animation_callback( step, n_frames, tm, graph, joint_names, thetas, covs, surface): angle = 0.5 * np.cos(2.0 * np.pi * (0.5 + step / n_frames)) @@ -228,6 +255,10 @@ def animation_callback( return graph, surface +# %% +# Setup +# ----- +# We load the URDF file, BASE_DIR = "test/test_data/" data_dir = BASE_DIR search_path = "." @@ -239,24 +270,41 @@ def animation_callback( with open(filename, "r") as f: robot_urdf = f.read() +# %% +# define the kinematic chain that we are interested in, joint_names = ["joint%d" % i for i in range(1, 7)] tm = ProbabilisticRobotKinematics( robot_urdf, "tcp", "linkmount", joint_names, mesh_path=data_dir) +# %% +# define the joint angles, thetas = np.array([1, 1, 1, 0, 1, 0]) for joint_name, theta in zip(joint_names, thetas): tm.set_joint(joint_name, theta) +# %% +# and define the covariances of the joints. covs = np.zeros((len(thetas), 6, 6)) covs[0] = np.diag([0, 0, 1, 0, 0, 0]) covs[1] = np.diag([0, 1, 0, 0, 0, 0]) covs[2] = np.diag([0, 1, 0, 0, 0, 0]) covs[4] = np.diag([0, 1, 0, 0, 0, 0]) covs *= 0.05 + +# %% +# PPOE and Visualization +# ---------------------- +# +# Then we can finally use PPOE to compute the end-effector pose and its +# covariance. T, cov = tm.probabilistic_forward_kinematics(thetas, covs) +# %% +# We compute the 3D projection of the 6D covariance matrix. x, y, z = pu.to_projected_ellipsoid(T, cov, factor=1, n_steps=50) +# %% +# The following code visualizes the result. fig = pv.figure() graph = fig.plot_graph(tm, "robot_arm", show_visuals=True) fig.plot_transform(np.eye(4), s=0.3) @@ -271,3 +319,13 @@ def animation_callback( fig.show() else: fig.save_image("__open3d_rendered_image.jpg") + +# %% +# References +# ---------- +# +# .. [1] Meyer, Strobl, Triebel (2022): The Probabilistic Robot Kinematics +# Model and its Application to Sensor Fusion. In IEEE/RSJ International +# Conference on Intelligent Robots and Systems (IROS), Kyoto, Japan, 2022, +# pp. 3263-3270, doi: 10.1109/IROS47612.2022.9981399. +# https://elib.dlr.de/191928/1/202212_ELIB_PAPER_VERSION_with_copyright.pdf From 725672afed1303c5df701a80a9c33b44d9ff94ba Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 28 Sep 2024 17:35:28 +0200 Subject: [PATCH 17/62] Better view configuration --- .../visualizations/vis_probabilistic_robot_kinematics.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/examples/visualizations/vis_probabilistic_robot_kinematics.py b/examples/visualizations/vis_probabilistic_robot_kinematics.py index 5a13c68d8..70078c122 100644 --- a/examples/visualizations/vis_probabilistic_robot_kinematics.py +++ b/examples/visualizations/vis_probabilistic_robot_kinematics.py @@ -279,7 +279,8 @@ def animation_callback( # %% # define the joint angles, thetas = np.array([1, 1, 1, 0, 1, 0]) -for joint_name, theta in zip(joint_names, thetas): +current_thetas = -0.5 * thetas +for joint_name, theta in zip(joint_names, current_thetas): tm.set_joint(joint_name, theta) # %% @@ -297,7 +298,7 @@ def animation_callback( # # Then we can finally use PPOE to compute the end-effector pose and its # covariance. -T, cov = tm.probabilistic_forward_kinematics(thetas, covs) +T, cov = tm.probabilistic_forward_kinematics(current_thetas, covs) # %% # We compute the 3D projection of the 6D covariance matrix. @@ -310,7 +311,7 @@ def animation_callback( fig.plot_transform(np.eye(4), s=0.3) surface = Surface(x, y, z, c=(0, 0.5, 0.5)) surface.add_artist(fig) -fig.view_init(elev=-20) +fig.view_init(elev=5, azim=50) n_frames = 200 if "__file__" in globals(): fig.animate(animation_callback, n_frames, loop=True, From 726211fdd7a8617472ccabd8a3b5e861e1e32f14 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sat, 28 Sep 2024 17:45:08 +0200 Subject: [PATCH 18/62] Improve citation --- .../plot_concatenate_uncertain_transforms.py | 23 +++++++++++-------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/examples/plots/plot_concatenate_uncertain_transforms.py b/examples/plots/plot_concatenate_uncertain_transforms.py index 7560a8e99..6c622a074 100644 --- a/examples/plots/plot_concatenate_uncertain_transforms.py +++ b/examples/plots/plot_concatenate_uncertain_transforms.py @@ -11,16 +11,19 @@ Gaussian in Cartesian space, but it is Gaussian in exponential coordinate space of SO(3). -This example adapted and modified to 3D from - -Barfoot, Furgale: Associating Uncertainty With Three-Dimensional Poses for Use -in Estimation Problems, http://ncfrn.mcgill.ca/members/pubs/barfoot_tro14.pdf - -The banana distribution was analyzed in detail by - -Long, Wolfe, Mashner, Chirikjian: The Banana Distribution is Gaussian: -A Localization Study with Exponential Coordinates, -http://www.roboticsproceedings.org/rss08/p34.pdf +This example adapted and modified to 3D from Barfoot and Furgale [1]_. +The banana distribution was analyzed in detail by Long et al. [2]_. + +References +---------- +.. [1] Barfoot, T. D., Furgale, P. T. (2014). Associating Uncertainty With + Three-Dimensional Poses for Use in Estimation Problems. IEEE Transactions on + Robotics 30(3), pp. 679-693, doi: 10.1109/TRO.2014.2298059. + +.. [2] Long, A. W., Wolfe, K. C., Mashner, M. J., Chirikjian, G. S. (2013). + The Banana Distribution is Gaussian: A Localization Study with Exponential + Coordinates. In Robotics: Science and Systems VIII, pp. 265-272. + http://www.roboticsproceedings.org/rss08/p34.pdf """ import numpy as np import matplotlib.pyplot as plt From 7e6a9e03fa8f66dcba3fe6d2f6986ca5045fbe82 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 29 Sep 2024 14:01:23 +0200 Subject: [PATCH 19/62] Link references --- doc/source/user_guide/transformations.rst | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index d695605a0..d3ab7164b 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -196,13 +196,13 @@ coordinates of transformation and typically we use the variable name Stheta. .. warning:: Note that we use the screw theory definition of exponential coordinates - and :math:`se(3)` (see next section) used by Paden (1985), Lynch and Park - (2017), and Corke (2017). They separate the parameter :math:`\theta` from + and :math:`se(3)` (see next section) used by Lynch and Park (2017) [1]_, + and Corke (2017) [2]_. They separate the parameter :math:`\theta` from the screw axis. Additionally, they use the first three components to encode rotation and the last three components to encode translation. There is an - alternative definition used by Eade (2017) and Sola et al. (2018). They use - a different order of the 3D vector components and they do not separate - :math:`\theta` from the screw axis in their notation. + alternative definition used by Eade (2017) [3]_ and Sola et al. (2018) + [4]_. They use a different order of the 3D vector components and they do + not separate :math:`\theta` from the screw axis in their notation. --------------------------- Logarithm of Transformation @@ -251,8 +251,9 @@ Twist We call spatial velocity (translation and rotation) **twist**. Similarly to the matrix logarithm, a twist :math:`\mathcal{V} = \mathcal{S} \dot{\theta}` -is described by a screw axis :math:`S` and a scalar :math:`\dot{\theta}` -and :math:`\left[\mathcal{V}\right] = \left[\mathcal{S}\right] \dot{\theta} \in se(3)` +is described by a screw axis :math:`\mathcal S` and a scalar +:math:`\dot{\theta}` and +:math:`\left[\mathcal{V}\right] = \left[\mathcal{S}\right] \dot{\theta} \in se(3)` is the matrix representation of a twist. ---------------- From dfe469b771a37ac2e242582c367a3acbf4b8c5de Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Mon, 30 Sep 2024 13:30:39 +0200 Subject: [PATCH 20/62] Add references --- doc/source/user_guide/introduction.rst | 21 ++++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/doc/source/user_guide/introduction.rst b/doc/source/user_guide/introduction.rst index 0d8536ba4..952e5f9a0 100644 --- a/doc/source/user_guide/introduction.rst +++ b/doc/source/user_guide/introduction.rst @@ -6,6 +6,9 @@ Introduction to 3D Rigid Transformations Basics ------ +Following Waldron and Schmiedeler [1]_, we define the basic terms that we use +throughout this user guide. + .. list-table:: :widths: 15 35 15 35 @@ -53,6 +56,10 @@ its frame) is always expressed with respect to another frame. Frame Notation -------------- +Notation is important for describing and understanding of physical quantities +in 3D. Furgale [2]_ [3]_ presents one of the most consistent and clear +approaches and we use it here. + For physical quantities we use the notation :math:`_{A}\boldsymbol{x}_{BC}`, where :math:`\boldsymbol{x}` is a physical quantity of frame C with respect to frame B expressed in frame A. For example, @@ -149,8 +156,16 @@ representations on the following pages. References ---------- -1. Waldron, K., Schmiedeler, J. (2008). Kinematics. In: Siciliano, B., Khatib, +.. [1] Waldron, K., Schmiedeler, J. (2008). Kinematics. In: Siciliano, B., Khatib, O. (eds) Springer Handbook of Robotics. Springer, Berlin, Heidelberg. https://doi.org/10.1007/978-3-540-30301-5_2 -2. Representing Robot Pose: The good, the bad, and the ugly (slides): http://static.squarespace.com/static/523c5c56e4b0abc2df5e163e/t/53957839e4b05045ad65021d/1402304569659/Workshop+-+Rotations_v102.key.pdf -3. Representing Robot Pose: The good, the bad, and the ugly (blog): http://paulfurgale.info/news/2014/6/9/representing-robot-pose-the-good-the-bad-and-the-ugly + +.. [2] Furgale, P. (2014). Representing Robot Pose: The good, the bad, and the + ugly (slides). In What Sucks in Robotics and How to Fix It: Lessons Learned + from Building Complex Systems (ICRA workshop). Note: these slides seem to be + lost, but the blog below conveys the same message. + http://static.squarespace.com/static/523c5c56e4b0abc2df5e163e/t/53957839e4b05045ad65021d/1402304569659/Workshop+-+Rotations_v102.key.pdf + +.. [3] Furgale, P. (2014). Representing Robot Pose: The good, the bad, and the + ugly (blog). + https://web.archive.org/web/20220420162355/http://paulfurgale.info/news/2014/6/9/representing-robot-pose-the-good-the-bad-and-the-ugly From 367fe1ef210d30436acf3d693d428abc48efe12a Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Mon, 30 Sep 2024 14:29:32 +0200 Subject: [PATCH 21/62] Math for quaternion conjugate --- pytransform3d/rotations/_quaternion_operations.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/pytransform3d/rotations/_quaternion_operations.py b/pytransform3d/rotations/_quaternion_operations.py index b6c2b96a6..ff14b4999 100644 --- a/pytransform3d/rotations/_quaternion_operations.py +++ b/pytransform3d/rotations/_quaternion_operations.py @@ -143,11 +143,19 @@ def q_prod_vector(q, v): def q_conj(q): - """Conjugate of quaternion. + r"""Conjugate of quaternion. The conjugate of a unit quaternion inverts the rotation represented by - this unit quaternion. The conjugate of a quaternion q is often denoted - as q*. + this unit quaternion. + + The conjugate of a quaternion :math:`\boldsymbol{q}` is often denoted as + :math:`\boldsymbol{q}^*`. For a quaternion :math:`\boldsymbol{q} = w + + x \boldsymbol{i} + y \boldsymbol{j} + z \boldsymbol{k}` it is defined as + + .. math:: + + \boldsymbol{q}^* = w - x \boldsymbol{i} - y \boldsymbol{j} + - z \boldsymbol{k}. Parameters ---------- From 1ecfee50c96e4302f05cc67209c5d264a0384d33 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Mon, 30 Sep 2024 14:49:51 +0200 Subject: [PATCH 22/62] Explain application of quaternion to vector --- .../rotations/_quaternion_operations.py | 31 +++++++++++++++++-- 1 file changed, 28 insertions(+), 3 deletions(-) diff --git a/pytransform3d/rotations/_quaternion_operations.py b/pytransform3d/rotations/_quaternion_operations.py index ff14b4999..a0eaa1b43 100644 --- a/pytransform3d/rotations/_quaternion_operations.py +++ b/pytransform3d/rotations/_quaternion_operations.py @@ -116,10 +116,31 @@ def concatenate_quaternions(q1, q2): def q_prod_vector(q, v): - """Apply rotation represented by a quaternion to a vector. + r"""Apply rotation represented by a quaternion to a vector. We use Hamilton's quaternion multiplication. + To apply the rotation defined by a unit quaternion :math:`\boldsymbol{q} + \in \mathbb{S}^3` to a vector :math:`\boldsymbol{v} \in \mathbb{R}^3`, we + first represent the vector as a quaternion: we set the scalar part to 0 and + the vector part is exactly the original vector + :math:`\left(\begin{array}{c}0\\\boldsymbol{v}\end{array}\right) \in + \mathbb{R}^4`. Then we left-multiply the quaternion and right-multiply + its conjugate + + .. math:: + + \left(\begin{array}{c}0\\\boldsymbol{w}\end{array}\right) + = + \boldsymbol{q} + \cdot + \left(\begin{array}{c}0\\\boldsymbol{v}\end{array}\right) + \cdot + \boldsymbol{q}^* + + The vector part :math:`\boldsymbol{w}` of the resulting quaternion is + the rotated vector. + Parameters ---------- q : array-like, shape (4,) @@ -130,12 +151,16 @@ def q_prod_vector(q, v): Returns ------- - w : array-like, shape (3,) + w : array, shape (3,) 3d vector See Also -------- - rotor_apply : The same operation with a different name. + rotor_apply + The same operation with a different name. + + concatenate_quaternions + Hamilton's quaternion multiplication. """ q = check_quaternion(q) t = 2 * np.cross(q[1:], v) From b24323a75f3a65727b960fb55cfd1a6c226d8945 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Mon, 30 Sep 2024 15:12:10 +0200 Subject: [PATCH 23/62] Reference dq conjugates --- .../_dual_quaternion_operations.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/pytransform3d/transformations/_dual_quaternion_operations.py b/pytransform3d/transformations/_dual_quaternion_operations.py index 8b5bbd43b..20053c062 100644 --- a/pytransform3d/transformations/_dual_quaternion_operations.py +++ b/pytransform3d/transformations/_dual_quaternion_operations.py @@ -24,6 +24,11 @@ def dq_conj(dq): ------- dq_conjugate : array, shape (8,) Conjugate of dual quaternion: (pw, -px, -py, -pz, -qw, qx, qy, qz) + + See Also + -------- + dq_q_conj + Quaternion conjugate of dual quaternion. """ dq = check_dual_quaternion(dq) return np.r_[dq[0], -dq[1:5], dq[5:]] @@ -32,14 +37,14 @@ def dq_conj(dq): def dq_q_conj(dq): """Quaternion conjugate of dual quaternion. + For unit dual quaternions that represent transformations, this function + is equivalent to the inverse of the corresponding transformation matrix. + There are three different conjugates for dual quaternions. The one that we use here converts (pw, px, py, pz, qw, qx, qy, qz) to (pw, -px, -py, -pz, qw, -qx, -qy, -qz). It is the quaternion conjugate applied to each of the two quaternions. - For unit dual quaternions that represent transformations, this function - is equivalent to the inverse of the corresponding transformation matrix. - Parameters ---------- dq : array-like, shape (8,) @@ -50,6 +55,11 @@ def dq_q_conj(dq): ------- dq_q_conjugate : array, shape (8,) Conjugate of dual quaternion: (pw, -px, -py, -pz, qw, -qx, -qy, -qz) + + See Also + -------- + dq_conj + Conjugate of a dual quaternion. """ dq = check_dual_quaternion(dq) return np.r_[dq[0], -dq[1:4], dq[4], -dq[5:]] From afcf8985291bdec150313cf3b6a27deee2e7865f Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 1 Oct 2024 10:42:37 +0200 Subject: [PATCH 24/62] Fix typo --- doc/source/user_guide/rotations.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index ce795127e..2583f56c8 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -310,7 +310,7 @@ The unit quaternion space :math:`\mathbb{S}^3` can be used to represent orientations with an encoding based on the rotation axis and angle. A rotation quaternion is a four-dimensional unit vector (versor) :math:`\boldsymbol{\hat{q}}`. -The following equation describes its relation to axis-axis notation. +The following equation describes its relation to axis-angle notation. .. math:: From a0b5d5e70779ce1f8fcaf50e6dd736f0faaa9785 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 1 Oct 2024 17:47:38 +0200 Subject: [PATCH 25/62] Explain banana distribution example --- .../plot_concatenate_uncertain_transforms.py | 52 ++++++++++++++----- 1 file changed, 38 insertions(+), 14 deletions(-) diff --git a/examples/plots/plot_concatenate_uncertain_transforms.py b/examples/plots/plot_concatenate_uncertain_transforms.py index 6c622a074..2762ee3d9 100644 --- a/examples/plots/plot_concatenate_uncertain_transforms.py +++ b/examples/plots/plot_concatenate_uncertain_transforms.py @@ -3,27 +3,15 @@ Concatenate Uncertain Transforms ================================ -Each of the poses has an associated covariance that is considered. In this example, we assume that a robot is moving with constant velocity along the x-axis, however, there is noise in the orientation of the robot that accumulates and leads to different paths when sampling. Uncertainty accumulation leads to the so-called banana distribution, which does not seem -Gaussian in Cartesian space, but it is Gaussian in exponential coordinate -space of SO(3). +Gaussian in Cartesian space, but it is Gaussian in exponential coordinates +of SE(3). This example adapted and modified to 3D from Barfoot and Furgale [1]_. The banana distribution was analyzed in detail by Long et al. [2]_. - -References ----------- -.. [1] Barfoot, T. D., Furgale, P. T. (2014). Associating Uncertainty With - Three-Dimensional Poses for Use in Estimation Problems. IEEE Transactions on - Robotics 30(3), pp. 679-693, doi: 10.1109/TRO.2014.2298059. - -.. [2] Long, A. W., Wolfe, K. C., Mashner, M. J., Chirikjian, G. S. (2013). - The Banana Distribution is Gaussian: A Localization Study with Exponential - Coordinates. In Robotics: Science and Systems VIII, pp. 265-272. - http://www.roboticsproceedings.org/rss08/p34.pdf """ import numpy as np import matplotlib.pyplot as plt @@ -33,6 +21,16 @@ import pytransform3d.plot_utils as ppu +# %% +# We configure the example here. You can change the random seed if you want. +# We assume :math:`\Delta t = 1 s` and constant velocity, so that in each step +# we concatenate the transformation :math:`\boldsymbol{T}_{vel}` defined +# via its exponential coordinates here. The covariance associated with +# :math:`\boldsymbol{T}_{vel}` is constructed from it's Cholesky decomposition +# through :math:`\boldsymbol{LL}^T`. Since it is a diagonal matrix at +# the moment, we just define the standard deviation of each velocity component. +# In the default configuration we have some uncertainty in the rotational +# components of the velocity. rng = np.random.default_rng(0) cov_pose_chol = np.diag([0, 0.02, 0.03, 0, 0, 0]) cov_pose = np.dot(cov_pose_chol, cov_pose_chol.T) @@ -42,6 +40,13 @@ n_mc_samples = 1000 n_skip_trajectories = 1 # plot every n-th trajectory +# %% +# We compute each path with respect to the initial pose of the robot, which +# we set to :math:`\boldsymbol{I}_{4 \times 4}`. The covariance of the initial +# pose is :math:`\boldsymbol{0}_{6 \times 6}`. We concatenate the current +# pose with :math:`\boldsymbol{T}_{vel}` in each step and factor in the +# uncertainty of the pose and the transformation. Hence, uncertainties will +# accumulate in the covariance of the pose. T_est = np.eye(4) path = np.zeros((n_steps + 1, 6)) path[0] = pt.exponential_coordinates_from_transform(T_est) @@ -51,6 +56,9 @@ T_est, cov_est, T_vel, cov_pose) path[t + 1] = pt.exponential_coordinates_from_transform(T_est) +# %% +# We perform Monte-Carlo sampling of trajectories for comparison. +# This implementation is vectorized with NumPy. T = np.eye(4) mc_path = np.zeros((n_steps + 1, n_mc_samples, 4, 4)) mc_path[0, :] = T @@ -64,6 +72,10 @@ mc_path_vec = np.einsum( "tinm,tin->tim", mc_path[:, :, :3, :3], mc_path[:, :, :3, 3]) +# %% +# We plot the MC-sampled trajectories and final poses, mean trajectory, +# projected equiprobably hyperellipsoid of the final distribution, and +# the equiprobably ellipsoid of the final distribution of the position. ax = ppu.make_3d_axis(100) for i in range(0, mc_path_vec.shape[1], n_skip_trajectories): @@ -97,3 +109,15 @@ plt.ylabel("y") ax.view_init(elev=70, azim=-90) plt.show() + +# %% +# References +# ---------- +# .. [1] Barfoot, T. D., Furgale, P. T. (2014). Associating Uncertainty With +# Three-Dimensional Poses for Use in Estimation Problems. IEEE Transactions on +# Robotics 30(3), pp. 679-693, doi: 10.1109/TRO.2014.2298059. +# +# .. [2] Long, A. W., Wolfe, K. C., Mashner, M. J., Chirikjian, G. S. (2013). +# The Banana Distribution is Gaussian: A Localization Study with Exponential +# Coordinates. In Robotics: Science and Systems VIII, pp. 265-272. +# http://www.roboticsproceedings.org/rss08/p34.pdf From 5fe39e92a4cb90a337b022bf470754053e44a84c Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 1 Oct 2024 17:52:59 +0200 Subject: [PATCH 26/62] Fix typo --- examples/plots/plot_concatenate_uncertain_transforms.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/plots/plot_concatenate_uncertain_transforms.py b/examples/plots/plot_concatenate_uncertain_transforms.py index 2762ee3d9..9db10ba7f 100644 --- a/examples/plots/plot_concatenate_uncertain_transforms.py +++ b/examples/plots/plot_concatenate_uncertain_transforms.py @@ -26,7 +26,7 @@ # We assume :math:`\Delta t = 1 s` and constant velocity, so that in each step # we concatenate the transformation :math:`\boldsymbol{T}_{vel}` defined # via its exponential coordinates here. The covariance associated with -# :math:`\boldsymbol{T}_{vel}` is constructed from it's Cholesky decomposition +# :math:`\boldsymbol{T}_{vel}` is constructed from its Cholesky decomposition # through :math:`\boldsymbol{LL}^T`. Since it is a diagonal matrix at # the moment, we just define the standard deviation of each velocity component. # In the default configuration we have some uncertainty in the rotational From 32e6c353628c14327b3a7c2509eef98b1d0c0d11 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 1 Oct 2024 18:01:30 +0200 Subject: [PATCH 27/62] Fix typo --- examples/visualizations/vis_probabilistic_robot_kinematics.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/visualizations/vis_probabilistic_robot_kinematics.py b/examples/visualizations/vis_probabilistic_robot_kinematics.py index 70078c122..49ab8a4c6 100644 --- a/examples/visualizations/vis_probabilistic_robot_kinematics.py +++ b/examples/visualizations/vis_probabilistic_robot_kinematics.py @@ -172,7 +172,7 @@ def probabilistic_forward_kinematics(self, thetas, covs): # %% # Mesh Visualization # ------------------ -# To visualize the 6D covariance in the tangent space of SO(3), we project its +# To visualize the 6D covariance in the tangent space of SE(3), we project its # equiprobable hyper-ellipsoid to 3D and represent it as a mesh. We can then # visualize the mesh with this class. class Surface(pv.Artist): From e9b9a1e411dadb22ea3df1df0de8b5eb9048869c Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Wed, 2 Oct 2024 11:17:16 +0200 Subject: [PATCH 28/62] Use boldsymbol for rotation matrices --- doc/source/user_guide/euler_angles.rst | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/doc/source/user_guide/euler_angles.rst b/doc/source/user_guide/euler_angles.rst index 4881a61fb..ae07e5987 100644 --- a/doc/source/user_guide/euler_angles.rst +++ b/doc/source/user_guide/euler_angles.rst @@ -44,20 +44,20 @@ Range of Angles Euler angles rotate about three basis vectors by the angles :math:`\alpha`, :math:`\beta`, and :math:`\gamma`. If we want to find the -Euler angles that correspond to one rotation matrix :math:`R`, there is an -infinite number of solutions because we can always add or subtract +Euler angles that correspond to one rotation matrix :math:`\boldsymbol{R}`, +there is an infinite number of solutions because we can always add or subtract :math:`2\pi` to one of the angles and get the same result. In addition, for proper Euler angles .. math:: - R(\alpha, \beta, \gamma) = R(\alpha + \pi, -\beta, \gamma - \pi). + \boldsymbol{R}(\alpha, \beta, \gamma) = \boldsymbol{R}(\alpha + \pi, -\beta, \gamma - \pi). For Cardan angles .. math:: - R(\alpha, \beta, \gamma) = R(\alpha + \pi, \pi - \beta, \gamma - \pi). + \boldsymbol{R}(\alpha, \beta, \gamma) = \boldsymbol{R}(\alpha + \pi, \pi - \beta, \gamma - \pi). For this reason the proper Euler angles are typically restricted to From 4148917456707de04b79f122799590aa1c8c2d51 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Wed, 2 Oct 2024 11:23:36 +0200 Subject: [PATCH 29/62] Make frame order consistent --- doc/source/user_guide/rotations.rst | 18 +++++++++--------- doc/source/user_guide/transformations.rst | 11 ++++++----- 2 files changed, 15 insertions(+), 14 deletions(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 2583f56c8..767566a8b 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -104,8 +104,8 @@ matrices and typically we use the variable name R for a rotation matrix. There are two conventions on how to interpret rotations: active or passive rotation. The standard in pytransform3d is an active rotation. -We can use a rotation matrix :math:`\boldsymbol R_{AB}` to transform a point -:math:`_B\boldsymbol{p}` from frame :math:`B` to frame :math:`A`. +We can use a rotation matrix :math:`\boldsymbol R_{BA}` to transform a point +:math:`_A\boldsymbol{p}` from frame :math:`A` to frame :math:`B`. .. warning:: @@ -115,21 +115,21 @@ We can use a rotation matrix :math:`\boldsymbol R_{AB}` to transform a point to a row vector from the right side. We will use the **pre-multiplication** convention. -This means that we rotate a point :math:`_B\boldsymbol{p}` by +This means that we rotate a point :math:`_A\boldsymbol{p}` by .. math:: - _A\boldsymbol{p} = \boldsymbol{R}_{ABB} \boldsymbol{p} + _B\boldsymbol{p} = \boldsymbol{R}_{BAA} \boldsymbol{p} This is called **linear map**. Note that with our index notation (as explained in :ref:`Frame Notation`) and these conventions, the second index of the rotation matrix and the left index -of the point have to be the same (:math:`B` in this example). The rotation is +of the point have to be the same (:math:`A` in this example). The rotation is applied incorrectly if this is not the case. -*Each column* of a rotation matrix :math:`\boldsymbol{R}_{AB}` is a basis -vector of frame :math:`A` with respect to frame :math:`B`. We can plot the +*Each column* of a rotation matrix :math:`\boldsymbol{R}_{BA}` is a basis +vector of frame :math:`B` with respect to frame :math:`A`. We can plot the basis vectors of an orientation to visualize it. Here, we can see orientation represented by the rotation matrix @@ -154,12 +154,12 @@ represented by the rotation matrix green for the y-axis and blue for the z-axis (RGB for xyz). We can easily chain multiple rotations: we can apply the rotation defined -by :math:`\boldsymbol R_{AB}` after the rotation :math:`\boldsymbol R_{BC}` +by :math:`\boldsymbol R_{CB}` after the rotation :math:`\boldsymbol R_{BA}` by applying the rotation .. math:: - \boldsymbol R_{AC} = \boldsymbol R_{AB} \boldsymbol R_{BC}. + \boldsymbol R_{CA} = \boldsymbol R_{CB} \boldsymbol R_{BA}. Note that the indices have to align again. Otherwise rotations are not applied in the correct order. diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index d3ab7164b..9e35646c9 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -97,16 +97,17 @@ setting the last component to zero (see :func:`~pytransform3d.transformations.vector_to_direction`): :math:`\left( x,y,z,0 \right)^T`. -We can use a transformation matrix :math:`\boldsymbol T_{AB}` to transform a -point :math:`{_B}\boldsymbol{p}` from frame :math:`B` to frame :math:`A`: +We can use a transformation matrix :math:`\boldsymbol T_{BA}` to transform a +point :math:`{_A}\boldsymbol{p}` from frame :math:`A` to frame :math:`B`: .. math:: - \boldsymbol{T}_{AB} {_B}\boldsymbol{p} = + \boldsymbol{T}_{BA} {_A}\boldsymbol{p} = \left( \begin{array}{c} - \boldsymbol{R} {_B}\boldsymbol{p} + \boldsymbol t\\ + \boldsymbol{R}_{BA} {_A}\boldsymbol{p} + {_B}\boldsymbol{t}_{BA}\\ 1\\ - \end{array} \right). + \end{array} \right) = + {_B}\boldsymbol{p}. You can use :func:`~pytransform3d.transformations.transform` to apply a transformation matrix to a homogeneous vector. From 6f1542460bd3ab602dcec653baa5a792caacb05b Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Wed, 2 Oct 2024 11:44:03 +0200 Subject: [PATCH 30/62] Add reference --- doc/source/user_guide/rotations.rst | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 767566a8b..706e6bf75 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -458,7 +458,7 @@ Modified Rodrigues Parameters ----------------------------- Another minimal representation of rotation are modified Rodrigues parameters -(MRP) [6]_ +(MRP) [6]_ [8]_ .. math:: @@ -519,3 +519,6 @@ References doi: 10.1007/s10851-017-0765-x. .. [7] Hauser, K.: Robotic Systems (draft), http://motion.pratt.duke.edu/RoboticSystems/3DRotations.html +.. [8] Shuster, M. D. (1993). A Survey of Attitude Representations. + Journal of the Astronautical Sciences, 41, 439-517. + http://malcolmdshuster.com/Pub_1993h_J_Repsurv_scan.pdf From 0689645c771e4e26e8994fed6128feed84dba116 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Wed, 2 Oct 2024 18:30:38 +0200 Subject: [PATCH 31/62] Notes on MPR --- doc/source/user_guide/rotations.rst | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 706e6bf75..1b4b88d92 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -483,6 +483,12 @@ parameters. MRPs have a singuarity at :math:`2 \pi` which we can avoid by ensuring the angle of rotation does not exceed :math:`\pi`. +.. warning:: + + MRPs have two representations for the same rotation: + :math:`\psi` and :math:`-\frac{1}{||\psi||^2} \psi` represent the same + rotation and correspond to two antipodal unit quaternions [8]_. + **Pros** * Minimal representation. @@ -491,8 +497,9 @@ parameters. * The representation is not straightforward to interpret. * Normalization of angle required to avoid singularity. -* Concatenation and transformation of vectors requires conversion to rotation - matrix or quaternion. +* Each rotation has two representations as modified Rodrigues parameters. +* Transformation of vectors requires conversion to rotation matrix or + quaternion. ---------- References From 838ad704fc05fd30702846eb2db381ca341bf409 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Wed, 2 Oct 2024 19:36:43 +0200 Subject: [PATCH 32/62] Pros and cons of transformation representations --- doc/source/user_guide/transformations.rst | 52 +++++++++++++++++++++++ 1 file changed, 52 insertions(+) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index 9e35646c9..2a8e351e7 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -112,6 +112,22 @@ point :math:`{_A}\boldsymbol{p}` from frame :math:`A` to frame :math:`B`: You can use :func:`~pytransform3d.transformations.transform` to apply a transformation matrix to a homogeneous vector. +**Pros** + +* It is easy to apply transformations on vectors in homogeneous coordinates by + matrix-vector multiplication. +* Concatenation of transformations is trivial through matrix multiplication. +* You can directly read the basis vectors and translation from the columns. +* No singularities. + +**Cons** + +* We use 16 values for 6 degrees of freedom. +* Not every 4x4 matrix is a valid transformation matrix, which means for + example that we cannot simply apply an optimization algorithm to + transformation matrices or interpolate between them. Renormalization is + computationally expensive. + ----------------------- Position and Quaternion ----------------------- @@ -131,6 +147,17 @@ a 2D array. pytransform3d uses a numpy array of shape (7,) to represent position and quaternion and typically we use the variable name pq. +**Pros** + +* More compact than the matrix representation and less susceptible to + round-off errors. +* Compact representation. + +**Cons** + +* Separation of translation and rotation component. Both have to be handled + individually. + ---------------- Screw Parameters ---------------- @@ -205,6 +232,20 @@ coordinates of transformation and typically we use the variable name Stheta. [4]_. They use a different order of the 3D vector components and they do not separate :math:`\theta` from the screw axis in their notation. +**Pros** + +* Minimal representation. +* Can also represent velocity and acceleration when we replace + :math:`\theta` by :math:`\dot{\theta}` or :math:`\ddot{\theta}` respectively, + which makes numerical integration and differentiation easy. + +**Cons** + +* There might be discontinuities and ambiguities. This has to + be considered. Normalization is recommended. +* Concatenation and transformation of vectors requires conversion to + transformation matrix or dual quaternion. + --------------------------- Logarithm of Transformation --------------------------- @@ -302,6 +343,17 @@ quaternion encodes the translation component as :math:`\boldsymbol{t}` is a quaternion with the translation in the vector component and the scalar 0, and rotation quaternions have the same ambiguity. +**Pros** + +* No singularities. +* Efficient and compact form for representing transformations [7]_. + +**Cons** + +* The representation is not straightforward to interpret. +* There are always two unit dual quaternions that represent exactly the same + transformation. + ---------- References ---------- From d0f80c913847669b766b9be1725d8dafb0969f51 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Thu, 3 Oct 2024 10:58:58 +0200 Subject: [PATCH 33/62] Concatenation of MRPs --- doc/source/api.rst | 9 +++ pytransform3d/rotations/__init__.py | 2 + pytransform3d/rotations/_mrp.py | 55 +++++++++++++++++++ pytransform3d/rotations/_mrp.pyi | 5 ++ .../rotations/_quaternion_operations.py | 2 +- pytransform3d/test/test_rotations.py | 12 ++++ 6 files changed, 84 insertions(+), 1 deletion(-) create mode 100644 pytransform3d/rotations/_mrp.py create mode 100644 pytransform3d/rotations/_mrp.pyi diff --git a/doc/source/api.rst b/doc/source/api.rst index 8d87639da..27876c1d5 100644 --- a/doc/source/api.rst +++ b/doc/source/api.rst @@ -137,6 +137,15 @@ Rotors ~rotor_apply ~rotor_slerp +Modified Rodrigues Parameters +----------------------------- + +.. autosummary:: + :toctree: _apidoc/ + :template: function.rst + + ~concatenate_mrp + Plotting -------- diff --git a/pytransform3d/rotations/__init__.py b/pytransform3d/rotations/__init__.py index 402e1eb22..23bbac453 100644 --- a/pytransform3d/rotations/__init__.py +++ b/pytransform3d/rotations/__init__.py @@ -87,6 +87,7 @@ from ._quaternion_operations import ( quaternion_integrate, quaternion_gradient, concatenate_quaternions, q_conj, q_prod_vector, quaternion_diff, quaternion_dist, quaternion_from_euler) +from ._mrp import concatenate_mrp from ._slerp import (slerp_weights, pick_closest_quaternion, quaternion_slerp, axis_angle_slerp, rotor_slerp) from ._testing import ( @@ -207,6 +208,7 @@ "euler_from_quaternion", "quaternion_from_angle", "quaternion_from_euler", + "concatenate_mrp", "cross_product_matrix", "mrp_from_quaternion", "quaternion_from_mrp", diff --git a/pytransform3d/rotations/_mrp.py b/pytransform3d/rotations/_mrp.py new file mode 100644 index 000000000..a22cd105d --- /dev/null +++ b/pytransform3d/rotations/_mrp.py @@ -0,0 +1,55 @@ +"""Modified Rodrigues parameters.""" +import numpy as np +from ._utils import check_mrp + + +def concatenate_mrp(mrp1, mrp2): + r"""Concatenate two rotations defined by modified Rodrigues parameters. + + Suppose we want to apply two extrinsic rotations given by modified + Rodrigues parameters mrp1 and mrp2 to a vector v. We can either apply mrp2 + to v and then mrp1 to the result or we can concatenate mrp1 and mrp2 and + apply the result to v. + + The solution for concatenation of two rotations + :math:`\boldsymbol{p}_1,\boldsymbol{p}_2` is given by Shuster [1]_: + + .. math:: + + \boldsymbol{p} = + \frac{ + (1 - ||\boldsymbol{p}_1||^2) \boldsymbol{p}_2 + + (1 - ||\boldsymbol{p}_2||^2) \boldsymbol{p}_1 + - 2 \boldsymbol{p}_2 \times \boldsymbol{p}_1} + {1 + ||\boldsymbol{p}_2||^2 ||\boldsymbol{p}_1||^2 + - 2 \boldsymbol{p}_2 \cdot \boldsymbol{p}_1}. + + Parameters + ---------- + mrp1 : array-like, shape (3,) + Modified Rodrigues parameters. + + mrp2 : array-like, shape (3,) + Modified Rodrigues parameters. + + Returns + ------- + mrp12 : array, shape (3,) + Modified Rodrigues parameters that represent the concatenated rotation + of mrp1 and mrp2. + + References + ---------- + .. [1] Shuster, M. D. (1993). A Survey of Attitude Representations. + Journal of the Astronautical Sciences, 41, 439-517. + http://malcolmdshuster.com/Pub_1993h_J_Repsurv_scan.pdf + """ + mrp1 = check_mrp(mrp1) + mrp2 = check_mrp(mrp2) + norm1_sq = np.linalg.norm(mrp1) ** 2 + norm2_sq = np.linalg.norm(mrp2) ** 2 + cross_product = np.cross(mrp2, mrp1) + scalar_product = np.dot(mrp2, mrp1) + return ( + (1 - norm1_sq) * mrp2 + (1 - norm2_sq) * mrp1 - 2 * cross_product + ) / (1 + norm2_sq * norm1_sq - 2 * scalar_product) diff --git a/pytransform3d/rotations/_mrp.pyi b/pytransform3d/rotations/_mrp.pyi new file mode 100644 index 000000000..ff1490f9f --- /dev/null +++ b/pytransform3d/rotations/_mrp.pyi @@ -0,0 +1,5 @@ +import numpy as np +import numpy.typing as npt + + +def concatenate_mrp(mrp1: npt.ArrayLike, mrp2: npt.ArrayLike) -> np.ndarray: ... diff --git a/pytransform3d/rotations/_quaternion_operations.py b/pytransform3d/rotations/_quaternion_operations.py index a0eaa1b43..2187febe5 100644 --- a/pytransform3d/rotations/_quaternion_operations.py +++ b/pytransform3d/rotations/_quaternion_operations.py @@ -100,7 +100,7 @@ def concatenate_quaternions(q1, q2): Returns ------- - q12 : array-like, shape (4,) + q12 : array, shape (4,) Quaternion that represents the concatenated rotation q1 * q2 See Also diff --git a/pytransform3d/test/test_rotations.py b/pytransform3d/test/test_rotations.py index b21d2db74..6526e0cfb 100644 --- a/pytransform3d/test/test_rotations.py +++ b/pytransform3d/test/test_rotations.py @@ -2251,3 +2251,15 @@ def test_norm_angle_precision(): assert_array_equal(pr.norm_angle(a_eps), a_eps) assert_array_equal(pr.norm_angle(a_epsneg), a_epsneg) + + +def test_concatenate_mrp(): + rng = np.random.default_rng(283) + for _ in range(5): + q1 = pr.random_quaternion(rng) + q2 = pr.random_quaternion(rng) + q12 = pr.concatenate_quaternions(q1, q2) + mrp1 = pr.mrp_from_quaternion(q1) + mrp2 = pr.mrp_from_quaternion(q2) + mrp12 = pr.concatenate_mrp(mrp1, mrp2) + pr.assert_quaternion_equal(q12, pr.quaternion_from_mrp(mrp12)) From 5e0d34bb9f44f2680379f9a91a3eec7b6c3eac7c Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Thu, 3 Oct 2024 11:02:13 +0200 Subject: [PATCH 34/62] Update overview table --- doc/source/user_guide/rotations.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 1b4b88d92..9cf74ba69 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -44,7 +44,7 @@ is not implemented in pytransform3d then it is shown in brackets. | Euler angles | `(1)` | No | No | No | | :math:`(\alpha, \beta, \gamma)` | | | | | +----------------------------------------+---------------+--------------------+---------------+---------------+ -| Modified Rodrigues parameters | Negative | No | No | No | +| Modified Rodrigues parameters | Negative | No | Yes | No | | :math:`\psi` | | | | | +----------------------------------------+---------------+--------------------+---------------+---------------+ From 2283f93575a05480a97351d6df787680639dc0c8 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Thu, 3 Oct 2024 11:04:32 +0200 Subject: [PATCH 35/62] Float type --- pytransform3d/rotations/_mrp.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/pytransform3d/rotations/_mrp.py b/pytransform3d/rotations/_mrp.py index a22cd105d..bdf2ae46e 100644 --- a/pytransform3d/rotations/_mrp.py +++ b/pytransform3d/rotations/_mrp.py @@ -51,5 +51,5 @@ def concatenate_mrp(mrp1, mrp2): cross_product = np.cross(mrp2, mrp1) scalar_product = np.dot(mrp2, mrp1) return ( - (1 - norm1_sq) * mrp2 + (1 - norm2_sq) * mrp1 - 2 * cross_product - ) / (1 + norm2_sq * norm1_sq - 2 * scalar_product) + (1.0 - norm1_sq) * mrp2 + (1.0 - norm2_sq) * mrp1 - 2.0 * cross_product + ) / (1.0 + norm2_sq * norm1_sq - 2.0 * scalar_product) From 9e5834ef934a115014081064a8bb68724b74735c Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Thu, 3 Oct 2024 15:50:28 +0200 Subject: [PATCH 36/62] Restructure rotation section --- doc/source/user_guide/introduction.rst | 6 +- doc/source/user_guide/rotations.rst | 114 ++++++++++++++----------- 2 files changed, 65 insertions(+), 55 deletions(-) diff --git a/doc/source/user_guide/introduction.rst b/doc/source/user_guide/introduction.rst index 952e5f9a0..ec3a2fd83 100644 --- a/doc/source/user_guide/introduction.rst +++ b/doc/source/user_guide/introduction.rst @@ -115,12 +115,12 @@ representations on the following pages. | Rotation matrix | (3, 3) | X | | | :math:`\pmb{R}` | | | | +----------------------------------------+---------------------+------------------+---------------+ -| Compact axis-angle | (3,) | X | | -| :math:`\pmb{\omega}` | | | | -+----------------------------------------+---------------------+------------------+---------------+ | Axis-angle | (4,) | X | | | :math:`(\hat{\pmb{\omega}}, \theta)` | | | | +----------------------------------------+---------------------+------------------+---------------+ +| Rotation vector | (3,) | X | | +| :math:`\pmb{\omega}` | | | | ++----------------------------------------+---------------------+------------------+---------------+ | Logarithm of rotation | (3, 3) | X | | | :math:`\left[\pmb{\omega}\right]` | | | | +----------------------------------------+---------------------+------------------+---------------+ diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 9cf74ba69..4ae9678b9 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -20,33 +20,33 @@ Not all representations support all operations directly without conversion to another representation. The following table is an overview. If the operation is not implemented in pytransform3d then it is shown in brackets. -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Representation | Inverse | Rotation of vector | Concatenation | Interpolation | -+========================================+===============+====================+===============+===============+ -| Rotation matrix | Transpose | Yes | Yes | No | -| :math:`\pmb{R}` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Compact axis-angle | Negative | No | No | (Yes) `(2)` | -| :math:`\pmb{\omega}` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Axis-angle | Negative axis | No | No | SLERP | -| :math:`(\hat{\pmb{\omega}}, \theta)` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Logarithm of rotation | Negative | No | No | (Yes) `(2)` | -| :math:`\left[\pmb{\omega}\right]` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Quaternion | Conjugate | Yes | Yes | SLERP | -| :math:`\pmb{q}` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Rotor | Reverse | Yes | Yes | SLERP | -| :math:`R` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Euler angles | `(1)` | No | No | No | -| :math:`(\alpha, \beta, \gamma)` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ -| Modified Rodrigues parameters | Negative | No | Yes | No | -| :math:`\psi` | | | | | -+----------------------------------------+---------------+--------------------+---------------+---------------+ ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Representation | Inverse | Rotation of vector | Concatenation | Interpolation | Renormalization | ++========================================+===============+====================+===============+===============+=================+ +| Rotation matrix | Transpose | Yes | Yes | No | Required | +| :math:`\pmb{R}` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Axis-angle | Negative axis | No | No | SLERP | Not necessary | +| :math:`(\hat{\pmb{\omega}}, \theta)` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Rotation vector | Negative | No | No | (Yes) `(2)` | Not required | +| :math:`\pmb{\omega}` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Logarithm of rotation | Negative | No | No | (Yes) `(2)` | Not required | +| :math:`\left[\pmb{\omega}\right]` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Quaternion | Conjugate | Yes | Yes | SLERP | Required | +| :math:`\pmb{q}` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Rotor | Reverse | Yes | Yes | SLERP | Required | +| :math:`R` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Euler angles | `(1)` | No | No | No | Not necessary | +| :math:`(\alpha, \beta, \gamma)` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ +| Modified Rodrigues parameters | Negative | No | Yes | No | Not required | +| :math:`\psi` | | | | | | ++----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ Footnotes: @@ -54,7 +54,7 @@ Footnotes: another convention CBA (e.g., zyx), reversing the order of angles, and taking the negative of these. -`(2)` Linear interpolation is approximately correct. +`(2)` Linear interpolation is approximately correct for small differences. --------------- Rotation Matrix @@ -225,23 +225,52 @@ Note that the axis-angle representation has a singularity at represent the identity rotation in this case. However, we can modify the representation to avoid this singularity. -It is possible to write this in a more compact way as a rotation vector [2]_: +--------------- +Rotation Vector +--------------- + +Since :math:`||\hat{\boldsymbol{\omega}}|| = 1`, it is possible to write this +in a more compact way as a rotation vector [2]_ .. math:: - \boldsymbol{\omega} = \hat{\boldsymbol{\omega}} \theta \in \mathbb{R}^3 + \boldsymbol{\omega} = \hat{\boldsymbol{\omega}} \theta \in \mathbb{R}^3. +In code, we call this the compact axis-angle representation. pytransform3d uses a numpy array of shape (3,) for the compact axis-angle -representation of a rotation and typically we use the variable name a. +representation of a rotation and typically it uses the variable name a. We can also refer to this representation as **exponential coordinates of -rotation** [5]_. We can easily represent angular velocity as +rotation** [5]_. We can represent angular velocity as :math:`\hat{\boldsymbol{\omega}} \dot{\theta}` and angular acceleration as :math:`\hat{\boldsymbol{\omega}} \ddot{\theta}` so that we can easily do component-wise integration and differentiation with this representation. + +**Pros** + +* Minimal representation. +* Can also represent angular velocity and acceleration when we replace + :math:`\theta` by :math:`\dot{\theta}` or :math:`\ddot{\theta}` respectively, + which makes numerical integration and differentiation easy. + +**Cons** + +* There might be discontinuities during interpolation as an angle of 0 and + any multiple of :math:`2\pi` represent the same orientation. This has to + be considered. Normalization is recommended. +* When :math:`\theta = \pi`, the axes :math:`\hat{\boldsymbol{\omega}}` and + :math:`-\hat{\boldsymbol{\omega}}` represent the same rotation, which is + a problem for interpolation. +* Concatenation and transformation of vectors requires conversion to rotation + matrix or quaternion. + +--------------------- +Logarithm of Rotation +--------------------- + In addition, we can represent :math:`\hat{\boldsymbol{\omega}} \theta` by -the cross-product matrix +the cross-product matrix (:func:`~pytransform3d.rotations.cross_product_matrix`) .. math:: @@ -262,25 +291,6 @@ where :math:`\left[\hat{\boldsymbol{\omega}}\right] \theta` is the matrix logarithm of a rotation matrix and :math:`so(3)` is the Lie algebra of the Lie group :math:`SO(3)`. -**Pros** - -* Minimal representation (as rotation vector, also referred to as compact - axis-angle in the code). -* Can also represent angular velocity and acceleration when we replace - :math:`\theta` by :math:`\dot{\theta}` or :math:`\ddot{\theta}` respectively, - which makes numerical integration and differentiation easy. - -**Cons** - -* There might be discontinuities during interpolation as an angle of 0 and - any multiple of :math:`2\pi` represent the same orientation. This has to - be considered. Normalization is recommended. -* When :math:`\theta = \pi`, the axes :math:`\hat{\boldsymbol{\omega}}` and - :math:`-\hat{\boldsymbol{\omega}}` represent the same rotation, which is - a problem for interpolation. -* Concatenation and transformation of vectors requires conversion to rotation - matrix or quaternion. - ----------- Quaternions ----------- From fa709e2e061dcc18c6e72338e1242d7ce573105a Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Thu, 3 Oct 2024 16:03:49 +0200 Subject: [PATCH 37/62] Add overview table for transformations --- doc/source/user_guide/transformations.rst | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index 2a8e351e7..3ce733f8e 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -39,6 +39,28 @@ that are available in pytransform3d. :width: 50% :align: center +Not all representations support all operations directly without conversion to +another representation. The following table is an overview. + ++----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ +| Representation | Inverse | Transformation of vector | Concatenation | Interpolation | Renormalization | ++========================================+============+==========================+===============+===============+=================+ +| Transformation matrix | Inverse | Yes | Yes | No | Required | +| :math:`\pmb{R}` | | | | | | ++----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ +| Exponential coordinates | Negative | No | No | ScLERP | Not necessary | +| :math:`\mathcal{S}\theta` | | | | | | ++----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ +| Logarithm of transformation | Negative | No | No | No | Not necessary | +| :math:`\left[\mathcal{S}\theta\right]` | | | | | | ++----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ +| Position and quaternion | No | No | No | No | Required | +| :math:`(\pmb{p}, \pmb{q})` | | | | | | ++----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ +| Dual quaternion | Quaternion | Yes | Yes | ScLERP | Required | +| :math:`\pmb{p} + \epsilon \pmb{q}` | Conjugate | | | | | ++----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ + --------------------- Transformation Matrix From 74c7a2ab60101da732fd4a32ee141c4a3d94f803 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 10:51:42 +0200 Subject: [PATCH 38/62] Detailed explanation of quat. product --- .../rotations/_quaternion_operations.py | 21 +++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/pytransform3d/rotations/_quaternion_operations.py b/pytransform3d/rotations/_quaternion_operations.py index 2187febe5..a176f2f5a 100644 --- a/pytransform3d/rotations/_quaternion_operations.py +++ b/pytransform3d/rotations/_quaternion_operations.py @@ -82,13 +82,26 @@ def quaternion_gradient(Q, dt=1.0): def concatenate_quaternions(q1, q2): - """Concatenate two quaternions. + r"""Concatenate two quaternions. + + We concatenate two quaternions by quaternion multiplication + :math:`\boldsymbol{q}_1\boldsymbol{q}_2`. We use Hamilton's quaternion multiplication. - Suppose we want to apply two extrinsic rotations given by quaternions - q1 and q2 to a vector v. We can either apply q2 to v and then q1 to - the result or we can concatenate q1 and q2 and apply the result to v. + If the two quaternions are divided up into scalar part and vector part + each, i.e., + :math:`\boldsymbol{q} = (w, \boldsymbol{v}), w \in \mathbb{R}, + \boldsymbol{v} \in \mathbb{R}^3`, then the quaternion product is + + .. math:: + + \boldsymbol{q}_{12} = + (w_1 w_2 - \boldsymbol{v}_1 \cdot \boldsymbol{v}_2, + w_1 \boldsymbol{v}_2 + w_2 \boldsymbol{v}_1 + + \boldsymbol{v}_1 \times \boldsymbol{v}_2) + + with the scalar product :math:`\cdot` and the cross product :math:`\times`. Parameters ---------- From b2127476a964ffa0b3e3a595bd2f9c45b7ddcb6d Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 10:57:38 +0200 Subject: [PATCH 39/62] Explain quaternion operations --- doc/source/user_guide/rotations.rst | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 4ae9678b9..55e2fffdc 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -358,6 +358,21 @@ functions :func:`~pytransform3d.rotations.quaternion_wxyz_from_xyzw` and This must be considered during operations like interpolation, distance calculation, or (approximate) equality checks. +The quaternion product +(:func:`~pytransform3d.rotations.concatenate_quaternions`) can be used to +concatenate rotations like the matrix product can be used to concatenate +rotations represented by rotation matrices. + +The inverse of the rotation represented by the unit quaternion +:math:`\boldsymbol{q}` is represented by the conjugate +:math:`\boldsymbol{q}^*` (:func:`~pytransform3d.rotations.q_conj`). + +We can rotate a vector by representing it as a pure quaternion (i.e., with +a scalar part of 0) and then left-multiplying the quaternion and +right-multiplying its conjugate +:math:`\boldsymbol{q}\boldsymbol{v}\boldsymbol{q}^*` +with the quaternion product (:func:`~pytransform3d.rotations.q_prod_vector`). + **Pros** * More compact than the matrix representation and less susceptible to From 8a11c4300244547e4ab73541e157e93b188f4a21 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 11:36:06 +0200 Subject: [PATCH 40/62] Pros of dual quaternions --- doc/source/user_guide/transformations.rst | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index 3ce733f8e..1d6043a3a 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -367,8 +367,14 @@ component and the scalar 0, and rotation quaternions have the same ambiguity. **Pros** -* No singularities. +* Normalization is a simple operation: scaling the dual quaternion to unit + norm. Note that only the orientation part defines the norm of the quaternion, + since :math:`\epsilon^2 = 0` (see + :func:`~pytransform3d.transformations.check_dual_quaternion`). +* Easy interpolation with + :func:`~pytransform3d.transformations.dual_quaternion_sclerp`. * Efficient and compact form for representing transformations [7]_. +* No singularities. **Cons** From b2874ac91280e9e6f7654d2002cd85b434429052 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 16:25:17 +0200 Subject: [PATCH 41/62] Correct dq normalization --- doc/source/user_guide/transformations.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index 1d6043a3a..c55dececf 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -369,8 +369,8 @@ component and the scalar 0, and rotation quaternions have the same ambiguity. * Normalization is a simple operation: scaling the dual quaternion to unit norm. Note that only the orientation part defines the norm of the quaternion, - since :math:`\epsilon^2 = 0` (see - :func:`~pytransform3d.transformations.check_dual_quaternion`). + since :math:`\epsilon^2 = 0` and the scalar product of the real and dual + part is 0 (see :func:`~pytransform3d.transformations.check_dual_quaternion`). * Easy interpolation with :func:`~pytransform3d.transformations.dual_quaternion_sclerp`. * Efficient and compact form for representing transformations [7]_. From 19c5363dbea9e265eb95948eb2cb73986bbb6926 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 17:57:41 +0200 Subject: [PATCH 42/62] Update documentation of dual quat. multiplication --- .../_dual_quaternion_operations.py | 21 ++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/pytransform3d/transformations/_dual_quaternion_operations.py b/pytransform3d/transformations/_dual_quaternion_operations.py index 20053c062..6b12893a0 100644 --- a/pytransform3d/transformations/_dual_quaternion_operations.py +++ b/pytransform3d/transformations/_dual_quaternion_operations.py @@ -66,12 +66,18 @@ def dq_q_conj(dq): def concatenate_dual_quaternions(dq1, dq2): - """Concatenate dual quaternions. + r"""Concatenate dual quaternions. - Suppose we want to apply two extrinsic transforms given by dual - quaternions dq1 and dq2 to a vector v. We can either apply dq2 to v and - then dq1 to the result or we can concatenate dq1 and dq2 and apply the - result to v. + We concatenate two dual quaternions by dual quaternion multiplication + + .. math:: + + (\boldsymbol{p}_1 + \epsilon \boldsymbol{q}_1) + (\boldsymbol{p}_2 + \epsilon \boldsymbol{q}_2) + = \boldsymbol{p}_1 \boldsymbol{p}_2 + \epsilon ( + \boldsymbol{p}_1 \boldsymbol{q}_2 + \boldsymbol{q}_1 \boldsymbol{p}_2) + + using Hamilton multiplication of quaternions. .. warning:: @@ -93,6 +99,11 @@ def concatenate_dual_quaternions(dq1, dq2): dq3 : array, shape (8,) Product of the two dual quaternions: (pw, px, py, pz, qw, qx, qy, qz) + + See Also + -------- + pytransform3d.rotations.concatenate_quaternions + Quaternion multiplication. """ dq1 = check_dual_quaternion(dq1) dq2 = check_dual_quaternion(dq2) From 1ce313199e376514efff097e3cf425d53d20fb5f Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 18:07:27 +0200 Subject: [PATCH 43/62] Explain transformation by dual quat. --- .../rotations/_quaternion_operations.py | 2 +- .../_dual_quaternion_operations.py | 24 ++++++++++++++++++- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/pytransform3d/rotations/_quaternion_operations.py b/pytransform3d/rotations/_quaternion_operations.py index a176f2f5a..71feaeea1 100644 --- a/pytransform3d/rotations/_quaternion_operations.py +++ b/pytransform3d/rotations/_quaternion_operations.py @@ -149,7 +149,7 @@ def q_prod_vector(q, v): \cdot \left(\begin{array}{c}0\\\boldsymbol{v}\end{array}\right) \cdot - \boldsymbol{q}^* + \boldsymbol{q}^*. The vector part :math:`\boldsymbol{w}` of the resulting quaternion is the rotated vector. diff --git a/pytransform3d/transformations/_dual_quaternion_operations.py b/pytransform3d/transformations/_dual_quaternion_operations.py index 6b12893a0..ebbc35d65 100644 --- a/pytransform3d/transformations/_dual_quaternion_operations.py +++ b/pytransform3d/transformations/_dual_quaternion_operations.py @@ -114,7 +114,29 @@ def concatenate_dual_quaternions(dq1, dq2): def dq_prod_vector(dq, v): - """Apply transform represented by a dual quaternion to a vector. + r"""Apply transform represented by a dual quaternion to a vector. + + To apply the transformation defined by a unit dual quaternion + :math:`\boldsymbol{q}` to a point :math:`\boldsymbol{v} \in \mathbb{R}^3`, + we first represent the vector as a dual quaternion: we set the real part to + (1, 0, 0, 0) and the dual part is a pure quaternion with the scalar part + 0 and the vector as its vector part + :math:`\left(\begin{array}{c}0\\\boldsymbol{v}\end{array}\right) \in + \mathbb{R}^4`. Then we left-multiply the dual quaternion and right-multiply + its dual quaternion conjugate + + .. math:: + + \left(\begin{array}{c}1\\0\\0\\0\\0\\\boldsymbol{w}\end{array}\right) + = + \boldsymbol{q} + \cdot + \left(\begin{array}{c}1\\0\\0\\0\\0\\\boldsymbol{v}\end{array}\right) + \cdot + \boldsymbol{q}^*. + + The vector part of the dual part :math:`\boldsymbol{w}` of the resulting + quaternion is the rotated point. Parameters ---------- From 5f2470a60136cfe5785eb170a997a8e1998b2e09 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 18:22:57 +0200 Subject: [PATCH 44/62] Rephrase dual quat text --- doc/source/user_guide/transformations.rst | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index c55dececf..4a1e64dc4 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -341,14 +341,14 @@ and the dual quaternion is orthogonal to the real quaternion. The real quaternion is used to represent the rotation and the dual quaternion contains information about the rotation and translation. -Dual quaternions support similar operations as transformation matrices -(inversion through the conjugate of the two individual quaternions +Dual quaternions support similar operations as transformation matrices: +inversion through the conjugate of the two individual quaternions :func:`~pytransform3d.transformations.dq_q_conj`, concatenation through :func:`~pytransform3d.transformations.concatenate_dual_quaternions`, and transformation of a point by -:func:`~pytransform3d.transformations.dq_prod_vector`), -they can be renormalized efficiently (with -:func:`~pytransform3d.transformations.check_dual_quaternion`, and +:func:`~pytransform3d.transformations.dq_prod_vector`. +They can be renormalized efficiently (with +:func:`~pytransform3d.transformations.check_dual_quaternion`), and interpolation between two dual quaternions is possible (with :func:`~pytransform3d.transformations.dual_quaternion_sclerp`). From 456ca0a5d6c5380124a7906a8c1acd76c029f5d3 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Sun, 6 Oct 2024 18:37:08 +0200 Subject: [PATCH 45/62] Extend citation --- doc/source/user_guide/transformations.rst | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index 4a1e64dc4..d4aa7e682 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -399,5 +399,8 @@ References https://en.wikipedia.org/wiki/Dual_quaternion .. [6] Jia, Y.-B.: Dual Quaternions. https://faculty.sites.iastate.edu/jia/files/inline-files/dual-quaternion.pdf -.. [7] Kenwright, B. A Beginners Guide to Dual-Quaternions. +.. [7] Kenwright, B. (2012). A Beginners Guide to Dual-Quaternions: What They + Are, How They Work, and How to Use Them for 3D Character Hierarchies. In + 20th International Conference in Central Europe on Computer Graphics, + Visualization and Computer Vision. http://wscg.zcu.cz/WSCG2012/!_WSCG2012-Communications-1.pdf From 42e41bb6c7e9cbcab208b397cf77a71f8fe3db17 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Mon, 7 Oct 2024 11:36:03 +0200 Subject: [PATCH 46/62] Make intro of rotations and transf. similar --- doc/source/user_guide/rotations.rst | 8 ++++---- doc/source/user_guide/transformations.rst | 22 +++++++++++----------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 55e2fffdc..f476e3eea 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -8,14 +8,14 @@ matrices [7]_. The minimum number of components that are required to describe any rotation from :math:`SO(3)` is 3. However, there is no representation that is non-redundant, continuous, and free of singularities. -Here is an overview of the representations and the conversions between them -that are available in pytransform3d. - -.. image:: ../_static/rotations.png +.. figure:: ../_static/rotations.png :alt: Rotations :width: 50% :align: center + Overview of the representations and the conversions between them that are + available in pytransform3d. + Not all representations support all operations directly without conversion to another representation. The following table is an overview. If the operation is not implemented in pytransform3d then it is shown in brackets. diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index d4aa7e682..a534b3c21 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -6,10 +6,19 @@ The group of all proper rigid transformations (rototranslations) in 3D Cartesian space is :math:`SE(3)` (SE: special Euclidean group). Transformations consist of a rotation and a translation. Those can be represented in different ways just like rotations can be expressed -in different ways. +in different ways. The minimum number of components that are required to +describe any transformation from :math:`SE(3)` is 6. + +.. figure:: ../_static/transformations.png + :alt: Conversions between representations of transformations + :width: 50% + :align: center + + Overview of the representations and the conversions between them that are + available in pytransform3d. For most representations of orientations we can find -an analogous representation of transformations [1]_: +an analogous representation of transformations: * A **transformation matrix** :math:`\boldsymbol T` is similar to a rotation matrix :math:`\boldsymbol R`. @@ -31,14 +40,6 @@ an analogous representation of transformations [1]_: :math:`p_w + p_x i + p_y j + p_z k + \epsilon (q_w + q_x i + q_y j + q_z k)` is similar to a (unit) quaternion :math:`w + x i + y j + z k`. -Here is an overview of the representations and the conversions between them -that are available in pytransform3d. - -.. image:: ../_static/transformations.png - :alt: Transformations - :width: 50% - :align: center - Not all representations support all operations directly without conversion to another representation. The following table is an overview. @@ -61,7 +62,6 @@ another representation. The following table is an overview. | :math:`\pmb{p} + \epsilon \pmb{q}` | Conjugate | | | | | +----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+ - --------------------- Transformation Matrix --------------------- From ee961237008275fc373c1ec44c47aeb4140593e1 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 8 Oct 2024 15:35:40 +0200 Subject: [PATCH 47/62] Fix typo --- doc/source/user_guide/transformation_ambiguities.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/user_guide/transformation_ambiguities.rst b/doc/source/user_guide/transformation_ambiguities.rst index a2ad0183a..352aafbcb 100644 --- a/doc/source/user_guide/transformation_ambiguities.rst +++ b/doc/source/user_guide/transformation_ambiguities.rst @@ -4,7 +4,7 @@ Transformation Ambiguities and Conventions ========================================== -Heterogenous software systems that consist of proprietary and open source +Heterogeneous software systems that consist of proprietary and open source software are often combined when we work with transformations. For example, suppose you want to transfer a trajectory demonstrated by a human to a robot. The human trajectory could be measured from an RGB-D camera, fused From ddd9fb36cadd3c96e34d5b76a1c13b1cd376c71a Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 8 Oct 2024 16:06:43 +0200 Subject: [PATCH 48/62] Remove . --- doc/source/user_guide/rotations.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index f476e3eea..6506255a0 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -495,7 +495,7 @@ Hence, there is an easy conversion from unit quaternions to MRP: .. math:: - \psi = \frac{\left( \begin{array}{c} x\\ y\\ z\\ \end{array} \right)}{1 + w}. + \psi = \frac{\left( \begin{array}{c} x\\ y\\ z\\ \end{array} \right)}{1 + w} given some quaternion with a scalar :math:`w` and a vector :math:`\left(x, y, z \right)^T`. From ae3934ea8e8e26de5ca49883e4063cdcd9232bf9 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 8 Oct 2024 17:16:32 +0200 Subject: [PATCH 49/62] Streamline pros and cons --- doc/source/user_guide/rotations.rst | 86 ++++++++++------------- doc/source/user_guide/transformations.rst | 56 ++++++--------- 2 files changed, 59 insertions(+), 83 deletions(-) diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 6506255a0..736c85999 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -184,19 +184,15 @@ This will be done, for instance, to obtain rotation matrices from Euler angles **Pros** -* It is easy to apply rotations on point vectors by matrix-vector - multiplication. -* Concatenation of rotations is trivial through matrix multiplication. -* You can directly read the basis vectors from the columns. -* No singularities. +* Supported operations: all except interpolation. +* Interpretation: each column is a basis vector. +* Singularities: none. +* Ambiguities: none that are specific for rotation matrices. **Cons** -* We use 9 values for 3 degrees of freedom. -* Not every 3x3 matrix is a valid rotation matrix, which means for example - that we cannot simply apply an optimization algorithm to rotation matrices - or interpolate between rotation matrices. Renormalization is - computationally expensive in comparison to quaternions. +* Representation: 9 values for 3 degrees of freedom. +* Renormalization: expensive in comparison to quaternions. ---------- Axis-Angle @@ -249,21 +245,18 @@ component-wise integration and differentiation with this representation. **Pros** -* Minimal representation. -* Can also represent angular velocity and acceleration when we replace - :math:`\theta` by :math:`\dot{\theta}` or :math:`\ddot{\theta}` respectively, - which makes numerical integration and differentiation easy. +* Representation: minimal. +* Supported operations: interpolation; can also represent angular velocity and + acceleration. **Cons** -* There might be discontinuities during interpolation as an angle of 0 and - any multiple of :math:`2\pi` represent the same orientation. This has to - be considered. Normalization is recommended. -* When :math:`\theta = \pi`, the axes :math:`\hat{\boldsymbol{\omega}}` and - :math:`-\hat{\boldsymbol{\omega}}` represent the same rotation, which is - a problem for interpolation. -* Concatenation and transformation of vectors requires conversion to rotation - matrix or quaternion. +* Ambiguities: an angle of 0 and any multiple of :math:`2\pi` represent + the same orientation; when :math:`\theta = \pi`, the axes + :math:`\hat{\boldsymbol{\omega}}` and :math:`-\hat{\boldsymbol{\omega}}` + represent the same rotation. +* Supported operations: concatenation and transformation of vectors requires + conversion to another representation. --------------------- Logarithm of Rotation @@ -375,24 +368,18 @@ with the quaternion product (:func:`~pytransform3d.rotations.q_prod_vector`). **Pros** -* More compact than the matrix representation and less susceptible to - round-off errors. -* The quaternion elements vary continuously over the unit sphere in - :math:`\mathbb{R}^4` as the orientation changes, avoiding discontinuous - jumps (inherent to three-dimensional parameterizations). -* Expression of the rotation matrix in terms of quaternion parameters - involves no trigonometric functions. -* Concatenation is simple and computationally cheaper with the quaternion - product than with rotation matrices. -* No singularities. -* Renormalization is cheap in comparison to rotation matrices: we only - have to divide by the norm of the quaternion. +* Representation: compact. +* Renormalization: cheap in comparison to rotation matrices; + less susceptible to round-off errors than matrix representation. +* Discontinuities: none. +* Computational efficiency: the quaternion product is cheaper than the matrix + product. +* Singularities: none. **Cons** -* The representation is not straightforward to interpret. -* There are always two unit quaternions that represent exactly the same - rotation. +* Interpretation: not straightforward. +* Ambiguities: double cover. ------------ Euler Angles @@ -414,16 +401,17 @@ information. **Pros** -* Minimal representation. -* Euler angles are easy to interpret for users (when the convention is clearly +* Representation: minimal. +* Interpretation: easy to interpret for users (when the convention is clearly defined) in comparison to axis-angle or quaternions. **Cons** -* 24 different conventions. -* Singularities (gimbal lock). -* Concatenation and transformation of vectors requires conversion to rotation - matrix or quaternion. +* Ambiguities: 24 different conventions, infinitely many Euler angles + represent the same rotation without proper limits for the angles. +* Singularity: gimbal lock. +* Supported operations: all operations require conversion to another + representation. ------ @@ -516,15 +504,15 @@ parameters. **Pros** -* Minimal representation. +* Representation: minimal. **Cons** -* The representation is not straightforward to interpret. -* Normalization of angle required to avoid singularity. -* Each rotation has two representations as modified Rodrigues parameters. -* Transformation of vectors requires conversion to rotation matrix or - quaternion. +* Interpretation: not straightforward. +* Singularity: at :math:`\theta = 2 \pi`. +* Ambiguity: double cover. +* Supported operations: transformation of vectors requires conversion to + another representation. ---------- References diff --git a/doc/source/user_guide/transformations.rst b/doc/source/user_guide/transformations.rst index a534b3c21..41db7ab55 100644 --- a/doc/source/user_guide/transformations.rst +++ b/doc/source/user_guide/transformations.rst @@ -136,19 +136,15 @@ transformation matrix to a homogeneous vector. **Pros** -* It is easy to apply transformations on vectors in homogeneous coordinates by - matrix-vector multiplication. -* Concatenation of transformations is trivial through matrix multiplication. -* You can directly read the basis vectors and translation from the columns. -* No singularities. +* Supported operations: all except interpolation. +* Interpretation: each column represents either a basis vector or the + translation. +* Singularities: none. **Cons** -* We use 16 values for 6 degrees of freedom. -* Not every 4x4 matrix is a valid transformation matrix, which means for - example that we cannot simply apply an optimization algorithm to - transformation matrices or interpolate between them. Renormalization is - computationally expensive. +* Rrepresentation: 16 values for 6 degrees of freedom. +* Renormalization: inherited from rotation matrix. ----------------------- Position and Quaternion @@ -171,14 +167,12 @@ quaternion and typically we use the variable name pq. **Pros** -* More compact than the matrix representation and less susceptible to - round-off errors. -* Compact representation. +* Representation: compact. **Cons** -* Separation of translation and rotation component. Both have to be handled - individually. +* Supported operation: translation and rotation component are separated and + have to be handled individually. ---------------- Screw Parameters @@ -256,17 +250,14 @@ coordinates of transformation and typically we use the variable name Stheta. **Pros** -* Minimal representation. -* Can also represent velocity and acceleration when we replace - :math:`\theta` by :math:`\dot{\theta}` or :math:`\ddot{\theta}` respectively, - which makes numerical integration and differentiation easy. +* Representation: minimal. +* Supported operations: interpolation; can also represent spatial velocity and + acceleration. **Cons** -* There might be discontinuities and ambiguities. This has to - be considered. Normalization is recommended. -* Concatenation and transformation of vectors requires conversion to - transformation matrix or dual quaternion. +* Supported operations: concatenation and transformation of vectors requires + conversion to another representation. --------------------------- Logarithm of Transformation @@ -367,20 +358,17 @@ component and the scalar 0, and rotation quaternions have the same ambiguity. **Pros** -* Normalization is a simple operation: scaling the dual quaternion to unit - norm. Note that only the orientation part defines the norm of the quaternion, - since :math:`\epsilon^2 = 0` and the scalar product of the real and dual - part is 0 (see :func:`~pytransform3d.transformations.check_dual_quaternion`). -* Easy interpolation with - :func:`~pytransform3d.transformations.dual_quaternion_sclerp`. -* Efficient and compact form for representing transformations [7]_. -* No singularities. +* Representation: compact. +* Renormalization: cheap in comparison to transformation matrix. +* Supported operations: all, including interpolation with ScLERP. +* Computational efficiency: the dual quaternion product is slightly + cheaper than the matrix product. +* Singularities: none. **Cons** -* The representation is not straightforward to interpret. -* There are always two unit dual quaternions that represent exactly the same - transformation. +* Interpretation: not straightforward. +* Ambiguities: double cover. ---------- References From e8125862178ad6ef71dab6a317a7548ba8115571 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 8 Oct 2024 17:19:22 +0200 Subject: [PATCH 50/62] Correct docstring --- pytransform3d/trajectories.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pytransform3d/trajectories.py b/pytransform3d/trajectories.py index b4052f8c0..76788ccbf 100644 --- a/pytransform3d/trajectories.py +++ b/pytransform3d/trajectories.py @@ -623,7 +623,7 @@ def mirror_screw_axis_direction(Sthetas): Returns ------- - Sthetas : array-like, shape (n_steps, 6) + Sthetas : array, shape (n_steps, 6) Exponential coordinates of transformation: (omega_x, omega_y, omega_z, v_x, v_y, v_z) """ From 4227f69a83432479eab60bebbd25bacbe0cf68ac Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Fri, 11 Oct 2024 17:50:50 +0200 Subject: [PATCH 51/62] Use bold font for MRP (psi) --- doc/source/user_guide/introduction.rst | 2 +- doc/source/user_guide/rotations.rst | 13 ++++++++----- pytransform3d/rotations/_mrp.py | 14 +++++++------- 3 files changed, 16 insertions(+), 13 deletions(-) diff --git a/doc/source/user_guide/introduction.rst b/doc/source/user_guide/introduction.rst index ec3a2fd83..3666239d3 100644 --- a/doc/source/user_guide/introduction.rst +++ b/doc/source/user_guide/introduction.rst @@ -134,7 +134,7 @@ representations on the following pages. | :math:`(\alpha, \beta, \gamma)` | | | | +----------------------------------------+---------------------+------------------+---------------+ | Modified Rodrigues parameters | (3,) | X | | -| :math:`\psi` | | | | +| :math:`\pmb{\psi}` | | | | +----------------------------------------+---------------------+------------------+---------------+ | Transformation matrix | (4, 4) | X | X | | :math:`\pmb{T}` | | | | diff --git a/doc/source/user_guide/rotations.rst b/doc/source/user_guide/rotations.rst index 736c85999..d050ebf19 100644 --- a/doc/source/user_guide/rotations.rst +++ b/doc/source/user_guide/rotations.rst @@ -45,7 +45,7 @@ is not implemented in pytransform3d then it is shown in brackets. | :math:`(\alpha, \beta, \gamma)` | | | | | | +----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ | Modified Rodrigues parameters | Negative | No | Yes | No | Not required | -| :math:`\psi` | | | | | | +| :math:`\pmb{\psi}` | | | | | | +----------------------------------------+---------------+--------------------+---------------+---------------+-----------------+ Footnotes: @@ -475,7 +475,8 @@ Another minimal representation of rotation are modified Rodrigues parameters .. math:: - \psi = \tan \left(\frac{\theta}{4}\right) \hat{\boldsymbol{\omega}} + \boldsymbol{\psi} = \tan \left(\frac{\theta}{4}\right) + \hat{\boldsymbol{\omega}} This representation is similar to the compact axis-angle representation. However, the angle of rotation is converted to :math:`\tan(\frac{\theta}{4})`. @@ -483,7 +484,8 @@ Hence, there is an easy conversion from unit quaternions to MRP: .. math:: - \psi = \frac{\left( \begin{array}{c} x\\ y\\ z\\ \end{array} \right)}{1 + w} + \boldsymbol{\psi} = \frac{ + \left( \begin{array}{c} x\\ y\\ z\\ \end{array} \right)}{1 + w} given some quaternion with a scalar :math:`w` and a vector :math:`\left(x, y, z \right)^T`. @@ -499,8 +501,9 @@ parameters. .. warning:: MRPs have two representations for the same rotation: - :math:`\psi` and :math:`-\frac{1}{||\psi||^2} \psi` represent the same - rotation and correspond to two antipodal unit quaternions [8]_. + :math:`\boldsymbol{\psi}` and :math:`-\frac{1}{||\boldsymbol{\psi}||^2} + \boldsymbol{\psi}` represent the same rotation and correspond to two + antipodal unit quaternions [8]_. **Pros** diff --git a/pytransform3d/rotations/_mrp.py b/pytransform3d/rotations/_mrp.py index bdf2ae46e..edc66ea81 100644 --- a/pytransform3d/rotations/_mrp.py +++ b/pytransform3d/rotations/_mrp.py @@ -12,17 +12,17 @@ def concatenate_mrp(mrp1, mrp2): apply the result to v. The solution for concatenation of two rotations - :math:`\boldsymbol{p}_1,\boldsymbol{p}_2` is given by Shuster [1]_: + :math:`\boldsymbol{\psi}_1,\boldsymbol{\psi}_2` is given by Shuster [1]_: .. math:: - \boldsymbol{p} = + \boldsymbol{\psi} = \frac{ - (1 - ||\boldsymbol{p}_1||^2) \boldsymbol{p}_2 - + (1 - ||\boldsymbol{p}_2||^2) \boldsymbol{p}_1 - - 2 \boldsymbol{p}_2 \times \boldsymbol{p}_1} - {1 + ||\boldsymbol{p}_2||^2 ||\boldsymbol{p}_1||^2 - - 2 \boldsymbol{p}_2 \cdot \boldsymbol{p}_1}. + (1 - ||\boldsymbol{\psi}_1||^2) \boldsymbol{\psi}_2 + + (1 - ||\boldsymbol{\psi}_2||^2) \boldsymbol{\psi}_1 + - 2 \boldsymbol{\psi}_2 \times \boldsymbol{\psi}_1} + {1 + ||\boldsymbol{\psi}_2||^2 ||\boldsymbol{\psi}_1||^2 + - 2 \boldsymbol{\psi}_2 \cdot \boldsymbol{\psi}_1}. Parameters ---------- From d93760a4a10d51c200da8a5e4247c6d442933e5e Mon Sep 17 00:00:00 2001 From: Alex McClung Date: Mon, 7 Oct 2024 11:22:00 +1100 Subject: [PATCH 52/62] Add remove_frame method --- .../_transform_graph_base.py | 42 +++++++++++++++++++ 1 file changed, 42 insertions(+) diff --git a/pytransform3d/transform_manager/_transform_graph_base.py b/pytransform3d/transform_manager/_transform_graph_base.py index 4b964ea20..d75ffd88d 100644 --- a/pytransform3d/transform_manager/_transform_graph_base.py +++ b/pytransform3d/transform_manager/_transform_graph_base.py @@ -177,6 +177,48 @@ def remove_transform(self, from_frame, to_frame): del self.j[ij_index] self._recompute_shortest_path() return self + + def remove_frame(self, frame): + """Remove a frame (node) from the graph. + + Parameters + ---------- + frame : Hashable + The frame to remove. + + Returns + ------- + self : TransformManager + This object for chaining. + """ + if frame not in self.nodes: + raise KeyError(f"Frame '{frame}' is not in the graph.") + + # Find the index of the frame to remove + frame_index = self.nodes.index(frame) + + # Remove all transformations (edges) associated with the frame + transforms_to_remove = [] + for (from_frame, to_frame) in self.transform_to_ij_index.keys(): + if from_frame == frame or to_frame == frame: + transforms_to_remove.append((from_frame, to_frame)) + + for (from_frame, to_frame) in transforms_to_remove: + self.remove_transform(from_frame, to_frame) + + # Remove the frame from the node list + self.nodes.pop(frame_index) + + # Update the transform_to_ij_index dictionary + self.transform_to_ij_index = { + k: v if v < frame_index else v - 1 + for k, v in self.transform_to_ij_index.items() + } + + # Recompute the shortest path since we've removed a node + self._recompute_shortest_path() + + return self def get_transform(self, from_frame, to_frame): """Request a transformation. From d862b2789d3236a09ae923203a3246d102b3c2ab Mon Sep 17 00:00:00 2001 From: Alex McClung Date: Mon, 7 Oct 2024 19:32:02 +1100 Subject: [PATCH 53/62] Update the connection logic indices of remove_frame, add type hints in _transform_graph_base.pyi --- .../_transform_graph_base.py | 25 +++++++++++-------- .../_transform_graph_base.pyi | 2 ++ 2 files changed, 17 insertions(+), 10 deletions(-) diff --git a/pytransform3d/transform_manager/_transform_graph_base.py b/pytransform3d/transform_manager/_transform_graph_base.py index d75ffd88d..2203907c2 100644 --- a/pytransform3d/transform_manager/_transform_graph_base.py +++ b/pytransform3d/transform_manager/_transform_graph_base.py @@ -180,12 +180,12 @@ def remove_transform(self, from_frame, to_frame): def remove_frame(self, frame): """Remove a frame (node) from the graph. - + Parameters ---------- frame : Hashable The frame to remove. - + Returns ------- self : TransformManager @@ -193,10 +193,10 @@ def remove_frame(self, frame): """ if frame not in self.nodes: raise KeyError(f"Frame '{frame}' is not in the graph.") - + # Find the index of the frame to remove frame_index = self.nodes.index(frame) - + # Remove all transformations (edges) associated with the frame transforms_to_remove = [] for (from_frame, to_frame) in self.transform_to_ij_index.keys(): @@ -205,19 +205,24 @@ def remove_frame(self, frame): for (from_frame, to_frame) in transforms_to_remove: self.remove_transform(from_frame, to_frame) - + # Remove the frame from the node list self.nodes.pop(frame_index) - + + # Adjust the connection indices in self.i and self.j + self.i = [index if index < frame_index else index - 1 for index in self.i] + self.j = [index if index < frame_index else index - 1 for index in self.j] + # Update the transform_to_ij_index dictionary self.transform_to_ij_index = { - k: v if v < frame_index else v - 1 - for k, v in self.transform_to_ij_index.items() + (from_frame, to_frame): ij_index + for (from_frame, to_frame), ij_index in self.transform_to_ij_index.items() + if from_frame != frame and to_frame != frame } - + # Recompute the shortest path since we've removed a node self._recompute_shortest_path() - + return self def get_transform(self, from_frame, to_frame): diff --git a/pytransform3d/transform_manager/_transform_graph_base.pyi b/pytransform3d/transform_manager/_transform_graph_base.pyi index ebbc5f9cf..549f73577 100644 --- a/pytransform3d/transform_manager/_transform_graph_base.pyi +++ b/pytransform3d/transform_manager/_transform_graph_base.pyi @@ -52,6 +52,8 @@ class TransformGraphBase(abc.ABC): self, from_frame: Hashable, to_frame: Hashable) -> "TransformGraphBase": ... + def remove_frame(self, frame: Hashable) -> "TransformGraphBase": ... + def get_transform( self, from_frame: Hashable, to_frame: Hashable) -> np.ndarray: ... From f87c249cc82caa83bfb47c2dc99512afe4c05d22 Mon Sep 17 00:00:00 2001 From: Alex McClung Date: Mon, 7 Oct 2024 19:57:27 +1100 Subject: [PATCH 54/62] Write a unit test for remove_frame --- pytransform3d/test/test_transform_manager.py | 32 ++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/pytransform3d/test/test_transform_manager.py b/pytransform3d/test/test_transform_manager.py index a6dd841ae..97e14ff85 100644 --- a/pytransform3d/test/test_transform_manager.py +++ b/pytransform3d/test/test_transform_manager.py @@ -25,6 +25,38 @@ def test_request_added_transform(): A2B_2 = tm.get_transform("A", "B") assert_array_almost_equal(A2B, A2B_2) +def test_remove_frame(): + """Test removing a frame from the transform manager.""" + tm = TransformManager() + tm.add_transform("A", "B", np.eye(4)) + tm.add_transform("A", "D", np.eye(4)) + tm.add_transform("B", "C", np.eye(4)) + + assert tm.has_frame("A") + assert tm.has_frame("B") + assert tm.has_frame("C") + assert tm.has_frame("D") + + tm.remove_frame("B") + assert not tm.has_frame("B") + + # Ensure connections involving "B" are removed + with pytest.raises(KeyError, match="Unknown frame"): + tm.get_transform("A", "B") + with pytest.raises(KeyError, match="Unknown frame"): + tm.get_transform("B", "C") + + assert tm.has_frame("A") + assert tm.has_frame("C") + assert tm.has_frame("D") + + # Ensure we cannot retrieve paths involving the removed frame + with pytest.raises(KeyError, match="Cannot compute path"): + tm.get_transform("A", "C") + + A2D = TM.get_transform("A", "D") + assert_array_almost_equal(A2D, np.eye(4)) + def test_request_inverse_transform(): """Request an inverse transform from the transform manager.""" From d720de277a15cec64bdb62b3b25020fafa2eacbc Mon Sep 17 00:00:00 2001 From: Alex McClung Date: Sun, 13 Oct 2024 11:55:52 +1100 Subject: [PATCH 55/62] Create _find_connected_transforms method, test the ij indices upon remove_frame, test random transforms upon remove frame --- pytransform3d/test/test_transform_manager.py | 34 ++++++++++++++----- .../_transform_graph_base.py | 22 ++++++------ .../_transform_graph_base.pyi | 2 ++ 3 files changed, 38 insertions(+), 20 deletions(-) diff --git a/pytransform3d/test/test_transform_manager.py b/pytransform3d/test/test_transform_manager.py index 97e14ff85..5293c8e0d 100644 --- a/pytransform3d/test/test_transform_manager.py +++ b/pytransform3d/test/test_transform_manager.py @@ -28,19 +28,32 @@ def test_request_added_transform(): def test_remove_frame(): """Test removing a frame from the transform manager.""" tm = TransformManager() - tm.add_transform("A", "B", np.eye(4)) - tm.add_transform("A", "D", np.eye(4)) - tm.add_transform("B", "C", np.eye(4)) + + rng = np.random.default_rng(0) + + A2B = pt.random_transform(rng) + A2D = pt.random_transform(rng) + B2C = pt.random_transform(rng) + D2E = pt.random_transform(rng) - assert tm.has_frame("A") + tm.add_transform("A", "B", A2B) + tm.add_transform("A", "D", A2D) + tm.add_transform("B", "C", B2C) + tm.add_transform("D", "E", D2E) + assert tm.has_frame("B") - assert tm.has_frame("C") - assert tm.has_frame("D") + + # Check that connections are correctly represented in self.i and self.j + assert tm.i == [tm.nodes.index("A"), tm.nodes.index("A"), tm.nodes.index("B"), tm.nodes.index("D")] + assert tm.j == [tm.nodes.index("B"), tm.nodes.index("D"), tm.nodes.index("C"), tm.nodes.index("E")] tm.remove_frame("B") assert not tm.has_frame("B") - # Ensure connections involving "B" are removed + # Ensure connections involving "B" are removed and the remaining connections are correctly represented + assert tm.i == [tm.nodes.index("A"), tm.nodes.index("D")] + assert tm.j == [tm.nodes.index("D"), tm.nodes.index("E")] + with pytest.raises(KeyError, match="Unknown frame"): tm.get_transform("A", "B") with pytest.raises(KeyError, match="Unknown frame"): @@ -49,14 +62,17 @@ def test_remove_frame(): assert tm.has_frame("A") assert tm.has_frame("C") assert tm.has_frame("D") + assert tm.has_frame("E") # Ensure we cannot retrieve paths involving the removed frame with pytest.raises(KeyError, match="Cannot compute path"): tm.get_transform("A", "C") - A2D = TM.get_transform("A", "D") - assert_array_almost_equal(A2D, np.eye(4)) + A2D = tm.get_transform("A", "D") + assert_array_almost_equal(A2D, A2D) + D2E = tm.get_transform("D", "E") + assert_array_almost_equal(D2E, D2E) def test_request_inverse_transform(): """Request an inverse transform from the transform manager.""" diff --git a/pytransform3d/transform_manager/_transform_graph_base.py b/pytransform3d/transform_manager/_transform_graph_base.py index 2203907c2..5f7aad560 100644 --- a/pytransform3d/transform_manager/_transform_graph_base.py +++ b/pytransform3d/transform_manager/_transform_graph_base.py @@ -146,6 +146,14 @@ def _recompute_shortest_path(self): return_predecessors=True) self._cached_shortest_paths.clear() + def _find_connected_transforms(self, frame): + """Find all transformations connected to a frame.""" + connected_transforms = [] + for (from_frame, to_frame) in self.transform_to_ij_index.keys(): + if from_frame == frame or to_frame == frame: + connected_transforms.append((from_frame, to_frame)) + return connected_transforms + def remove_transform(self, from_frame, to_frame): """Remove a transformation. @@ -177,7 +185,7 @@ def remove_transform(self, from_frame, to_frame): del self.j[ij_index] self._recompute_shortest_path() return self - + def remove_frame(self, frame): """Remove a frame (node) from the graph. @@ -194,19 +202,12 @@ def remove_frame(self, frame): if frame not in self.nodes: raise KeyError(f"Frame '{frame}' is not in the graph.") - # Find the index of the frame to remove - frame_index = self.nodes.index(frame) # Remove all transformations (edges) associated with the frame - transforms_to_remove = [] - for (from_frame, to_frame) in self.transform_to_ij_index.keys(): - if from_frame == frame or to_frame == frame: - transforms_to_remove.append((from_frame, to_frame)) - - for (from_frame, to_frame) in transforms_to_remove: + for (from_frame, to_frame) in self._find_connected_transforms(frame): self.remove_transform(from_frame, to_frame) - # Remove the frame from the node list + frame_index = self.nodes.index(frame) self.nodes.pop(frame_index) # Adjust the connection indices in self.i and self.j @@ -220,7 +221,6 @@ def remove_frame(self, frame): if from_frame != frame and to_frame != frame } - # Recompute the shortest path since we've removed a node self._recompute_shortest_path() return self diff --git a/pytransform3d/transform_manager/_transform_graph_base.pyi b/pytransform3d/transform_manager/_transform_graph_base.pyi index 549f73577..b41c4497e 100644 --- a/pytransform3d/transform_manager/_transform_graph_base.pyi +++ b/pytransform3d/transform_manager/_transform_graph_base.pyi @@ -48,6 +48,8 @@ class TransformGraphBase(abc.ABC): def _recompute_shortest_path(self): ... + def _find_connected_transforms(self, frame: Hashable) -> List[Hashable]: ... + def remove_transform( self, from_frame: Hashable, to_frame: Hashable) -> "TransformGraphBase": ... From 2901dcfaa9b0d22d11a16ed57468db4682619a19 Mon Sep 17 00:00:00 2001 From: David Wendorff <42057206+savidini@users.noreply.github.com> Date: Fri, 27 Sep 2024 16:00:30 +0200 Subject: [PATCH 56/62] Update README.md changed logo link to be relative and markdown --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 034c94c98..445d662d9 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ - +![pytransform3d logo](/doc/source/_static/logo.png) [![CircleCI](https://dl.circleci.com/status-badge/img/gh/dfki-ric/pytransform3d/tree/main.svg?style=svg)](https://dl.circleci.com/status-badge/redirect/gh/dfki-ric/pytransform3d/tree/main) [![codecov](https://codecov.io/gh/dfki-ric/pytransform3d/branch/main/graph/badge.svg?token=jB10RM3Ujj)](https://codecov.io/gh/dfki-ric/pytransform3d) From cce77fe599c79d2295a16500e4ada8e0106a8c5d Mon Sep 17 00:00:00 2001 From: David Wendorff Date: Fri, 27 Sep 2024 17:09:19 +0200 Subject: [PATCH 57/62] Revert "Update README.md" This reverts commit 9571615ab7bd5368db696ff3305a3bedf9161c9f. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 445d662d9..034c94c98 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -![pytransform3d logo](/doc/source/_static/logo.png) + [![CircleCI](https://dl.circleci.com/status-badge/img/gh/dfki-ric/pytransform3d/tree/main.svg?style=svg)](https://dl.circleci.com/status-badge/redirect/gh/dfki-ric/pytransform3d/tree/main) [![codecov](https://codecov.io/gh/dfki-ric/pytransform3d/branch/main/graph/badge.svg?token=jB10RM3Ujj)](https://codecov.io/gh/dfki-ric/pytransform3d) From 474bb440036114ec2f1c73dfd2612457c46a8d9f Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 15 Oct 2024 17:49:35 +0200 Subject: [PATCH 58/62] Fix unit test --- pytransform3d/test/test_transform_manager.py | 21 ++++++++++++-------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/pytransform3d/test/test_transform_manager.py b/pytransform3d/test/test_transform_manager.py index 5293c8e0d..f7f6b311e 100644 --- a/pytransform3d/test/test_transform_manager.py +++ b/pytransform3d/test/test_transform_manager.py @@ -25,6 +25,7 @@ def test_request_added_transform(): A2B_2 = tm.get_transform("A", "B") assert_array_almost_equal(A2B, A2B_2) + def test_remove_frame(): """Test removing a frame from the transform manager.""" tm = TransformManager() @@ -35,7 +36,7 @@ def test_remove_frame(): A2D = pt.random_transform(rng) B2C = pt.random_transform(rng) D2E = pt.random_transform(rng) - + tm.add_transform("A", "B", A2B) tm.add_transform("A", "D", A2D) tm.add_transform("B", "C", B2C) @@ -43,14 +44,20 @@ def test_remove_frame(): assert tm.has_frame("B") + A2D = tm.get_transform("A", "D") + D2E = tm.get_transform("D", "E") + # Check that connections are correctly represented in self.i and self.j - assert tm.i == [tm.nodes.index("A"), tm.nodes.index("A"), tm.nodes.index("B"), tm.nodes.index("D")] - assert tm.j == [tm.nodes.index("B"), tm.nodes.index("D"), tm.nodes.index("C"), tm.nodes.index("E")] + assert tm.i == [tm.nodes.index("A"), tm.nodes.index("A"), + tm.nodes.index("B"), tm.nodes.index("D")] + assert tm.j == [tm.nodes.index("B"), tm.nodes.index("D"), + tm.nodes.index("C"), tm.nodes.index("E")] tm.remove_frame("B") assert not tm.has_frame("B") - # Ensure connections involving "B" are removed and the remaining connections are correctly represented + # Ensure connections involving "B" are removed and the remaining + # connections are correctly represented. assert tm.i == [tm.nodes.index("A"), tm.nodes.index("D")] assert tm.j == [tm.nodes.index("D"), tm.nodes.index("E")] @@ -68,11 +75,9 @@ def test_remove_frame(): with pytest.raises(KeyError, match="Cannot compute path"): tm.get_transform("A", "C") - A2D = tm.get_transform("A", "D") - assert_array_almost_equal(A2D, A2D) + assert_array_almost_equal(A2D, tm.get_transform("A", "D")) + assert_array_almost_equal(D2E, tm.get_transform("D", "E")) - D2E = tm.get_transform("D", "E") - assert_array_almost_equal(D2E, D2E) def test_request_inverse_transform(): """Request an inverse transform from the transform manager.""" From 2c228ec1c1ad0519e734952b240457b7915b171e Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 15 Oct 2024 17:51:18 +0200 Subject: [PATCH 59/62] PEP8 --- pytransform3d/transform_manager/_transform_graph_base.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/pytransform3d/transform_manager/_transform_graph_base.py b/pytransform3d/transform_manager/_transform_graph_base.py index 5f7aad560..1f198e69c 100644 --- a/pytransform3d/transform_manager/_transform_graph_base.py +++ b/pytransform3d/transform_manager/_transform_graph_base.py @@ -211,13 +211,16 @@ def remove_frame(self, frame): self.nodes.pop(frame_index) # Adjust the connection indices in self.i and self.j - self.i = [index if index < frame_index else index - 1 for index in self.i] - self.j = [index if index < frame_index else index - 1 for index in self.j] + self.i = [index if index < frame_index else index - 1 + for index in self.i] + self.j = [index if index < frame_index else index - 1 + for index in self.j] # Update the transform_to_ij_index dictionary self.transform_to_ij_index = { (from_frame, to_frame): ij_index - for (from_frame, to_frame), ij_index in self.transform_to_ij_index.items() + for (from_frame, to_frame), ij_index + in self.transform_to_ij_index.items() if from_frame != frame and to_frame != frame } From 4e4694a84e2f841b61a0035ee40d96466dae35e6 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 15 Oct 2024 17:58:41 +0200 Subject: [PATCH 60/62] Increase coverage --- pytransform3d/test/test_transform_manager.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/pytransform3d/test/test_transform_manager.py b/pytransform3d/test/test_transform_manager.py index f7f6b311e..e0aba0b7a 100644 --- a/pytransform3d/test/test_transform_manager.py +++ b/pytransform3d/test/test_transform_manager.py @@ -79,6 +79,12 @@ def test_remove_frame(): assert_array_almost_equal(D2E, tm.get_transform("D", "E")) +def test_remove_frame_does_not_exist(): + tm = TransformManager() + with pytest.raises(KeyError, match="not in the graph"): + tm.remove_frame("Any") + + def test_request_inverse_transform(): """Request an inverse transform from the transform manager.""" rng = np.random.default_rng(0) From eaa2d187adfbafe8f443f22274f3d4c3fb5b7279 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 15 Oct 2024 20:05:39 +0200 Subject: [PATCH 61/62] Update unit test for remove_frame --- pytransform3d/test/test_transform_manager.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/pytransform3d/test/test_transform_manager.py b/pytransform3d/test/test_transform_manager.py index e0aba0b7a..5ce1f2dd1 100644 --- a/pytransform3d/test/test_transform_manager.py +++ b/pytransform3d/test/test_transform_manager.py @@ -44,8 +44,7 @@ def test_remove_frame(): assert tm.has_frame("B") - A2D = tm.get_transform("A", "D") - D2E = tm.get_transform("D", "E") + A2E = tm.get_transform("A", "E") # Check that connections are correctly represented in self.i and self.j assert tm.i == [tm.nodes.index("A"), tm.nodes.index("A"), @@ -75,8 +74,10 @@ def test_remove_frame(): with pytest.raises(KeyError, match="Cannot compute path"): tm.get_transform("A", "C") - assert_array_almost_equal(A2D, tm.get_transform("A", "D")) - assert_array_almost_equal(D2E, tm.get_transform("D", "E")) + tm.get_transform("A", "D") + tm.get_transform("D", "E") + + assert_array_almost_equal(A2E, tm.get_transform("A", "E")) def test_remove_frame_does_not_exist(): From 8cbc70b0c8d7482d2d6ea24e658da7b1466286c2 Mon Sep 17 00:00:00 2001 From: Alexander Fabisch Date: Tue, 15 Oct 2024 20:06:49 +0200 Subject: [PATCH 62/62] Version 3.7.0 --- pytransform3d/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pytransform3d/__init__.py b/pytransform3d/__init__.py index 1f6c50921..640a7d03a 100644 --- a/pytransform3d/__init__.py +++ b/pytransform3d/__init__.py @@ -1,4 +1,4 @@ """3D transformations for Python.""" -__version__ = "3.6.2" +__version__ = "3.7.0"