From d887ac1d0288af5d3bd2910b75eebddad0cf8db3 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Fri, 27 Sep 2024 12:15:23 +0200 Subject: [PATCH 01/15] Remove deprecated imports of warning breaking some builds. --- ahrs/filters/flae.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/ahrs/filters/flae.py b/ahrs/filters/flae.py index 2dc58e9..0548cde 100644 --- a/ahrs/filters/flae.py +++ b/ahrs/filters/flae.py @@ -332,7 +332,6 @@ """ -import warnings import numpy as np from ..common.mathfuncs import cosd from ..common.mathfuncs import sind @@ -341,8 +340,6 @@ from ..common.constants import MUNICH_HEIGHT from ..utils.core import _assert_numerical_iterable -warnings.filterwarnings('error') - # Reference Observations in Munich, Germany from ..utils.wmm import WMM MAG = WMM(latitude=MUNICH_LATITUDE, longitude=MUNICH_LONGITUDE, height=MUNICH_HEIGHT).magnetic_elements From 86a276958eb92738e3eb2f03865fc3a7474dfbd8 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Fri, 27 Sep 2024 12:23:40 +0200 Subject: [PATCH 02/15] Add support for BibTeX citations using sphinxcontrib-bibtex. --- docs/source/bibliography.rst | 4 ++++ docs/source/conf.py | 7 ++++++- docs/source/index.rst | 1 + docs/source/refs.bib | 10 ++++++++++ docs/source/requirements.txt | 1 + pyproject.toml | 1 + 6 files changed, 23 insertions(+), 1 deletion(-) create mode 100644 docs/source/bibliography.rst create mode 100644 docs/source/refs.bib diff --git a/docs/source/bibliography.rst b/docs/source/bibliography.rst new file mode 100644 index 0000000..0d21440 --- /dev/null +++ b/docs/source/bibliography.rst @@ -0,0 +1,4 @@ +Bibliography +============ + +.. bibliography:: diff --git a/docs/source/conf.py b/docs/source/conf.py index 9d965f8..52157af 100644 --- a/docs/source/conf.py +++ b/docs/source/conf.py @@ -15,9 +15,11 @@ # -- General configuration --------------------------------------------------- extensions = [ + 'sphinxcontrib.bibtex', 'sphinx.ext.autodoc', 'sphinx.ext.mathjax', - 'sphinx.ext.napoleon'] + 'sphinx.ext.napoleon', +] # Napoleon settings napoleon_numpy_docstring = True @@ -42,3 +44,6 @@ html_logo = "ahrs_logo.png" html_favicon = "ahrs_icon.ico" html_css_files = [] # Explicitly set to an empty list + +# Bibliography file +bibtex_bibfiles = ['refs.bib'] diff --git a/docs/source/index.rst b/docs/source/index.rst index d7c9133..804825b 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -88,6 +88,7 @@ Loading and visualizing the data is left to the preference of the user. metrics constants nomenclature + bibliography Indices ======= diff --git a/docs/source/refs.bib b/docs/source/refs.bib new file mode 100644 index 0000000..e50c6b3 --- /dev/null +++ b/docs/source/refs.bib @@ -0,0 +1,10 @@ +@article{BarItzhack2000, + title={New method for Extracting the Quaternion from a Rotation Matrix}, + author={Itzhack Yoav Bar-Itzhack}, + journal={Journal of Guidance, Control, and Dynamics}, + volume={23}, + number={6}, + pages={1085--1087}, + year={2000}, + publisher={American Institute of Aeronautics and Astronautics} +} diff --git a/docs/source/requirements.txt b/docs/source/requirements.txt index 5fe924f..eed8fb0 100644 --- a/docs/source/requirements.txt +++ b/docs/source/requirements.txt @@ -1,2 +1,3 @@ sphinx<7.2 +sphinxcontrib-bibtex pydata_sphinx_theme diff --git a/pyproject.toml b/pyproject.toml index 86bf4e6..a996ed3 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -55,6 +55,7 @@ dev = [ ] docs = [ "sphinx", + "sphinxcontrib-bibtex", "pydata_sphinx_theme" ] build = [ From 839cc962a48619c8de2bdfb5114c01e77d797a70 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Fri, 27 Sep 2024 12:31:39 +0200 Subject: [PATCH 03/15] Add virtual environment to gitignore. --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 8c0d609..9ed7c6f 100644 --- a/.gitignore +++ b/.gitignore @@ -20,6 +20,7 @@ dist/* # developer environments .idea .vscode +.env # Documentation doctest/* From 503d4e79e899bee5dddf637726483d2213218d1b Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Fri, 27 Sep 2024 18:14:07 +0200 Subject: [PATCH 04/15] Lock version of sphinxcontrib-bibtex to be 2.6.3 or newer to avoid problem with pybtex. --- docs/source/requirements.txt | 2 +- pyproject.toml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/source/requirements.txt b/docs/source/requirements.txt index eed8fb0..3391bed 100644 --- a/docs/source/requirements.txt +++ b/docs/source/requirements.txt @@ -1,3 +1,3 @@ sphinx<7.2 -sphinxcontrib-bibtex +sphinxcontrib-bibtex>=2.6.3 pydata_sphinx_theme diff --git a/pyproject.toml b/pyproject.toml index a996ed3..3fed171 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -55,7 +55,7 @@ dev = [ ] docs = [ "sphinx", - "sphinxcontrib-bibtex", + "sphinxcontrib-bibtex>=2.6.3", "pydata_sphinx_theme" ] build = [ From 00ececb8c6ce5b68cf90a6cc3589a29155fe0d32 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Fri, 27 Sep 2024 18:14:55 +0200 Subject: [PATCH 05/15] Fix invalid backslash to avoid parsing errors. --- ahrs/filters/flae.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ahrs/filters/flae.py b/ahrs/filters/flae.py index 0548cde..5c4870a 100644 --- a/ahrs/filters/flae.py +++ b/ahrs/filters/flae.py @@ -120,7 +120,7 @@ \\end{bmatrix} \\end{array} -Intuitively, we would solve it with :math:`\mathbf{q}=\\mathbf{P}_{\\Sigma D}^\\dagger\\mathbf{D}_\\Sigma^b`, +Intuitively, we would solve it with :math:`\\mathbf{q}=\\mathbf{P}_{\\Sigma D}^\\dagger\\mathbf{D}_\\Sigma^b`, but the pseudo-inverse of :math:`\\mathbf{P}_{\\Sigma D}` is very difficult to compute. However, it is possible to transform the equation by the pseudo-inverse matrices of :math:`\\mathbf{q}` and :math:`\\mathbf{D}_\\Sigma^b`: From def73922d55d0e8660597b5b77d3c7394af18f99 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Fri, 27 Sep 2024 18:50:02 +0200 Subject: [PATCH 06/15] Correct definition of SCADA. --- docs/source/nomenclature.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/nomenclature.rst b/docs/source/nomenclature.rst index 45dd584..23b84ab 100644 --- a/docs/source/nomenclature.rst +++ b/docs/source/nomenclature.rst @@ -238,7 +238,7 @@ RNAV Area Navigation RTU Remote Terminal Unit SBAS Satellite-Based Augmentation System SBC Single Board Computer -SCADA System Control and Data Acquisition +SCADA Supervisory Control and Data Acquisition SCI Serial Communications Interface SI Système International d'unités SLERP Spherical Linear Interpolation From d0921969a40fc73942b0ca77816fecaa128e4b5c Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Sat, 28 Sep 2024 17:14:33 +0200 Subject: [PATCH 07/15] Update sudmodules' and filters' docstrings to use bibtex. --- ahrs/common/dcm.py | 43 +-- ahrs/common/orientation.py | 21 +- ahrs/common/quaternion.py | 155 ++++---- ahrs/filters/angular.py | 30 +- ahrs/filters/aqua.py | 29 +- ahrs/filters/davenport.py | 26 +- ahrs/filters/ekf.py | 52 +-- ahrs/filters/famc.py | 13 +- ahrs/filters/fkf.py | 8 +- ahrs/filters/flae.py | 10 +- ahrs/filters/fourati.py | 19 +- ahrs/filters/fqa.py | 8 +- ahrs/filters/madgwick.py | 8 +- ahrs/filters/mahony.py | 40 +- ahrs/filters/oleq.py | 11 +- ahrs/filters/quest.py | 12 +- ahrs/filters/roleq.py | 10 +- ahrs/filters/saam.py | 13 +- ahrs/filters/tilt.py | 36 +- ahrs/filters/triad.py | 33 +- ahrs/utils/wgs84.py | 10 +- ahrs/utils/wmm.py | 52 +-- docs/source/refs.bib | 749 ++++++++++++++++++++++++++++++++++++- 23 files changed, 944 insertions(+), 444 deletions(-) diff --git a/ahrs/common/dcm.py b/ahrs/common/dcm.py index 10f566e..414cb38 100644 --- a/ahrs/common/dcm.py +++ b/ahrs/common/dcm.py @@ -58,10 +58,11 @@ rotation matrix in :math:`SO(3)`. `Direction cosines `_ are -cosines of angles between a vector and a base coordinate frame [WikipediaDCM]_. -In this case, the direction cosines describe the differences between orthogonal -vectors :math:`\\mathbf{r}_i` and the base frame. The matrix containing these -differences is commonly named the **Direction Cosine Matrix**. +cosines of angles between a vector and a base coordinate frame +:cite:p:`Wiki_DirectionCosine`. In this case, the direction cosines describe +the differences between orthogonal vectors :math:`\\mathbf{r}_i` and the base +frame. The matrix containing these differences is commonly named the +**Direction Cosine Matrix**. These matrices are used for two main purposes: @@ -72,32 +73,12 @@ Because of the latter, the DCM is also known as the **rotation matrix**. DCMs are, therefore, the most common representation of rotations -[WikipediaRotMat]_, especially in real applications of spacecraft tracking and -location. +:cite:p:`Wolfram_RotationMatrix`, especially in real applications of spacecraft +tracking and location. Throughout this package they will be used to represent the attitudes with respect to the global frame. -References ----------- -.. [WikipediaDCM] Wikipedia: Direction Cosine. - (https://en.wikipedia.org/wiki/Direction_cosine) -.. [WikipediaRotMat] Wikipedia: Rotation Matrix - (https://mathworld.wolfram.com/RotationMatrix.html) -.. [Ma] Yi Ma, Stefano Soatto, Jana Kosecka, and S. Shankar Sastry. An - Invitation to 3-D Vision: From Images to Geometric Models. Springer - Verlag. 2003. - (https://www.eecis.udel.edu/~cer/arv/readings/old_mkss.pdf) -.. [Huyhn] Huynh, D.Q. Metrics for 3D Rotations: Comparison and Analysis. J - Math Imaging Vis 35, 155–164 (2009). -.. [Curtis] Howard D Curtis. Orbital Mechanics for Engineering Students (Third - Edition) Butterworth-Heinemann. 2014. -.. [Kuipers] Kuipers, Jack B. Quaternions and Rotation Sequences: A Primer with - Applications to Orbits, Aerospace and Virtual Reality. Princeton; - Oxford: Princeton University Press, 1999. -.. [Diebel] Diebel, James. Representing Attitude; Euler Angles, Unit - Quaternions, and Rotation. Stanford University. 20 October 2006. - """ from typing import Tuple @@ -1039,14 +1020,14 @@ def to_quaternion(self, method: str='shepperd', **kw) -> np.ndarray: There are five methods available to obtain a quaternion from a Direction Cosine Matrix: - * ``'shepperd'`` as described in [Chiaverini]_. - * ``'hughes'`` as described in [Hughes]_. - * ``'itzhack'`` as described in [Bar-Itzhack]_ using version ``3`` by + * ``'chiaverini'`` as described in :cite:p:`Chiaverini1999`. + * ``'hughes'`` as described in :cite:p:`hughes1986spacecraft17`. + * ``'itzhack'`` as described in :cite:p:`BarItzhack2000` using version ``3`` by default. Possible options are integers ``1``, ``2`` or ``3``. - * ``'sarabandi'`` as described in [Sarabandi]_ with a threshold equal + * ``'sarabandi'`` as described in :cite:p:`sarabandi2019` with a threshold equal to ``0.0`` by default. Possible threshold values are floats between ``-3.0`` and ``3.0``. - * ``'shepperd'`` as described in [Shepperd]_. + * ``'shepperd'`` as described in :cite:p:`shepperd1978`. Parameters ---------- diff --git a/ahrs/common/orientation.py b/ahrs/common/orientation.py index f4b6d99..2a41ae0 100644 --- a/ahrs/common/orientation.py +++ b/ahrs/common/orientation.py @@ -104,7 +104,6 @@ def q_random(size: int = 1) -> np.ndarray: return q[0] return q - def q_norm(q: np.ndarray) -> np.ndarray: """ Normalize quaternion [WQ1]_ :math:`\\mathbf{q}_u`, also known as a versor @@ -1085,7 +1084,7 @@ def slerp(q0: np.ndarray, q1: np.ndarray, t_array: np.ndarray, threshold: float arc of a great circle passing through any two existing quaternion endpoints lying on the unit radius hypersphere. - Based on the method detailed in [Wiki_SLERP]_ + Based on the method detailed in :cite:p:`Wiki_SLERP`. Parameters ---------- @@ -1106,10 +1105,6 @@ def slerp(q0: np.ndarray, q1: np.ndarray, t_array: np.ndarray, threshold: float q : numpy.ndarray New quaternion representing the interpolated rotation. - References - ---------- - .. [Wiki_SLERP] https://en.wikipedia.org/wiki/Slerp - """ qdot = q0@q1 # Ensure SLERP takes the shortest path @@ -1132,7 +1127,7 @@ def slerp(q0: np.ndarray, q1: np.ndarray, t_array: np.ndarray, threshold: float def chiaverini(dcm: np.ndarray) -> np.ndarray: """ Quaternion from a Direction Cosine Matrix with Chiaverini's algebraic - method [Chiaverini]_. + method :cite:p:`Chiaverini1999`. Defining the unit quaternion as: @@ -1218,7 +1213,8 @@ def chiaverini(dcm: np.ndarray) -> np.ndarray: def hughes(C: np.ndarray) -> np.ndarray: """ - Quaternion from a Direction Cosine Matrix with Hughes' method [Hughes]_. + Quaternion from a Direction Cosine Matrix with trigonometric Hughes' method + :cite:p:`hughes1986spacecraft17`. Defining the quaternion (reluctantly called "Euler Parameters" in Hughes' book) as: @@ -1320,7 +1316,7 @@ def hughes(C: np.ndarray) -> np.ndarray: def sarabandi(dcm: np.ndarray, eta: float = 0.0) -> np.ndarray: """ Quaternion from a Direction Cosine Matrix using Sarabandi's method - [Sarabandi]_. + :cite:p:`sarabandi2019`. A rotation matrix :math:`\\mathbf{R}` can be expressed as: @@ -1521,7 +1517,7 @@ def sarabandi(dcm: np.ndarray, eta: float = 0.0) -> np.ndarray: def itzhack(dcm: np.ndarray, version: int = 3) -> np.ndarray: """ Quaternion from a Direction Cosine Matrix with Bar-Itzhack's method - [Bar-Itzhack]_. + :cite:p:`BarItzhack2000`. This method to compute the quaternion from a Direction Cosine Matrix (DCM) is based on the eigenvalue decomposition of the matrix :math:`\\mathbf{K}`, @@ -1775,13 +1771,14 @@ def itzhack(dcm: np.ndarray, version: int = 3) -> np.ndarray: q = eigvec[:, np.where(np.isclose(eigval, 1.0))[0]].flatten().real else: q = eigvec[:, eigval.argmax()] - q = np.roll(q, 1) # Original implementation uses [qx, qy, qz, qw] + q = np.roll(q, 1) # Re-arrange quaternion to [qw, qx, qy, qz] q[0] *= -1 # Original implementation computes inverse rotation return q / np.linalg.norm(q) def shepperd(dcm: np.ndarray) -> np.ndarray: """ - Quaternion from a Direction Cosine Matrix with Shepperd's method [Shepperd]_. + Quaternion from a Direction Cosine Matrix with Shepperd's method + :cite:p:`Shepperd1978`. Since it was proposed in 1978, the Shepperd method has been widely used in the aerospace industry. diff --git a/ahrs/common/quaternion.py b/ahrs/common/quaternion.py index b52f2e7..5cd12a0 100644 --- a/ahrs/common/quaternion.py +++ b/ahrs/common/quaternion.py @@ -3,9 +3,11 @@ Quaternion ========== -Quaternions were initially defined by `William Hamilton `_ -in 1843 to describe a `Cayley-Dickson construction `_ -in four dimensions. +Quaternions were initially defined by `William Hamilton +`_ in 1843 to describe a +`Cayley-Dickson construction +`_ in four +dimensions. Since then, many interpretations have appeared for different applications. The most common definition of a quaternion :math:`\\mathbf{q}` is as an ordered @@ -16,7 +18,8 @@ where :math:`w`, :math:`x`, :math:`y` and :math:`z` are real numbers, and :math:`i`, :math:`j` and :math:`k` are three imaginary unit numbers defined so -that [Sola]_ [Kuipers]_ [WikiQuaternion]_ : +that :cite:p:`sola2017quaternion` :cite:p:`kuipers1999` +:cite:p:`Wiki_Quaternion`: .. math:: i^2 = j^2 = k^2 = ijk = -1 @@ -54,8 +57,9 @@ followed by the scalar part, increasing the confusion among readers. Here, the definition above will be used throughout the package. -Let's say, for example, we want to use the quaternion :math:`\\mathbf{q}=\\begin{pmatrix}0.7071 & 0 & 0.7071 & 0\\end{pmatrix}` -with this class: +Let's say, for example, we want to use the quaternion +:math:`\\mathbf{q}=\\begin{pmatrix}0.7071 & 0 & 0.7071 & 0\\end{pmatrix}` with +this class: .. code:: python @@ -88,11 +92,12 @@ .. math:: \\mathbf{a}' = \\mathbf{qa} -Back in the XVIII century `Leonhard Euler `_ -showed that any **rotation around the origin** can be described by a -three-dimensional axis and a rotation magnitude. -`Euler's Rotation Theorem `_ -is the basis for most three-dimensional rotations out there. +Back in the XVIII century `Leonhard Euler +`_ showed that any **rotation +around the origin** can be described by a three-dimensional axis and a rotation +magnitude. `Euler's Rotation Theorem +`_ is the basis for +most three-dimensional rotations out there. Later, in 1840, `Olinde Rodrigues `_ came up with a formula using Euler's principle in vector form: @@ -176,7 +181,7 @@ * When :math:`\\theta=180` (half-circle), then :math:`q_w=0`, making :math:`\\mathbf{q}` a **pure quaternion**. * The negative values of a versor, :math:`\\begin{pmatrix}-q_w & -q_x & -q_y & -q_z\\end{pmatrix}` - represent the *same rotation* [Grosskatthoefer]_. + represent the *same rotation* :cite:p:`grosskatthoefer2012`. .. code:: python @@ -194,13 +199,14 @@ True To summarize, unit quaternions can also be defined using Euler's rotation -theorem [#]_ in the form [Kuipers]_: +theorem [#]_ in the form :cite:p:`kuipers1999`: .. math:: \\mathbf{q} = \\begin{bmatrix}\\cos\\theta \\\\ \\mathbf{v}\\sin\\theta\\end{bmatrix} -And they have similar algebraic characteristics as normal vectors [Sola]_ [Eberly]_. -For example, given two quaternions :math:`\\mathbf{p}` and :math:`\\mathbf{q}`: +And they have similar algebraic characteristics as normal vectors +:cite:p:`sola2017quaternion` :cite:p:`eberly2002`. For example, given two +quaternions :math:`\\mathbf{p}` and :math:`\\mathbf{q}`: .. math:: \\mathbf{p} \\pm \\mathbf{q} = \\begin{bmatrix}p_w\\pm q_w \\\\ \\mathbf{p}_v \\pm \\mathbf{q}_v \\end{bmatrix} @@ -218,9 +224,10 @@ >>> p-q Quaternion([ 0.62597531, -0.1299716 , 0.69342116, 0.33230917]) -The **quaternion product** uses the `Hamilton product `_ -to perform their multiplication [#]_, which can be represented in vector form, -as a known scalar-vector form, or even as a matrix multiplication: +The **quaternion product** uses the `Hamilton product +`_ to perform their +multiplication [#]_, which can be represented in vector form, as a known +scalar-vector form, or even as a matrix multiplication: .. math:: \\begin{array}{rl} @@ -296,47 +303,6 @@ quaternion product, but here is not used in order to avoid any confusions with the `outer product `_. -References ----------- -.. [Bar-Itzhack] Y. Bar-Itzhack. New method for Extracting the Quaternion from - a Rotation Matrix. Journal of Guidance, Control, and Dynamics, - 23(6):1085–1087, 2000. (https://arc.aiaa.org/doi/abs/10.2514/2.4654) -.. [Chiaverini] S. Chiaverini & B. Siciliano. The Unit Quaternion: A Useful - Tool for Inverse Kinematics of Robot Manipulators. Systems Analysis - Modelling Simulation. May 1999. - (https://www.researchgate.net/publication/262391661) -.. [Dantam] Dantam, N. (2014) Quaternion Computation. Institute for Robotics - and Intelligent Machines. Georgia Tech. (http://www.neil.dantam.name/note/dantam-quaternion.pdf) -.. [Eberly] Eberly, D. (2010) Quaternion Algebra and Calculus. Geometric Tools. - https://www.geometrictools.com/Documentation/Quaternions.pdf -.. [Grosskatthoefer] K. Grosskatthoefer. Introduction into quaternions from - spacecraft attitude representation. TU Berlin. 2012. - (http://www.tu-berlin.de/fileadmin/fg169/miscellaneous/Quaternions.pdf) -.. [Hughes] P. Hughes. Spacecraft Attitude Dynamics. 1986. p. 18 -.. [Kuffner] James J. Kuffner. Effective Sampling and Distance Metrics for 3D - Rigid Body Path Planning. Proc. 2004 IEEE International Conference on - Robotics and Automation. 2004. -.. [Kuipers] Kuipers, Jack. Quaternions and Rotation Sequences. Princenton - University Press. 1999. -.. [Markley2007] F. Landis Markley. Averaging Quaternions. Journal of Guidance, - Control, and Dynamics. Vol 30, Num 4. 2007 - (https://arc.aiaa.org/doi/abs/10.2514/1.28949) -.. [Sarabandi] Sarabandi, S. et al. (2018) Accurate Computation of Quaternions - from Rotation Matrices. - (http://www.iri.upc.edu/files/scidoc/2068-Accurate-Computation-of-Quaternions-from-Rotation-Matrices.pdf) -.. [Sarkka] Särkkä, S. (2007) Notes on Quaternions (https://users.aalto.fi/~ssarkka/pub/quat.pdf) -.. [Shepperd] S.W. Shepperd. "Quaternion from rotation matrix." Journal of - Guidance and Control, Vol. 1, No. 3, pp. 223-224, 1978. - (https://arc.aiaa.org/doi/10.2514/3.55767b) -.. [Shoemake] K. Shoemake. Uniform random rotations. Graphics Gems III, pages - 124-132. Academic, New York, 1992. -.. [Sola] Solà, Joan. Quaternion kinematics for the error-state Kalman Filter. - October 12, 2017. (http://www.iri.upc.edu/people/jsola/JoanSola/objectes/notes/kinematics.pdf) -.. [WikiConversions] https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles -.. [WikiQuaternion] https://en.wikipedia.org/wiki/Quaternion -.. [Wiki_SLERP] https://en.wikipedia.org/wiki/Slerp -.. [MarioGC1] https://mariogc.com/post/angular-velocity-quaternions/ - """ import numpy as np @@ -368,7 +334,7 @@ def slerp(q0: np.ndarray, q1: np.ndarray, t_array: np.ndarray, threshold: float It returns as many rotations between ``q0`` and ``q1`` as elements in ``t_array``. - Based on the method detailed in [Wiki_SLERP]_. + Based on the method detailed in :cite:p:`Wiki_SLERP`. Parameters ---------- @@ -412,8 +378,8 @@ def random_attitudes(n: int = 1, representation: str = 'quaternion') -> np.ndarr Generate random attitudes To generate a random quaternion a mapping in SO(3) is first created and - then transformed as explained originally by [Shoemake]_ and summarized in - [Kuffner]_. + then transformed as explained originally by :cite:p:`shoemake1992` and + summarized in :cite:p:`kuffner2004`. First, three uniform random values are sampled from the interval [0, 1]: @@ -1139,7 +1105,7 @@ def __mul__(self, q: np.ndarray) -> np.ndarray: Given two unit quaternions :math:`\\mathbf{p}=(p_w, p_x, p_y, p_z)` and :math:`\\mathbf{q} = (q_w, q_x, q_y, q_z)`, their product is obtained - [Dantam]_ [MWQW]_ as: + :cite:p:`dantam2014` [MWQW]_ as: .. math:: @@ -1183,7 +1149,7 @@ def __matmul__(self, q: np.ndarray) -> np.ndarray: Given two unit quaternions :math:`\\mathbf{p}=(p_w, p_x, p_y, p_z)` and :math:`\\mathbf{q} = (q_w, q_x, q_y, q_z)`, their product is obtained - [Dantam]_ [MWQW]_ as: + :cite:p:`dantam2014` [MWQW]_ as: .. math:: \\mathbf{pq} = @@ -1395,7 +1361,7 @@ def product(self, q: np.ndarray) -> np.ndarray: Given two unit quaternions :math:`\\mathbf{p}=(p_w, \\mathbf{p}_v)` and :math:`\\mathbf{q} = (q_w, \\mathbf{q}_v)`, their product is defined - [Sola]_ [Dantam]_ as: + :cite:p:`sola2017quaternion` :cite:p:`dantam2014` as: .. math:: \\begin{eqnarray} @@ -1492,7 +1458,7 @@ def mult_L(self) -> np.ndarray: Matrix form of a left-sided quaternion multiplication Q. Matrix representation of quaternion product with a left sided - quaternion [Sarkka]_: + quaternion :cite:p:`särkkä2007`: .. math:: \\mathbf{qp} = \\mathbf{L}(\\mathbf{q})\\mathbf{p} = @@ -1521,7 +1487,7 @@ def mult_R(self) -> np.ndarray: Matrix form of a right-sided quaternion multiplication Q. Matrix representation of quaternion product with a right sided - quaternion [Sarkka]_: + quaternion :cite:p:`särkkä2007`: .. math:: \\mathbf{qp} = \\mathbf{R}(\\mathbf{p})\\mathbf{q} = @@ -1648,8 +1614,9 @@ def to_angles(self) -> np.ndarray: """ Return corresponding Euler angles of quaternion. - Given a unit quaternion :math:`\\mathbf{q} = \\begin{pmatrix}q_w & q_x & q_y & q_z\\end{pmatrix}`, - its corresponding Euler angles [WikiConversions]_ are: + Given a unit quaternion + :math:`\\mathbf{q} = \\begin{pmatrix}q_w & q_x & q_y & q_z\\end{pmatrix}`, + its corresponding Euler angles :cite:p:`Wiki_Conversions` are: .. math:: \\begin{bmatrix} @@ -1682,7 +1649,7 @@ def to_DCM(self) -> np.ndarray: where :math:`\\mathbf{q}_v = \\begin{bmatrix}q_x & q_y & q_z\\end{bmatrix}` is the vector part, and :math:`q_w` is the scalar part. - The resulting matrix :math:`\\mathbf{R}` [WikiConversions]_ has the + The resulting matrix :math:`\\mathbf{R}` :cite:p:`Wiki_Conversions` has the form: .. math:: @@ -1739,11 +1706,14 @@ def from_DCM(self, dcm: np.ndarray, method: str = 'shepperd', **kw) -> np.ndarra There are five methods available to obtain a quaternion from a Direction Cosine Matrix: - * ``'chiaverini'`` as described in [Chiaverini]_ - * ``'hughes'`` as described in [Hughes]_ - * ``'itzhack'`` as described in [Bar-Itzhack]_ - * ``'sarabandi'`` as described in [Sarabandi]_ - * ``'shepperd'`` as described in [Shepperd]_ + * ``'chiaverini'`` as described in :cite:p:`Chiaverini1999`. + * ``'hughes'`` as described in :cite:p:`hughes1986spacecraft17`. + * ``'itzhack'`` as described in :cite:p:`BarItzhack2000` using version ``3`` by + default. Possible options are integers ``1``, ``2`` or ``3``. + * ``'sarabandi'`` as described in :cite:p:`sarabandi2019` with a threshold equal + to ``0.0`` by default. Possible threshold values are floats between + ``-3.0`` and ``3.0``. + * ``'shepperd'`` as described in :cite:p:`shepperd1978`. Parameters ---------- @@ -1941,8 +1911,15 @@ def random(self) -> np.ndarray: Generate a random quaternion A mapping in SO(3) is first created and then transformed as explained - originally by [Shoemake]_. It calls the function :func:`random_attitudes` - with ``n=1``. + originally by :cite:p:`shoemake1992`. It calls the function + :func:`random_attitudes` with ``n=1``. + + .. warning:: + + The generated random quaternion is returned as a NumPy array, + but **it is not set in the object**. To create a :class:`Quaternion` + object with random values, we can indicate this when creating the + object. See examples below. Returns ------- @@ -1952,8 +1929,12 @@ def random(self) -> np.ndarray: Examples -------- >>> q = Quaternion() + >>> q + Quaternion([1., 0., 0., 0.]) >>> q.random() - array([ 0.18257419, -0.36514837, 0.54772256, -0.73029674]) + array([-0.13952338, 0.96330741, -0.18034361, -0.14159178]) + >>> q + Quaternion([1., 0., 0., 0.]) It can be called when the Quaternion object is created: @@ -2613,14 +2594,14 @@ def from_DCM(self, DCM: np.ndarray, method: str='shepperd', inplace: bool = True There are five methods available to obtain a quaternion from a Direction Cosine Matrix: - * ``'chiaverini'`` as described in [Chiaverini]_. - * ``'hughes'`` as described in [Hughes]_. - * ``'itzhack'`` as described in [Bar-Itzhack]_ using version ``3`` by + * ``'chiaverini'`` as described in :cite:p:`Chiaverini1999`. + * ``'hughes'`` as described in :cite:p:`hughes1986spacecraft17`. + * ``'itzhack'`` as described in :cite:p:`BarItzhack2000` using version ``3`` by default. Possible options are integers ``1``, ``2`` or ``3``. - * ``'sarabandi'`` as described in [Sarabandi]_ with a threshold equal + * ``'sarabandi'`` as described in :cite:p:`sarabandi2019` with a threshold equal to ``0.0`` by default. Possible threshold values are floats between ``-3.0`` and ``3.0``. - * ``'shepperd'`` as described in [Shepperd]_. + * ``'shepperd'`` as described in :cite:p:`shepperd1978`. Parameters ---------- @@ -2690,7 +2671,7 @@ def to_angles(self) -> np.ndarray: Return corresponding roll-pitch-yaw angles of quaternion. Having a unit quaternion :math:`\\mathbf{q} = \\begin{pmatrix}q_w & q_x & q_y & q_z\\end{pmatrix}`, - its corresponding roll-pitch-yaw angles [WikiConversions]_ are: + its corresponding roll-pitch-yaw angles :cite:p:`Wiki_Conversions` are: .. math:: \\begin{bmatrix} @@ -2741,7 +2722,7 @@ def to_DCM(self) -> np.ndarray: is the vector part, :math:`q_w` is the scalar part, and :math:`\\|\\mathbf{q}\\|=1`. The `rotation matrix `_ - :math:`\\mathbf{R}` [WikiConversions]_ built from :math:`\\mathbf{q}` + :math:`\\mathbf{R}` :cite:p:`Wiki_Conversions` built from :math:`\\mathbf{q}` has the form: .. math:: @@ -2799,7 +2780,7 @@ def to_DCM(self) -> np.ndarray: def average(self, span: Tuple[int, int] = None, weights: np.ndarray = None) -> np.ndarray: """ - Average quaternion using Markley's method [Markley2007]_ + Average quaternion using Markley's method :cite:`markley2007`. It has to be clear that we intend to average **attitudes** rather than quaternions. It just happens that we represent these attitudes with @@ -3033,7 +3014,7 @@ def angular_velocities(self, dt: float) -> np.ndarray: \\end{array} where :math:`\\Delta t` is the time step between consecutive - quaternions [MarioGC1]_. + quaternions :cite:p:`garcia2022`. Parameters ---------- diff --git a/ahrs/filters/angular.py b/ahrs/filters/angular.py index 636b478..cd9aab9 100644 --- a/ahrs/filters/angular.py +++ b/ahrs/filters/angular.py @@ -7,12 +7,12 @@ updated via integration of angular rate measurements of a gyroscope. The easiest way to do so is by integrating the differential -equation for a local rotation rate [Sola]_. +equation for a local rotation rate :cite:p:`sola2017quaternion`. In a kinematic system, the angular velocity :math:`\\boldsymbol\\omega` of a rigid body at any instantaneous time is described with respect to a fixed frame coinciding instantaneously with its body frame. Thus, this angular -velocity is *in terms of* the body frame [Jia]_. +velocity is *in terms of* the body frame :cite:p:`jia2024`. Accumulating rotation over time in quaternion form is done by integrating the differential equation of :math:`\\mathbf{q}` with a defined rotation rate. @@ -28,7 +28,8 @@ In the simplest practical case, the angular rates are measured by `gyroscopes `_, reading instantaneous angular -velocities, :math:`\\boldsymbol\\omega(t_n)=\\begin{bmatrix}\\omega_x&\\omega_y&\\omega_z\\end{bmatrix}^T`, +velocities, :math:`\\boldsymbol\\omega(t_n) +=\\begin{bmatrix}\\omega_x&\\omega_y&\\omega_z\\end{bmatrix}^T`, in *rad/s*, at discrete times :math:`t_n = n\\Delta t` in the local sensor frame. @@ -44,7 +45,8 @@ An orientation (attitude) is described with a quaternion :math:`\\mathbf{q} (t)` at a time :math:`t`, and with :math:`\\mathbf{q} (t+\\Delta t)` at a time :math:`t+\\Delta t`. This is after a rotation change :math:`\\Delta\\mathbf{q}` -during :math:`\\Delta t` seconds is performed on the local frame [Jia]_. +during :math:`\\Delta t` seconds is performed on the local frame +:cite:p:`jia2024`. This rotation change about the instantaneous axis :math:`\\mathbf{u}=\\frac{\\boldsymbol\\omega}{\\|\\boldsymbol\\omega\\|}` @@ -147,7 +149,7 @@ We recognize the power-series expansion of `Euler's formula `_, which helps to map the quaternion :math:`\\mathbf{q}` from a rotation vector -:math:`\\mathbf{v}`. This **exponential map** [Sola]_ is formerly defined as: +:math:`\\mathbf{v}`. This **exponential map** :cite:p:`sola2017quaternion` is formerly defined as: .. math:: \\mathbf{q} = e^\\mathbf{v} = @@ -252,9 +254,9 @@ \\mathbf{q}_{t+1} \\gets \\frac{\\mathbf{q}_{t+1}}{\\|\\mathbf{q}_{t+1}\\|} Numerical Integration based on Runge-Kutta methods can be employed to increase -the accuracy, and are shown to be more effective. See [Sola]_ and [Zhao]_ for a -comparison of the different methods, their accuracy, and their computational -load. +the accuracy, and are shown to be more effective. See :cite:p:`sola2017quaternion` +and :cite:p:`zhao2013` for a comparison of the different methods, their +accuracy, and their computational load. Footnotes --------- @@ -273,18 +275,6 @@ \\mathbf{q}^{i\\geq 4} &=& \\frac{1}{2^i}\\mathbf{q}\\boldsymbol\\omega^i + \\cdots \\end{array} -References ----------- - -.. [Jia] Yan-Bin Jia. Quaternions. 2018. - (http://web.cs.iastate.edu/~cs577/handouts/quaternion.pdf) -.. [Sola] Solà, Joan. Quaternion kinematics for the error-state Kalman Filter. - October 12, 2017. - (http://www.iri.upc.edu/people/jsola/JoanSola/objectes/notes/kinematics.pdf) -.. [Zhao] F. Zhao and B.G.M. van Wachem. A novel Quaternion integration - approach for describing the behaviour of non-spherical particles. - (https://link.springer.com/content/pdf/10.1007/s00707-013-0914-2.pdf) - """ import numpy as np diff --git a/ahrs/filters/aqua.py b/ahrs/filters/aqua.py index 48daa93..661382d 100644 --- a/ahrs/filters/aqua.py +++ b/ahrs/filters/aqua.py @@ -3,9 +3,10 @@ Algebraic Quaternion Algorithm ============================== -Roberto Valenti's Algebraic Quaterion Algorithm (AQUA) [Valenti2015]_ estimates -a quaternion with the algebraic solution of a system from inertial/magnetic -observations, solving `Wahba's Problem `_. +Roberto Valenti's Algebraic Quaterion Algorithm (AQUA) :cite:p:`valenti2015` +estimates a quaternion with the algebraic solution of a system from +inertial+magnetic observations, solving `Wahba's Problem +`_. AQUA computes the "tilt" quaternion and the "heading" quaternion separately in two sub-parts. This avoids the impact of the magnetic disturbances on the roll @@ -15,7 +16,7 @@ together with accelerometer and magnetic field readings. The correction part of the filter is based on the independently estimated quaternions and works for both IMU (Inertial Measurement Unit) and MARG (Magnetic, Angular Rate, and -Gravity) sensors [Valenti2016]_. +Gravity) sensors :cite:p:`valenti2016`. Quaternion as Orientation ------------------------- @@ -383,10 +384,10 @@ ^L_G\\mathbf{q} = \\, ^L_G\\mathbf{q}_\\omega \\, \\Delta\\mathbf{q}_\\mathrm{acc} \\, \\Delta\\mathbf{q}_\\mathrm{mag} \\end{equation} -The delta quaternions are computed and filtered independently by the high-frequency -noise. This correction is divided in two steps: correction of roll and pitch of -the predicted quaternion, and then the correction of the yaw angle if readings -of the magnetic field are provided. +The delta quaternions are computed and filtered independently by the +high-frequency noise. This correction is divided in two steps: correction of +roll and pitch of the predicted quaternion, and then the correction of the yaw +angle if readings of the magnetic field are provided. Accelerometer-Based Correction ------------------------------ @@ -557,18 +558,6 @@ --------- .. [#] Any vector :math:`\\mathbf{x}` is a **unit vector** if :math:`\\|\\mathbf{x}\\|=1`. -References ----------- -.. [Valenti2015] Valenti, R.G.; Dryanovski, I.; Xiao, J. Keeping a Good - Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs. Sensors - 2015, 15, 19302-19330. - (https://res.mdpi.com/sensors/sensors-15-19302/article_deploy/sensors-15-19302.pdf) -.. [Valenti2016] R. G. Valenti, I. Dryanovski and J. Xiao, "A Linear Kalman - Filter for MARG Orientation Estimation Using the Algebraic Quaternion - Algorithm," in IEEE Transactions on Instrumentation and Measurement, vol. - 65, no. 2, pp. 467-481, 2016. - (https://ieeexplore.ieee.org/document/7345567) - """ import numpy as np diff --git a/ahrs/filters/davenport.py b/ahrs/filters/davenport.py index c3171b3..62c6aff 100644 --- a/ahrs/filters/davenport.py +++ b/ahrs/filters/davenport.py @@ -19,14 +19,14 @@ nonnegative weights for each observation. This famous formulation is known as `Wahba's problem `_. -A first elegant solution was proposed by [Davenport1968]_ that solves this in -terms of quaternions, yielding a unique optimal solution. The corresponding -**gain function** is defined as: +A first elegant solution was proposed by :cite:p:`davenport1968` that solves +this in terms of quaternions, yielding a unique optimal solution. The +corresponding **objective function** is defined as: .. math:: g(\\mathbf{A}) = 1 - L(\\mathbf{A}) = \\sum_{i=1}^Nw_i\\mathbf{U}^T\\mathbf{AV} -The gain function is at maximum when the loss function :math:`L(\\mathbf{A})` +The objective function is at maximum when the loss function :math:`L(\\mathbf{A})` is at minimum. The goal is, then, to find the optimal attitude matrix :math:`\\mathbf{A}`, which *maximizes* :math:`g(\\mathbf{A})`. We first notice that: @@ -37,13 +37,15 @@ =& \\mathrm{tr}(\\mathbf{AB}^T) \\end{array} -where :math:`\\mathrm{tr}` denotes the `trace `_ -of a matrix, and :math:`\\mathbf{B}` is the *attitude profile matrix*: +where :math:`\\mathrm{tr}` denotes the `trace +`_ of a matrix, and +:math:`\\mathbf{B}` is the *attitude profile matrix*: .. math:: \\mathbf{B} = \\sum_{i=1}^Nw_i\\mathbf{UV} -Now, we must parametrize the attitude matrix in terms of a quaternion :math:`\\mathbf{q}`: +Now, we must parametrize the attitude matrix in terms of a quaternion +:math:`\\mathbf{q}` :cite:p:`lerner1978` : .. math:: \\mathbf{A}(\\mathbf{q}) = (q_w^2-\\mathbf{q}_v\\cdot\\mathbf{q}_v)\\mathbf{I}_3+2\\mathbf{q}_v\\mathbf{q}_v^T-2q_w\\lfloor\\mathbf{q}\\rfloor_\\times @@ -54,7 +56,7 @@ :math:`\\mathbf{x}`. See the `quaternion page <../quaternion.html>`_ for further details about this representation mapping. -The gain function, in terms of quaternion, becomes: +The objective function, in terms of quaternion, becomes: .. math:: g(\\mathbf{q}) = (q_w^2-\\mathbf{q}_v\\cdot\\mathbf{q}_v)\\mathrm{tr}\\mathbf{B}^T + 2\\mathrm{tr}\\big(\\mathbf{q}_v\\mathbf{q}_v^T\\mathbf{B}^T\\big) + 2q_w\\mathrm{tr}(\\lfloor\\mathbf{q}\\rfloor_\\times\\mathbf{B}^T) @@ -95,14 +97,6 @@ step of computing the eigenvalues and eigenvectors to find the optimal quaternion. -References ----------- -.. [Davenport1968] Paul B. Davenport. A Vector Approach to the Algebra of Rotations - with Applications. NASA Technical Note D-4696. August 1968. - (https://ntrs.nasa.gov/archive/nasa/casi.ntrs.nasa.gov/19680021122.pdf) -.. [Lerner2] Lerner, G. M. "Three-Axis Attitude Determination" in Spacecraft - Attitude Determination and Control, edited by J.R. Wertz. 1978. p. 426-428. - """ import numpy as np diff --git a/ahrs/filters/ekf.py b/ahrs/filters/ekf.py index c8328f2..8bcb1e1 100644 --- a/ahrs/filters/ekf.py +++ b/ahrs/filters/ekf.py @@ -9,11 +9,11 @@ The **state** is the physical state, which can be described by dynamic variables. The **noise** in the measurements means that there is a certain -degree of uncertainty in them [Hartikainen2011]_. +degree of uncertainty in them :cite:p:`hartikainen2011`. A `dynamical system `_ is a system whose state evolves over time, so differential equations are normally -used to model them [Labbe2015]_. There is also noise in the dynamics of the +used to model them :cite:p:`labbe2015`. There is also noise in the dynamics of the system, **process noise**, which means we cannot be entirely deterministic, but we can get indirect noisy measurements. @@ -23,7 +23,7 @@ The instantaneous state of the system is represented with a vector updated through discrete time increments to generate the next state. The simplest of -the state space models are linear models [Hartikainen2011]_, which can be +the state space models are linear models :cite:p:`hartikainen2011`, which can be expressed with equations of the following form: .. math:: @@ -66,7 +66,8 @@ A common way to obtain :math:`\\mathbf{F}` uses the `matrix exponential `_, which can be expanded -with a `Taylor series `_ [Sola]_: +with a `Taylor series `_ +:cite:p:`sola2017quaternion` : .. math:: \\mathbf{F} = e^{\\mathbf{A}\\Delta t} = \\mathbf{I} + \\mathbf{A}\\Delta t + \\frac{(\\mathbf{A}\\Delta t)^2}{2!} + \\frac{(\\mathbf{A}\\Delta t)^3}{3!} + \\cdots = \\sum_{k=0}^\\infty\\frac{(\\mathbf{A}\\Delta t)^k}{k!} @@ -77,7 +78,7 @@ Kalman Filter ------------- -The solution proposed by [Kalman1960]_ models a system with a set of +The solution proposed by :cite:p:`kalman1960` models a system with a set of :math:`n^{th}`-order differential equations, converts them into an equivalent set of first-order differential equations, and puts them into the matrix form :math:`\\dot{\\mathbf{x}}=\\mathbf{Ax}`. Once in this form several techniques @@ -149,7 +150,7 @@ The EKF handles nonlinearity by forming a Gaussian approximation to the joint distribution of state :math:`\\mathbf{x}` and measurements :math:`\\mathbf{z}` using `Taylor series `_ based -transformations [Hartikainen2011]_. +transformations :cite:p:`hartikainen2011`. Likewise, the EKF is split into two steps: @@ -211,7 +212,7 @@ Gyroscope data are treated as external inputs to the filter rather than as measurements, and their measurement noises enter the filter as *process noise* -rather than as measurement noise [Sabatini2011]_. +rather than as measurement noise :cite:p:`sabatini2011`. For this model, the quaternion :math:`\\mathbf{q}` will be the **state vector**, and the angular velocity :math:`\\boldsymbol\\omega`, in *rad/s*, will be the @@ -254,7 +255,7 @@ Using the `Euler-Rodrigues rotation formula `_ -to redefine the quaternion [Sabatini2011]_ we find: +to redefine the quaternion :cite:p:`sabatini2011` we find: .. math:: \\hat{\\mathbf{q}}_t = @@ -316,10 +317,10 @@ The angular rates :math:`\\boldsymbol\\omega` are measured by the gyroscopes in the local *sensor frame*. Hence, this term describes the evolution of the -orientation with respect to the local frame [Sola]_. +orientation with respect to the local frame :cite:p:`sola2017quaternion`. Using the definition of :math:`\\dot{\\mathbf{q}}`, the predicted state, -:math:`\\hat{\\mathbf{q}}_t` is written as [Wertz]_: +:math:`\\hat{\\mathbf{q}}_t` is written as :cite:p:`spence1978`: .. math:: \\begin{array}{rcl} @@ -488,9 +489,10 @@ The assumption that the noise variances of the gyroscope axes are all equal (:math:`\\sigma_{wx}=\\sigma_{wy}=\\sigma_{wz}`) is almost never true in reality. It is possible to infer the individual variances through a careful - modeling and calibration process [Lam2003]_. If these three different - values are at hand, it is then recommended to compute the Process Noise - Covariance with :math:`\\mathbf{W}_t\\boldsymbol\\Sigma_\\boldsymbol\\omega\\mathbf{W}_t^T`. + modeling and calibration process :cite:p:`lam2003`. If these three + different values are at hand, it is then recommended to compute the Process + Noise Covariance with + :math:`\\mathbf{W}_t\\boldsymbol\\Sigma_\\boldsymbol\\omega\\mathbf{W}_t^T`. Finally, the prediction step of this model would propagate the covariance matrix like: @@ -718,7 +720,7 @@ The measurement noise covariance matrix, :math:`\\mathbf{R}\\in\\mathbb{R}^{6\\times 6}`, is expressed directly in terms of the statistics of the measurement noise -affecting each sensor [Sabatini2011]_. The sensor noises are considered as +affecting each sensor :cite:p:`sabatini2011`. The sensor noises are considered as uncorrelated and isotropic, which creates a diagonal matrix: .. math:: @@ -757,7 +759,7 @@ \\mathbf{q}_t \\leftarrow \\frac{1}{\\|\\mathbf{q}_t\\|}\\mathbf{q}_t Even though it is neither elegant nor optimal, this "brute-force" approach to -compute the final quaternion is proven to work generally well [Sabatini2011]_. +compute the final quaternion is proven to work generally well :cite:p:`sabatini2011`. Initial values -------------- @@ -784,7 +786,7 @@ where :math:`\\mathbf{a}_0` and :math:`\\mathbf{m}_0` are the accelerometer and magnetometer measurements. Each column of this rotation matrix should be -normalized. Then, we get the initial quaternion with [Chiaverini]_: +normalized. Then, we get the initial quaternion with :cite:p:`Chiaverini1999`: .. math:: \\mathbf{q}_0 = @@ -861,24 +863,6 @@ above sea level to estimate this magnitude. For the purpose of analysis a common value of *9.81* is given. -References ----------- -.. [Kalman1960] Rudolf Kalman. A New Approach to Linear Filtering and Prediction - Problems. 1960. -.. [Hartikainen2011] J. Hartikainen, A. Solin and S. Särkkä. Optimal Filtering with - Kalman Filters and Smoothers. 2011 -.. [Sabatini2011] Sabatini, A.M. Kalman-Filter-Based Orientation Determination - Using Inertial/Magnetic Sensors: Observability Analysis and Performance - Evaluation. Sensors 2011, 11, 9182-9206. - (https://www.mdpi.com/1424-8220/11/10/9182) -.. [Labbe2015] Roger R. Labbe Jr. Kalman and Bayesian Filters in Python. - (https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python) -.. [Lam2003] Lam, Quang & Stamatakos, Nick & Woodruff, Craig & Ashton, Sandy. - Gyro Modeling and Estimation of Its Random Noise Sources. AAIA 2003. - DOI: 10.2514/6.2003-5562. - (https://www.researchgate.net/publication/268554081) - - """ import numpy as np diff --git a/ahrs/filters/famc.py b/ahrs/filters/famc.py index 0f15dd9..fc399ec 100644 --- a/ahrs/filters/famc.py +++ b/ahrs/filters/famc.py @@ -15,7 +15,8 @@ The matrix operations in these solutions are the main focus of attention in this method. The operations are analytically simplified, where the accuracy is maintained, while the time consumption is reduced, yielding the **Fast -Accelerometer-Magnetometer Combination (FAMC)**, whose main contributions are: +Accelerometer-Magnetometer Combination (FAMC)** :cite:p:`liu2018`, whose main +contributions are: - Analytic eigenvalue results are given for the dynamic magnetometer reference vector. @@ -112,7 +113,8 @@ corresponding to an eigenvalue equal to 1, disorienting the system and rendering this estimator useless on polar regions. -Finally, we must compute the eigenvector of the eigenvalule 1. We start defining: +Finally, we must compute the eigenvector of the eigenvalule 1. We start +defining: .. math:: \\mathbf{S} = \\mathbf{K} - \\mathbf{I} @@ -151,13 +153,6 @@ .. math:: \\mathbf{q} = \\frac{1}{\\sqrt{a^2+b^2+c^2+1}}\\begin{pmatrix}-1 & a & b & c\\end{pmatrix} -References ----------- -.. [Liu] Zhuohua Liu, Wei Liu, Xiangyang Gong, and Jin Wu, "Simplified Attitude - Determination Algorithm Using Accelerometer and Magnetometer with Extremely - Low Execution Time," Journal of Sensors, vol. 2018, Article ID 8787236, 11 - pages, 2018. https://doi.org/10.1155/2018/8787236. - """ import numpy as np diff --git a/ahrs/filters/fkf.py b/ahrs/filters/fkf.py index ff946d3..6fa9c44 100644 --- a/ahrs/filters/fkf.py +++ b/ahrs/filters/fkf.py @@ -3,12 +3,8 @@ Fast Kalman Filter ================== -References ----------- -.. [Guo] Siwen Guo, Jin Wu, Zuocai Wang, and Jide Qian, "Novel MARG-Sensor - Orientation Estimation Algorithm Using Fast Kalman Filter." Journal of - Sensors, vol. 2017, Article ID 8542153, 12 pages. - https://doi.org/10.1155/2017/8542153 and https://github.com/zarathustr/FKF +Quaternion-based Fast Kalman Filter algorithm for orientation estimation +:cite:p:`guo2017`. """ diff --git a/ahrs/filters/flae.py b/ahrs/filters/flae.py index 5c4870a..2a731b8 100644 --- a/ahrs/filters/flae.py +++ b/ahrs/filters/flae.py @@ -4,7 +4,7 @@ ============================== The Fast Linear Attitude Estimator (FLAE) obtains the attitude quaternion with -an eigenvalue-based solution as proposed by [Wu]_. +an eigenvalue-based solution as proposed by :cite:p:`wu2018`. A symbolic solution to the corresponding characteristic polynomial is also derived for a higher computation speed. @@ -322,14 +322,6 @@ the Newton iteration can be also used to achieve a similar performance to that of QUEST. -References ----------- -.. [Wu] Jin Wu, Zebo Zhou, Bin Gao, Rui Li, Yuhua Cheng, et al. Fast Linear - Quaternion Attitude Estimator Using Vector Observations. IEEE Transactions - on Automation Science and Engineering, Institute of Electrical and - Electronics Engineers, 2018. - (https://hal.inria.fr/hal-01513263) - """ import numpy as np diff --git a/ahrs/filters/fourati.py b/ahrs/filters/fourati.py index d4a2af6..233dce8 100644 --- a/ahrs/filters/fourati.py +++ b/ahrs/filters/fourati.py @@ -3,9 +3,10 @@ Fourati's nonlinear attitude estimation ======================================= -Attitude estimation algorithm as proposed by [Fourati]_, whose approach -combines a quaternion-based nonlinear filter with the Levenberg Marquardt -Algorithm (LMA.) +Attitude estimation algorithm as proposed in :cite:p:`fourati2011`, whose +approach combines a quaternion-based nonlinear filter with the +`Levenberg-Marquardt Algorithm (LMA.) +`_. The estimation algorithm has a complementary structure that exploits measurements from an accelerometer, a magnetometer and a gyroscope, combined in @@ -92,7 +93,8 @@ so that they operate with a *Hamilton product*. To achieve an optimal attitude estimation, a nonlinear system is developed, -whose **output** is the stack of the accelerometer and magnetometer measurements: +whose **output** is the stack of the accelerometer and magnetometer +measurements: .. math:: \\mathbf{y} = \\begin{bmatrix}f_x & f_y & f_z & h_x & h_y & h_z\\end{bmatrix}^T @@ -210,15 +212,6 @@ :math:`\\Delta_t`, which is actually the inverse of the sampling frequency :math:`f=\\frac{1}{\\Delta_t}`. -References ----------- -.. [Fourati] Hassen Fourati, Noureddine Manamanni, Lissan Afilal, Yves - Handrich. A Nonlinear Filtering Approach for the Attitude and Dynamic Body - Acceleration Estimation Based on Inertial and Magnetic Sensors: Bio-Logging - Application. IEEE Sensors Journal, Institute of Electrical and Electronics - Engineers, 2011, 11 (1), pp. 233-244. 10.1109/JSEN.2010.2053353. - (https://hal.archives-ouvertes.fr/hal-00624142/file/Papier_IEEE_Sensors_Journal.pdf) - """ from typing import Union diff --git a/ahrs/filters/fqa.py b/ahrs/filters/fqa.py index 33f8a2e..14c39ae 100644 --- a/ahrs/filters/fqa.py +++ b/ahrs/filters/fqa.py @@ -5,7 +5,7 @@ The factored quaternion algorithm (FQA) produces a quaternion output to represent the orientation, restricting the use of magnetic data to the -determination of the rotation about the vertical axis. +determination of the rotation about the vertical axis :cite:p:`yun2008`. The FQA and the `TRIAD <../triad.html>`_ algorithm produce an equivalent solution to the same problem, with the difference that the former produces a @@ -223,12 +223,6 @@ .. [#] The local geomagnetic field can be obtained with the World Magnetic Model. See the `WMM documentation <../WMM.html>`_ page for further details. -References ----------- -.. [Yun] Xiaoping Yun et al. (2008) A Simplified Quaternion-Based Algorithm for - Orientation Estimation From Earth Gravity and Magnetic Field Measurements. - https://ieeexplore.ieee.org/document/4419916 - """ import numpy as np diff --git a/ahrs/filters/madgwick.py b/ahrs/filters/madgwick.py index c55b943..f6bb623 100644 --- a/ahrs/filters/madgwick.py +++ b/ahrs/filters/madgwick.py @@ -9,7 +9,7 @@ This is an orientation filter applicable to IMUs consisting of tri-axial gyroscopes and accelerometers, and MARG arrays, which also include tri-axial -magnetometers, proposed by Sebastian Madgwick [Madgwick]_. +magnetometers, proposed by Sebastian Madgwick :cite:p:`madgwick2010`. The filter employs a quaternion representation of orientation to describe the nature of orientations in three-dimensions and is not subject to the @@ -368,12 +368,6 @@ phenomenon known as `Geomagnetic secular variation `_, but such shift can be omited for practical purposes. -References ----------- -.. [Madgwick] Sebastian Madgwick. An efficient orientation filter for inertial - and inertial/magnetic sensor arrays. April 30, 2010. - http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/ - """ import numpy as np diff --git a/ahrs/filters/mahony.py b/ahrs/filters/mahony.py index a03db38..970e154 100644 --- a/ahrs/filters/mahony.py +++ b/ahrs/filters/mahony.py @@ -3,19 +3,21 @@ Mahony Orientation Filter ========================= -This estimator proposed by Robert Mahony et al. [Mahony2008]_ is formulated as -a deterministic kinematic observer on the Special Orthogonal group SO(3) driven -by an instantaneous attitude and angular velocity measurements. +This estimator proposed by Robert Mahony et al. :cite:p:`mahony2008` is formulated +as a deterministic kinematic observer on the Special Orthogonal group SO(3) +driven by an instantaneous attitude and angular velocity measurements +:cite:p:`hamel2006`. By exploiting the geometry of the special orthogonal group a related observer, the *passive complementary filter*, is derived that decouples the gyro -measurements from the reconstructed attitude in the observer inputs. +measurements from the reconstructed attitude in the observer inputs +:cite:p:`mahony2005`. Direct and passive filters are extended to estimate gyro bias on-line. This -leads to an observer on SO(3), termed the **Explicit Complementary Filter**, -that requires only accelerometer and gyro outputs, suitable for hardware -implementation, and providing good estimates as well as online gyro bias -computation. +leads to an observer on SO(3), termed the **Explicit Complementary Filter** +:cite:p:`euston2008`, that requires only accelerometer and gyro outputs, +suitable for hardware implementation, and providing good estimates as well as +online gyro bias computation. Sensor Models ------------- @@ -242,28 +244,6 @@ .. math:: \\mathbf{q}_t = \\mathbf{q}_{t-1} + \\dot{\\hat{\\mathbf{q}}}_t\\Delta t -References ----------- -.. [Mahony2008] Robert Mahony, Tarek Hamel, and Jean-Michel Pflimlin. Nonlinear - Complementary Filters on the Special Orthogonal Group. IEEE Transactions - on Automatic Control, Institute of Electrical and Electronics Engineers, - 2008, 53 (5), pp.1203-1217. - (https://hal.archives-ouvertes.fr/hal-00488376/document) -.. [Mahony2005] Robert Mahony, Tarek Hamel, and Jean-Michel Pflimlin. - Complementary filter design on the special orthogonal group SO(3). - Proceedings of the 44th IEEE Conference on Decision and Control, and the - European Control Conference 2005. Seville, Spain. December 12-15, 2005. - (https://folk.ntnu.no/skoge/prost/proceedings/cdc-ecc05/pdffiles/papers/1889.pdf) -.. [Euston] Mark Euston, Paul W. Coote, Robert E. Mahony, Jonghyuk Kim, and - Tarek Hamel. A complementary filter for attitude estimation of a fixed-wing - UAV. IEEE/RSJ International Conference on Intelligent Robots and Systems, - 340-345. 2008. - (http://users.cecs.anu.edu.au/~Jonghyuk.Kim/pdf/2008_Euston_iros_v1.04.pdf) -.. [Hamel] Tarek Hamel and Robert Mahony. Attitude estimation on SO(3) based on - direct inertial measurements. IEEE International Conference on Robotics and - Automation. ICRA 2006. pp. 2170-2175 - (http://users.cecs.anu.edu.au/~Robert.Mahony/Mahony_Robert/2006_MahHamPfl-C68.pdf) - """ import numpy as np diff --git a/ahrs/filters/oleq.py b/ahrs/filters/oleq.py index 2d24379..d5487bb 100644 --- a/ahrs/filters/oleq.py +++ b/ahrs/filters/oleq.py @@ -23,7 +23,8 @@ L(\\mathbf{C}) = \\sum_{i=1}^n a_i \\|\\mathbf{D}_i^b - \\mathbf{CD}_i^r \\|^2 being :math:`a_i` the weight of the *i*-th sensor output. The goal of **OLEQ** -is to find this optimal attitude, but in the form of a quaternion [Zhou2018]_. +is to find this optimal attitude, but in the form of a quaternion +:cite:p:`zhou2018`. First, notice that the attitude matrix is related to quaternion :math:`\\mathbf{q}=\\begin{bmatrix}q_w & q_x & q_y & q_z\\end{bmatrix}^T` via: @@ -138,14 +139,6 @@ This equals the least-square of the set of pre-computed single rotated quaternions. -References ----------- -.. [Zhou2018] Zhou, Z.; Wu, J.; Wang, J.; Fourati, H. Optimal, Recursive and - Sub-Optimal Linear Solutions to Attitude Determination from Vector - Observations for GNSS/Accelerometer/Magnetometer Orientation Measurement. - Remote Sens. 2018, 10, 377. - (https://www.mdpi.com/2072-4292/10/3/377) - """ import numpy as np diff --git a/ahrs/filters/quest.py b/ahrs/filters/quest.py index 7e15eb5..e6ef82c 100644 --- a/ahrs/filters/quest.py +++ b/ahrs/filters/quest.py @@ -3,7 +3,8 @@ QUEST ===== -QUaternion ESTimator as described by Shuster in [Shuster1981]_ and [Shuster1978]_. +QUaternion ESTimator as described by Shuster in :cite:p:`shuster1981` and +:cite:p:`shuster1978`. We start to define the goal of finding an orthogonal matrix :math:`\\mathbf{A}` that minimizes the loss function: @@ -188,15 +189,6 @@ only if the angle of rotation is equal to :math:`\\pi`, even if :math:`\\mathbf{X}` does not vanish along. -References ----------- -.. [Shuster1981] Shuster, M.D. and Oh, S.D. "Three-Axis Attitude Determination - from Vector Observations," Journal of Guidance and Control, Vol.4, No.1, - Jan.-Feb. 1981, pp. 70-77. -.. [Shuster1978] Shuster, Malcom D. Approximate Algorithms for Fast Optimal - Attitude Computation, AIAA Guidance and Control Conference. August 1978. - (http://www.malcolmdshuster.com/Pub_1978b_C_PaloAlto_scan.pdf) - """ from typing import Union diff --git a/ahrs/filters/roleq.py b/ahrs/filters/roleq.py index c662d0c..8eae052 100644 --- a/ahrs/filters/roleq.py +++ b/ahrs/filters/roleq.py @@ -4,7 +4,7 @@ ================================================ This is a modified `OLEQ <./oleq.html>`_, where a recursive estimation of the -attitude is made with the measured angular velocity [Zhou2018]_. This +attitude is made with the measured angular velocity :cite:p:`zhou2018`. This estimation is set as the initial value for the OLEQ estimation, simplyfing the rotational operations. @@ -70,14 +70,6 @@ magnetometers) have to be provided, along with the an initial quaternion, :math:`\\mathbf{q}_0` from which the attitude will be built upon. -References ----------- -.. [Zhou2018] Zhou, Z.; Wu, J.; Wang, J.; Fourati, H. Optimal, Recursive and - Sub-Optimal Linear Solutions to Attitude Determination from Vector - Observations for GNSS/Accelerometer/Magnetometer Orientation Measurement. - Remote Sens. 2018, 10, 377. - (https://www.mdpi.com/2072-4292/10/3/377) - """ import numpy as np diff --git a/ahrs/filters/saam.py b/ahrs/filters/saam.py index cf8c04e..e680aed 100644 --- a/ahrs/filters/saam.py +++ b/ahrs/filters/saam.py @@ -3,8 +3,8 @@ Super-fast Attitude from Accelerometer and Magnetometer ======================================================= -This novel estimator proposed by [Wu]_, offers an extremely simplified -computation of `Davenport's <../davenport.html>`_ solution to +This novel estimator proposed by :cite:p:`wu2018-2`, offers an extremely +simplified computation of `Davenport's <../davenport.html>`_ solution to `Wahba's problem `_, where the full solution is reduced to a couple of floating point operations, without losing much accuracy, and sparing computational time. @@ -104,15 +104,6 @@ making it very suitable for low-cost and simple processors. Its accuracy is comparable to that of QUEST and FQA, but it is one order of magnitude faster. -References ----------- -.. [Wu] Jin Wu, Zebo Zhou, Hassen Fourati, Yuhua Cheng. A Super Fast Attitude - Determination Algorithm for Consumer-Level Accelerometer and Magnetometer. - IEEE Transactions on Con-sumer Electronics, Institute of Electrical and - Electronics Engineers, 2018, 64 (3), pp. 375. 381.10.1109/tce.2018.2859625. - hal-01922922 - (https://hal.inria.fr/hal-01922922/document) - """ import numpy as np diff --git a/ahrs/filters/tilt.py b/ahrs/filters/tilt.py index 6e5eebb..b0e903d 100644 --- a/ahrs/filters/tilt.py +++ b/ahrs/filters/tilt.py @@ -8,13 +8,13 @@ The simplest way to estimate the attitude from the gravitational acceleration is using 3D `geometric quadrants `_. -Although some methods use ``arctan`` to estimate the angles [ST-AN4509]_ [AD-AN1057]_, -it is preferred to use ``arctan2`` to explore all quadrants searching the tilt -angles. +Although some methods use ``arctan`` to estimate the angles :cite:p:`stm4509` +:cite:p:`fisher2010` it is preferred to use ``arctan2`` to explore all +quadrants searching the tilt angles. First, we normalize the gravity vector, so that it has magnitude equal to 1. -Then, we get the angles to the main axes with `arctan2 `_ -[FS-AN3461]_ [Trimpe]_: +Then, we get the angles to the main axes with `arctan2 +`_ :cite:p:`pedley2013` :cite:p:`trimpe2012`: .. math:: \\begin{array}{ll} @@ -68,7 +68,7 @@ :math:`\\|\\mathbf{m}\\|=1`. The yaw angle :math:`\\psi` is the tilt-compensated heading angle relative to -magnetic North, computed as [FS-AN4248]_: +magnetic North, computed as :cite:p:`ozyagcilar2015`: .. math:: \\begin{array}{ll} @@ -91,28 +91,6 @@ Setting the property ``as_angles`` to ``True`` will avoid this last conversion returning the attitude as angles. -References ----------- -.. [Trimpe] Sebastian Trimpe and Raffaello D'Andrea. The Balancing cube. A - dynamic sculpture as test bed for distributed estimation and control. IEEE - Control Systems Magazine. December 2012. - (http://trimpe.is.tuebingen.mpg.de/publications/trimpe-CSM12.pdf) -.. [FS-AN3461] Mark Pedley. Tilt Sensing Using a Three-Axis Accelerometer. - Freescale Semiconductor Application Note. Document Number: AN3461. 2013. - (https://www.nxp.com/files-static/sensors/doc/app_note/AN3461.pdf) -.. [FS-AN4248] Talat Ozyagcilar. Implementing a Tilt-Compensated eCompass using - Accelerometer and Magnetometer sensors. Freescale Semoconductor Application - Note. Document Number: AN4248. 2015. - (https://www.nxp.com/files-static/sensors/doc/app_note/AN4248.pdf) -.. [AD-AN1057] Christopher J. Fisher. Using an Accelerometer for Inclination - Sensing. Analog Devices. Application Note. AN-1057. - (https://www.analog.com/media/en/technical-documentation/application-notes/AN-1057.pdf) -.. [ST-AN4509] Tilt measurement using a low-g 3-axis accelerometer. - STMicroelectronics. Application note AN4509. 2014. - (https://www.st.com/resource/en/application_note/dm00119046.pdf) -.. [WikiConversions] Wikipedia: Conversion between quaternions and Euler angles. - (https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles) - """ import numpy as np @@ -298,7 +276,7 @@ def estimate(self, acc: np.ndarray, mag: np.ndarray = None, representation: str The orientation of the roll and pitch angles is estimated using the measurements of the accelerometers, and finally converted to a - quaternion representation according to [WikiConversions]_ + quaternion representation according to :cite:p:`Wiki_Conversions`. Parameters ---------- diff --git a/ahrs/filters/triad.py b/ahrs/filters/triad.py index 5cc1541..078ce22 100644 --- a/ahrs/filters/triad.py +++ b/ahrs/filters/triad.py @@ -3,10 +3,10 @@ TRIAD ===== -The Tri-Axial Attitude Determination (`TRIAD `_) -was first described in [Black]_ to algebraically estimate an attitude -represented as a Direction Cosine Matrix from two orthogonal vector -observations. +The Tri-Axial Attitude Determination (`TRIAD +`_) was first described by Harold +Black in :cite:p:`black1964` to algebraically estimate an attitude represented +as a Direction Cosine Matrix from two orthogonal vector observations. Given two non-parallel reference *unit vectors* :math:`\\mathbf{v}_1` and :math:`\\mathbf{v}_2` and their corresponding *unit vectors* :math:`\\mathbf{w}_1` @@ -29,10 +29,10 @@ \\end{array} The TRIAD method, initially developed to estimate the attitude of spacecrafts -[Shuster2007]_, uses the position of the sun (using a `star tracker +:cite:p:`shuster2007`, uses the position of the sun (using a `star tracker `_) and the magnetic field of Earth -as references [Hall]_ [Makley]_. These are represented as vectors to build an -appropriate *reference* frame :math:`\\mathbf{M}_r`: +as references :cite:p:`hall2000` :cite:p:`markley2014`. These are represented +as vectors to build an appropriate *reference* frame :math:`\\mathbf{M}_r`: .. math:: \\mathbf{M}_r = \\begin{bmatrix} \\mathbf{q}_r & \\mathbf{r}_r & \\mathbf{s}_r \\end{bmatrix} @@ -75,7 +75,7 @@ It is only required that :math:`\\mathbf{M}_r` has an inverse, but that is already ensured, since :math:`\\mathbf{q}_r`, :math:`\\mathbf{r}_r`, -and :math:`\\mathbf{s}_r` are linearly independent [Lerner1]_. +and :math:`\\mathbf{s}_r` are linearly independent :cite:p:`lerner1978`. Strapdown INS ------------- @@ -224,21 +224,6 @@ .. [#] This package's author resides in Munich, and examples of geographical locations will take it as a reference. -References ----------- -.. [Black] Black, Harold. "A Passive System for Determining the Attitude of a - Satellite," AIAA Journal, Vol. 2, July 1964, pp. 1350–1351. -.. [Lerner1] Lerner, G. M. "Three-Axis Attitude Determination" in Spacecraft - Attitude Determination and Control, edited by J.R. Wertz. 1978. p. 420-426. -.. [Hall] Chris Hall. Spacecraft Attitude Dynamics and Control. Chapter 4: - Attitude Determination. 2003. - (http://www.dept.aoe.vt.edu/~cdhall/courses/aoe4140/attde.pdf) -.. [Makley] F.L. Makley et al. Fundamentals of Spacecraft Attitude - Determination and Control. 2014. Pages 184-186. -.. [Shuster2007] Shuster, Malcolm D. The optimization of TRIAD. The Journal of - the Astronautical Sciences, Vol. 55, No 2, April – June 2007, pp. 245–257. - (http://www.malcolmdshuster.com/Pub_2007f_J_OptTRIAD_AAS.pdf) - """ import numpy as np @@ -414,7 +399,7 @@ def estimate(self, w1: np.ndarray, w2: np.ndarray, representation: str = 'rotmat """ Attitude Estimation. - The equation numbers in the code refer to [Lerner1]_. + The equation numbers in the code refer to :cite:p:`lerner1978`. Parameters ---------- diff --git a/ahrs/utils/wgs84.py b/ahrs/utils/wgs84.py index 4fd141c..861538f 100644 --- a/ahrs/utils/wgs84.py +++ b/ahrs/utils/wgs84.py @@ -1,9 +1,9 @@ """ -The World Geodetic System 1984 (WGS 84) [WGS84]_ describes the best geodetic -reference system for the Earth available for the practical applications of -mapping, charting, geopositioning, and navigation, using data, techniques and -technology available through 2013 by the United States of America's National -Geospatial-Intelligence Agency (NGA.) +The World Geodetic System 1984 (WGS 84) :cite:p:`wgs84-2014` describes the best +geodetic reference system for the Earth available for the practical +applications of mapping, charting, geopositioning, and navigation, using data, +techniques and technology available through 2013 by the United States of +America's National Geospatial-Intelligence Agency (NGA.) The WGS 84 Coordinate System is a Conventional Terrestrial Reference System (`CTRS `_), diff --git a/ahrs/utils/wmm.py b/ahrs/utils/wmm.py index f3aa3aa..685dd9b 100644 --- a/ahrs/utils/wmm.py +++ b/ahrs/utils/wmm.py @@ -1,12 +1,12 @@ """ -The main utility of the World Magnetic Model (WMM) [WMM]_ is to provide -magnetic declination for any desired location on the globe. +The main utility of the World Magnetic Model (WMM) :cite:p:`chulliat2020` is to +provide magnetic declination for any desired location on the globe. In addition to the magnetic declination, the WMM also provides the complete geometry of the field from 1 km below the World Geodetic System (WGS 84) -[WGS84]_ ellipsoid surface to approximately 850 km above it. The magnetic field -extends deep into the Earth and far out into space, but the WMM is not valid at -these extremes. +:cite:p:`wgs84-2014` ellipsoid surface to approximately 850 km above it. The +magnetic field extends deep into the Earth and far out into space, but the WMM +is not valid at these extremes. Earth's magnetic field is viewed as a magnetic dipole produced by a sphere of uniform magnetization. The "south" of the dipole lies on the northern @@ -45,12 +45,12 @@ *Gaussian coefficients* of degree :math:`n` and order :math:`m`; :math:`r`, :math:`\\theta`, and :math:`\\phi` are the geocentric radius, coelevation and longitude in spherical polar coordinates; and :math:`P_n^m(\\theta)` are the -associated Legendre functions [Heiskanen]_. +associated Legendre functions :cite:p`hofmann2006`. The time-dependent Gauss coefficients are estimated empirically from a -least-squares fit using satellite magnetic measurements [Langel]_. These -coefficients are provided by the NCEI Geomagnetic Modeling Team and British -Geological Survey in a file with extension COF [WMM2020]_. +least-squares fit using satellite magnetic measurements :cite:p:`langel1998`. +These coefficients are provided by the NCEI Geomagnetic Modeling Team and +British Geological Survey in a file with extension COF :cite:p:`chulliat2020`. With degree :math:`n=1` only dipoles are considered. For :math:`n=2` the quadrupoles, :math:`n=3` the octuploles, and so on. The method of this WMM @@ -168,9 +168,9 @@ released the latest model on December 10th, 2019. This script is based on the originally conceived one by Christopher Weiss -(cmweiss@gmail.com) [Weiss]_, who adapted it from the geomagc software and -World Magnetic Model of the NOAA Satellite and Information Service, National -Geophysical Data Center [Chulliat]_. +(cmweiss@gmail.com) :cite:p:`weiss2016`, who adapted it from the geomagc +software and World Magnetic Model of the NOAA Satellite and Information +Service, National Geophysical Data Center :cite:p:`chulliat2020`. License ------- @@ -182,30 +182,6 @@ incorporated and stating that such material is not subject to copyright protection. -References ----------- -.. [Chulliat] Chulliat, A., W. Brown, P. Alken, C. Beggan, M. Nair, G. Cox, A. - Woods, S. Macmillan, B. Meyer and M. Paniccia, The US/UK World Magnetic - Model for 2020-2025: Technical Report, National Centers for Environmental - Information, NOAA, doi:10.25923/ytk1-yx35, 2020. - (https://www.ngdc.noaa.gov/geomag/WMM/data/WMM2020/WMM2020_Report.pdf) -.. [Heiskanen] W. A. Heiskanen and H. Moritz. Physical Geodesy. TU Graz. 1993. -.. [Langel] R. A. Langel and W. J. Hinze. The Magnetic Field of Earth's - Lithosphere: The Satellite Perspective. Cambridge University Press. 1998. -.. [Weiss] Christopher Weiss' GeoMag repository (https://github.com/cmweiss/geomag) -.. [Wertz] James R. Wertz. Spacecraft Attitude Determination and Control. - Kluwer Academics. 1978. -.. [WGS84] World Geodetic System 1984. Its Definition and Relationships with - Local Geodetic Systems. National Geospatial-Intelligence Agency (NGA) - Standarization Document. 2014. - ftp://ftp.nga.mil/pub2/gandg/website/wgs84/NGA.STND.0036_1.0.0_WGS84.pdf -.. [WMM] The World Magnetic Model (https://www.ncei.noaa.gov/products/world-magnetic-model) -.. [WMM-TR] Chulliat, A. et al. (2020). The US/UK World Magnetic Model for - 2020-2025 : Technical Report. https://doi.org/10.25923/ytk1-yx35 -.. [WMM2020] WMM2020 Model values: NCEI Geomagnetic Modeling Team and British - Geological Survey. 2019. World Magnetic Model 2020. NOAA National Centers - for Environmental Information. doi: 10.25921/11v3-da71, 2020. - """ # PSL @@ -562,8 +538,8 @@ def reset_date(self, date: Union[datetime.date, int, float]) -> None: def denormalize_coefficients(self, latitude: float) -> None: """ Recursively estimate associated Legendre polynomials and derivatives - done in a recursive way as described by Michael Plett in [Wertz]_ for - an efficient computation. + done in a recursive way as described by Michael Plett in + :cite:p:`plett1978` for an efficient computation. Given the Gaussian coefficients, it is possible to estimate the magnetic field at any latitude on Earth for a certain date. diff --git a/docs/source/refs.bib b/docs/source/refs.bib index e50c6b3..72267fd 100644 --- a/docs/source/refs.bib +++ b/docs/source/refs.bib @@ -1,10 +1,743 @@ @article{BarItzhack2000, - title={New method for Extracting the Quaternion from a Rotation Matrix}, - author={Itzhack Yoav Bar-Itzhack}, - journal={Journal of Guidance, Control, and Dynamics}, - volume={23}, - number={6}, - pages={1085--1087}, - year={2000}, - publisher={American Institute of Aeronautics and Astronautics} + author = {Itzhack Yoav Bar-Itzhack}, + title = {New method for Extracting the Quaternion from a Rotation Matrix}, + journal = {Journal of Guidance, Control, and Dynamics}, + volume = {23}, + number = {6}, + pages = {1085--1087}, + year = {2000}, + publisher = {American Institute of Aeronautics and Astronautics}, + doi = {10.2514/2.4654} +} + +@article{black1964, + author = {Black, Harold D.}, + title = {A passive system for determining the attitude of a satellite}, + journal = {AIAA Journal}, + volume = {2}, + number = {7}, + pages = {1350-1351}, + year = {1964}, + doi = {10.2514/3.2555} +} + +@article{Chiaverini1999, + author = {Chiaverini, Stefano and Siciliano, Bruno}, + year = {1999}, + month = {05}, + pages = {45-60}, + title = {The Unit Quaternion: A Useful Tool for Inverse Kinematics of Robot Manipulators}, + volume = {35}, + journal = {Systems Analysis Modelling Simulation} +} + +@techreport{chulliat2020, + author = {Chulliat, A. and Brown, W. and Alken, P. and Beggan, C. and Nair, M. and Cox, G. and Woods, A. and Macmillan, S. and Meyer, B. and M. Paniccia}, + title = {The US/UK World Magnetic Model for 2020-2025 : Technical Report}, + institution = {National Centers for Environmental Information, NOAA}, + year = {2020}, + doi = {10.25923/ytk1-yx35}, + url = {https://repository.library.noaa.gov/view/noaa/24390/noaa_24390_DS1.pdf}, + address = {United States; Great Britain}, + annote = {Public Domain}, + type = {PDF-29.84 MB}, +} + +@book{curtis2014, + author = {Curtis, Howard D.}, + title = {Orbital Mechanics for Engineering Students}, + year = {2014}, + edition = {3}, + publisher = {Elsevier Ltd}, + isbn = {978-0-08-097747-8}, + doi = {10.1016/C2011-0-69685-1} +} + +@techreport{dantam2014, + author = {Dantam, Neil}, + title = {Quaternion Computation}, + institution = {Institute for Robotics and Intelligent Machines. Georgia Institute of Technology}, + year = {2002}, + url = {http://www.neil.dantam.name/note/dantam-quaternion.pdf} +} + +@techreport{davenport1968, + title = {A Vector Approach to the Algebra of Rotations with Applications}, + author = {Davenport, Paul B.}, + series = {NASA technical note}, + institution = {Goddard Space Flight Center}, + url = {https://ntrs.nasa.gov/citations/19680021122}, + year = {1968}, + month = {08}, + publisher = {National Aeronautics and Space Administration} +} + +@techreport{diebel2006, + author = {Diebel, James}, + year = {2006}, + month = {10}, + title = {Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors}, + institute = {Stanford University}, + url = {https://www.astro.rug.nl/software/kapteyn-beta/_downloads/attitude.pdf} +} + +@techreport{eberly2002, + title = {Quaternion Algebra and Calculus}, + author = {Eberly, David H.}, + institution = {Magic Software, Inc.}, + year = {2002}, + url = {https://www.sci.utah.edu/~jmk/papers/Quaternions.pdf} +} + +@InProceedings{euston2008, + author = {Euston, Mark and Coote, Paul and Mahony, Robert and Kim, Jonghyuk and Hamel, Tarek}, + booktitle = {2008 IEEE/RSJ International Conference on Intelligent Robots and Systems}, + title = {A complementary filter for attitude estimation of a fixed-wing UAV}, + year = {2008}, + pages = {340-345}, + keywords = {Low pass filters;Acceleration;Atmospheric modeling;Unmanned aerial vehicles;Vehicles;Global positioning system;Airplanes}, + doi = {10.1109/IROS.2008.4650766} +} + +@techreport{fisher2010, + author = {Fisher, Christopher J.}, + title = {Using an Accelerometer for Inclination Sensing}, + institution = {Analog Devices, Inc}, + year = {2010}, + month = {}, + number = {AN-1057}, + note = {}, + url = {https://www.analog.com/en/resources/app-notes/an-1057.html}, + address = {}, + annote = {}, + type = {}, +} + +@article{fourati2011, + author = {Fourati, Hassen and Manamanni, Noureddine and Afilal, Lissan and Handrich, Yves}, + title = {A Nonlinear Filtering Approach for the Attitude and Dynamic Body Acceleration Estimation Based on Inertial and Magnetic Sensors: Bio-Logging Application}, + year = {2011}, + volume = {09}, + number = {15}, + pages = {233-244}, + keywords = {Estimation;Nonlinear filters;Magnetometers;Gyroscopes;Accelerometers;Magnetic separation;Quaternions;Attitude;bio-logging;complementary nonlinear filter;dynamic body acceleration (DBA);inertial measurement unit (MTi-G);MEMS inertial/magnetic sensors}, + journal = {IEEE Sensors Journal}, + doi = {10.1109/JSEN.2010.2053353}, + url = {https://hal.science/hal-00624142} +} + +@misc{garcia2022, + author = {Garcia, Mario}, + title = {Angular Velocity from Quaternions}, + howpublished = {\url{https://mariogc.com/post/angular-velocity-quaternions/}}, + year = {2022}, + note = {Accessed: 2024-09-27} +} + +@techreport{grosskatthoefer2012, + title = {Introduction into quaternions for spacecraft attitude representation}, + author = {Großekatthöfer, Karsten}, + institution = {Department of Astronautics and Aeronautics. Technical University of Berlin}, + year = {2012}, + month = {05}, + day = {31}, + url = {https://argos.vu/wp-content/uploads/2017/01/Quaternions-1.pdf} +} + +@article{guo2017, + author = {Guo, Siwen and Wu, Jin and Wang, Zuocai and Qian, Jide}, + title = {Novel MARG-Sensor Orientation Estimation Algorithm Using Fast Kalman Filter}, + journal = {Journal of Sensors}, + volume = {2017}, + number = {1}, + doi = {10.1155/2017/8542153}, + url = {https://onlinelibrary.wiley.com/doi/abs/10.1155/2017/8542153}, + abstract = {Orientation estimation from magnetic, angular rate, and gravity (MARG) sensor array is a key problem in mechatronic-related applications. This paper proposes a new method in which a quaternion-based Kalman filter scheme is designed. The quaternion kinematic equation is employed as the process model. With our previous contributions, we establish the measurement model of attitude quaternion from accelerometer and magnetometer, which is later proved to be the fastest (computationally) one among representative attitude determination algorithms of such sensor combination. Variance analysis is later given enabling the optimal updating of the proposed filter. The algorithm is implemented on real-world hardware where experiments are carried out to reveal the advantages of the proposed method with respect to conventional ones. The proposed approach is also validated on an unmanned aerial vehicle during a real flight. Results show that the proposed one is faster than any other Kalman-based ones and even faster than some complementary ones while the attitude estimation accuracy is maintained.}, + year = {2017} +} + +@book{hall2000, + author = {Hall, Christopher D.}, + title = {Spacecraft Attitude Dynamics and Control}, + editor = {}, + publisher = {}, + year = {2000}, + month = {01}, + day = {16}, + isbn = {978-0-7506-7038-4}, +} + +@InProceedings{hamel2006, + author = {Hamel, Tarek and Mahony, Robert}, + booktitle = {Proceedings 2006 IEEE International Conference on Robotics and Automation, 2006. ICRA 2006.}, + title = {Attitude estimation on SO(3) based on direct inertial measurements}, + year = {2006}, + pages = {2170-2175}, + keywords = {Filters;Unmanned aerial vehicles;Costs;Magnetic field measurement;Velocity measurement;Attitude control;Magnetic separation;Angular velocity;Filtering;Measurement units}, + doi = {10.1109/ROBOT.2006.1642025} +} + +@techreport{hartikainen2011, + author = {Hartikainen, Jouni and Solin, Arno and Särkkä, Simo}, + title = {Optimal filtering with Kalman filters and smoothers}, + subtitle = {A manual for the Matlab toolbox EKF/UKF}, + institution = {Department of Biomedical Engineering and Computational Science. Aalto University School of Science}, + year = {2011}, + month = {09}, +} + +@book{hofmann2006, + author = {Hofmann-Wellenhof, Bernhard and Moritz, Helmut}, + title = {Physical Geodesy}, + edition = {2}, + publisher = {Springer Vienna}, + isbn = {978-3-211-33544-4}, + year = {2006}, + month = {10}, + day = {10}, + doi = {10.1007/978-3-211-33545-1} +} + +@inbook{hughes1986spacecraft17, + author = {Hughes, P.C.}, + title = {Spacecraft Attitude Dynamics}, + isbn = {9780471818427}, + lccn = {lc85006556}, + pages = {17--18}, + year = {1986}, + publisher = {J. Wiley} +} + +@article{huynh2009, + title = {Metrics for 3D rotations: Comparison and analysis}, + author = {Huynh, Du Q}, + journal = {Journal of Mathematical Imaging and Vision}, + volume = {35}, + pages = {155--164}, + year = {2009}, + publisher = {Springer} +} + +@techreport{jia2024, + author = {Jia, Yan-Bin}, + institution = {Department of Computer Science. Iowa State University}, + title = {Quaternions}, + year = {2024}, + month = {09}, + day = {24}, + url = {https://faculty.sites.iastate.edu/jia/files/inline-files/quaternion.pdf} +} + +@article{kalman1960, + author = {Kálmán, Rudolf Emil}, + title = {A New Approach to Linear Filtering and Prediction Problems}, + journal = {Journal of Basic Engineering}, + volume = {82}, + number = {1}, + pages = {35-45}, + year = {1960}, + month = {03}, + issn = {0021-9223}, + doi = {10.1115/1.3662552}, + eprint = {https://www.unitedthc.com/DSP/Kalman1960.pdf} +} + +@InProceedings{kuffner2004, + author = {Kuffner, J.J.}, + booktitle = {IEEE International Conference on Robotics and Automation, 2004. Proceedings. ICRA '04. 2004}, + title = {Effective sampling and distance metrics for 3D rigid body path planning}, + year = {2004}, + volume = {4}, + number = {}, + pages = {3993-3998 Vol.4}, + publisher = {IEEE}, + keywords = {Sampling methods;Path planning;Interpolation;Quaternions;Kinematics;Orbital robotics;Satellites;Proteins;Topology;Geophysics computing}, + doi = {10.1109/ROBOT.2004.1308895} +} + +@InProceedings{kuipers1999, + author = {Kuipers, Jack B.}, + title = {Quaternions and Rotation Sequences}, + booktitle = {Geometry, Integrability and Quantization}, + year = {1999}, + month = {09}, + editor = {Mladenov, Ivaïlo M. and Naber, Gregory L.}, + publisher = {Coral Press}, + address = {Sofia}, + pages = {127--143}, + doi = {10.7546/giq-1-2000-127-143}, + url = {https://api.semanticscholar.org/CorpusID:116093978} +} + +@misc{labbe2015, + author = {Labbe Jr, Roger R.}, + title = {Kalman and Bayesian Filters in Python}, + howpublished = {\url{https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python}}, + year = {2015}, + month = {05}, + day = {23}, + note = {Accessed: 2024-09-27} +} + +@InProceedings{lam2003, + author = {Lam, Quang and Stamatakos, Nick and Woodruff, Craig and Ashton, Sandy}, + title = {Gyro Modeling and Estimation of Its Random Noise Sources}, + booktitle = {AIAA Guidance, Navigation, and Control Conference and Exhibit}, + month = {08}, + volume = {5562}, + isbn = {978-1-62410-090-1}, + doi = {10.2514/6.2003-5562}, + year = {2003}, + url = {https://arc.aiaa.org/doi/abs/10.2514/6.2003-5562}, + eprint = {https://arc.aiaa.org/doi/pdf/10.2514/6.2003-5562} +} + +@book{langel1998, + author = {Langel, R. A. and Hinze, W. J.}, + title = {The Magnetic Field of the Earth’s Lithosphere: The Satellite Perspective}, + publisher = {Cambridge University Press}, + place = {Cambridge}, + year = {1998}, + month = {12}, + isbn = {9780511629549}, + doi = {10.1017/CBO9780511629549} +} + +@inbook{lerner1978, + author = {Lerner, Gerald M.}, + title = {Three-Axis Attitude Determination}, + booktitle = {Spacecraft Attitude Determination and Control}, + chapter = {12}, + editor = {Wertz, James, R.}, + pages = {420--428}, + isbn = {90-277-0959-9}, + publisher = {Kluwer Academic Publishers}, + year = {1978} +} + +@article{liu2018, + author = {Liu, Zhuohua and Liu, Wei and Gong, Xiangyang and Wu, Jin}, + title = {Simplified Attitude Determination Algorithm Using Accelerometer and Magnetometer with Extremely Low Execution Time}, + journal = {Journal of Sensors}, + volume = {2018}, + number = {1}, + doi = {10.1155/2018/8787236}, + url = {https://onlinelibrary.wiley.com/doi/abs/10.1155/2018/8787236}, + abstract = {Accelerometer-magnetometer attitude determination is a common and vital medium processing technique in industrial robotics and consumer electronics. In this paper, we report a novel analytic attitude solution to the accelerometer-magnetometer combination in the sense of Wahba’s problem. The Davenport matrix is analytically given and its eigenvalues are computed. Through derivations, the eigenvalues are simplified to very short expressions. Then, the corresponding eigenvectors are given accordingly via matrix row operations. The system is highly optimized based on the factorization and simplification of the obtained row-echelon form, which makes it computationally fast in practice. In this way, it is named as the fast accelerometer-magnetometer combination (FAMC). Experiments on the correctness and advantages of the proposed solution are conducted. The results show that compared with conventional solutions, the proposed analytic solution is not only correct and accurate, but to our knowledge, the most time efficient as well.}, + year = {2018} +} + +@book{ma2003, + author = {Ma, Yi and Soatto, Stefano and Košecká, Jana and Sastry, S. Shankar}, + title = {An Invitation to 3-D Vision: From Images to Geometric Models}, + series = {Interdisciplinary Applied Mathematics}, + year = {2003}, + month = {11}, + edition = {1}, + publisher = {Springer New York, NY}, + isbn = {978-0-387-00893-6}, + doi = {10.1007/978-0-387-21779-6} +} + +@techreport{madgwick2010, + author = {Madgwick, Sebastian O. H.}, + title = {An efficient orientation filter for inertial and inertial/magnetic sensor arrays}, + institution = {University of Bristol}, + year = {2010}, + month = {04}, + day = {30}, + url = {https://x-io.co.uk/downloads/madgwick_internal_report.pdf} +} + +@InProceedings{mahony2005, + author = {Mahony, R. and Hamel, T. and Pflimlin, J.-M.}, + booktitle = {Proceedings of the 44th IEEE Conference on Decision and Control}, + title = {Complementary filter design on the special orthogonal group SO(3)}, + year = {2005}, + pages = {1477-1484}, + keywords = {Passive filters;Quaternions;Unmanned aerial vehicles;Attitude control;Costs;Measurement units;Remotely operated vehicles;Mobile robots;Sensor systems;Noise robustness}, + doi = {10.1109/CDC.2005.1582367}, + url = {https://folk.ntnu.no/skoge/prost/proceedings/cdc-ecc05/pdffiles/papers/1889.pdf} +} + +@article{mahony2008, + author = {Mahony, Robert and Hamel, Tarek and Pflimlin, Jean-Michel}, + journal = {IEEE Transactions on Automatic Control}, + title = {Nonlinear Complementary Filters on the Special Orthogonal Group}, + year = {2008}, + volume = {53}, + number = {5}, + pages = {1203-1218}, + keywords = {Passive filters;Costs;Measurement units;Noise level;Time varying systems;Additive noise;Filtering;Kinematics;Position measurement;Angular velocity;Attitude estimates;complementary filter;nonlinear observer;special orthogonal group}, + doi = {10.1109/TAC.2008.923738}, + url = {https://ieeexplore.ieee.org/document/4608934} +} + +@article{markley2007, + author = {Markley, Landis and Cheng, Yang and Crassidis, John and Oshman, Yaakov}, + title = {Averaging Quaternions}, + year = {2007}, + month = {07}, + pages = {1193-1196}, + volume = {30}, + journal = {Journal of Guidance, Control, and Dynamics}, + doi = {10.2514/1.28949} +} + +@book{markley2014, + author = {Markley, F. Landis and Crassidis, John L.}, + title = {Fundamentals of Spacecraft Attitude Determination and Control}, + series = {Space Technology Library}, + year = {2014}, + month = {06}, + edition = {1}, + publisher = {Springer New York, NY}, + isbn = {978-1-4939-0801-1}, + doi = {10.1007/978-1-4939-0802-8} +} + +@techreport{ozyagcilar2015, + author = {Ozyagcilar, Talat}, + title = {Implementing a Tilt-Compensated eCompass using Accelerometer and Magnetometer Sensors}, + institution = {Freescale Semiconductor, Inc}, + year = {2015}, + month = {11}, + number = {AN4248}, + note = {Rev 4.0}, + url = {https://www.nxp.com/docs/en/application-note/AN4248.pdf}, + address = {}, + annote = {}, + type = {}, +} + +@techreport{ozyagcilar2015-2, + author = {Ozyagcilar, Talat}, + title = {Accuracy of Angle Estimation in eCompass and 3D Pointer Applications}, + institution = {Freescale Semiconductor, Inc}, + year = {2015}, + month = {11}, + number = {AN4249}, + note = {Rev 1.0}, + url = {https://www.nxp.com/docs/en/application-note/AN4249.pdf}, + address = {}, + annote = {}, + type = {}, +} + +@techreport{pedley2013, + author = {Pedley, Mark}, + title = {Tilt Sensing Using a Three-Axis Accelerometer}, + institution = {Freescale Semiconductor, Inc}, + year = {2013}, + month = {}, + number = {AN3461}, + note = {Rev 6}, + url = {https://www.nxp.com/docs/en/application-note/AN3461.pdf}, + address = {}, + annote = {}, + type = {}, +} + +@inbook{plett1978, + author = {Plett, Michael}, + title = {Magnetic Field Models}, + booktitle = {Spacecraft Attitude Determination and Control}, + chapter = {Appendix H}, + editor = {Wertz, James, R.}, + pages = {779--786}, + isbn = {90-277-0959-9}, + publisher = {Kluwer Academic Publishers}, + year = {1978} +} + +@article{sabatini2011, + author = {Sabatini, Angelo Maria}, + title = {Kalman-Filter-Based Orientation Determination Using Inertial/Magnetic Sensors: Observability Analysis and Performance Evaluation}, + journal = {Sensors}, + volume = {11}, + number = {10}, + pages = {9182--9206}, + doi = {10.3390/s111009182}, + url = {https://www.mdpi.com/1424-8220/11/10/9182}, + PubMedID = {22163689}, + issn = {1424-8220}, + abstract = {In this paper we present a quaternion-based Extended Kalman Filter (EKF) for estimating the three-dimensional orientation of a rigid body. The EKF exploits the measurements from an Inertial Measurement Unit (IMU) that is integrated with a tri-axial magnetic sensor. Magnetic disturbances and gyro bias errors are modeled and compensated by including them in the filter state vector. We employ the observability rank criterion based on Lie derivatives to verify the conditions under which the nonlinear system that describes the process of motion tracking by the IMU is observable, namely it may provide sufficient information for performing the estimation task with bounded estimation errors. The observability conditions are that the magnetic field, perturbed by first-order Gauss-Markov magnetic variations, and the gravity vector are not collinear and that the IMU is subject to some angular motions. Computer simulations and experimental testing are presented to evaluate the algorithm performance, including when the observability conditions are critical.}, + year = {2011}, +} + +@InProceedings{sarabandi2019, + author = {Sarabandi, Soheil and Thomas, Federico}, + title = {Accurate Computation of Quaternions from Rotation Matrices}, + booktitle = {Advances in Robot Kinematics 2018}, + year = {2019}, + month = {06}, + day = {23}, + publisher = {Springer International Publishing}, + address = {Cham}, + pages = {39--46}, + abstract = {The main non-singular alternative to {\$}{\$}3{\backslash}times 3{\$}{\$}proper orthogonal matrices, for representing rotations in {\$}{\$}{\{}{\backslash}mathbb R{\}}^3{\$}{\$}, is quaternions. Thus, it is important to have reliable methods to pass from one representation to the other. While passing from a quaternion to the corresponding rotation matrix is given by Euler-Rodrigues formula, the other way round can be performed in many different ways. Although all of them are algebraically equivalent, their numerical behavior can be quite different. In 1978, Shepperd proposed a method for computing the quaternion corresponding to a rotation matrix which is considered the most reliable method to date. Shepperd's method, thanks to a voting scheme between four possible solutions, always works far from formulation singularities. In this paper, we propose a new method which outperforms Shepperd's method without increasing the computational cost.}, + isbn = {978-3-319-93188-3}, + editor = {Lenarcic, Jadran and Parenti-Castelli, Vincenzo}, + doi = {10.1007/978-3-319-93188-3_5} +} + +@techreport{särkkä2007, + title = {Notes on Quaternions}, + author = {Särkkä, Simo}, + institution = {Department of Electrical Engineering and Automation (EEA), Aalto University}, + year = {2007}, + url = {https://users.aalto.fi/~ssarkka/pub/quat.pdf} +} + +@misc{sola2017quaternion, + title = {Quaternion kinematics for the error-state Kalman filter}, + author = {Solà, Joan}, + year = {2017}, + eprint = {1711.02508}, + doi = {10.48550/arXiv.1711.02508}, + url = {https://arxiv.org/abs/1711.02508}, +} + +@inbook{spence1978, + author = {Spence Jr, C. B. and Markley, F. Landis}, + title = {Attitude Propagation}, + booktitle = {Spacecraft Attitude Determination and Control}, + chapter = {17}, + editor = {Wertz, James, R.}, + pages = {559--566}, + isbn = {90-277-0959-9}, + publisher = {Kluwer Academic Publishers}, + year = {1978} +} + +@article{shepperd1978, + author = {Shepperd, Stanley W.}, + title = {Quaternion from Rotation Matrix}, + journal = {Journal of Guidance and Control}, + volume = {1}, + number = {3}, + pages = {223-224}, + year = {1978}, + doi = {10.2514/3.55767b} +} + +@incollection{shoemake1992, + author = {Shoemake, Ken}, + title = {III.6 - Uniform Random Rotations}, + booktitle = {Graphics Gems III (IBM Version)}, + publisher = {Morgan Kaufmann}, + pages = {124-132}, + year = {1992}, + isbn = {978-0-12-409673-8}, + doi = {10.1016/B978-0-08-050755-2.50036-1}, + editor = {Kirk, David}, + abstract = {A planar rotation can be represented in several ways—for example, as an angle between 0 and 2π or as a unit complex number x + iy = cos θ + i sin θ. Planar rotations combine by summing their angles modulo 2π ; so one way to generate a uniform planar rotation is to generate a uniform angle. This chapter describes a uniformly distributed spatial rotation as one not having a uniformly distributed angle. For a unit quaternion, the ω component is the cosine of half the angle of rotation. When the angle is uniformly distributed between 0 and 2π, the average magnitude of ω will be 2/π 0.6366, which exceeds the correct value for a uniform rotation by a factor of 3/2. It is easy to generate random unit quaternions and, hence, rotations with the correct distribution. Pairs of independent variables with Gaussian distribution can easily be generated using the polar or Box–Muller method, which transforms a point uniformly distributed within the unit disk. The Gaussian generation can be folded into the unit quaternion generation to give an efficient algorithm.} +} + +@InProceedings{shuster1978, + author = {Shuster, Malcolm D.}, + title = {Approximate algorithms for fast optimal attitude computation}, + booktitle = {AIAA Guidance and Control Conference}, + address = {Palo Alto, California}, + year = {1978}, + month = {08}, + doi = {10.2514/6.1978-1249}, + URL = {https://arc.aiaa.org/doi/abs/10.2514/6.1978-1249}, + eprint = {https://www.malcolmdshuster.com/Pub_1978b_C_PaloAlto_scan.pdf} +} + +@article{shuster1981, + author = {Shuster, Malcolm. D. and Oh, S. D.}, + title = {Three-axis Attitude Determination from Vector Observations}, + journal = {Journal of Guidance and Control}, + volume = {4}, + number = {1}, + pages = {70--77}, + year = {1981}, + doi = {10.2514/3.19717}, + url = {https://malcolmdshuster.com/Pub_1981a_J_TRIAD-QUEST_scan.pdf} +} + +@article{shuster2007, + author = {Shuster, Malcolm D.}, + year = {2007}, + month = {04-06}, + pages = {245--257}, + title = {The optimization of TRIAD}, + volume = {55}, + number = {2}, + journal = {The Journal of the Astronautical Sciences}, + doi = {10.1007/BF03256523}, + eprint = {https://www.malcolmdshuster.com/Pub_2007f_J_OptTRIAD_AAS.pdf}, +} + +@techreport{stm4509, + author = {STMicroElectronics}, + title = {Tilt measurement using a low-g 3-axis accelerometer}, + institution = {STMicroelectronics}, + year = {2014}, + month = {06}, + day = {10}, + number = {AN4509}, + note = {Rev 1.0}, + url = {https://www.st.com/resource/en/application_note/dm00119046.pdf}, + address = {}, + annote = {}, + type = {}, +} + +@article{trimpe2012, + author = {Trimpe, Sebastian and D’Andrea, Raffaello}, + journal = {IEEE Control Systems Magazine}, + title = {The Balancing Cube: A Dynamic Sculpture As Test Bed for Distributed Estimation and Control}, + year = {2012}, + volume = {32}, + number = {6}, + pages = {48-75}, + keywords = {Modular designs;Sensors;Mathematical model;Accelerometers;Computational modeling;Noise measurement;State estimation}, + doi = {10.1109/MCS.2012.2214135} +} + +@article{valenti2015, + author = {Valenti, Roberto G. and Dryanovski, Ivan and Xiao, Jizhong}, + title = {Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs}, + journal = {Sensors}, + year = {2015}, + volume = {15}, + number = {8}, + pages = {19302--19330}, + doi = {10.3390/s150819302}, + ISSN = {1424-8220}, + abstract = {Orientation estimation using low cost sensors is an important task for Micro Aerial Vehicles (MAVs) in order to obtain a good feedback for the attitude controller. The challenges come from the low accuracy and noisy data of the MicroElectroMechanical System (MEMS) technology, which is the basis of modern, miniaturized inertial sensors. In this article, we describe a novel approach to obtain an estimation of the orientation in quaternion form from the observations of gravity and magnetic field. Our approach provides a quaternion estimation as the algebraic solution of a system from inertial/magnetic observations. We separate the problems of finding the “tilt” quaternion and the heading quaternion in two sub-parts of our system. This procedure is the key for avoiding the impact of the magnetic disturbances on the roll and pitch components of the orientation when the sensor is surrounded by unwanted magnetic flux. We demonstrate the validity of our method first analytically and then empirically using simulated data. We propose a novel complementary filter for MAVs that fuses together gyroscope data with accelerometer and magnetic field readings. The correction part of the filter is based on the method described above and works for both IMU (Inertial Measurement Unit) and MARG (Magnetic, Angular Rate, and Gravity) sensors. We evaluate the effectiveness of the filter and show that it significantly outperforms other common methods, using publicly available datasets with ground-truth data recorded during a real flight experiment of a micro quadrotor helicopter.}, + PubMedID = {26258778}, + url = {https://www.mdpi.com/1424-8220/15/8/19302}, +} + +@article{valenti2016, + author = {Valenti, Roberto G. and Dryanovski, Ivan and Xiao, Jizhong}, + journal = {IEEE Transactions on Instrumentation and Measurement}, + title = {A Linear Kalman Filter for MARG Orientation Estimation Using the Algebraic Quaternion Algorithm}, + year = {2016}, + volume = {65}, + number = {2}, + pages = {467--481}, + keywords = {Quaternions;Kalman filters;Magnetometers;Estimation;Acceleration;Magnetic sensors;Inertial sensors;Kalman filtering;magnetic sensors;orientation estimation;quaternions.;Inertial sensors;Kalman filtering;magnetic sensors;orientation estimation;quaternions}, + doi = {10.1109/TIM.2015.2498998} +} + +@misc{weiss2016, + author = {Weisstein, Christopher}, + title = {geomag}, + year = {2016}, + month = {01}, + day = {15}, + howpublished = {\url{https://github.com/cmweiss/geomag}}, + note = {Accessed: 2024-09-27} +} + +@techreport{wgs84-2014, + author = {World Geodetic System 1984}, + title = {Department of Defense World Geodetic System 1984: Its Definition and Relationships with Local Geodetic Systems}, + institution = {National Center for Geospatial Intelligence Standards (NCGIS), National Geospatial-Intelligence Agency (NGA)}, + number = {NGA.STND.0036_1.0.0_WGS84}, + note = {Version 1.0.0}, + year = {2014}, + month = {07}, + day = {08}, +} + +@misc{Wiki_SLERP, + author = {Wikipedia}, + title = {SLERP}, + howpublished = {\url{https://en.wikipedia.org/wiki/Slerp}}, + note = {Accessed: 2020-06-12} +} + +@misc{Wiki_Conversions, + author = {Wikipedia}, + title = {Conversion between quaternions and Euler angles}, + howpublished = {\url{https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles}}, + note = {Accessed: 2024-09-27} +} + +@misc{Wiki_DirectionCosine, + author = {Wikipedia}, + title = {Direction Cosine}, + howpublished = {\url{https://en.wikipedia.org/wiki/Direction_cosine}}, + note = {Accessed: 2024-09-27} +} + +@misc{Wiki_Quaternion, + author = {Wikipedia}, + title = {Quaternion}, + howpublished = {\url{https://en.wikipedia.org/wiki/Quaternion}}, + note = {Accessed: 2024-09-27} +} + +@misc{Wolfram_RotationMatrix, + author = {Weisstein, Eric W.}, + title = {Rotation Matrix}, + institution = {MathWorld--A Wolfram Web Resource}, + howpublished = {\url{https://mathworld.wolfram.com/RotationMatrix.htmle}}, + note = {Accessed: 2024-09-27} +} + +@article{wu2018, + author = {Wu, Jin and Zhou, Zebo and Gao, Bin and Li, Rui and Cheng, Yuhua and Fourati, Hassen}, + title = {Fast Linear Quaternion Attitude Estimator Using Vector Observations}, + journal = {IEEE Transactions on Automation Science and Engineering}, + year = {2018}, + volume = {15}, + number = {1}, + pages = {307-319}, + keywords = {Quaternions;Robustness;Eigenvalues and eigenfunctions;Mathematical model;Sensors;Matrix decomposition;Position measurement;Attitude determination;attitude quaternion;eigenvalue problem;pseudoinverse matrix;vector observations;wahba’s problem}, + doi = {10.1109/TASE.2017.2699221} +} + +@article{wu2018-2, + author = {Wu, Jin and Zhou, Zebo and Fourati, Hassen and Cheng, Yuhua}, + title = {A Super Fast Attitude Determination Algorithm for Consumer-Level Accelerometer and Magnetometer}, + journal = {IEEE Transactions on Consumer Electronics}, + year = {2018}, + month = {07}, + volume = {64}, + number = {3}, + doi = {10.1109/TCE.2018.2859625} +} + +@article{yun2008, + author = {Yun, Xiaoping and Bachmann, Eric R. and McGhee, Robert B.}, + journal = {IEEE Transactions on Instrumentation and Measurement}, + title = {A Simplified Quaternion-Based Algorithm for Orientation Estimation From Earth Gravity and Magnetic Field Measurements}, + year = {2008}, + volume = {57}, + number = {3}, + pages = {638-650}, + keywords = {Earth;Gravity;Magnetic field measurement;Quaternions;Magnetic sensors;Accelerometers;Magnetometers;Coordinate measuring machines;Computational efficiency;Azimuth;Accelerometers;inertial sensors;magnetic sensors;motion measurement;orientation estimation;quaternions;Accelerometers;inertial sensors;magnetic sensors;motion measurement;orientation estimation;quaternions}, + doi = {10.1109/TIM.2007.911646} +} + +@article{zhao2013, + author = {Zhao, Facheng and Wachem, Berend}, + year = {2013}, + month = {07}, + pages = {3091--3109}, + title = {A novel Quaternion integration approach for describing the behaviour of non-spherical particles}, + volume = {224}, + journal = {Acta Mechanica}, + doi = {10.1007/s00707-013-0914-2} +} + +@article{zhou2018, + author = {Zhou, Zebo and Wu, Jin and Wang, Jinling and Fourati, Hassen}, + title = {Optimal, Recursive and Sub-Optimal Linear Solutions to Attitude Determination from Vector Observations for GNSS/Accelerometer/Magnetometer Orientation Measurement}, + journal = {Remote Sensing}, + volume = {10}, + year = {2018}, + number = {3}, + article-number = {377}, + url = {https://www.mdpi.com/2072-4292/10/3/377}, + issn = {2072-4292}, + abstract = {The integration of the Accelerometer and Magnetometer (AM) provides continuous, stable and accurate attitude information for land-vehicle navigation without magnetic distortion and external acceleration. However, magnetic disturbance and linear acceleration strongly degrade the overall system performance. As an important complement, the Global Navigation Satellite System (GNSS) produces the heading estimates, thus it can potentially benefit the AM system. Such a GNSS/AM system for attitude estimation is mathematically converted to a multi-observation vector pairs matching problem in this paper. The optimal and sub-optimal attitude determination and their time-varying recursive variants are all comprehensively investigated and discussed. The developed methods are named as the Optimal Linear Estimator of Quaternion (OLEQ), Suboptimal-OLEQ (SOLEQ) and Recursive-OLEQ (ROLEQ) for different application scenarios. The theory is established based on our previous contributions, and the multi-vector matrix multiplications are decomposed with the eigenvalue factorization. Some analytical results are proven and given, which provides the reader with a brand new viewpoint of the attitude determination and its evolution. With the derivations of the two-vector case, the n-vector case is then naturally formed. Simulations are carried out showing the advantages of the accuracy, robustness and time consumption of the proposed OLEQs, compared with representative methods. The algorithms are then implemented using the C++ programming language on the designed hardware with a GNSS module, three-axis accelerometer and three-axis magnetometer, giving an effective validation of them in real-world applications. The designed schemes have proven their fast speed and good accuracy in these verification scenarios.}, + doi = {10.3390/rs10030377} } From a5406bd47eef74d32ff88bdb52969222a11763d0 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Sat, 28 Sep 2024 19:10:47 +0200 Subject: [PATCH 08/15] Add missing bibtex references in WGS submodule. --- ahrs/utils/wgs84.py | 57 +++++++++++++++----------------------------- docs/source/refs.bib | 52 ++++++++++++++++++++++++++++++++++++++++ 2 files changed, 71 insertions(+), 38 deletions(-) diff --git a/ahrs/utils/wgs84.py b/ahrs/utils/wgs84.py index 861538f..461d21b 100644 --- a/ahrs/utils/wgs84.py +++ b/ahrs/utils/wgs84.py @@ -119,7 +119,7 @@ field are so small that they are considered linear for this model. The definition of the **potential of the normal gravity field** :math:`U` -[Heiskanen]_ is: +:cite:p:`hofmann2006` is: .. math:: U = V + \\Phi @@ -201,7 +201,7 @@ Using the property :math:`\\tan\\beta=\\frac{b}{a}\\tan\\phi`, we define a closed form formula to find the normal gravity :math:`\\mathrm{g}` at any given latitude -:math:`\\phi` [Somigliana1929]_: +:math:`\\phi` :cite:p:`somigliana1929`: .. math:: \\mathrm{g}(\\phi) = \\frac{ag_e \\cos^2\\phi + bg_p\\sin^2\\phi}{\\sqrt{a^2\\cos^2\\phi + b^2\\sin^2\\phi}} @@ -243,9 +243,9 @@ Other Gravitational Methods --------------------------- -The well known **International Gravity Formula** [Lambert]_ as described by -Helmut Moritz in [Tscherning]_ for the `Geodetic Reference System 1980 -`_ +The well known **International Gravity Formula** :cite:p:`lambert1945` as +described by Helmut Moritz in 1984 :cite:p:`moritz1984` for the `Geodetic +Reference System 1980 `_ is implemented in ``ahrs``: .. math:: @@ -270,6 +270,9 @@ Although this is thought and mainly used for European latitudes. +Advanced Gravitational Methods +------------------------------ + All methods above can be used for cartography and basic gravitational references. For more advanced and precise estimations it is recommended to use the `EGM2008 `_, @@ -278,7 +281,8 @@ Because of its high complexity and demanding computation, the implementation of the EGM2008 is left out of this module in favour of the more convenient -applications developed in `Fortran by the NGA `_. +applications developed in `Fortran by the NGA +`_. Footnotes --------- @@ -286,30 +290,6 @@ terms of spherical harmonics. But that definition is out of the scope of this package. -References ----------- -.. [WGS84] World Geodetic System 1984. Its Definition and Relationships with - Local Geodetic Systems. National Geospatial-Intelligence Agency (NGA) - Standarization Document. 2014. - (ftp://ftp.nga.mil/pub2/gandg/website/wgs84/NGA.STND.0036_1.0.0_WGS84.pdf) -.. [Heiskanen] Heiskanen, W. A. and Moritz, H. Physical Geodesy. W. H. Freeman - and Company. 1967. -.. [WELMEC2021] WELMEC Directives 2014/31/EU and 2014/32/EU: Common Application. - Non-Automatic Weighing Instruments (NAWI); Automatic Weighing Instruments - (AWI); Multi-dimensional Measuring Instruments (MDMI.) - (https://www.welmec.org/welmec/documents/guides/2/2021/WELMEC_Guide_2_v2021.pdf) -.. [Lambert] Walter D. Lambert. The International Gravity Formula. U.S. Coast - and Geodetic Survey. 1945. (http://earth.geology.yale.edu/~ajs/1945A/360.pdf) -.. [Somigliana1929] Carlo Somigliana. Teoria generale del campo gravitazionale - dell'ellissoide di rotazione. Memorie della Società Astronomia Italiana, - Vol. 4, p.425. 1929 - (http://articles.adsabs.harvard.edu/pdf/1929MmSAI...4..425S) -.. [Tscherning] C. Tscherning. The Geodesist's Handbook 1984. Association - Internationale de Géodésie. 1984. - (https://office.iag-aig.org/doc/5d7f91ee333a3.pdf) -.. [Jekeli2016] C. Jekeli. Geometric Reference Systems in Geodesy. Division of - Geodetic Science, School of Earth Sciences, Ohio State University. 2016. - (https://kb.osu.edu/server/api/core/bitstreams/404dbfb8-da94-5f09-baf4-dbee438ece83/content) """ import numpy as np @@ -329,10 +309,10 @@ def international_gravity(lat: float, epoch: str = '1980') -> float: """ International Gravity Formula - Estimate the normal gravity, :math:`\\mathrm{g}`, using the International Gravity - Formula [Lambert]_, adapted from Stokes' formula, and adopted by the - `International Association of Geodesy `_ at its - Stockholm Assembly in 1930. + Compute the normal gravity, :math:`\\mathrm{g}`, using the International + Gravity Formula :cite:p:`lambert1945`, adapted from Stokes' formula, and + adopted by the `International Association of Geodesy `_ + in 1930. The expression for gravity on a spheroid, which combines gravitational attraction and centrifugal acceleration, at a certain latitude, @@ -428,7 +408,8 @@ def welmec_gravity(lat: float, h: float = 0.0) -> float: Reference normal gravity of WELMEC's gravity zone Gravity zones are implemented by European States on their territories for - weighing instruments that are sensitive to variations of gravity [WELMEC2021]_. + weighing instruments that are sensitive to variations of gravity + :cite:p:`welmec2023`. Manufacturers may adjust their instruments using the reference gravity formula: @@ -494,8 +475,8 @@ def normal_gravity(self, lat: float, h: float = 0.0) -> float: body using Somigliana's formula (on surface) and a series expansion (above surface). - Somigliana's closed formula as desribed by H. Moritz in [Tscherning]_ - is: + Somigliana's closed formula as desribed by H. Moritz in + :cite:p:`moritz1984` is: .. math:: \\mathrm{g} = \\frac{a\\mathrm{g}_e \\cos^2\\phi + b\\mathrm{g}_p\\sin^2\\phi}{\\sqrt{a^2cos^2\\phi + b^2\\sin^2\\phi}} @@ -566,7 +547,7 @@ def vertical_curvature_radius(self, lat: float) -> float: def meridian_curvature_radius(self, lat: float) -> float: """ Radius of the curvature in the prime meridian, estimated at a given - latitude, :math:`\\phi`, as per [Jekeli2016]_: + latitude, :math:`\\phi`, as per :cite:p:`jekeli2016`: .. math:: R_M = \\frac{a(1-e^2)}{(1-e^2\\sin^2\\phi)^{\\frac{3}{2}}} diff --git a/docs/source/refs.bib b/docs/source/refs.bib index 72267fd..152f772 100644 --- a/docs/source/refs.bib +++ b/docs/source/refs.bib @@ -218,6 +218,15 @@ @article{huynh2009 publisher = {Springer} } +@techreport{jekeli2016, + author = {Jekeli, Christopher}, + institution = {Division of Geodesy and Geomatics Engineering. The Ohio State University}, + title = {Geometric Reference Systems in Geodesy}, + year = {2016}, + month = {08}, + url = {http://hdl.handle.net/1811/77986}, +} + @techreport{jia2024, author = {Jia, Yan-Bin}, institution = {Department of Computer Science. Iowa State University}, @@ -292,6 +301,16 @@ @InProceedings{lam2003 eprint = {https://arc.aiaa.org/doi/pdf/10.2514/6.2003-5562} } +@article{lambert1945, + author = {Lambert, Walter D.}, + title = {The International Gravity Formula}, + journal = {American Journal of Science}, + pages = {360--392}, + publisher = {J.D. & E.S. Dana}, + year = {1945}, + url = {http://earth.geology.yale.edu/~ajs/1945A/360.pdf} +} + @book{langel1998, author = {Langel, R. A. and Hinze, W. J.}, title = {The Magnetic Field of the Earth’s Lithosphere: The Satellite Perspective}, @@ -396,6 +415,19 @@ @book{markley2014 doi = {10.1007/978-1-4939-0802-8} } +@inproceedings{moritz1984, + author = {Moritz, Helmut}, + booktitle = {The Geodesist's Handbook 1984}, + editor = {Tscherning, Carl Christian}, + title = {Geodetic Reference Systems}, + year = {1984}, + volume = {58}, + number = {3}, + pages = {388--398}, + publisher = {The International Association of Geodesy}, + url = {https://office.iag-aig.org/doc/5d7f91ee333a3.pdf} +} + @techreport{ozyagcilar2015, author = {Ozyagcilar, Talat}, title = {Implementing a Tilt-Compensated eCompass using Accelerometer and Magnetometer Sensors}, @@ -498,6 +530,17 @@ @misc{sola2017quaternion url = {https://arxiv.org/abs/1711.02508}, } +@article{somigliana1929, + author = {Somigliana, Carlo}, + title = {Teoria generale del campo gravitazionale dell'ellissoide di rotazione}, + journal = {Memorie della Società Astronomia Italiana}, + year = {1929}, + month = {09}, + volume = {4}, + pages = {425--428}, + url = {https://ui.adsabs.harvard.edu/abs/1929MmSAI...4..425S} +} + @inbook{spence1978, author = {Spence Jr, C. B. and Markley, F. Landis}, title = {Attitude Propagation}, @@ -635,6 +678,14 @@ @misc{weiss2016 note = {Accessed: 2024-09-27} } +@techreport{welmec2023, + author = {WELMEC Secretariat}, + institution = {European Cooperation in Legal Metrology}, + title = {WELMEC Guide 2. Guide for Non-automatic Weighing Instruments (NAWI) Automatic Weighing Instruments (AWI) Multi-dimensional Measuring Instruments (MDMI)}, + year = {2023}, + url = {https://www.welmec.org/welmec/documents/guides/2/2023/WELMEC_Guide_2_2023_Guide_for_NAWI_AWI_and_MDMI.pdf} +} + @techreport{wgs84-2014, author = {World Geodetic System 1984}, title = {Department of Defense World Geodetic System 1984: Its Definition and Relationships with Local Geodetic Systems}, @@ -644,6 +695,7 @@ @techreport{wgs84-2014 year = {2014}, month = {07}, day = {08}, + url = {https://nsgreg.nga.mil/doc/view?i=4085}, } @misc{Wiki_SLERP, From 77d70ee23c614904216f8a98b41c83571250c2d3 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Sat, 28 Sep 2024 19:26:48 +0200 Subject: [PATCH 09/15] Update to bibtex citation in submodule metrics. --- ahrs/utils/metrics.py | 35 ++++++++++------------------------- docs/source/refs.bib | 26 ++++++++++++++++++++++++-- 2 files changed, 34 insertions(+), 27 deletions(-) diff --git a/ahrs/utils/metrics.py b/ahrs/utils/metrics.py index 425d465..7f8d4a2 100644 --- a/ahrs/utils/metrics.py +++ b/ahrs/utils/metrics.py @@ -2,16 +2,6 @@ """ Common metrics used in 3D Orientation representations. -References ----------- -.. [Huynh] Huynh, D.Q. Metrics for 3D Rotations: Comparison and Analysis. J - Math Imaging Vis 35, 155-164 (2009). -.. [Kuffner] Kuffner, J.J. Effective Sampling and Distance Metrics for 3D Rigid - Body Path Planning. IEEE International Conference on Robotics and - Automation (ICRA 2004) -.. [Hartley] R. Hartley, J. Trumpf, Y. Dai, H. Li. Rotation Averaging. - International Journal of Computer Vision. Volume 101, Number 2. 2013. - """ import numpy as np @@ -65,7 +55,7 @@ def _quaternions_guard_clauses(q1: Union[list, np.ndarray], q2: Union[list, np.n def euclidean(x: np.ndarray, y: np.ndarray, **kwargs) -> float: """ - Euclidean distance between two arrays as described in [Huynh]_: + Euclidean distance between two arrays as described in :cite:p:`huynh2009`: .. math:: d(\\mathbf{x}, \\mathbf{y}) = \\sqrt{(x_0-y_0)^2 + \\dots + (x_n-y_n)^2} @@ -115,7 +105,7 @@ def chordal(R1: np.ndarray, R2: np.ndarray) -> Union[float, np.ndarray]: The chordal distance between two rotations :math:`\\mathbf{R}_1` and :math:`\\mathbf{R}_2` in SO(3) is the Euclidean distance between them in the embedding space :math:`\\mathbb{R}^{3\\times 3}=\\mathbb{R}^9` - [Hartley]_: + :cite:p:`hartley2013`: .. math:: d(\\mathbf{R}_1, \\mathbf{R}_2) = \\|\\mathbf{R}_1-\\mathbf{R}_2\\|_F @@ -158,7 +148,7 @@ def chordal(R1: np.ndarray, R2: np.ndarray) -> Union[float, np.ndarray]: def identity_deviation(R1: np.ndarray, R2: np.ndarray) -> float: """ - Deviation from Identity Matrix as defined in [Huynh]_: + Deviation from Identity Matrix as defined in :cite:p:`huynh2009`: .. math:: d(\\mathbf{R}_1, \\mathbf{R}_2) = \\|\\mathbf{I}-\\mathbf{R}_1\\mathbf{R}_2^T\\|_F @@ -200,7 +190,7 @@ def identity_deviation(R1: np.ndarray, R2: np.ndarray) -> float: def angular_distance(R1: np.ndarray, R2: np.ndarray) -> float: """ Angular distance between two rotations :math:`\\mathbf{R}_1` and - :math:`\\mathbf{R}_2` in SO(3), as defined in [Hartley]_: + :math:`\\mathbf{R}_2` in SO(3), as defined in :cite:p:`hartley2013`: .. math:: d(\\mathbf{R}_1, \\mathbf{R}_2) = \\|\\log(\\mathbf{R}_1\\mathbf{R}_2^T)\\| @@ -240,8 +230,8 @@ def angular_distance(R1: np.ndarray, R2: np.ndarray) -> float: def qdist(q1: np.ndarray, q2: np.ndarray) -> float: """ - Euclidean distance between two unit quaternions as defined in [Huynh]_ and - [Hartley]_: + Euclidean distance between two unit quaternions as defined in :cite:p:`huynh2009` and + :cite:p:`hartley2013`: .. math:: d(\\mathbf{q}_1, \\mathbf{q}_2) = \\mathrm{min} \\{ \\|\\mathbf{q}_1-\\mathbf{q}_2\\|, \\|\\mathbf{q}_1-\\mathbf{q}_2\\|\\} @@ -287,7 +277,8 @@ def qdist(q1: np.ndarray, q2: np.ndarray) -> float: def qeip(q1: np.ndarray, q2: np.ndarray) -> float: """ - Euclidean distance of inner products as defined in [Huynh]_ and [Kuffner]_: + Euclidean distance of inner products as defined in :cite:p:`huynh2009` and + :cite:p:`kuffner2004`: .. math:: d(\\mathbf{q}_1, \\mathbf{q}_2) = 1 - |\\mathbf{q}_1\\cdot\\mathbf{q}_2| @@ -333,7 +324,7 @@ def qeip(q1: np.ndarray, q2: np.ndarray) -> float: def qcip(q1: np.ndarray, q2: np.ndarray) -> float: """ - Cosine of inner products as defined in [Huynh]_: + Cosine of inner products as defined in :cite:p:`huynh2009`: .. math:: d(\\mathbf{q}_1, \\mathbf{q}_2) = \\arccos(|\\mathbf{q}_1\\cdot\\mathbf{q}_2|) @@ -379,7 +370,7 @@ def qcip(q1: np.ndarray, q2: np.ndarray) -> float: def qad(q1: np.ndarray, q2: np.ndarray) -> float: """ - Quaternion Angle Difference as defined in [Thibaud]_: + Quaternion Angle Difference as defined in :cite:p:`thibaud2017`: .. math:: @@ -412,12 +403,6 @@ def qad(q1: np.ndarray, q2: np.ndarray) -> float: >>> ahrs.utils.qad(q1, -q1) 0.0 - References - ---------- - .. [Thibaud] Thibaud Michel, Pierre Genevès, Hassen Fourati, Nabil Layaïda. - On Attitude Estimation with Smartphones. IEEE International Conference on - Pervasive Computing and Communications, Mar 2017, Kona, United States. - ⟨hal-01376745v2⟩ """ _quaternions_guard_clauses(q1, q2) q1, q2 = np.copy(q1), np.copy(q2) diff --git a/docs/source/refs.bib b/docs/source/refs.bib index 152f772..47820d0 100644 --- a/docs/source/refs.bib +++ b/docs/source/refs.bib @@ -186,6 +186,16 @@ @techreport{hartikainen2011 month = {09}, } +@article{hartley2013, + author = {Hartley, R. and Trumpf, J. and Dai, Y. and Li, H.}, + title = {Rotation Averaging}, + journal = {International Journal of Computer Vision}, + number = {2}, + volume = {101}, + year = {2013}, + doi = {10.1007/s11263-012-0601-0}, +} + @book{hofmann2006, author = {Hofmann-Wellenhof, Bernhard and Moritz, Helmut}, title = {Physical Geodesy}, @@ -253,12 +263,12 @@ @article{kalman1960 @InProceedings{kuffner2004, author = {Kuffner, J.J.}, - booktitle = {IEEE International Conference on Robotics and Automation, 2004. Proceedings. ICRA '04. 2004}, title = {Effective sampling and distance metrics for 3D rigid body path planning}, + booktitle = {IEEE International Conference on Robotics and Automation, 2004. Proceedings. ICRA '04. 2004}, year = {2004}, volume = {4}, number = {}, - pages = {3993-3998 Vol.4}, + pages = {3993--3998}, publisher = {IEEE}, keywords = {Sampling methods;Path planning;Interpolation;Quaternions;Kinematics;Orbital robotics;Satellites;Proteins;Topology;Geophysics computing}, doi = {10.1109/ROBOT.2004.1308895} @@ -629,6 +639,18 @@ @techreport{stm4509 type = {}, } +@InProceedings{thibaud2017, + author = {Michel, Thibaud and Genevès, Pierre and Fourati, Hassen and Layaïda, Nabil}, + booktitle = {2017 IEEE International Conference on Pervasive Computing and Communications (PerCom)}, + title = {On attitude estimation with smartphones}, + year = {2017}, + month = {03}, + pages = {267-275}, + keywords = {Estimation;Smart phones;Magnetometers;Acceleration;Accelerometers;Algorithm design and analysis;Context}, + doi = {10.1109/PERCOM.2017.7917873}, + url = {https://inria.hal.science/hal-01376745v2}, +} + @article{trimpe2012, author = {Trimpe, Sebastian and D’Andrea, Raffaello}, journal = {IEEE Control Systems Magazine}, From 5de6584661b689bf34f33246f5c0874ba1b03a98 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Sun, 29 Sep 2024 18:45:16 +0200 Subject: [PATCH 10/15] Complete conversion of references to bibtex. --- ahrs/common/constants.py | 44 ++++----------- ahrs/common/dcm.py | 10 +--- ahrs/common/mathfuncs.py | 7 +-- ahrs/common/orientation.py | 40 ++++---------- ahrs/common/quaternion.py | 4 +- docs/source/refs.bib | 108 ++++++++++++++++++++++++++++++++++++- 6 files changed, 131 insertions(+), 82 deletions(-) diff --git a/ahrs/common/constants.py b/ahrs/common/constants.py index 805c96b..0cbca3a 100644 --- a/ahrs/common/constants.py +++ b/ahrs/common/constants.py @@ -20,9 +20,10 @@ **Geodesy** The following constants are set as defined in the latest report of the World -Geodetic System 1984 [WGS84]_ and can be compared against [Chambat]_. The -CODATA constants are differentiated with a suffix of their origin indicating -their epoch as of [CODATA2014]_ or [CODATA2018]_. +Geodetic System 1984 :cite:p:`wgs84-2014` and can be compared against +:cite:p:`chambat2001`. The CODATA constants :cite:p:`mohr2016` and +:cite:p:`tiesinga2021` are differentiated with an ending indicating their epoch +as ``CODATA2014`` and ``CODATA2018`` respectively. ==================================== ============================================== ============= Name Description Value @@ -67,9 +68,9 @@ ``UNIVERSAL_GRAVITATION_WGS84`` Universal Gravitation defined in WGS84 ``6.67428e-11`` ==================================== ============================================== ============= -The values above are set as defined in [WGS84]_, although most of these values -can be also obtained with the class ``WGS`` of this package, which builds the -World's Geodetic System independently. +The values above are set as defined in :cite:p:`wgs84-2014`, although most of +these values can be also obtained with the class ``WGS`` of this package, which +builds the World's Geodetic System independently. The elemental defining parameters (equatorial radius, flattening, gravitational constant and rotational velocity) are set, by default, to that of Earth's, and @@ -93,8 +94,9 @@ 0.0066943799901413165 These values are, so far, determined for the Earth. However, other celestial -bodies have been measured and their values are, as defined in [Archinal]_, -[Park]_ and [Williams]_, set as follows: +bodies have been measured and their values are, as defined in +:cite:p:`archinal2018`, :cite:p:`park2019` and :cite:p:`williams2024`, set as +follows: ========================== ========================== Name Value @@ -145,32 +147,6 @@ ``PLUTO_MASS`` ``1.303e22`` ========================== ========================== -References ----------- -.. [WGS84] World Geodetic System 1984. Its Definition and Relationships with - Local Geodetic Systems. National Geospatial-Intelligence Agency (NGA) - Standarization Document. 2014. - (ftp://ftp.nga.mil/pub2/gandg/website/wgs84/NGA.STND.0036_1.0.0_WGS84.pdf) -.. [Chambat] F. Chambat. Mean radius, mass, and inertia for reference Earth - models. Physics of the Earth and Planetary Interiors Vol 124 (2001) - p237–253. -.. [Archinal] Archinal, B.A. et al. 2018. "Report of the IAU/IAG Working Group - on cartographic coordinates and rotational elements: 2015" Celestial Mech. - Dyn. Astr. 130:22. - (https://astropedia.astrogeology.usgs.gov/download/Docs/WGCCRE/WGCCRE2015reprint.pdf) -.. [CODATA2018] 2018 CODATA Recommended Values of the Fundamental Constants of - Physics and Chemistry. NIST. June 2019. - (https://physics.nist.gov/cuu/pdf/wallet_2018.pdf) -.. [CODATA2014] 2014 CODATA Recommended Values of the Fundamental Constants of - Physics and Chemistry. NIST. August 2015. - (https://physics.nist.gov/cuu/pdf/wallet_2014.pdf) -.. [Park] Ryan S. Park. Planets and Pluto: Physical Characteristics. NASA Jet - Propulsion Laboratory. California Institute of Technology. 29th May 2020. - (https://ssd.jpl.nasa.gov/?planet_phys_par) -.. [Williams] David R. Williams. Planetary Fact Sheet - Metric. NASA Goddard - Space Flight Center. 21st October 2019. - (https://nssdc.gsfc.nasa.gov/planetary/factsheet/) - """ import math diff --git a/ahrs/common/dcm.py b/ahrs/common/dcm.py index 414cb38..9765863 100644 --- a/ahrs/common/dcm.py +++ b/ahrs/common/dcm.py @@ -604,7 +604,7 @@ def log(self) -> np.ndarray: Logarithm of DCM. The logarithmic map is defined as the inverse of the exponential map - [Cardoso]_ . It corresponds to the logarithm given by the Rodrigues + :cite:p:`cardoso2009`. It corresponds to the logarithm given by the Rodrigues rotation formula: .. math:: @@ -639,14 +639,6 @@ def log(self) -> np.ndarray: [-0.26026043, 0. , 0.5473806 ], [-0.29531805, -0.5473806 , 0. ]]) - Reference - --------- - .. [Cardoso] J. Cardoso and F. Silva Leite. Exponentials of - skew-symmetric matrices and logarithms of orthogonal matrices. - Journal of Computational and Applied Mathematics. Volume 233, Issue - 11, 1 April 2010, Pages 2867-2875. - (https://www.sciencedirect.com/science/article/pii/S0377042709007791) - """ trace_R = self.A.trace() if np.isclose(trace_R, 3.0): diff --git a/ahrs/common/mathfuncs.py b/ahrs/common/mathfuncs.py index adf12ac..440be0d 100644 --- a/ahrs/common/mathfuncs.py +++ b/ahrs/common/mathfuncs.py @@ -76,7 +76,8 @@ def sind(x): def skew(x): """ - Return the 3-by-3 skew-symmetric matrix [Wiki_skew]_ of a 3-element vector x. + Return the 3-by-3 skew-symmetric matrix :cite:p:`Wiki_skew` of a 3-element + vector ``x``. Parameters ---------- @@ -102,10 +103,6 @@ def skew(x): [ 6. 0. -4.] [-5. 4. 0.]] - References - ---------- - .. [Wiki_skew] https://en.wikipedia.org/wiki/Skew-symmetric_matrix - """ if isinstance(x, (list, tuple, np.ndarray)): x = np.copy(x) diff --git a/ahrs/common/orientation.py b/ahrs/common/orientation.py index 2a41ae0..4314e9e 100644 --- a/ahrs/common/orientation.py +++ b/ahrs/common/orientation.py @@ -53,13 +53,6 @@ def q_conj(q: np.ndarray) -> np.ndarray: [ 0.578965, -0.202390, -0.280560, -0.738321], [ 0.848611, -0.442224, -0.112601, -0.267611]]) - References - ---------- - .. [1] Dantam, N. (2014) Quaternion Computation. Institute for Robotics - and Intelligent Machines. Georgia Tech. - (http://www.neil.dantam.name/note/dantam-quaternion.pdf) - .. [2] https://en.wikipedia.org/wiki/Quaternion#Conjugation,_the_norm,_and_reciprocal - """ q = np.copy(q) if q.ndim > 2 or q.shape[-1] != 4: @@ -106,8 +99,8 @@ def q_random(size: int = 1) -> np.ndarray: def q_norm(q: np.ndarray) -> np.ndarray: """ - Normalize quaternion [WQ1]_ :math:`\\mathbf{q}_u`, also known as a versor - [WV1]_ : + Normalize quaternion :cite:p:`Wiki_Quaternion` :math:`\\mathbf{q}_u`, also + known as a versor :cite:p:`Wiki_Versor`: .. math:: @@ -141,11 +134,6 @@ def q_norm(q: np.ndarray) -> np.ndarray: >>> np.linalg.norm(q) 1.0 - References - ---------- - .. [WQ1] https://en.wikipedia.org/wiki/Quaternion#Unit_quaternion - .. [WV1] https://en.wikipedia.org/wiki/Versor - """ if q.ndim > 2 or q.shape[-1] != 4: raise ValueError(f"Quaternion must be of shape (4,) or (N, 4), but has shape {q.shape}") @@ -158,7 +146,8 @@ def q_prod(p: np.ndarray, q: np.ndarray) -> np.ndarray: Product of two unit quaternions. Given two unit quaternions :math:`\\mathbf{p}=(p_w, \\mathbf{p}_v)` and - :math:`\\mathbf{q} = (q_w, \\mathbf{q}_v)`, their product is defined [ND]_ [MWQW]_ + :math:`\\mathbf{q} = (q_w, \\mathbf{q}_v)`, their product is defined + :cite:p:`dantam2014` :cite:p:`MathWorks_QuaternionMultiplication`. as: .. math:: @@ -214,14 +203,6 @@ def q_prod(p: np.ndarray, q: np.ndarray) -> np.ndarray: >>> quaternion.q_prod(q[0], q[1]) array([-0.36348726, 0.38962514, 0.34188103, 0.77407146]) - References - ---------- - .. [ND] Dantam, N. (2014) Quaternion Computation. Institute for Robotics - and Intelligent Machines. Georgia Tech. - (http://www.neil.dantam.name/note/dantam-quaternion.pdf) - .. [MWQM] Mathworks: Quaternion Multiplication. - https://www.mathworks.com/help/aeroblks/quaternionmultiplication.html - """ pq = np.zeros(4) pq[0] = p[0]*q[0] - p[1]*q[1] - p[2]*q[2] - p[3]*q[3] @@ -540,8 +521,9 @@ def rotation(ax: Union[str, int] = None, ang: float = 0.0, degrees: bool = False """ Return a Direction Cosine Matrix - The rotation matrix :math:`\\mathbf{R}` [1]_ is created for the given axis - with the given angle :math:`\\theta`. Where the possible rotation axes are: + The rotation matrix :math:`\\mathbf{R}` :cite:p:`Wolfram_RotationMatrix` is + created for the given axis with the given angle :math:`\\theta`. Where the + possible rotation axes are: .. math:: @@ -613,10 +595,6 @@ def rotation(ax: Union[str, int] = None, ang: float = 0.0, degrees: bool = False [0. 1. 0.], [0. 0. 1.]]) - References - ---------- - .. [1] http://mathworld.wolfram.com/RotationMatrix.html - """ # Default values valid_axes = list('xyzXYZ') @@ -1559,7 +1537,7 @@ def itzhack(dcm: np.ndarray, version: int = 3) -> np.ndarray: and :math:`\\mathbf{a}` are a set of nonnegative weights assign to each pair. - Paul Davenport [Davenport1968]_ finds the optimal quaternion, + Paul Davenport :cite:p:`davenport1968` finds the optimal quaternion, :math:`\\mathbf{q}^*`, that minimizes the cost function, through the eigenvalue decomposition of the matrix :math:`\\mathbf{K}`: @@ -1778,7 +1756,7 @@ def itzhack(dcm: np.ndarray, version: int = 3) -> np.ndarray: def shepperd(dcm: np.ndarray) -> np.ndarray: """ Quaternion from a Direction Cosine Matrix with Shepperd's method - :cite:p:`Shepperd1978`. + :cite:p:`shepperd1978`. Since it was proposed in 1978, the Shepperd method has been widely used in the aerospace industry. diff --git a/ahrs/common/quaternion.py b/ahrs/common/quaternion.py index 5cd12a0..0ada01a 100644 --- a/ahrs/common/quaternion.py +++ b/ahrs/common/quaternion.py @@ -1105,7 +1105,7 @@ def __mul__(self, q: np.ndarray) -> np.ndarray: Given two unit quaternions :math:`\\mathbf{p}=(p_w, p_x, p_y, p_z)` and :math:`\\mathbf{q} = (q_w, q_x, q_y, q_z)`, their product is obtained - :cite:p:`dantam2014` [MWQW]_ as: + :cite:p:`dantam2014` :cite:p:`MathWorks_QuaternionMultiplication` as: .. math:: @@ -1149,7 +1149,7 @@ def __matmul__(self, q: np.ndarray) -> np.ndarray: Given two unit quaternions :math:`\\mathbf{p}=(p_w, p_x, p_y, p_z)` and :math:`\\mathbf{q} = (q_w, q_x, q_y, q_z)`, their product is obtained - :cite:p:`dantam2014` [MWQW]_ as: + :cite:p:`dantam2014` :cite:p:`MathWorks_QuaternionMultiplication` as: .. math:: \\mathbf{pq} = diff --git a/docs/source/refs.bib b/docs/source/refs.bib index 47820d0..7dc3294 100644 --- a/docs/source/refs.bib +++ b/docs/source/refs.bib @@ -1,3 +1,13 @@ +@article{archinal2018, + author = {Archinal, B. and A’hearn, M. and Conrad, Al and Consolmagno, Guy and Hestroffer, D. and Hilton, James and Krasinsky, G. and Neumann, G. and Oberst, Jürgen and Ping, J. and Seidelmann, P. and Tholen, David and Thomas, P. and Williams, Iwan}, + title = {Report of the IAU Working Group on Cartographic Coordinates and Rotational Elements: 2015}, + journal = {Celestial Mechanics and Dynamical Astronomy}, + year = {2018}, + volume = {130}, + number = {22}, + doi = {10.1007/s10569-017-9805-5} +} + @article{BarItzhack2000, author = {Itzhack Yoav Bar-Itzhack}, title = {New method for Extracting the Quaternion from a Rotation Matrix}, @@ -21,6 +31,29 @@ @article{black1964 doi = {10.2514/3.2555} } +@article{cardoso2009, + author = {Cardoso, João R. and Silva Leite, F.}, + title = {Exponentials of skew-symmetric matrices and logarithms of orthogonal matrices}, + journal = {Journal of Computational and Applied Mathematics}, + volume = {233}, + number = {11}, + year = {2009}, + month = {04}, + pages = {2867--2875}, + doi = {10.1016/j.cam.2009.11.032} +} + +@article{chambat2001, + author = {Chambat, Frédéric and Valette, Bernard}, + title = {Mean radius, mass, and inertia for reference Earth models}, + journal = {Physics of the Earth and Planetary Interiors}, + volume = {124}, + number = {3--4}, + pages = {237--253}, + year = {2001}, + doi = {10.1016/S0031-9201(01)00200-X} +} + @article{Chiaverini1999, author = {Chiaverini, Stefano and Siciliano, Bruno}, year = {1999}, @@ -425,6 +458,22 @@ @book{markley2014 doi = {10.1007/978-1-4939-0802-8} } +@article{mohr2016, + author = {Mohr, Peter J. and Newell, David B. and Taylor, Barry N.}, + title = {CODATA Recommended Values of the Fundamental Physical Constants: 2014}, + journal = {Journal of Physical and Chemical Reference Data}, + volume = {45}, + number = {4}, + pages = {043102}, + year = {2016}, + month = {11}, + abstract = {This paper gives the 2014 self-consistent set of values of the constants and conversion factors of physics and chemistry recommended by the Committee on Data for Science and Technology (CODATA). These values are based on a least-squares adjustment that takes into account all data available up to 31 December 2014. Details of the data selection and methodology of the adjustment are described. The recommended values may also be found at http://physics.nist.gov/constants.}, + issn = {0047-2689}, + doi = {10.1063/1.4954402}, + url = {https://www.nist.gov/publications/codata-recommended-values-fundamental-physical-constants-2014}, + eprint = {https://pubs.aip.org/aip/jpr/article-pdf/doi/10.1063/1.4954402/16741741/043102\_1\_online.pdf}, +} + @inproceedings{moritz1984, author = {Moritz, Helmut}, booktitle = {The Geodesist's Handbook 1984}, @@ -466,6 +515,16 @@ @techreport{ozyagcilar2015-2 type = {}, } +@misc{park2019, + author = {Park, Ryan}, + title = {Planetary Physical Parameters}, + year = {2019}, + month = {12}, + day = {12}, + howpublished = {\url{https://ssd.jpl.nasa.gov/planets/phys_par.html}}, + note = {Accessed: 2024-09-28} +} + @techreport{pedley2013, author = {Pedley, Mark}, title = {Tilt Sensing Using a Three-Axis Accelerometer}, @@ -651,6 +710,20 @@ @InProceedings{thibaud2017 url = {https://inria.hal.science/hal-01376745v2}, } +@article{tiesinga2021, + author = {Tiesinga, Eite and Mohr, Peter J. and Newell, David B. and Taylor, Barry N.}, + title = {CODATA recommended values of the fundamental physical constants: 2018}, + journal = {Reviews of Modern Physics}, + year = {2021}, + month = {Apr--Jun}, + volume = {93}, + issue = {2}, + numpages = {63}, + publisher = {American Physical Society}, + doi = {10.1103/RevModPhys.93.025010}, + url = {https://www.nist.gov/publications/codata-recommended-values-fundamental-physical-constants-2018} +} + @article{trimpe2012, author = {Trimpe, Sebastian and D’Andrea, Raffaello}, journal = {IEEE Control Systems Magazine}, @@ -748,11 +821,44 @@ @misc{Wiki_Quaternion note = {Accessed: 2024-09-27} } +@misc{Wiki_Skew, + author = {Wikipedia}, + title = {Skew-symmetric matrix}, + howpublished = {\url{https://en.wikipedia.org/wiki/Skew-symmetric_matrix}}, + note = {Accessed: 2024-09-28} +} + +@misc{Wiki_Versor, + author = {Wikipedia}, + title = {Versor}, + howpublished = {\url{https://en.wikipedia.org/wiki/Versor}}, + note = {Accessed: 2024-09-28} +} + +@misc{williams2024, + author = {Park, Ryan}, + title = {Planetary Fact Sheet - Metric}, + institution = {NASA Goddard Space Flight Center}, + year = {2024}, + month = {03}, + day = {22}, + howpublished = {\url{https://nssdc.gsfc.nasa.gov/planetary/factsheet/}}, + note = {Accessed: 2024-09-28} +} + +@misc{MathWorks_QuaternionMultiplication, + author = {Mathworks}, + title = {quatmultiply}, + institution = {The MathWorks, Inc.}, + howpublished = {\url{https://www.mathworks.com/help/aerotbx/ug/quatmultiply.html}}, + note = {Accessed: 2024-09-28} +} + @misc{Wolfram_RotationMatrix, author = {Weisstein, Eric W.}, title = {Rotation Matrix}, institution = {MathWorld--A Wolfram Web Resource}, - howpublished = {\url{https://mathworld.wolfram.com/RotationMatrix.htmle}}, + howpublished = {\url{https://mathworld.wolfram.com/RotationMatrix.html}}, note = {Accessed: 2024-09-27} } From 5d1319dcf73287611f6e4d02a2f9185b64723e93 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Sun, 29 Sep 2024 18:46:58 +0200 Subject: [PATCH 11/15] Correct equation of Taylor series in Quaternion Linearization. --- ahrs/filters/angular.py | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/ahrs/filters/angular.py b/ahrs/filters/angular.py index cd9aab9..04920fe 100644 --- a/ahrs/filters/angular.py +++ b/ahrs/filters/angular.py @@ -166,7 +166,8 @@ Using the `Euler-Rodrigues rotation formula `_ -and the exponential map from above we find a **closed-form solution** [Wertz]_: +and the exponential map from above we find a **closed-form solution** +:cite:p:`spence1978`: .. math:: \\mathbf{q}_{t+1} = @@ -199,7 +200,7 @@ \\frac{1}{3!}\\dddot{\\mathbf{q}}_t\\Delta t^3 + \\cdots Using the definition of :math:`\\dot{\\mathbf{q}}` the new orientation -:math:`\\mathbf{q}_{t+1}` is written as [Wertz]_: +:math:`\\mathbf{q}_{t+1}` is written as :cite:p:`spence1978`: .. math:: \\begin{array}{rcl} @@ -208,8 +209,8 @@ \\frac{1}{3!}\\Big(\\frac{1}{2}\\boldsymbol\\Omega(\\boldsymbol\\omega)\\Delta t\\Big)^3 + \\cdots\\Bigg]\\mathbf{q}_t \\\\ && \\qquad{} + \\frac{1}{4}\\dot{\\boldsymbol\\Omega}(\\boldsymbol\\omega)\\Delta t^2\\mathbf{q}_t + \\Big[\\frac{1}{12}\\dot{\\boldsymbol\\Omega}(\\boldsymbol\\omega)\\boldsymbol\\Omega(\\boldsymbol\\omega) - + \\frac{1}{24}\\boldsymbol\\Omega(\\boldsymbol\\omega)\\dot{\\boldsymbol\\Omega}(\\boldsymbol\\omega) - + \\frac{1}{12}\\ddot{\\boldsymbol\\Omega}(\\boldsymbol\\omega)\\Big]\\Delta t^3\\mathbf{q}_t + + \\frac{1}{24}\\boldsymbol\\Omega(\\boldsymbol\\omega)\\dot{\\boldsymbol\\Omega}(\\boldsymbol\\omega)\\Big]\\Delta t^3\\mathbf{q}_t + + \\frac{1}{12}\\ddot{\\boldsymbol\\Omega}(\\boldsymbol\\omega)\\Delta t^3\\mathbf{q}_t + \\cdots \\end{array} @@ -222,11 +223,6 @@ \\frac{1}{2!}\\Big(\\frac{1}{2}\\boldsymbol\\Omega(\\boldsymbol\\omega)\\Delta t\\Big)^2 + \\frac{1}{3!}\\Big(\\frac{1}{2}\\boldsymbol\\Omega(\\boldsymbol\\omega)\\Delta t\\Big)^3 + \\cdots\\Bigg]\\mathbf{q}_t -The error of the approximation vanishes rapidly at higher orders, or when the -time step :math:`\\Delta t \\to 0`. The more terms we have, the better our -approximation should be, assuming the sensor signals are unbiased and noiseless, -with the downside of a big computational demand. - Notice the series for :math:`\\mathbf{q}_{t+1}` also follows the form of the matrix exponential: @@ -234,6 +230,11 @@ e^{\\frac{\\Delta t}{2}\\boldsymbol\\Omega(\\boldsymbol\\omega)} = \\sum_{k=0}^\\infty \\frac{1}{k!} \\Big(\\frac{\\Delta t}{2}\\boldsymbol\\Omega(\\boldsymbol\\omega)\\Big)^k +The error of the approximation vanishes rapidly at higher orders (:math:`k \\to +0`), or when the time step :math:`\\Delta t \\to 0`. The more terms we have, +the better our approximation should be, assuming the sensor signals are +unbiased and noiseless, with the downside of a big computational demand. + For our purpose a truncation up to the second term, making it of first order (:math:`k=1`), is implemented. From aeef6dcecab851c9ce658630f0014af7bbc970b1 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Sun, 29 Sep 2024 19:22:23 +0200 Subject: [PATCH 12/15] Fix equation of quaternion derivative in footnote, and add context. --- ahrs/filters/angular.py | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/ahrs/filters/angular.py b/ahrs/filters/angular.py index 04920fe..5ef57ec 100644 --- a/ahrs/filters/angular.py +++ b/ahrs/filters/angular.py @@ -270,12 +270,15 @@ .. math:: \\begin{array}{rcl} - \\dot{\\mathbf{q}} &=& \\frac{1}{2}\\mathbf{q}\\boldsymbol\\omega \\\\ - \\ddot{\\mathbf{q}} &=& \\frac{1}{4}\\mathbf{q}\\boldsymbol\\omega^2 + \\frac{1}{2}\\mathbf{q}\\dot{\\boldsymbol\\omega} \\\\ - \\dddot{\\mathbf{q}} &=& \\frac{1}{6}\\mathbf{q}\\boldsymbol\\omega^3 + \\frac{1}{4}\\mathbf{q}\\dot{\\boldsymbol\\omega}\\boldsymbol\\omega + \\frac{1}{2}\\mathbf{q}\\boldsymbol\\omega\\dot{\\boldsymbol\\omega} \\\\ - \\mathbf{q}^{i\\geq 4} &=& \\frac{1}{2^i}\\mathbf{q}\\boldsymbol\\omega^i + \\cdots + \\dot{\\mathbf{q}}_n &=& \\frac{1}{2}\\mathbf{q}_n\\boldsymbol\\omega_n \\\\ + \\ddot{\\mathbf{q}}_n &=& \\frac{1}{4}\\mathbf{q}_n\\boldsymbol\\omega^2_n + \\frac{1}{2}\\mathbf{q}_n\\dot{\\boldsymbol\\omega} \\\\ + \\dddot{\\mathbf{q}}_n &=& \\frac{1}{2^3}\\mathbf{q}_n\\boldsymbol\\omega^3_n + \\frac{1}{4}\\mathbf{q}_n\\dot{\\boldsymbol\\omega}\\boldsymbol\\omega_n + \\frac{1}{2}\\mathbf{q}\\boldsymbol\\omega_n\\dot{\\boldsymbol\\omega} \\\\ + \\mathbf{q}^{i\\geq 4}_n &=& \\frac{1}{2^i}\\mathbf{q}_n\\boldsymbol\\omega^i_n + \\cdots \\end{array} + where all products and the powers of :math:`\\boldsymbol\\omega` are + interpreted in terms of the quaternion product. + """ import numpy as np From d5bc3c5623d17b13d8d827d20bfb9e201fe7a427 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Tue, 1 Oct 2024 14:30:33 +0200 Subject: [PATCH 13/15] Fix examples in docstring of DCM to use DEG2RAD. --- ahrs/common/dcm.py | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/ahrs/common/dcm.py b/ahrs/common/dcm.py index 9765863..f55929f 100644 --- a/ahrs/common/dcm.py +++ b/ahrs/common/dcm.py @@ -319,6 +319,7 @@ class DCM(np.ndarray): All DCM are created as an identity matrix, which means no rotation. >>> from ahrs import DCM + >>> from ahrs import DEG2RAD >>> DCM() DCM([[1., 0., 0.], [0., 1., 0.], @@ -327,15 +328,15 @@ class DCM(np.ndarray): A rotation around a single axis can be defined by giving the desired axis and its value, in degrees. - >>> DCM(x=10.0) + >>> DCM(x=10.0*DEG2RAD) DCM([[ 1. , 0. , 0. ], [ 0. , 0.98480775, -0.17364818], [ 0. , 0.17364818, 0.98480775]]) - >>> DCM(y=20.0) + >>> DCM(y=20.0*DEG2RAD) DCM([[ 0.93969262, 0. , 0.34202014], [ 0. , 1. , 0. ], [-0.34202014, 0. , 0.93969262]]) - >>> DCM(z=30.0) + >>> DCM(z=30.0*DEG2RAD) DCM([[ 0.8660254, -0.5 , 0. ], [ 0.5 , 0.8660254, 0. ], [ 0. , 0. , 1. ]]) @@ -343,7 +344,7 @@ class DCM(np.ndarray): If we want a rotation conforming the roll-pitch-yaw sequence, we can give the corresponding angles. - >>> DCM(rpy=[30.0, 20.0, 10.0]) + >>> DCM(rpy=np.array([30.0, 20.0, 10.0])*DEG2RAD) DCM([[ 0.81379768, -0.44096961, 0.37852231], [ 0.46984631, 0.88256412, 0.01802831], [-0.34202014, 0.16317591, 0.92541658]]) @@ -352,7 +353,7 @@ class DCM(np.ndarray): Notice the angles are given in reverse order, as it is the way the matrices are multiplied. - >>> DCM(z=30.0) @ DCM(y=20.0) @ DCM(x=10.0) + >>> DCM(z=30.0*DEG2RAD) @ DCM(y=20.0*DEG2RAD) @ DCM(x=10.0*DEG2RAD) DCM([[ 0.81379768, -0.44096961, 0.37852231], [ 0.46984631, 0.88256412, 0.01802831], [-0.34202014, 0.16317591, 0.92541658]]) @@ -361,11 +362,11 @@ class DCM(np.ndarray): elements: the order of the axis to rotate about, and the value of the rotation angles (again in reverse order) - >>> DCM(euler=('zyz', [40.0, 50.0, 60.0])) + >>> DCM(euler=('zyz', np.array([40.0, 50.0, 60.0])*DEG2RAD)) DCM([[-0.31046846, -0.74782807, 0.58682409], [ 0.8700019 , 0.02520139, 0.49240388], [-0.38302222, 0.66341395, 0.64278761]]) - >>> DCM(z=40.0) @ DCM(y=50.0) @ DCM(z=60.0) + >>> DCM(z=40.0*DEG2RAD) @ DCM(y=50.0*DEG2RAD) @ DCM(z=60.0*DEG2RAD) DCM([[-0.31046846, -0.74782807, 0.58682409], [ 0.8700019 , 0.02520139, 0.49240388], [-0.38302222, 0.66341395, 0.64278761]]) @@ -383,7 +384,7 @@ class DCM(np.ndarray): Finally, we can also build the rotation matrix from an axis-angle representation: - >>> DCM(axang=([1., 2., 3.], 60.0)) + >>> DCM(axang=([1., 2., 3.], 60.0*DEG2RAD)) DCM([[-0.81295491, 0.52330834, 0.25544608], [ 0.03452394, -0.3945807 , 0.91821249], [ 0.58130234, 0.75528436, 0.30270965]]) From 4f4ae100f6372a59a6f182fed55d111aea19bab6 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Tue, 1 Oct 2024 14:34:06 +0200 Subject: [PATCH 14/15] Add Jupyter Notebook to showcase basic implementations of ahrs. --- notebooks/Showcase.ipynb | 482 +++++++++++++++++++++++++++++++++++++++ notebooks/tools.py | 380 ++++++++++++++++++++++++++++++ 2 files changed, 862 insertions(+) create mode 100644 notebooks/Showcase.ipynb create mode 100644 notebooks/tools.py diff --git a/notebooks/Showcase.ipynb b/notebooks/Showcase.ipynb new file mode 100644 index 0000000..7b1ac6d --- /dev/null +++ b/notebooks/Showcase.ipynb @@ -0,0 +1,482 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "e9072b21-4c8a-4dc3-8110-2edfafe869bf", + "metadata": {}, + "source": [ + "# AHRS\n", + "\n", + "This Notebook showcases the most important classes and functions included in the Python package `ahrs`.\n", + "\n", + "Here we will explore the basic use of:\n", + "\n", + "- Class [DCM](https://ahrs.readthedocs.io/en/latest/dcm/classDCM.html)\n", + "- Class [Quaternion](https://ahrs.readthedocs.io/en/latest/quaternion/classQuaternion.html)\n", + "- Class [QuaternionArray](https://ahrs.readthedocs.io/en/latest/quaternion/classQuaternionArray.html)\n", + "- Some [Attitude estimation algorithms](https://ahrs.readthedocs.io/en/latest/filters.html)\n", + "- The [World Magnetic Model](https://ahrs.readthedocs.io/en/latest/wmm.html)\n", + "- The [World Geodetic System](https://ahrs.readthedocs.io/en/latest/wgs84.html)\n", + "- [Metrics functions](https://ahrs.readthedocs.io/en/latest/metrics.html) for orientation representations.\n", + "- And diverse tools included in `ahrs`.\n", + "\n", + "## Helping Packages\n", + "\n", + "Plotting and data-handling tools are imported from the script `tools.py` located in the current directory. These tools simplify the visualization of orientations in 3d, or time-series data, but are **NOT** included in the `ahrs` package.\n", + "\n", + "Packages `matplotlib` and `ipympl` are required to build interactive visualizations in the Notebook. Make sure you have those installed.\n", + "\n", + "Once you have `ahrs` installed (which also installs `numpy`) and you have the forementioned libraries, we can start by setting our notebook up." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "id": "65b78e9a", + "metadata": {}, + "outputs": [], + "source": [ + "# Use widgets\n", + "%matplotlib widget\n", + "\n", + "# Import NumPy\n", + "import numpy as np\n", + "\n", + "# Seed random generator\n", + "GENERATOR = np.random.default_rng(42)\n", + "\n", + "# Import plotting tools\n", + "from tools import plot\n", + "from tools import plot3" + ] + }, + { + "cell_type": "markdown", + "id": "54f309e6-e977-4944-96ff-b726738ea81c", + "metadata": {}, + "source": [ + "### Helping functions\n", + "\n", + "The plotting functions imported from the script `tools.py` in the current directory simplify the visualization of orientations in 3d, or time-series data. These two functions are:\n", + "\n", + "- `plot` shows time-series data in vertically stacked plots.\n", + "- `plot3` shows a 3D scene, where particles, frames, and items exist and interact in the same space.\n", + "\n", + "These functions use `matplotlib` with the `ipympl` backend to use interactive visualizations in the Notebook. Make sure you have those installed.\n", + "\n", + "## AHRS Basics\n", + "\n", + "We can start now. Let's import our favorite package." + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "4e670fb6-1974-4705-bece-0b40a183a99d", + "metadata": {}, + "outputs": [], + "source": [ + "import ahrs" + ] + }, + { + "cell_type": "markdown", + "id": "1a8c2f0f-9986-4b91-97eb-e6cf15edbce3", + "metadata": {}, + "source": [ + "## Attitude Representations\n", + "\n", + "The first elements we want to manipulate and use are the representations of any Attitude (that's the \"A\" in AHRS.)\n", + "\n", + "There are many ways to mathematically represent the attitude:\n", + "\n", + "1. Direction Cosine Matrix.\n", + "2. Euler Angles.\n", + "3. Axis-Angle.\n", + "4. Quaternion.\n", + "\n", + "Let's check the most intuitive first.\n", + "\n", + "### Direction Cosine Matrix\n", + "\n", + "The [Direction Cosine Matrix](https://ahrs.readthedocs.io/en/latest/dcm.html)can be built with the class [DCM](https://ahrs.readthedocs.io/en/latest/dcm/classDCM.html). This represents either:\n", + "\n", + "- the **orientation** of a frame in 3D space with respect to another reference frame in the same space, or\n", + "- the **linear operation**, where a point (or points) is (are) rotated according the rotation described in the DCM.\n", + "\n", + "Normally the global frame is represented by the 3x3 Identity matrix." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "c07441ae-945d-4872-bec0-b988bd4328b7", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Global frame:\n", + "[[1. 0. 0.]\n", + " [0. 1. 0.]\n", + " [0. 0. 1.]]\n" + ] + }, + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "af951b8628e04da1a5dd3dc9308a7701", + "version_major": 2, + "version_minor": 0 + }, + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAoAAAAHgCAYAAAA10dzkAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMCwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy88F64QAAAACXBIWXMAAA9hAAAPYQGoP6dpAACus0lEQVR4nOydeXwU9fnHP7ObZI8EBESCRBS8b1CQCHhADSJngj28KnjXA7RQf17F+0ClKipYPGrxqOVIIJyCggSloFgstVVRqSAtEhQRIXvN7sz8/ojfYXazx9w7s/u8Xy9f6mZ35zubyXw/+xyfh5MkSQJBEARBEARRNHjyvQCCIAiCIAjCXkgAEgRBEARBFBkkAAmCIAiCIIoMEoAEQRAEQRBFBglAgiAIgiCIIoMEIEEQBEEQRJFBApAgCIIgCKLIIAFIEARBEARRZJAAJAiCIAiCKDJIABIEQRAEQRQZJAAJgiAIgiCKDBKABEEQBEEQRQYJQIIgCIIgiCKDBCBBEARBEESRQQKQIAiCIAiiyCABSBAEQRAEUWSQACQIgiAIgigySAASBEEQBEEUGSQACYIgCIIgigwSgARBEARBEEUGCUCCIAiCIIgigwQgQRAEQRBEkUECkCAIgiAIosggAUgQBEEQBFFkkAAkCIIgCIIoMkgAEgRBEARBFBkkAAmCIAiCIIoMEoAEQRAEQRBFBglAgiAIgiCIIoMEIEEQBEEQRJFBApAgCIIgCKLIIAFIEARBEARRZJAAJAiCIAiCKDJIABIEQRAEQRQZJAAJgiAIgiCKDBKABEEQBEEQRQYJQIIgCIIgiCKjJN8LIAiicJAkCaIoQpIkeL1ecByX7yURBEEQaSABSBCEKUiShHg8jkgkAkEQ4PV6UVpaCq/XK/9DgpAgCMIZcJIkSfleBEEQ7kYQBMTjcYiiiEQiAVEUAUD+N8dx8Hg8siAsKSmBx+MhQUgQBJEnSAASBKEbSZKQSCSQSCQAtAo9JgQ9Ho/8HPYPCUKCIAhnQAKQIAhdiKIoiz0AsnhLFYCpZBKEHMehtLRUFoUkCAmCIKyDBCBBEJpgwk0p9JhQSyQSaGlpgSRJKC0thcfjyVn7x8RgLBZDIpGA3+9PihCWlJSQICQIgjAZEoAEQaiGNXoIggDgQOQOAGKxGHieB8dxsqgTBEHuCGb/ZBJy8XhcFoDZUsYkCAmCIIxDXcAEQahCFEWEw2E5usfElyiKiEajkCQJgUAAoigmpYBFUYQgCHKjSC5BqBSVXq83KWUcjUbl55AgJAiC0A8JQIIgssIiefF4HDzPo6SkJCnlG41GUVJSAp/PB47jwPN80us9Ho8s1oDMgpD5B0qSpEsQsmYSEoQEQRC5IQFIEERGUlO+TFQpa/Z8Pp8s7gDkFF2ZBGE0GpXFozJC6PV6k16fSRCySCR7DglCgiCIzFANIEEQbVA2erCIHMdxcqpXFEVwHAe/39+m25cJxkxdwJlgNYBlZWVJfoKpKeNUQZhu7elqCEkQEgRBHIAigARBJJHO209p8cLzPCoqKuDz+Sw5PhN5LELI0sWZagi1RAhjsRii0agchSRBSBBEsUICkCAIGRb1EwRBbrQAINfb8TwPv99vmfhLR6rIUwpC1nXM7GZyCUJ2LiQICYIodkgAEgQhN3qwtKtS/LD6PI/Hg2AwqDm1azZqBSGbLqJWELL3IEFIEEQxQAKQIIqcTI0eQKu3XzweR1lZGcrKyuQmi2zYLZIyCcJEIpEUycwlCFNH17H3icViSe9BgpAgiEKABCBBFDGsri416pfq7Zer8UJJvvvKlIKQpXozCUIm5JRkEoSxWAz79+9HMBgkQUgQhOshAUgQRYiy0UOSpDbj3FK9/RjMAsYtsO7fTIKQRfdSjalT34PjOJSUlEAQBLmxhCKEBEG4GRKABFFkMIsVLd5+hYKZglBNyri0tDTnCDyCIIh8QAKQIIqETN5+wIFGD47jHNHoYRdaBCETeuneI5MgTCQSST9ngpBNUyFBSBBEviABSBBFQGqjh1J88DwPnudRWlpqq72LE0knCAVBSLKMMRIhVApCJgRJEBIEkQ9IABJEgaP09lOmIZm3nyiK8Pv9KCmh20EqrPYPODDCzufzyWl0IynjRCKBeDzeRhAyUUiCkCAIK6E7PkEUKFq8/ZwgNNzQYKIUhACSav9IEBIE4SZIABJEAaLF208LakRaMYkUJgiZKCRBSBCEWyABSBAFhhXefoQ6sgnCeDyOWCwmp5JJEBIEkU9IABJEgaD09gOSo35MfKTz9tNzHEIdWgUhawZJfQ+1glBpO0OCkCCIbJAAJIgCQBRF8DyPUCiEQCCQV28/Eh2ZUSsIWWRQqyCMRqMQBAF+v7+NICwWax+CINRBApAgXIzS24/ZlTDxV6zefm7CbEHIrgeO43JGCOl6IIjihgQgQbiU1EYPlvZjj5O3n/vQIgiVqd7U92BpZfYeypQxgDZj60gQEkTxQQKQIFxINm+/SCQCAJY0eqhJ72aamEFoJ50gZLY+PM/LEV8m4rRMKmFfEgAShARRjJAAJAgXwSJCbJybUvwlEglEIhFUVFQ4xtuPMBeO45LqOFMFYSwWk6+LbBFCEoQEQZAAJAiXoNbbLxAIWCr+rIzuUeRQG6mCsKSkBLFYDADSRghJEBIEwSABSBAOR9noIUlSkr1Hqrefm6GIpTkwqx+g9fpgNYRmCUL2cxKEBOFuSAAShINJ9fZTir9M3n4URStulIKONYOwKKFSELJ0MRNvWgQh+0LCmkpIEBKE+yABSBAORdnokboBM28/v9+fNJvWaihK527MEoTK5iIShAThTkgAEoTDYI0erLhfWeuXy9uPBBqhBbWCUCkKSRASRGFAApAgHES2Rg+e58nbj7CUbIKQ1aCaIQgFQZAn05AgJIj8QAKQIBxCqrebsqYvGo1CFEVV3n5W1wDmen+KQhYOWgQhE3FqBGEkEpHrW9lzKEJIEPZCApAg8oyy0SOdtx+b/kDefkS+MVMQMsGnjBBm6jJONwKPIAhjkAAkiDwiiiISiUROb7+ysjJV70ebZHHDbILsQq8gVK4zW8qYBCFBWAcJQILIA2q9/dI1euQTNZsubczFi1pBGI/HUVpaqjplnCoIWf2hUhTSdUcQ2iABSBA2k9roocbbT+v7uxEWGSIKh0yCMBwOIxqNguf5pAhhuvpWEoQEYQ0kAAnCRpTefqmNHvny9rMC2nyJdDBB6Pf74ff7ARwog0iXMjYqCJVdxnRNEkQy7t5lCMIlGPH204IdmxxF6QijsLIHpVADIKeLM9UQ5hKE7NokQUgQuSEBSBAWI0kSeJ5HJBKBz+cjbz+CyECqyFMKQqWYKykpkUWdEvZ3pUYQptrOkCAkig0SgARhISySwWxeAoEAAO3eflqgCB1RKGQShKxz3ogg5HkesViMBCFRtJAAJAgLUHr7AUhK67rZ289Nay1G7LaBsRstgjCdmTQJQoI4AAlAgjAZlm4SRREA2jR6aPX204ITNimWrmP1VoS9OOEayAYTXWasUykIWTMIE4RMzKX6ECrJJQhbWlrAcRx8Ph8JQqLgIAFIECah7EZMbfRg3n4s6uckbz8z4Xke0WhUjswAyBqRIQizUIo9wBxByCL4rI6XIoREIUECkCBMINXbTyn+4vG4reIvH7OAU2samc2NMkWnZgMmCLMwQxACSKotpJQxUUiQACQIg6j19gOcn57TA7OxYQKXWd4AbVN0giDIvm+sDpJtsCQGCSvRIwjTvQdANYREYUACkCB0wgQN8yvL5e3HxrsV0kbAbGyUNY2ZIpBsniuDfX7sM2SfGU1zKGzMrAE0QjpBmPoFhed5ee6w2hpC9g97PQAShIQjIQFIEDrIlvLN5O1XCDd8ZU1jLBYzZGPDBCEThSwaw+qtRFFMSs3RpklYSbovKOxxLTWESlFIgpBwMiQACUIjLGKV2uhhpbefWuyYp8tmuXq9XlNtbNgG7Pf7wXGcLAi1TIUodsgD0jyY2CspKUFpaWlSxJoEIVEIkAAkCJWk8/ZjN2m13n5u36BZl2/Hjh0tn1zC6gPZmDBlvVY8HpefQx3GyZBwsIbUiHU6QaisaSVBSDgdEoAEoYJUbz92Y2fpSiu9/ZwAi24KggC/35+X80wVhNRh7E4KpQ42myCMx+OmCEJqKiGshAQgQWSB3dQTiURGbz9JklTZu7j1hp3a5RsKhfK9JADaTIBZIT9BaEGLWFUrCJkQTHdNahGEzGidBCGhFxKABJGBXN5+sVgMJSUl8Pl8qm++VqeAza4BTO3ydWoKO1NHZ7rNlzZMwg6sFoTRaFR+jlIQsrnIdH0TuSABSBBpYL5e6Ro9lN5+yq7BQiJTQ4vyc3DyBpNu82VRXGWHsVIUOvl8CgmnXztKzFyrFkGY6ZrMJgj37dsHAPD5fCQICVUU5u5FEDrR6u2nBbtuwEajdKkp30LYODiOk2sHASR1GMdiMeowJmwnmyBUfvlUKwhLSkrke1amCKGyYaoQ/q4JY5AAJIifYAawWrz9tOLUFCojnbFzIZKrw5gJQuowJuxCTdQ6myBk4o9dq2pSxiQIixsSgETRwxoI2Mav/FbtBG8/O9BynoW4UajpMFZOiiBBWBzkM12dGrXOJQhZWUPqe6itIVyxYgUOP/xwnHnmmfadJJFXSAASRU1qo4fyhqnW208tdmwkeo7hlJSvk+oL03UYsy7McDhMHcYGcMLv141kK2PgeR7hcBhlZWVJE3S01BD++c9/xvnnn08CsIggAUgULeyb9P79+1FRUZHW28/n8yXddI1iRwpYyzGKJeVrBCb22OcTCASow7gIcMrM4kykRq2V9X9qG52UgjAUCqGiosL28yDyB+UxiKKDpVLYTVKJKIqIRCJIJBIIBoOmij8nIUkSIpEI4vE4AoGAZvGXS2TaMZIuX7BaLZ/Ph2AwiPLycvnz43keoVAIkUhE7ha383Mo1M+cyA2LEPr9fgSDQQSDQbkxJBaL5bwuw+GwYQH47rvvYtSoUejWrRs4jkNjY2PO1zQ1NeH000+Hz+fD0UcfjVmzZhlaA6EeEoBEUcFSvsouXxb5i8fjCIfDcirU7Dovp0QS2CxfAAgGg5bUNRaTEEkVhJk2Xp7n5VIDq9dDECw66Pf7UV5envG6/POf/4xVq1ahpaUFwWDQ0DFDoRB69eqFGTNmqHr+1q1bMWLECAwePBibNm3Cb3/7W1xzzTVYsWKFoXUQ6qAUMFE0sJRdOm8/1gDhdm+/XJs/pXytR0uHMUvPEc7D6SngVHLVVma6Ljdu3IhHH30UO3fuxN13342NGzdi8ODBOPPMMxEIBDStYdiwYRg2bJjq58+cORM9e/bEE088AQA44YQTsHbtWjz11FMYOnSopmMT2qEIIFHwsKgfz/Npvf0ikQgEQZC/IVu9FqtJdwwmcvWmfJW4ZUN0CmzTDQQCKC8vl7usE4kEIpEIQqGQ/LtJLUkgCKtg1+X06dPx2WefoWPHjhg5ciS++uor/PrXv0aHDh2wfv16S9ewfv161NTUJD02dOhQy49LtOLeUAdBqIDZu7CNVVn0rPT2syLl6xSc0uVLtKJlhnEhehC6pQvYLetkGFkvx3GIxWK49NJLcfLJJ0OSJGzZsgVVVVUmrzKZ5uZmVFZWJj1WWVmJffv2IRKJaI5AEtogAUgUJEpvv2wp30AgUNANC2YZWBPWQDOMCScgiiLC4TDKy8sBtF6XxxxzTJ5XRVgNCUCi4Ej19lOKv0QigWg0Cq/Xa3s0zA6hmTqzWBAESwyss50HCRT9mDEejCg+jNYrsqYwu21gunbtil27diU9tmvXLrRv356ifzZAApAoKFjUTxCENlG/TN5+hbaBsi7ffKZ8C+0zBfLT2ZwqCHPNMHZDDaFbUqtuWacZMAHIIoB20b9/fyxbtizpsbfffhv9+/e3dR3FSmEVlxBFi9LbL1X8MW8/1uiRztuvUFLAPM8jEomgpKRETm+7Caen4/P9eWay9hBFEdFoFOFwGLFYzDbLGcIZGI0AhkIheL1ew2UiLS0t2LRpEzZt2gSg1eZl06ZN2L59OwDgzjvvxNixY+XnX3/99fjqq69w2223YfPmzXjuuecwd+5cTJw40dA6CHVQBJBwPdlSvqyOivm0pbtB2rWpWyluWMqX53n4/X5L6/3yLYKIA6SbYezxeOSUcaE3lBDmEAqFTMkW/P3vf8fgwYPl/580aRIAYNy4cZg1axZ27twpi0EA6NmzJ5YuXYqJEyfi6aefxmGHHYaXXnqJLGBsggQg4Wqyefsxx3s13n52RZ2sOI6yy7eiogKRSMT0YxDugI2sY3Nei63D2EzclAI2ulY2Bs7o+Q4aNCjrPS7dlI9BgwbhH//4h6HjEvogAUi4EpbyTSQSANDG2y8ajYLjuIK2dwEORDhZl68basAIe3BqhzHz4iScQzgcNjwFhHAfJAAJ15Hq7afcTPTYntiZAjaLbBHOfJlNE86GOowLFzMigOQRWnyQACRcA9uwEolETm8/rbYnbhI0ypRveXk53bQJXWjtMFb+vRUDbkoBG0XpAUgUDyQACVegxtuvpKTE8d9ijQrN1JRvKkpB7OTPgXAemWbFspRxqiCkGcbOwejfe0tLC6WAixASgITjEUUxKUWlxttPC3ZZjxi5QWttarESEpbOxUzhn67DWJky1ttQQl9OnAdFAIsTEoCEY2EpXxZ9SPX2i0ajAFDwjR7Mx7AYmloI51JsM4yLSaiGw2Hbp4AQ+YcEIOFIRFFEIpHQ7e3nVLRGGnOlfPOFlRFTN9VjFitO7TAuVoyKVYoAFickAAlHwSIL4XBYLlLX6+2nFiemgPWeq9trAN24ZkJbh7EgCFQ/6DBCoRAJwCKEBCDhGJSNHolEIilqoOx8tSIN6qSoUyGkfJ0+0o2wlnSCkEX02RcbJgSd2mHsJr9CM2xgDj74YBNXRLgBEoCEI2DefmyUlVFvPy3YufHkEkVmpHydtpESBMdxKC0tRWlpqSys2Mg66jDOP5QCLk5IABJ5JZe3XyQS0e3t5zSyCTMndfnmggQmYQQm9kpKSpI6jFndL+sw9ng8KCkpyVtDiZvKKIxGK8PhMNq1a2fiigg34Nxdhih4snn7sZRveXm5Ld5++UxXWpHypfRr8cF+524RLUpY1C/VcqZQO4zNxqxJIERxQQKQyAss9ZPJ2y8ajaKsrAx+v9/yteQzBezULt9ckMAkrCRThzEThKyhhEUJ3Sh6nQTZwBQnJAAJW2HF4IlEIqe3n5Nq86w4nlUp33xvholEIqmLmyI2hBKtf2vZOozJcsYcwuEwRQCLEBKAhG2wRg9RFAFk9/ZTPs9q7NosUtPbbu7yzQTP8/LvkYn91BQeRWwII7//XB3GZs0wdlsNoN61SpKEUChEEcAihAQgYTnM2491+3Ecp8rbrxDTjCw6VlZWhrKyMss2mHxENKPRqNywI4qi/LumiA1hJcoOY4BmGOuBuoCLExKAhKWkNnooxV82bz+7BYHVgokJpFgshoqKCt1zi50Ia2Jhv0f2GENLxMauqC9RuKTOMFaOrNPSYVwsEUCAagCLFRKAhGWkevspb1DM249FwtJhVxTL6pu8sraxEOxslKRrYmG/t0ybUqaITSKRQDQalaPB1PFZmNgtrFIFIXUYJ8O+wFEEsPggAUiYTi5vP2WqMJMYKpQIoFIglZWV2RLhsuOzY6LWjCYW5QatNAlO7fikdHF23GwDYyfpOoyZB6HyemONam7AiKgOhUIAQBHAIoQEIGEq2bz9WISnpKREVZev3RFAMyMTbjJ21goT8T6fz/QmFhaNYdGadDNlzSjwJwjgQHkCI/V6U3ayF+oXkHA4DAAUASxCCmdXIvJOLm+/eDwOn8+nqv7NzTfZVDubVIFkh7C16hiJREKu9wsEApb/nlLrBzMV+JPdDGEGyustEAjIDU1O/gJiNPIbCoVk9wWiuCABSBhG6e0HJEf9comhXO/rNlJTvvneHMxEWbeZLysXLfVcZDfjPNyWpi6GDmM2BcQtvxPCPEgAEoZI5+3HSPX203KDsfNmZEYKWG3K147zMvsYqXWbTqqNyjQxguxmCCNkEqrZOozj8bj8HDsj0mZEAKn+rzghAUjoIlejhxn1b3aKDCPCQGuU0yniSQ2pVj0cx8mRXqeh1SDYjdEawlkUQocxTQEpXkgAEprJ1uiRzdtPC1Y0ZliBkSinlZghMt06p5iRzW6GFfg7fXMm8oPeqJqaDmMWlTarRMEMD0BKARcnJAAJTYiiKBdD6/H2czJaRJPeKKcbbrK5zo1N98iEU88x1W5GKQgLIV3shsiy22oAjZCtw9hJJQotLS3UAVykkAAkVMFuXqzwWY+3nxbsjgBqOYaRxhbA+o3aznS2FWuwA2X0D1BnN+MGnP65FzOZShSUX6qV15taQWj0HsmaQIjigwQgkRN2g2Leb0a8/bTgRDNo5fk6KeVrBlrOzQ3RJi2osZth/7C/AaJwseOLJytRYOSrw5jmABcvJACJjLA0Gav3i8fjCAQC8s+0evvpXYMdqDGlNqOxxS7BqPVzi8Vilv8u3US64v5oNAqe5xEOh8luhjAdvR3GNAeY0AsJQCItmbz9WBTEjDRhLpyyqZqVFmU4KXpmRfq+EPF6vSgrK4PH44Hf73dkLZcbcHpTF8MJ61TbYSyKoqF7SigUoghgkUICkGiDMurHcRw8Ho98g4nH4+B53rYUqJ1iKd2xCjnlm87ixSwK6XNKhexmiHyQWrOqnFDC83zSc7REpSkFXLyQACRksnn7AUA0GoUkSQgGg7bMts2HGTRDmfI1My3qFGFkxOKlkES/GZDdDGE3qU1M7PrTE5UOhUI45JBD7Fw+4RDoTkQAOODtl67LVxAEeWC4XeJPuS67jyWKIiKRCERRRDAYdF1NXDabFpbyjcVi8Pv9lvn76f29OUUgG4Gl7QKBACoqKuD3++HxeJBIJBAOhxEOh+UvF2Ze324Tzk7GCSlgLbCotM/nQzAYRHl5uXzf4nkeoVAIkUgk7XVnVgRwxowZ6NGjB/x+P6qrq7Fhw4asz582bRqOO+44BAIBdO/eHRMnTpRLbQh7oAggIX9rzOXtFwgE8hqVs+NYdqR887VRm1nLSGJDPVrtZoxcc04XLW4TVm4g3WearcOYlSnMnDkTgiBg586dhm1g5syZg0mTJmHmzJmorq7GtGnTMHToUHz++efo0qVLm+e/8cYbuOOOO/Dyyy9jwIAB+OKLL3DFFVeA4zg8+eSThtZCqIcEYJHDIn/pxrmlNgewTjS712fXcVhhdSF2whZyLaObUGM3w2q4KF1MmEW6DuNu3bph8eLF2LhxIz7++GO88847OO+883DeeefhpJNO0nSPePLJJ3HttdfiyiuvBADMnDkTS5cuxcsvv4w77rijzfPXrVuHgQMH4tJLLwUA9OjRA5dccgk++OADE86WUAvdXYocjuPkRg9lFCwUCoHjOASDwaQidj2CbNMmDkOGlGLcOGd+32CRsUQi4cqUby5isZjs4ej3+0n8OQi2Kfv9fpSXl8tftli6OBQKIRqNyuKQIFLRE1X1eDy49NJL8de//hWnnHIK7rnnHpx99tlYvnw5qqurUV9fr/q9eJ7Hxo0bUVNTk/T+NTU1WL9+fdrXDBgwABs3bpTTxF999RWWLVuG4cOHazoPwhjO3JEJW1FG/bJ5++UaAZaJcBh47z0PjjpK1LUuK2GRMY/HY4vBr97PUM8xrLJ4IQFpHZnSxYViN+OWFLBb1gkYz5KEw2GcdNJJGDVqFP7v//4PPM9res/du3dDEARUVlYmPV5ZWYnNmzenfc2ll16K3bt346yzzpK76K+//nrcddddhs6F0AZFAAlwHCc3PgiCkDEKpveGyMpLIhHtr7dKLLGUrzIyVkikNu6QFYn7yFTYz65dVtjP8zwEQcj3cok8ovfeLEkSQqFQkhF0WVmZZc1hjKamJjzyyCN47rnn8NFHH2H+/PlYunQpHnzwQUuPSyRDEUAC8XgckUjEshFgTAD+pEfyTrpmiFgsludVmQf7fbZv3x5lZWX5Xg5hEtnsZuLxuGzfVFpaSvWDBnFTBNAoRruAO3fuDK/Xi127diU9vmvXLnTt2jXta+6++25cfvnluOaaawAAp5xyCkKhEK677jr8/ve/p2vXJuhTJiCKIvx+f876ML03xECgVTRqFYBWpEtZbZXH40EgELD9RmPlpsJSvjzPw+fzWSr+cv1eimXzzCdKu5ny8nL579dquxnCWeR7FFxZWRn69OmDVatWyY+JoohVq1ahf//+GY+Zeu9Vlj4Q9kARQEIebaUGPX+c7Mslz3NIJAAbbQRlrKpv1LsWs0mNaoqitnpLwv2wOtZAIGC53QxRGLBpQEZ9ACdNmoRx48ahb9++6NevH6ZNm4ZQKCR3BY8dOxZVVVWYMmUKAGDUqFF48skncdppp6G6uhpbtmzB3XffjVGjRlG5io2QACQsR2kxFQ4D7dure51Zokyt/51bv3mmWrywVKAbsVOIFzJkN2MMZobvBoxEAEOhEAAYigACwEUXXYTvvvsO99xzD5qbm9G7d28sX75cbgzZvn170uc5efJkcByHyZMnY8eOHTjkkEMwatQoPPzww4bWQWiDk+huW/SwOaa5YAaiWhsmJAkIBssgSRy2bYshQ1lIG1hxeyAQ0HQ8JWr971gNlZFjqcHs48RisTZRTTbRxai5aybURA2Y0NC6ibJaTKuL0PVg1zWiFy3rY2KQ/aMcLaZljqxWWDTS6U1XzBnADTW0oVAIfr9fV+Tsm2++wfHHH49IJOL43wlhPhQBJCxPBXFcaxQwFNJWB2hkXblSvple4xaUFi9Gp3oQxUeh280YxU1NIEbWGg6HUVpa6gqhS5gPCUBCNcwuRg9MALZawagXWnpEGUv5SpLkSHFkVGiyCJzH40EwGEw7Boog1JKaLma+bMqxYUoxSDVahUMoFEp7DyGKAxKAhGqM3CRYNvKnkhPLjqd35JldN0Cjx2ERmrKysrx+a88lYpkRNeE+ctnNAGjTUELkB/Y3ZqQG0GgDCOFeSAASmtC7qQeDEgBOsxWMluOlq4ez6lh2w8x/E4kE/H6/HK3J9nyCMIPUObIsXZxIJOT52ayZJFe62E2p1WLAqAcg4W5IABK2RMmSp4GoEydqj2dGytfOTUmrOFPbxUwQdpCpfrCQ7GbcIlSNRgDD4TClgIsYEoCEJvRGllhjotkRQL0pXz3HMgOt6zPz/MzCCWsgnIFauxnWXUw4i5aWFooAFjH0F0moxowIoJldwEZTvk5H7/mRQCPyRaZ0MYsQMmsg1mVM0WxjmDEFhARg8UICkNB0A9EbJSsv1zcOLt3xrOjydVIK2AyLF6oBLD6c+DtPTReHw2FIkuR4uxm3pICNQk0gxQ0JQEI1RqY0HEgBq7+pshuw8mZsZUrUCSlgZvHi9XodXZtj1WdlxGqIcHb0l5lNM4NlZjcjiiLZzeiEIoCEEUgAEqpJJ8jUoicFnIqVKV8j52YWPM+D5/m8W7wQhB0wuxmgdfJLOrsZj8eTl3F1FAEkigESgIQttNrAAJGI+tewGzArKBdFEYFAwPWRgdTomdLixYzzy/fGJYoiIpGI7Fdo9Xgxwj1kixyrsZuxY1ydmzAjAtiuXTsTV0S4CRKAhGYbGD03HZYCDoW0vU4URYTDYZSVlTk6JaoXN1q8ZLsOlFNK2GxRp9d7Efai9vdO4+qsJxQKobKyMt/LIPIECUACgPr6Pr03WZZl0JICjsViiEajOOiggywfVG5XClh5HCaW2CxOt9UzpqKcUuL1esHzPLxeb1K9V+p4sXyk9wj3kc1uxuz6QaPeem6CagCLGxKAhGb0iAstNYDKLthAIGCbxYudN3yW8i0EC5t0U0pSGzlSx4tlSu+JolgUGy9hjNR0sbJ+kOf5pHRxIX/BoBQwYQQSgIQm9N5sAgF1NYDKLt9gMCjbRtiF1cdi4pbjOMtSvnY2tEiShMhPv9TU88l27GzTJARBSHqO22s+7cKJNjB2oRSEkiQlCUK96eJi+CLCJoEQxQkJQEIzxiKAmW+qhW7szFK+ABAIBFwflWDpN6/Xa8iSR5ne4zgOiUQCJSUlSd2gxRDNMYNiEC25UEb/gNzj6lK/YLhJSBv9khcKhVBRUWHiigg3QQKQAGB9DWC2FHBqyld5Q7ZzQ7PyWEqLl0Ag4PqNmgkzn89numUNi+RkShdT8b97yYe9Sq5xdUCy3UwxQRHA4oYEIKEJvWbQzAYmVQCmpnzTbQ5uTgGz+jhBEGRxy/O8qcewE3Y+PM+joqLCFr/C1GgONZMQRshlNyOKohx9drrdjCRJuq95SZIoAljkkAAkNGNWEwhL+WYzPnZzBJD54bF6P+X7WylqraoBVNb7BQIBOaJiJrm+YKQ2k7DNmrziCL2kfsFgdahusJsxeh+hCGBxQwKQAKDdC1Ar7B4TiXBZU77pcGMEkEU2S0tL4fP5THnPfKIcUefz+eRGjXzDxooB6b3iaLQYoQWWLma+o5kizk66pqgLmNALCUBCM0YjgOFwWPWsWyd921YLi2wyS5RU7DgnM4+h9PdjYsuJvxc1tV7UTJJf3DBiTbnGdBHnQrGbYaKWfACLFxKAhC0wG5hQCLLxsVrsigAa3ZiUkc1cFi9u6DRM5+/nJnLVejk5tUc4EyvsZoxgRFC3tLQAANUAFjHuuqMTlqElBaxVvLSmTWIAfOB5Dh6P9Y0DetErzJQpUqeMrDMiMrP5+7kVNc0krHbQjedrpCGAOIBaUWXUbibfhEIhACQAixkSgISlMGEUCBzYmCIRQG3Zid6uYz3oFW1Kixc1kU0niMNspNb7ZVqvG6KYmdCS2qNmEkINWu1mzBDrRiKAbMa62yL7hHnQb57QBMdxbcZ8ZUIpjILBA8IoHFYvAO1Gi6hJZ/FixXH0oHdTSFfvVwykpvbSNZOIouhq0esE3FADaBa5ShDy/SUjFAo5JltB5AcSgIQm1NwsMnX5BoMSwmFO1Txg5fGcuOkyixePx1MQN1G31/uZSaZITjQalaODZkdyiMInU7rYiN2MEUEdCoWoAaTIKd67PJGElptINkHGNsp0wigYZF3AHABtkTYnwW7Yei1e7BKLaj83PfV+bhe8WmCRHACyRQg1kxQudkQpU79k5MNuJhwOo7y8nK7XIoYEIKGJbDeLXLVw2cbB6Tme2eSKNjKT2GwWL2pxiqhVW+9HHCBTJMepPnFOgV3zdI21RY/djNHPk0ygCRKAhGZSxYtaY+fWcXDaUsDpjpcPRFFENBoF4I6uWDWbQrHW+5mJMpLj8/momYQwBTV2Mx6PB4lEQnfEsqWlhVLARQ4JQAKA/kkg2VK+qSingahNATshAigIAiKRiLzJG11TvkWAWfV+ThDmTiNXM0lq7aDZo/ryfW0VAk77HDPZzcTjccTjcdlYX2vUmaWAieKFBCChGbbxa7U/CQRa/+2mCKDWc1SLHeeU7hiF6O/nVHLZgrB0MTWTEFpg15XH44EgCAgGg7quK2oCIeiOQ2iCRckikQji8TgCgYBqYcTuNT/5j6o+np0w0cTS2lrP0ckIgoBwOAyPx4NAIECCw2ZYZNDv96O8vFwul0gkEgiHwwiHw3JkthCjq26pAXRaBDATbJ25rqtQKCTfy5TXlVkRwBkzZqBHjx7w+/2orq7Ghg0bsj5/7969uOmmm3DooYfC5/Ph2GOPxbJlywyvg9AORQAJAOpvykxEtGvXTrP9SWsNYKsRtBbsNoIuBIuX1DWbXe/nxs/EKGZfh9RMQlhBLruZRYsW4ZNPPsH27dvRuXNnQ8eaM2cOJk2ahJkzZ6K6uhrTpk3D0KFD8fnnn6NLly5tns/zPIYMGYIuXbqgvr4eVVVV+Prrr9GhQwdD6yD0QQKQUA3P84jFYigpKUEgENAsAg6kgNW/zm6hEY/HIQiCbosXp+E2fz+n+j5aDTWTEFpRE6lMZzdz6KGHoqmpCStXrkQ0GsXXX3+NIUOGYMiQIejVq5emzMCTTz6Ja6+9FldeeSUAYObMmVi6dClefvll3HHHHW2e//LLL2PPnj1Yt26d3PHco0cP1ccjzIVyQIRMtpFfLOUbDAZRVlama5PWYwPDjm81zOIlFovB7/dbKv7sEjkskimKIoLBoOPFH3EAltYLBAIoLy+Xm4/i8ThCoZCcLhYEoSgFs5W4JQWsB47jMHjwYLzwwgsYNWoUrrvuOowePRpr167FueeeiyeeeEL1e/E8j40bN6KmpkZ+zOPxoKamBuvXr0/7mkWLFqF///646aabUFlZiZNPPhmPPPIIBEEwfG6EdmhHILKSrstX782RpYD1+ABaeVNmFi9spFshCKUDM5gDlvn7kfCwh2ymwdFoVE4Xx+NxR9d1FrKwygdGP89wOIxevXphwoQJmDBhgpwiVsvu3bshCAIqKyuTHq+srMTmzZvTvuarr77CO++8g8suuwzLli3Dli1bcOONNyIej+Pee+/VfS6EPty/0xGWka0D1s4IoJUoLV4CgQB4ns/3kgwTj8cRjUbh9/vh9/vzvZyCwgkCJtU0mNV4RaNRRCIRCIJAk0mInITDYVRUVMj/r7ymrEIURXTp0gUvvPACvF4v+vTpgx07dmDq1KkkAPMACUBChqUmcxk7648Atv5bSw0gw4roQarAtSsNYVUKOLXeL9+dy+w8SYBYCxN6TPgxexCe5yGKIjWTEGkx2gXcuXNneL1e7Nq1K+nxXbt2oWvXrmlfc+ihh6K0tDTpOjzhhBPQ3Nws34sJ+3BuvoDIC6zLF2j1icu0YdgVAbQqdZnJxsautKbZx2HnpKz3s/Jc1A6qJ+yFpYt9Ph+CwaB8LbBIdyZLEOIAbvnSYnSdoVAoKQKolbKyMvTp0werVq2SHxNFEatWrUL//v3TvmbgwIHYsmULRFGUH/viiy9w6KGHkvjLAyQACRme5xGJROTi80w3F703nUBAnw2MmTdjURQzClw33PTTQf5+BJBecKc2k/j9/rTNJHZ4D7pFWBULoVDI8CzgSZMm4cUXX8Qrr7yCzz77DDfccANCoZDcFTx27Fjceeed8vNvuOEG7NmzB7fccgu++OILLF26FI888ghuuukmQ+sg9EEpYCKJbLN8lRiLAOpLARuFFTnn2+LFzE0wn/N8KYLkPLJdW+lGirFmEqX3YLFPJnGLUDWyTkmS2tQA6uGiiy7Cd999h3vuuQfNzc3o3bs3li9fLjeGbN++Pek66t69O1asWIGJEyfi1FNPRVVVFW655RbcfvvthtZB6IMEICHj8/lU1cHprWHTMwmEHc8IWrzw3JICdpu/H+E8MjWTJBIJxGIxOZ1MzSSFSTgcNhwBBIDx48dj/PjxaX/W1NTU5rH+/fvj/fffN3xc5TEGDx6c8eeDBg3C6tWrTTteIUG7BqEZozYwWlPAgH7BxCxeWo+fffatHZYzZkDzfAkryDRBgppJnIkkSYb+9tlEJ7czYMAA7Ny5s83jixYtwvXXX48bb7wxD6tyByQACV3oEWQHJoFoe51eMZZIJBCNRuWieKeIOiPrYHYfXq836znle6KG3nPM97qJVlK9B7NNJlGbLnb6FyuGW9ZpBPZ7NGMWcL4pKytr03X82Wef4dZbb8Vdd92FX/7yl3lamfMhAUjIWH3Ts7MGkFm8+Hw+1d5WTr/p57PeLxU1n5XTP09CPR6PR24okSRJFoTsmvR4POQ9aDNGhGpLSwsAGK4BdCJ79+5FbW0tBg0ahAcffDDfy3E0JAAJzeiN0jABaGUXcC4PQ7XvYfUGpuXzo3o/wkkoo39sLGShNJOwv8tCF7ChnwqxC00AiqKISy+9FCUlJfjLX/5S8L9Ho9BOQtgGqwHU2gQCqBNM6cbWacWOG4ZeQeu0ej9K1TqLfP0+1DSTeL1e2WSeMAcjX1TD4TB8Pl/B1XLeddddWL9+PTZs2FAQ9Y1WQwKQkFF7MzEaAYzFOAgCoPbeo2ZdZlq8OGWTUtb7aRW0VEtXnDgh4pGpmSQWiyEej7epHyTsJxQKoby83BHXi1nMnj0bf/jDH7B06VIcc8wx+V6OKyABSOjCiAAEWtPAWrIPmY5ndnrUrhtirs/PSfV+BKEXZTMJixSyySTxeBwANDeTWImbUsBGIoBmmEA7iU2bNuHqq6/Go48+iqFDh+Z7Oa6BBCChGb3RJb//wH+Hw9oEYDq0WLw4iVw37Wg0aoqgzWcEMJFIyNNJ2OxPN2yqhLWw6yFTupiaSeyBzQEuhM939+7dqKurw6BBg/DrX/8azc3NST/3er045JBD8rQ6Z0MCkNCM3puGx9M6Di4S4TTPA04VM1ZavORLODm53k8LPM8jFovJ84jJR47IhNMmk7jJAsZoDWChRACXLl2Kr7/+Gl9//TUOPfTQNj8/4ogjsG3bNvsX5gJIABIyWpsT9FBe3pr+bbWC0fceeixe1JKvFLCRer905GMTY+l4QRAQCATkqTIcx2X0kWObu1s2XcI6UptJRFFEIpFo00zCrhu6ZvTT0tJSEB6AADBu3DiMGzcu38twJSQACc0YufHqMYNmEUAzLF7UYHUEMPXzc2u9n/JzUqbjA4EAOI5LGiuY6iOXacoEUbhojVh5PB7570F5zbC/l2KOKButVSykCCChHxKAhC70iqRWKxhtKWAAcmrIiMWLGuyMKrD0aDwet8Tfz0ohq0zLp5tOku3Y2aZMJBIJRCIRivQQSWS6ZsxuJnFTCtgIoVCo4DwACe2QACRktNjA6OWAGbT6FDCr92vXrp1hixenwOb5SpLk6no/M6KXyuigIAgQRREcx1GkRyPFIl6A5GsGKL5mEjMigIWSAib0QwKQ0IXe6JKWFDCrKeN5HmVlZbaJP6tTwIIgIBKJoH379nK61Gzs2PB4nofH4zE1esnqvNjvOtsMWooOEox03oNMDLJmEnbNZPuyVSzemSQACYAEIJGCGosXtunqiTiwe06uaSCpFi+JRELTcfRitaBgUS0rupftgtViJhIJdOzYMeOGaoYZdabaQYoOug9JkmyJdGcrMVDzJcINf5NGo72hUAgdO3Y0cUWEGyEBSGjGiABk4+CyzQNOtXgRBMHWb+ZWHYtNQvArDREtxIrzYMI8H6lroxs7UZxo+RJRLITDYRx22GH5XgaRZ0gAErrQu7keSAGnfz0TSUqLF7dv5IXi78dS1yUlJbaJ2GxQdJDQSq5mkng8DkmSbPUe1IMZEUDqAiZIABJJaEnbGRkHl1oDmMvixa21OaxDNl33stVdumaS2uzB7FucAkUHCT2kNpNEIhHE4/GCbyYJh8PUBUyQACT0ofdGyFLASgGYTSQZOZYezKhbY2TrkHXTRmLWaDo7oeig83BDlzITeX6/P+m6SW0myfd1Y/SzpCYQAiABSBjAjAigWhsRt0UAlfV++RJNRj+zXKlrt/xOiiE6aNQWhGiL8rrx+XwFdd2QACQAEoCETvRHAFv/HQ5rjyzZEUEwGgHUUu/nZAEliiIikYjlxtv5gKKDRCay3WNyXTcejyepdtCpfzOSJCEUCpEAJEgAEslYPQ+YCcD9+wXVTRF230j1CrNcqWw7MXJs1oVdWlpqu/G2kQ5zvcdTGx10smAn7CX1upEkSZ5WxBpJlLOuzW4mMaMJhGoACRKAhC70Rsp8PgFACSIRj2UmyPlA60QMp543z/PgeT6pC7uYyBbliUaj4DguqTGAKCz0ehVyHIfS0lLXTCahWcAEQAKQ0ImeG1gsFkNpKQfAh1jMC45T10VqZ1RI73npqfezOqKk5f3Z1BVBENJ2Yaei9nNyQ+F/JlKjPB6PB/F4HIIguL4GLB+4+VrQSrrJJGY2k5jRBNKuXTvdrycKAxKARBJWpICVdXEdOrTWneSaBGJkXUbRc15u9vdjc4kBIBAIuPY8rIZFBlM7RKl2kMiG05pJmN8hpYAJEoCEpaTWxVVUtN7csk0CyYQdNVhqb75G6/3simTmihSw82Dzd62uAS0UiqGzuBixI0qppplEObc43XqMjNVraWkBAGoCIUgAEvpQUwOYri7uwCQQ7cezC7XnZbRJIt8CijV7qK1bJDKTuqmLoohEImFbdJBsYNxJtmYSNnLR7GaS0E/pFxKABAlAIgkzNhBWT5bO4uWADYz24+RbMAHO8Pczg0I5DyeijP4BFB1kFFMNoF7UNpOwcZl6CIfD8Pv9VKZAkAAk9JEpAiiKIqLRKACkrYtjAlBrCtiujSPTccyu98vXRqi12SMTtJGrJ9/RQcK9ZGom4Xle/m+t1w7zAKS/YYIEIKGbVAHIUoqs2DndDYaNgtPaBJLueFaRehyr/P3sjmiminPaAOyHooPOxslRSmW6WBAE+frQeu2EQiGygCEAANTuR+giNQIYi8UQjUbh8/ng9/sz3nzYfSca5SCqc4GRj2cHqceJx+OIRCIoKSlxlW+hsgkEaBWx4XAYHk9h+S+6HRYZDAQCKC8vl/924vE4QqEQIpGIHO0hCCXprh1mVRQKhRAOh+VSHOW9mo2BM3oPmDFjBnr06AG/34/q6mps2LBB1etmz54NjuNQV1dn6PiEcSgCSCSh9qagFBhaUqPKL56RCKClDtnuCGCh1MlpNalWS7bfh97Nxe5JIE4iU3SQdYgCcHV00A2/UzesEWi7TuW1U1ZWltRMwrwH//vf/2L16tXgOM5wBHDOnDmYNGkSZs6cierqakybNg1Dhw7F559/ji5dumR83bZt23Drrbfi7LPPNnR8whwoAkjoJpFIIPxTO6/aujjWBQxo6wS2uws4EokgkUggGAy6VvxxHIdYLIZYLAa/3297p68bNlIno/QdDAaDFB0kVMOaSfx+P8rLyxEIBPDjjz9iyZIluOuuu/Dpp5/ixhtvxMKFC7Fv3z7N7//kk0/i2muvxZVXXokTTzwRM2fORDAYxMsvv5zxNYIg4LLLLsP999+PI4880sjpESZBApDQBRuNxVIQajd7jwfw+1sjR1qtYOyIAIqiiEgkAkmSLDV31jtKTy2FImKJVliEx+fzIRgMyr9TVtcZCoXkiLUTuuUJa9EaqfR6vTjzzDOxbNky3H///TjxxBNRUlKC2267DQcffDDuvPNO1e/F8zw2btyImpoa+TGPx4OamhqsX78+4+seeOABdOnSBVdffbXqYxHWQrsCkUSumwrrImXzYvVElcrLgWiUWcE4Z7NiotZt9X6pMBHLcZxlkz3c+tkUCsrOYqB1U6bOYuO4JQVshEQigZ49e+KZZ54B0JqWDWnoytu9ezcEQUBlZWXS45WVldi8eXPa16xduxZ/+tOfsGnTJt3rJsyHBCChGmUXaXl5ufzfWtFjBm11xIxFTwI/Lc6tGwHrxGbpHzeeA6EdVvsVDAYdWTtIRtXmYfSzZE0gjB49epixrIzs378fl19+OV588UV07tzZ0mMR2iABSLQhndhKtXiRJEm3IGu1guE0p4CtIF/zfK0QtDzPy5HZ0tJSJBIJU99fK7TZ54fU6CCzmaHoIAG0FYBa6dy5M7xeL3bt2pX0+K5du9C1a9c2z//Pf/6Dbdu2YdSoUfJj4k8WECUlJfj8889x1FFH6V4PoR+qASRyks7iJdVmRAt6zKCtEBPMGqV1TQfEn13CxSwByEQsz/MIBALyxm81VGvmDnLVDkajUaodhHuilEbX2dLSYkgAlpWVoU+fPli1apX8mCiKWLVqFfr379/m+ccffzz+9a9/YdOmTfI/o0ePxuDBg7Fp0yZ0795d91oIY1AEkMhItuiYEbuOAylgbTWAZm5Queb5umUzZM0eQPpO7Hyeh1s+w2KCooOE0QggAEyaNAnjxo1D37590a9fP0ybNg2hUAhXXnklAGDs2LGoqqrClClT4Pf7cfLJJye9vkOHDgDQ5nHCXkgAEm1g7vLRaBRerzfj1Ai930DZvUfLNBAzv5Xn8vezIwJgxjHYhBIW4XF65IJwHqmjxph3nNm1g26IrrlhjYDx+uRwOGzYB/Ciiy7Cd999h3vuuQfNzc3o3bs3li9fLjeGbN++3bZyGkI/JACJNvA8j2g0qso4WF8KOD82MFrq/eyIXhk5hrLZI9NQeCs3MqdvksWGGdcr845TRgeZGKToYOEQDodRUVFh+H3Gjx+P8ePHp/1ZU1NT1tfOmjXL8PEJ45AAJNogSRICgUDOm7xeEcBSwJGI+tcbFRxWzfPNB4UyoSQTVnd8FypmX9OZJks4pbO4WDEjAmg0BUwUBoW3exCG8fv9qqcLGGkCsSsCmKveLxWnpoCZB6MgCKoEOnsNQRglV3TQ4/GgpKQkY3TQDdehW62ftEICkGCQACR0o/dmqTcFrAe90TKnpYCVHoxOiWC6YVMnrEFPdNAJ12whYESoSpKEUChEApAAQAKQMIhdEUCtaUEj/n5O26gEQUAkEpE9GNWuz2nnQRQmaqKDHMc5fmZxsUQAQ6GQKTWAhPshAUjoRm+t1gEBaM3N1ox6P6ujW2rXxDZRNQ05TkMURSQSCZSWlhbExkoRT3Wkiw7yPI9YLIZQKES1g3mGUsAEgwQg0QarI0x6I4Bq0Frv52TMaPawSrTk8oHkeR6RSASCIIDneXnD93q9ZA9RRLDoIDOP9/l8mmoHibaY0QRCEUACIAFIGMSIDYyWSSBqjmVWd2y+J4HkazydGaQ2qrBzTCQSSCQS8qavFIRugiJWxnByZ3ExpIB5nkcikSABSAAgAUjkgeRJIOrIFnGyQjDlKwUsiiIikYgpdjX52EDZVBIm/uLxODwej5y+Vm76rKmFUoLGcaN4MdpZXKwY+V2HfnLfpxQwAZAAJNKgJQWsRyjpmQSSiULy91Nj7uxUlMLV7/cDODBmzOv1guM4uRkgl9lwPB5HaWkpbfpFhpOjg4VCS0sLABKARCskAAnbYTWAWlLA6SKAVtX72WVErDwGz/PgeR4+n08WR2YfwypShaskSXIDCAC5+1MpAlmUVrnpi6IIQRAQDocRjUYRj8eTIkC06bsXrVErig5mRpIk3VmOcDiMQCDgqrISwjpIABK60SuUAgF9PoDKDcTt0zDYuYiiKNflqDV3dhLxeDxJuEqSBEEQIEkSSkpKUFJSIj/GBB7D4/HI/yj/PxAIyI0DgiAgFotBkiRqJCli7IgOujGNrhXmAVjo50mow307J+Eo7LaBEUURsVjMlQ0SqbCaOY7jXHcuHMeB53lIkoRgMNhG6LFIH8Pr9UIURQCQn8M2cvZ+ytdwHCcLSJ/PJ0cUC6GRhDBGpuig8too5Oig0RrAILsBE0UPCUCiDVbXAOpJAQOtN75wOIzS0lJL6/3sSAGzmrl27dohEAi46hs5a7pJJBI46KCDksQfS0+lOx9lpA9o/QyU/7DoIM/zaaOD1EhCpEMp9IxEB4shAsg8AAv9PAl1kAAkdGN0FJyWJpBEIoFIJIKKigoEWBuxhVgpANm5lJSUWCr+rBCyypF0rJZIKeIyib90KAUeiwiGFXUBLDrI3lNLI4nyH6J4KIbooBGhGg6HKQJIyJAAJAxhLALIQRSBXJlPZb2fHdMwrPx2zJo9WKesm6IOLOLm9Xrh8/nQ0tIiCzcAqsXf/sR+tCtpl/QYx3HyBt2xY0f5eOz9WfpYbSMJmz7BcVxSqtgtnzVhDlqig8VAS0sLdQATMu4pOiJsw65JIADwUzApLaxGLpFIJNWZuRGWNo3H40lNDm6BRS1LS0uTbF7YRsoidLmY9808nPjOifho70fyYywdzuoJWWSQdRWzMXhsI1cKvEQiIYtDAPLrAoEAysvL5dnJPM8jFAohEokgHo8nvYawHid80WHRQb/fj/Lycvj9fng8HiQSCYRCIYTDYcTj8YKeWUwRQEJJcXztISxDXxfwgf8Oh5MFISOdIbKdG4iZQlOZNnWjV6Eyaqms9/N4PHJ0NleUTZIkTN0yFfd/cT8A4OXtL+P0Dqe3iSpmqx3U0kjC/s0aSQAkRQeVjSRkM1OcpEYHQ6FQ0t+q8tpwU4NWNmgMHKGEBCCRFjX1Y3o3TK8X8PkkxGJcWiuYbIbIdkQAzRQCuQSOkyOaqWPdvF5vUqcviySwOiulXQsThB6PB7zIY8K/JuD1/70OAJjQcwIePuFh+ffMInxqUNtIwp6TzmZGaVfDxKDSZsaNjSROvo7cACsVYHZG6WoHndJ1brQLmFLABIMEIGEIvRtPeTkQizErmAPvkc3fz20RQNaUkEngWH0+RppAWMpakiS52SOTzUs6uxZBEMDzPPYJ+3DVJ1fhvR/egwcePHnyk7j2iGvlz8ao8XW6RhK2RvYPe15qI4kyOlgIzQJOFq1OSAFrIVPtoNujg5QCJpSQACR0k20+by4OzAOG/B5q5vm6JQLoFKNqPZ+XMv3OOq7Vdvoq7Vq+Cn2FCz+6EF+Gv0S5txwvnvAihlYOlVNtwWDQVHGlTBWzNWttJAGSN3xlI4kgCK4Rg4R5qOkstis6yP6ejUQAO3fubOaSCBdDApBIi5bokR4B2GoF05oCTlfv51bUClnl852EIAhys4dyrFtqJC0X7+95HxdtvAi7+d04zH8Y6s+oxwnBExAKhRCPx1FWVoZYLCZH4ayIomSLDmZLFSs3fPYaJgYlSUpKF7sp+kOYg5ujg6FQCD169Mj3MgiHQAKQ0I2RxgyWhWhpEWVz51zzfO2a0QsYj5y5UcimpmWV5s4AVG9m876Zh9/88zeIiTGcdtBpmNd3Hrr6usrCsn379mmjbFbO/TWzkaSkpETuQqZGksJBzxdZu6ODRiOAkUiEagAJGRKAhGGMdAL/+GP+06Sp6Lm5soaGkpIS2SbFiuNoQcv7p6aslZE/tVG/1E7fkZUj8XLvlxHwBBAOh5MaYTiOS5rsYWdDhtFGktToYLp1OzH6k0/YhJhCx+nRQWoCIZQ4Z9clHIWVXoCtjQUCAA8SCR9KStQJSKdGAJlNip6GhnyngJWdvixlnW2mbyYydfpKQut0j2ydvpkaMlhE0uqGDLWNJIlEAhzHJX0uhdZIQpiHluigli9ZRr4QsVFwBAGQACRMQIuIYWnSQKB1EkQkktwFbOax9KL2BsvEUyKRkG1SnEa2z4sZbQMH/An1jHX7If4DLt14Kd79/l1TOn2Vkz0yNWRYNdkjUyNJIpFAIpGA1+uVhaDaRhKtM2mJ/GB1p3K26KBd0WMSgIQSEoCEIbTcMJX+fhUVrTe4VgHoTLJtCEqbFDXNHunIpwhI9ScEkJT+VCv+toa34sINF+KL0Beo8Fbg1dNfxdAuQ03rgs7UkJHJc9BsWERUFEX4/X74fD7NjSTAgeklqfOKzVq322xWih290UEjv2dmdk0CkGCQACQMoyYqlyoIWBNIOiPoTDhlg0u1STGyLisjmpnWlWq0ndrpq7a5J12n78ntTkY0Gk1KKZt5Ptk8B5U/Nysam86sWmsjCXtNuqiiHQ0wTsANAjWfa1QbHTR6vwiFQjQJhJAhAUikxawawEy2KK02MEAopG1ddqaA020I2aaUuIHUekUrOn0Be0beKT0HlZsmWwMTVXpTrtlS2OkaSdjnqGciSWpUkxpJipds0cFUQag2Us+gUXCEEhKAhGEyibJstigsAvjTXq0KO7+dpzuWkWYPtccwG+XvJhqNJtUr6mn20NLpaye5Uq6sIUNtyjV1/nEuzJhIooxqOnEEGZEflNFBr9crf1HQWjsoSRLVABJJkAAkDJGpMzdXpOxAClibUMhH12y6mbhmvrfVpIvCKiN/ZnX6Oikqmppy1eI5yMoV9P6ujUwkyRTVTLURoUYSczHqr2cX7NplVlOZagfTXdvsHkYRQIJB+QUiLUZuhLFYDNFoVC6aT4cbagDZZh2JRCCKomM7fTPBunrDP33ITPwpBYnaer8f4j+gdkMtXv/f6/DAg2knT8OjJz4KMSEiGo3C5/M5RvylwkRVIBBAeXm5vM5YLIZQKIRIJIJ4PC7/rhOJhKlj6li61+fzybWE7L2VtYCJREIWh8CBqKbf70d5eTn8fj84jkM8HpfXzfN8UrqZKGxSy1JYtzy7tllZQeq1vWvXLvk+YDQCOGPGDPTo0QN+vx/V1dXYsGFDxue++OKLOPvss9GxY0d07NgRNTU1WZ9P2AsJQMIQygggsxVhG2i21BmrAdSSAmbHsAOO4+R6Mtbs4bZ6LLZ+r9ebNNNXa+Tvq9BX+NnffoZ3v38XFd4K1J9Rj2uPuBY8zyMWi8Hv95uSErcDFkHx+XwoLy+XRT3P8/j+++8RDodNKbbPBIvQMCHo8/nktDSL+PE8j3g8Lot0BkuvB4NB+e+L/Y7D4bBsSZRvb0k34pYIYDZSvzCwa3v37t048cQTMWTIEHAchw8//BA8z+s6xpw5czBp0iTce++9+Oijj9CrVy8MHToU3377bdrnNzU14ZJLLsHq1auxfv16dO/eHeeffz527Nhh5FQJk+AkulsQaRBFUfYvywarRykrK5PFEotUZOO11zy49tpSDBkiYvHi3Mdha7KriPnHH3+ULV4yGRgbhX12aieHaCEejyMcDkMURXTs2FF3s0emTl9lStxtwjgVFvlj4pCljK32HEy3DmUjifLWnNpIooTVdrFaTic2kjAzcCdN/FFi573FCLFYDAA0R9v37NmD1157Dffffz86d+6MUCiE8847D7W1tbjiiitUv091dTXOOOMMTJ8+HUDr59a9e3dMmDABd9xxR87XC4KAjh07Yvr06Rg7dqymcyDMx5l/jUTe0dIFHI/HkUgkNNWAsSyElhQwYE8EMBaLged5tGvXzjLxZyVKy514PK6r2QNwRqev1bAIWuq1my/PQb2NJF6vF6WlpSgrK6NGEqINnTp1wsCBA9GxY0f873//w8cff4w333wT//rXv1S/B8/z2LhxI+688075MY/Hg5qaGqxfv17Ve4TDYcTjcXTq1EnzORDmQwKQMATP84hGo+jQoYOmb/dGuoCt8utSNksEAgHHRisykTrWDYBcI2Zmp6/aKK/TSefxx8iH56ASrY0k7PfLXkuNJNpwg08hYGymcjgcluuATzvtNJx22mmaXr97924IgoDKysqkxysrK7F582ZV73H77bejW7duqKmp0XRswhrctcMRjoGJJZYG1CqWAoHWSJ7WCKBViGJrMwPHcQgGg4hEIq6qpUo31k0ZwSotLTXU6QsRjuv0NYLWMXVWew6qOX6m6CAbN8dEYK6JJMo5y8qOUSujg276WypU2BSQfAndRx99FLNnz0ZTU5MlZS+EdkgAEppJ9fdTUyuYih4bGKsigGwjZ9EetZ2xRslkoaMV9vtIHesmSRJKS0uTfl9K+5NUcs30TRcpcyNaPf5SySWqtHoOakUZHWRfXJhAVTuRhKWKUyeSWFnz6IYIm9Mxcu8LhUJyZkAPnTt3htfrxa5du5Ie37VrF7p27Zr1tX/4wx/w6KOPYuXKlTj11FN1r4EwFxKARFrUjhHT23WoxwYm27r0kk3c2OXRZ4RcY92YoFVGrVgHoDKFuTW8FT//8OdtZvoaFUtOg3XKmmnpkyqqtHgOGoGl/CVJQvv27ZMsfoxMJOF5HqIoOq6RxErckgI2gtE5wGVlZejTpw9WrVqFuro6AK1fNFetWoXx48dnfN3jjz+Ohx9+GCtWrEDfvn11H58wH/ff0QnLSI1QseYCZdpM702T2cDoSQGbJczYZIx04sYNm4GWsW7KqFVqg8OGvRsw7pNx+D7+fdqZvm7zP0xHan2nVYImNVVs1Zg35SQIZTOOGRNJ2GvVGgwT9qL3s2c1gEaYNGkSxo0bh759+6Jfv36YNm0aQqEQrrzySgDA2LFjUVVVhSlTpgAAHnvsMdxzzz1444030KNHDzQ3NwMAKioqHN9xXQyQACRykmmer/LnWlGmgCUJUHtPM2PjyXU+dmHkXNKNdWMbfK5mD+Vmv+j7RfjNx62dvr3a9cJrJ72Grt6u2LdvHzweD8rLy10f/UlXH2kHqY0kmVLFWuvv2PlwHIdAIJDxfIxOJEmNDjIxKEmS5ppHp0fYnL4+hpEvv2bY3Fx00UX47rvvcM8996C5uRm9e/fG8uXL5caQ7du3J90v/vjHP4LnefziF79Iep97770X9913n6G1EMYhAUhkJds8X8BIBPDAf0ejwE8+xaowchPMdT5mHUctWo+RbaybGZ2+fs6PlpYW+b1YbaRbIz/K33e+O5eVqeJcKflM60yt99RyPrkaSVKfp2wkUUYH040f0yNkCe0YrQE0Yw7w+PHjM6Z8m5qakv5/27Ztho9HWAcJQCIjiUQirUdaKnqEklLwhcPqBaCRDTzXfGKnk9qpzEa9qY38MbJ1+kYiEXmEX7YUphssRDJ5/DmBbCn5TJ6DZp5PaiMJe38mDNU0kgBoI2TtNs8m1GNGCpgoLEgAEhlJrfdLh97O3JISoKxMAs9zCIWAgw9Wvy49gjO1Xi4XZnXo5jqGWpSdyn6/v02Rv1rxp+z09XJePHHSExk7fTN54RlNYdpBNo8/p6HGc5AZrgcCAdPPR5n2BdpOJMkVHUwnZJWNJEqRSRjDaASwS5cuJq+IcDMkAImMBINBS2/c5eUAzwORCAdAndjSevNTmiM7sZlBjchMFWepnb5qbWu+Cn0ld/q2K2mHV097Fed3OV91py9rcFCmMJUWIk5JFWv1+HMaqY0ksVgMoVBInlms7NC123NQTyNJPB5HNBpNigzm+xpJxS01gEYIhULUeEEkQQKQMIQRb75gEPjhB+vGwSmL/906s1Y51q2kpMT0mb56O33VpDDzkSouNNsaJrIPOugglJSU5NVzENDXSMLWXVZWZklHdLHA/ub1/j1FIhFTagCJwsH9d0jCMrTMA9ZXBygB4DQJQLVrYqOv9BTLs+PkMwWcLnJp9kxfZiNiVByr7Xa1SqQwCsm2BkgvZnMZOVsdYTPaSJJqnk2NJPZhVhMIUTiQACQMY7QT2OwIoFmTK/I1vipd5FIZ+TNzpm82GxG92C1S7PL4sxMW+c0mZjMZOdsVYVPbSKJ8nJ1LpkYSNlXI7nnFbkgBG40AhsNhEoBEEiQACVMw6gWotgYwF6kpU73YtRmkfm7pbD7M7vS1c6ZvJj+5aDQKwPgMXaUnnp0ef1bCIplaPCqt8hxUS7ZGklgsJv+/IAiq5hUrm43SdUQT2iEBSKRCApAwjBMigFaYO9udAs401s2sTt98d8Zm8pPTmyo24onnRMyMZJrhOWgEJvB4npdH1QHI2UiiXDt7vh1pbhZZdzJGopSSJFETCNEGEoBERrTcbPRFALWPg0tXm5fOH89tpHau6m32MNrpaydqZuiyzT4VJ3v86cHKaSV6PAfNgF1z5eXlSb9DoxNJqJFEHxQBJFJxxk5AuBq9mxUzf261gdGH0h/PzCiQnSng1Hovvc0e6/esx8UbL07b6ascG+dE0s3QZUbkQHKqmDX4uMHjTw3KNLbV00rUeA4qo7B618Ku6XTReDMmkijXnjqvONOXBrdjtE6RIoBEKiQACVMwVgOo/jXKCKBZzR6ZsKMJRBm51DvWDcjd6ZvPmcdaSZcqZinAUCiERCKBYDDomEimEfKdxtYivNWuTUsNo5GJJKlrZ0KW1ZdqaSRxQxOIESRJoggg0Qb330EJy7DaBoYJwFBI2+uUUTOrUppWbwZs4wdgyUzfgCcgR5Ws6PS1E2W9lyAIqKiokDe0XKliJ+O0NLbRGs1U6yKtXzjMmkjC1p6ukcTNNjNGRCqrLaUIIKGEBCCRN8rLW0XjTzpINZFIBD6fz/KollURQBal8Hg88savt9N3/L/G4y//+wuA9J2+ZWVlrhZ/QLKwqKiokH/nyqiPMmLlhjm0bM1OTmNrsfMBkBRtNuOz1zuRRLl29lq7/RKdRuinb9kUASSUkAAkDKPfCLr13602MLlJjZq58cat7MQtLS1FPB6XNzdAY6fv3y/Fu3uc1elrNqwzNp1hdaaoj9XNDUZhvyM3jarL1ozBavE8Hg8qKios6yoGjE0kydZIwvO8o64RswmFQnKpCUEwSAASGbFaYGmpAWSbJpsmYPXarHj/1E5ctnHF43FNIsVNnb5GUDZHqEljM8GX2iDANncnTJpgKUk3/46UqeKysjKEQiH5841EIrZ81mY3krCIrCAIjm0kMZICDofDrv3STFiHO+9AhKPQXwOoLgXMhA0rko/FYnqWqRmzUsCZxrqxdC+rZ1STlkrX6XtK+1NUTY5wE0abI1iDQL588NJRqALd6/WivLxcvg/kw3MQONBIwv62tDSS+P3+pEiynkYSJ8PGwLn5HAjzcf9diHAExppA0t+UmHBSWpgov91bCbtRGu0OTJfCVEYrWEomNS2VrvsyU6dvJBIx1QA735jdHKHGB89qL7liEej5TstnShXnaiRhRtBer7fNvGKnNJKYEQEkCCUkAAnDWDEJJNUYV7lZ5GtGr1bYJqmcuZup2SPXGK9p26fh4f88DCB9p2+hpHesrmHMlAK0cmSantFuTkYp/vx+f9bnpkvLp3oOWtmMobaRhK0rXSNJpiYY5RcHp//thUKhgrlHEOZBApDIiPWTQFr/nZoCZimYdOk/t9zAjIx1U2480UQU4z8ej7/u/CsA4IbuN+DB4x6EV/QiEiucMWhAflKk6VLFZnWLZmtgcStM/DEBrYVMnoNmzYVWc3ygbXSQRSeZQNXSSMLzPERRtCWKbGRcHUsBE4QSEoBEVtTU9+nvAm47Ci5VOKXDjgigkRRwurFuymgDs6zIRWqn7x9O/AOurLoSsVgM+0L7UFZWhmAwKBeuu1kEOiFFqjZVrNZYmEWw3e7DyDDTukat56DVjSSsPrB9+/bweDyaG0kAZJxI4iSbGRKARDpIABKGMZ4Cbn29GnNns2rz1KDn/VPPwYqZvgDQsWNHecPKVjfodJQNMk5KkaamirUIFOVsaqtHu9mF1b6FWjwHzfo8WcRZ+aXDSCMJkBzZNPvv0mgNIAlAIhUSgIQp6InKsftROHygTsppRfJqz4ul+5TNGErxpzbqB2jr9M0kUJzqgadEmSJ1en2SUqBkSxVzHJexfMGt2O0tqca3z2i6NZ34Ux4f0N5IAmSObCqjg/mwIyIBSKSDBCBhGL2bnDIFzIRTrveyMwKoFhbxAQ4YVOsVf3o7fVMjKKnF9qWlpXn3wFOijJK5LUWaKVUcDocRiUTg9/sLwoQbyL9ptRVNO9nEXzrMmkiSapFjZyMJpYCJdJAAJLKitr5PTwTQ52v9Jh0OA36/ehFgl1hQc5x0DSt6xrqlzvQdVTkKf+r9J12dvqkpKbs7L3Nh1OPPSbDPk+M4xONxtG/fHl6vV/X8XCfjRNNqo/6OWsVfuuMD+iaSZPrioGwkyRa1JxsYwmyc8VdNuBo9Ubl4PA6PhwcQhCRx4HkOORwlkrDLCibbcVJTY1o6fZWkzvS9uefNeOiEhwARhoWSmY0NZuCGGbhaSRclyxSJzbf4VosTxV8qWj0HjYq/dJgxkYS9Vln3mK6RxIgADIVC6Nq1q8GzJQoNZ/5lEwUNq2Xr2PGA4muNAqp7vRMigOnGuulp9rBzpq/axgarolWp3dGFQDahlG/bE71YIZTsIJvnYDwehyRJqKiosCwSa3QiSWrdY6qYjcfjKCsr0/U7CYfDqKioMO9kiYKABCCRFTUbk9oIYLpGibIyCTzPIRQCOnVSv658RQDTTSdRfutXG/UDcs/0tVoo5aobVKbTjFJoY9AAbUIpl+2JU5p23Cr+UlGKb9ZgVlpaKp9fvjwHjTaSRCKRNmMj1UBNIEQ6CuNOTOSdXLWCyqkYylq2YBDgeSAS4QCoE3X5ipakdq2mjnXTIv5SO30bzmjAye1PzpsfXqa6QVZ/aKRY3Qkef2Zj9JzsFN9qYefkJDseozCLoXbt2snnlC/PQaONJH6/H4FAQBaQ8Xg86efZxCw1gRDpKIy/ciLvZBMFiUQC4XAYJSUlbTo+s42Dy4adZtBA6007/NMi08301SL+5n0zDyM+GIHd/G6cdtBpaBrYhJPanYRIJIJEIoFgMJhXocRqq/x+P8rLy+X6w1gshlAoJEchcv0OmGB2wjmZhRXnxMR3IBCQP29mJN3S0oJoNKrq8zaC8pwKSfyxSL3ynJjwDgaDCAaDKC0tlb/shEIh+XVWfd6svq+srAx+vx8+n0+O/CrTv/F4PKnBhL1W+bfJfCbj8bj8t8maSpSYEQGcMWMGevToAb/fj+rqamzYsCHr8+fNm4fjjz8efr8fp5xyCpYtW2bo+IT5UASQyIrRcXC50pmtVjCcZgFoF+yGHIlE2ox1M6vTN+gNJs09dlI9mN66wdRZzk46J73YMdotXfqPNQZYkSpWGnEXyrg6ILP4S0WN56DVqXk1jSQsKs+6hRnKqGU6A+2FCxfi4IMPRktLiyEBOGfOHEyaNAkzZ85EdXU1pk2bhqFDh+Lzzz9Hly5d2jx/3bp1uOSSSzBlyhSMHDkSb7zxBurq6vDRRx/h5JNP1r0Owlw4ya5iKsKVsBtKLsLhMMrKyuSNK12tXDrOOKMU//qXB0uW8KipUXcpss5Yq7tIWe2QJEltOn21jnXL1OnLSZxrLVGUqUtBEGTxwjouPR5PwUzCcMJot9TPm0WS9KaKUwVtIfyegGRTeSOiTTnijX3Rs9PEWdlIwqLAgUAAQPpGEiVMRD700EOYPXs2du7ciTPPPBNXXHEFhg8fjsMOO0zTWqqrq3HGGWdg+vTp8tq6d++OCRMm4I477mjz/IsuugihUAhLliyRHzvzzDPRu3dvzJw5U9OxCesojK97hCNg3yXYZsmaPbLdLA9MA3He5sOiLszYV/nNHFBv8/JD/AfUflCLv/zvL/ByXkw7eRqmnDgFkiAhHA7LKR23bcCpqcuysjIkEgns3btXNnlWdka7FVa/mm/T6tTPm0WtlKlitalLEn+5YZ93MBiUP292LdiRmmcCnzXXtW/fPknsK6N9TKQy2Jex++67D59++ik6duyIXr164bXXXkOPHj3Qu3dv7N27V9U6eJ7Hxo0bUVNTk7S2mpoarF+/Pu1r1q9fn/R8ABg6dGjG5xP5gVLAhCmwDSSdMXI2fvpCqykFbPVmxaKXrCCe2bxoTfkCmTt9C80ShUVCJUmSzZDz6TdoFkrTar8Wo0qLUePvmCl1yURjvgWt2Zgp/lLJ5DloVWqewUpoUmsztTSScBwHnudxww034NRTT8WePXuwZs0aHHTQQarWsHv3bgiCgMrKyqTHKysrsXnz5rSvaW5uTvv85uZmLadPWAwJQCIrWjaHeDwOURTlWjk1BIMHxsFpwapv3am1a4XU6Wsl6QRtvvwGzSK19tOpZBqXpjQVVs7OZeLPjVHndCjrGO2qN83mOWiW4bfSkif170TLRBIguQu4U6dOGDNmjK41EYUFCUDCFOLxOOLxOA466CBNPm+sC7jVBia/pEYvWTedHvE3d8dcXP/x9W1m+rIoRSF1W+by+HOi5UkurDDitotM49Ki0ShisZic1iwEUq2Z8iFoMxl+s2isHs9BM+cVf/LJJ5AkSXYx0Ernzp3h9Xqxa9eupMd37dqVcbpI165dNT2fyA+FsQMReYPdgFlES6vJr94UsNkRQGayWlJSIqf6RFGU62u0dPo+/uXjuHLTlYiJMYyqHIUVZ65AV1/XpLrIQhF/sVhM3qjU/O7T1Q3qrWOzCuVoN7eJv1RY6rKsrEz24PT7/eB5XpOljxNxYh0j+0LDbFpY9I7ZtITDYfA8n2QEnYoZ84rZF66dO3fikksuwejRo3HcccfpOqeysjL06dMHq1atkh8TRRGrVq1C//79076mf//+Sc8HgLfffjvj84n8QBFAIivZbqqsOw2AbosB9rJQSNfLTSHVqoalUNi36mg02qYDMO2g+SydvuFw2JWdvplIN9VFK06bUwy4YwauVlgdozKVrUxd2mmIbBZOFH/pUEa/WTRWadOSek8xcxLL9u3bMWLECIwePRrTp0839KVz0qRJGDduHPr27Yt+/fph2rRpCIVCuPLKKwEAY8eORVVVFaZMmQIAuOWWW3DuuefiiSeewIgRIzB79mz8/e9/xwsvvGDonAhzKYw7HGE76dKleqIIrAbwp7I7VZgZAWQRp9SxbpIkyRETpThRznFVTsbYw+/BZRsvSzvTNxKNuDKVmAkrPP7yPacYKJwxaEpYHWO66y9dqjibOHEKbhF/qeT6wsPKTSoqKgxffzt37sTIkSNRU1NjWPwBrbYu3333He655x40Nzejd+/eWL58udzosX379qRjDBgwAG+88QYmT56Mu+66C8cccwwaGxvJA9BhkA8gkRVJksDzfNJjbFNWbiqsXk5rp+RDD3nx0EMluPZaAc8+m9tvkB2LdfvpRRnBSp3swWwXMm0srMaHpSq3x7bj0o8vxZfhLwu60xdIHulnVxNBJr9BM+sGC7ExJ5v4y4ZSnLBr3Cld3G4Vf7mIxWKyJRRwII2r5xrftWsXhg0bhjPOOAOzZs0qmOuZMB+KABJZSb3Bso0yXYpMXwSw9d922sCkm0usVvwByR2Af/v+b7hk4yX4Pv49qnxVeOPUN3Bqh1PlyGIhpRJZBJRF6ewi25xioG00VgupHaSFUptppInFCdHYdBSqfQ1roGP2SZmucTWNJLt378aoUaNw6qmn4s9//jOJPyIrhbEzEZaTq+ZL781YTwqYrUcP7Kaa2uyhx+MvtdN37ulzcbD3YIRCIdlDkKV13H4jdkpXrJl1g07oILUCZROLGZHn1C7u1HFjdqSKleKvUOxrgOSaU3aP0Os5+MMPP6C2thZHH300Xn/99YL54klYB10hRE6YhYAyYpbpeVphEUAtTSB6b/6pqWtJkmQRAaif7JFrpq/P58NBBx0kixMn252owampbCORKieMdrMCq5tY0s3ONWp5kotiEH/ZflfZPAfffvttrF27Fueeey6mTp2Kbt26Yc6cOQVTb0xYCwlAIivs5ptrEoLexowDKWDtqTstpKaulSlfAKpTWVo6fdNtlGakLe0kl8efk1DrN8hxnO11jHZg9+9K+ZkCsCRVXOziL5XUcohu3brhxx9/xLhx4yAIAo444gj89a9/xfDhw9GlSxerlk8UCIVR8EJYBqu3ydXcoT8F3PpvrV3AamFpvkQikTTWjZmkZhqmno49/J60M30hAuFwWE4rp65P6Q1WUVEhR5xisZijvdi0evw5iVS/QZ/PJ0eyv//+eyQSCUdFM42i7GDO1++Kie9gMCj/rQmCgHA4jFAoJNdaqqVQxR+LmBoV6hzH4ZRTTsGOHTtQXV2NNWvWoHfv3vjjH/+Ibt26Yfbs2SaumihEqAuYyAkb8ZYNVltXUVGh6b1Xr+YwbFgZTjxRxEcfxVW9Ru2x0qX59I51s2qmr7LbUhRFy2aKaiFdh3QhwK4bJsid1uGqF6fb1ygj4IlEa6d/rlRxIYu/aDRqSpQ2EongoosuQiQSwfLly9GuXTv5Z83NzfD7/ejQoYPBFROFjLu+1hOOxWgEUEsKWM2xWKevMiVr9kxfM1Ju2dKW+ei2tMLjzwmka2LJZobs9DnFjFgsJke3nbredKnibE0NLFJbSMbpgLniLxaL4fLLL8e+ffvw1ltvJYk/ADRyjVAFCUDCNPQEk9kkEK1jKrMdi91o2eQDZrJqRqevlTN909mdpHZbWtlEkg+PPzvIFqVVmiFn6nB1auMOuwbdFqXN1tQAtP6+ysrKNHuKOhkzxV88HscVV1yBnTt3YtWqVRTlI3RDApAwBSYWmI+eWgKBViGnxwcw3bEyjXVjKWyzOn1b127dxpvO7sTKJhKWHlWOCysEtBTbZ+pwdVrjjtK70G3iLxXllx5BENDS0iJH61taWhzzmRtBactjVPwlEglcc801+M9//oPVq1ejU6dOJq2SKEZIABI5sfLGqzSCliTAyKGyjXUDzOv0tTtClppCYxETs6w3nOLxZzZGauMypS3zOacYKFzvQjZX3OfzyZG/dJ95vutjtWKmJ6MgCLjxxhvx73//G6tXr8Yhhxxi0iqJYoUEIGEKeiOATACKIgeeB9QEn1KPlc6kWhn505LyTZ3p++RJT+KaI65p7WaMhB0RIcvmfad1k3Sqx59RWG2cWY0R6dKWdtcNFuoYNFZ6kDphJluqmH3m7DlOxEzxJ4oibr75Zrz//vtYs2YN1fgRpkACkDANPRsSE4BAaxRQrbZix2KRA47j2ox1M7vT14kRsnRNJKyGLZcwcZPHn1rsSI/mo26wUMegZRJ/qWQaB8jqBp2WKmZjE80Sf7feeiuampqwevVqVFVVmbRKotgpjLs+YSlqb6h6zKBLS4HSUgnxOIdQCOjYUf1r2abLNg+O43Q3e1jZ6WsXSmGSq4lE2UDg1AiKVvKRHrWjbrBQLVHUir9U1IwDzGeqmNXTmiX+7rrrLixduhRNTU3o0aOHOYskCJAAJExG7zSQH38EIhEOgLrXswhAIBCQBQ+LxgDqmz2A3J2+bhRJqZukcrh8LBYDx3GoqKhwTS1VLpwQIbOibjCdnVEhIIoiwmHjJRWp4wAzRcHtShWzv7GysjLD4k+SJDzwwAOYN28empqacNRRR5m0SoJohQQgYRpGvAB//FF9JzCLyrVv3z5J/LFOX47jDHf6Kmut3C6SmBhkkxnY5hSPx+UIqtnzW+3EqfY1RusGleKvkCxRmPizoqQiXRQ8dRwg+72YfZ0oxZ/R85IkCY8++ihmzZqF1atX47jjjjNplQRxABKARE60jl7TSiDQ+u9cAlBZ35U601frWDc1nb6FWGvl9XqT0qPpTHndNBXDLSJJS3oe0J8edTpmiqRcqEkVm3Wtmy3+nnrqKTz33HN45513cNJJJxl6P4LIBAlAwjT0RwAlAFxWAZg61o1F6PQ0e7ih09dMsnn8OaG7VS9u9S7M5fHIcRzi8TgCgYCrzisXdoq/VFJTxand80ZSxWaLvxkzZuCJJ57AW2+9hV69ehl6P4LIBglAwlSMTQNJXwOYLsUnSRLi8ThKS0s1d/pe+OGF+DL0pWs6fY2gxeMvtbs1NX1WWlrqGNuNQvEuTK0b5HkeLS0t8Hg88gxuN0VkM5FP8ZcOZfd8poismlSx2eLvpZdewsMPP4w333wTZ5xxhqH3I4hckAAkTEPvBpUtBZw61g2AXOvHmjRYfVuu4xdCp68WjHj8ZbPdUG6Q+fi8CtW7kAmQdu3aobS01HUR2Uw4TfylkitVnKlGln0xNUv8vfrqq7j77ruxePFiDBgwwOhpEUROCme3IyzD6hrA1hRwWwGYutFLkiTfoFkjQ6oJcqZoSSF2+mbDyBSMVDJtkNFoFIC9HmyFKtbTmQZrrRt0Ik4Xf6moTRV7PB7TItCSJGH27Nn4v//7PyxcuBDnnnuuSWdDENkpnDsokXf0+AACB8ygfyqBAtA6yYHVQWUb65ZqgpyupucPX/0BD3zxAIDC7fRlKBtl2FQUM0m3Qdo1Is1MUesk1Mwrtns2tBmY6YeXL9IZrcfjcbS0tMjnlUgkDH3u8+fPxy233IK5c+fivPPOM/kMCCIzJACJvHMgBZx5rFuuZo909WuReAQTP56IObvmAAAm9JyAh094uGA7fVNHhdkharM1kZhpyMtGu1khavOJnoimU+cUKzFzDJpTYF8q4/E4DjroIJSUlMjnCUCXndLixYtx/fXX44033sDw4cOtXD5BtIEEIJETKyeBAAeaQFpaDpj5Ghnr5vF40IIWXPbxgU7fR499FGO7jkW4JYx4PA6/348AU54FgBOMkLM1kejtsrRjtFu+MCui6bRO7kIUf0B6ax6lCNc6k3v58uW46qqrMGvWLNTW1tp2HgTBKJy7KeEIjNQA7t+faNPpq3em78/W/Qzv7nkX7Uraob5vPW48+kY5ZVlSUgJRFBEKhWRx4WaYsa6TjJCZGAwEAigvL5frNSORiOrPPV00uFCwKp3NPvdgMJj0uYfDYVuu92ISf0pYmjgYDCIYDMLr9bb53Pft24dEIgEAeOeddzB27Fi88MIL+MUvfmHp2t99912MGjUK3bp1A8dxaGxszPmapqYmnH766fD5fDj66KMxa9YsS9dI5IfCuaMSlqJGVOgVHj4f6+o9YObLxrpJkqR5pu/gdYPxZehLHOY/DCv7r8T5Xc6XjY4rKirQvn17lJeXw+fzyZGzlpYWRKNRJBIJXSI2X7BNpqSkxDHiLxVWv8bEoJrPPdX30YnnpRdW38qEglXo+dyNUKziL5XULz/sc3/66afRs2dPjBw5Er/85S/x+OOP49JLL7X82g6FQujVqxdmzJih6vlbt27FiBEjMHjwYGzatAm//e1vcc0112DFihWWrpOwH0oBE6aidTPheR6lpR4AZYjFvJCkuK6xbkD6Tt9D/Ye2aShh75utjsqJRfWpuNELT039GvPAY9M9nPr560HZdW5nRNPqukF2LRZad7bRiSzKz/2uu+5C165dcccdd6Bjx4747W9/iwULFmDUqFH4+c9/jqqqKgvOABg2bBiGDRum+vkzZ85Ez5498cQTTwAATjjhBKxduxZPPfUUhg4daskaifxAEUDCNLTUALL0XmtBdWu0IByGnPIFoDryJ0kSHvvyMVy56UrExBhGVY7CijNXoKuvKyKRiNw8kC3awmqoysvL5YhTLBZDKBRCJBJBPB53VGSQ53l5w3WL+EtHus99//79cmE9M0N2O+x6d0oto/JzZ38b8XgcoVAI4XAYPM+r/tzj8XhBiz/2WRll06ZNuPfee/Hoo49ix44d2Lx5M0aOHIlFixbhvffeM2HF5rB+/XrU1NQkPTZ06FCsX78+TysirKJw/loJS9Hb4JGO1G7ViopWkRcKQXO9X7aZvqkNJWqxq7NVL+kimoVCIpFA+/bt5Q7L1CYSt5kgA8nXu9Zr0Q6M+A2qsbBxI2bPmP7nP/+J2tpa/P73v8fNN98MjuNw5JFH4pZbbsEtt9xiworNo7m5GZWVlUmPVVZWYt++fYhEIgXVPFfsFM5fLJF31IhE5Vg3FvEJBJgRtLZ6v2wzfSPRA9/cjWy46Tpb2eZotyix2uMvn6RLZ6dOInGbCTLQ9suO08RfKlr8BlkKudDEH6uTNEv8ffrppxg1ahQmTpyIW2+91fHXAFE8FM5fLZF3ct3YWBdo6lg3v7/1dZGI+nq/TDN9rayLS42UxONx2yJUTo8iGSHXaDc3miADzrDmMUK2usF4PI5EIoHy8vKC+iIiSRLC4bBp4u/zzz/HyJEjcf3112Py5MmuuAa6du2KXbt2JT22a9cutG/fnqJ/BQYJQMJUMkUAs411CwRaozjhsPpO32wzfe3oQuQ4zrYIlSiKiEajrhUS2dBqhJwqSliaONfcVrtRir9CaWRh5Q8cx0EQBJSXl8uCyc0peobZkb///Oc/GDlyJH7961/jgQcecM010L9/fyxbtizpsbfffhv9+/fP04oIqyABSKhCiw2MJElJz2cRA7bJS5KU1OmbbhRcJpSdvqcfdDrm9p2bsdPXLrJFqJhgYaJEK6mF6G7ZRNRghhdetrmt+arXLIbfWXl5ufw7c3OKnsHEH/PSNMq2bdswcuRIXHjhhXj88cfzKopbWlqwZcsW+f+3bt2KTZs2oVOnTjj88MNx5513YseOHXj11VcBANdffz2mT5+O2267DVdddRXeeecdzJ07F0uXLs3XKRAWQQKQsIxcY904joPH45EngYRCmTdKSZLw+JbH0870jUQijjELVm5+SjGoHBelNl3JUuZusnlRixWj3dLNbbW7XtPs5gEnkUmwuzVFz1BGa83o9t2xYwdGjhyJCy64AE8//XTe70l///vfMXjwYPn/J02aBAAYN24cZs2ahZ07d2L79u3yz3v27ImlS5di4sSJePrpp3HYYYfhpZdeIguYAoSTnORtQTgWlmrLxf79+1H+k6JjooelLTNN9vjPfzicemoA7dpJaG5uGwbM1unLUqNuSLOxjZGZ72ZLV7IoVqGJv3yMdlNGqARBsCxCxSayKGtcCwW90drUa94JXfRKzE7VNzc344ILLsDAgQPx0ksvuSYCShQnJAAJVbAbeS5aWlrg8/nA83xSCoxtwkBbc+edOzkcfXQAXq+EH3+MQHkPztbpG41GXZtmU6YrU4144/G4pro4t+CEjlh2HbLrWZmiNxKhKuRorVlj65RRWfYlMJ91g2aLv++++w7Dhg1D79698eqrrxbU3y5RmJAAJFShVgDu3btXblZgGyGr98vk8bd3L1BV1VoI+MMPYbD9M7XT97XTX8OQQ4a4cgJGNpQbYyQSgSRJqKioQFlZmSOiJGbgxKYIFpFm17beJhISf9rJFJXVWyur5/hmXo/ff/89RowYgWOOOQazZ88uqFF4ROFCApBQhRoByPM89u7di3bt2iEQCCR1+gKZx7rxPNCxY6sA3LEjjA4dnNHpaycsNRqPx1FWVpaUKnd7d6VbmiLSpStzjUcr1Pm3QPLMYiuvPWXdILvHWNnNbbb427t3L0aOHImqqio0NDQU3JcAonAhAUioQhRFxOPxtD9j4oVtnCxaIAiCbAuTawM56KAAEgkOX34ZwVppjuM6fa0kU2o0NUrCxCBLV7oBo7NU84WadGWhi79EIpGXsXVW1g2yvzUApoi/ffv2oba2Fh07dkRjY2PBNf4QhQ0JQEIVmQSgUrz4/X5Eo1H5Rq1lrNuhhwawbx+HmxY+jRmx3wJI7vRl3cROmKNqJsrJKNk2JLsaGcykUFKjTAyydDHrZmdGyIVW65VP8ZdKJiGu50uQ2TWooVAIF154IUpLS7F06VIySSZcBwlAQhXpBGA68RIOh8FxHLxer6axbkceUYpdu0uBx3sBPT5u0+kLoOBMkJWNLFoiB6kpM7vrp9RQaHWaDJY+ZCnt0tJSx332RnCS+EvFSN2g2eIvEongF7/4BRKJBN58801UVFQYej+CyAfuv2MReYFFd0pKSmTxwmr+YrGY7AumprPyx/iP+FGKAugJT7QcT8fG4qrD7oQgwrSZvk7DiEBK5zXIxCSQf9+1XKPd3Ew8HocoiujQoQM8Ho8hn0en4WTxB2T2G1R+9unqBs0Wf9FoFJdeeikikQhWrFhB4o9wLRQBJFQhSRJ4ngfQ1qOOCT9RFOV/p3ZWZtsU49EQqk7chdCuk/HIkTW486tVkMrKwJ97LoS6OmD0aKBTJ5vP2DqsFEhavAatQOtoNzeRqwZVTxOJU4hGo7Z6M5pNprpBr9cLnudNE388z+PXv/41du7ciZUrV6Jjx44mnQFB2A8JQEIVTADmGuuW2umrVpD8b/eP2L35HfR9+5/wNi6AVzG6SCopgXjuuUjU1UEYORLo0sW+EzcZOwVSNq9BKwSJVZYhTkBrdCy1ds1pBshK3C7+UmGffTwel+cUV1RUGK6XjcfjuOKKK/DVV19h1apV6Ny5s4mrJgj7IQFIqEIURezfvz9po2BpGLWdvmoESSwWQ5znUb5tG0oXL0ZJYyM8n3wiv4fk8UA86ywItbUQamshHXqodSdtMvnsYrZakDg9fWgEowIpXROJU7q5C038MZRjKEtLS+XPXm+9bCKRwHXXXYePP/4Yq1evRmVlpYWrJwh7IAFIqEKSJOzbty9psgdL9Wpp9mCk6+5LJBLweDxtfMe4L7+Et7ER3oUL4f3HP5LeRzjzzFYxWFcH6fDDTTlXs1FuRk7YaDMJEj1iMB+j3ezCinNzSje38tyCwaDjU9RaUf69KW2V9PgNCoKA8ePHY/369WhqakK3bt1sOw+CsBISgIRqYrEYgAM3Ui02L9kQBEGOLpaVlckbYrqbMrdtW6sQXLgQ3g8+SH6f006DUFfXKgaPPtrQmsyCdY0CzuxiTidIWPNOLkHihNFuVmHHuWUSJFY3kRTy7w04ENXMJWzV+A2Koojf/va3WL16NVavXo3DbfqSOWPGDEydOhXNzc3o1asXnn32WfTr1y/j86dNm4Y//vGP2L59Ozp37oxf/OIXmDJlCvkSElkhAUiohud5WfiZJf5Sp0QoBUmuVCX3zTeyGPT87W/gfqpDBADxpJOQGDOmNU18wglAHjY5tR5/TiHTnNx00SknjnYzi3wJJDuaSEj8pUeZkfjuu+9w2WWX4YILLsB//vMfrF+/HmvWrEHPnj0tXPkB5syZg7Fjx2LmzJmorq7GtGnTMG/ePHz++efokqb++Y033sBVV12Fl19+GQMGDMAXX3yBK664AhdffDGefPJJW9ZMuBMSgIQqBEFALBbL2Oyhh1xWKJqGx3/7LbxLlqBkwQJ41qwB99P4OQAQjz0WQm0tEnV1kHr1skUMMlsWt03AYGTzGuQ4TvYvLDR7HqcIW+WMYrNqNkn8qaOlpQX19fV46qmn8J///AdVVVW48MILUVtbi7PPPttya6Pq6mqcccYZmD59OoDW+2D37t0xYcIE3HHHHW2eP378eHz22WdYtWqV/Njvfvc7fPDBB1i7dq2layXcTeEU7BCWsmDBApx22mm4//778fHHH8Po94Z4PC6P0crkg+fxeFBWVoZgMChPXBAEAeFwGOFwGDzPy4IUXbpAuOoqxBYvRmTbNsRmzoQwbBiksjJ4vvgCpVOnIjBwIPwnn4zSu+6CZ8MGQBExNJNEIoFIJILS0lJXij/ggNeg3+9HeXm5fB6RSAR79uyBIAgFZ/PiFPEHAF6vV772g8GgPFox7bWvgmIRf2acW3l5Of773/9i3759+OijjzBz5kxEIhFcdtllqK6uNmnF6eF5Hhs3bkRNTY38mMfjQU1NDdavX5/2NQMGDMDGjRuxYcMGAMBXX32FZcuWYfjw4ZaulXA/FAEkVBEKhbB48WI0NDTgzTffRGVlJWprazFmzBicdtppmqISqVYyWsk0IzdtdGTfPnjffLM1VfzWW+B+qscDALGqCsLo0RDq6iD27w+YUIRfyCbIzPybTXnJl9egFaSWIjj1PPQ0kRS6+DOzA12SJEydOhXTp0/HO++8g1NPPVX+mSiK2LFjB7p37250yRn55ptvUFVVhXXr1qF///7y47fddhvWrFmDD1LqnhnPPPMMbr31Vvn6uP766/HHP/7RsnUShQEJQEIzLS0tePPNN9HQ0IBly5ahU6dOGD16NC688EL07ds3403Yrq7KjE0MoRC8b73V2lG8fDm4lpYD79OlCxKjR0OorYV49tmADvFWyCbImdL16VKVbjE/ZjDx57Z0vZomEidFNa3AbPH3zDPPYOrUqXj77bfRp08fk1apHj0CsKmpCRdffDEeeughVFdXY8uWLbjllltw7bXX4u6777Zz+YTLIAFIGCIcDmPFihVoaGjAkiVL0K5dO9TW1qKurg7V1dWyCPv2228RjUbRuXNnS7sqVUdHolF4V61qFYPLloHbu/fA+3TqBGHECCTq6iAOHgyoEAX59PizGrVRTU01mw6BRTXdnK5nKBt4WBNJPB5HSUkJRf5yIEkSZs6ciQcffBArVqywPNWbCZ7nEQwGUV9fj7q6OvnxcePGYe/evVi4cGGb15x99tk488wzMXXqVPmx119/Hddddx1aWloc+7dH5B+6MghDBINBjBkzBq+//jqam5sxY8YM7N+/H7/61a9w3HHHYdKkSfjLX/6CQYMG4ZVXXrF0I2LRv0AgINetsQhIKBSSo48AAL8fwogR4F98EZGtWxFtbETiiisgde4Mbs8elLz2Gvw//zkCPXqg7Kqr4F20CFCkjxns/ROJhFyrVUiw6S9+vz9nSltZsxkMBrPXbDoAJv7KyspcL/4AyBHM8vJy+P1+WSCxhiSnff5GMFv8/fnPf8YDDzyAJUuW5E38AUBZWRn69OmT1NAhiiJWrVqVFBFUwqadKGH3IYrvENmgCCBhCTzPY+XKlZg+fTqWL1+O8vJy/OpXv8KFF16Is846y9b6uEwdrWkjg4kEPH/7W2tkcNEieJqbD7xPeTmEoUNbjacvuABSebmjPf6MYtZoNyNeg1ahFH+ZmpDcSmraN9VayQ2R2WyYLf5ef/113HrrrVi8eDEGDRpkziINMGfOHIwbNw7PP/88+vXrh2nTpmHu3LnYvHkzKisrMXbsWFRVVWHKlCkAgPvuuw9PPvkkXnjhBTkFfMMNN6BPnz6YM2dOns+GcDIkAAnLePXVV3HDDTfgqaeeQs+ePVFfX4/GxkaIooiRI0dizJgxOOecc2zdgNPVTTEx0qZuTxTh+eADeQqJ57//PfA+fj/4QYPAjx4Nz+jR4ApsKLxVI8K0eA1aBatnLMRGnVw1f06ZRKIX9qUkdVqQHiRJwrx58zB+/Hg0NDRg6NChJq3SONOnT5eNoHv37o1nnnlGjkwOGjQIPXr0wKxZswC0Xs8PP/wwXnvtNezYsQOHHHIIRo0ahYcffhgdOnTI30kQjocEIGEJH3zwAYYOHYr6+vokS4NEIoF3330X8+bNQ2NjI2KxGEaOHIm6ujoMHjzY9lQc2wjj8TiALJMYJAmejz5qFYONjfB89dWBH5WWQhw8GIm6OggjRgAuHhJv59i6bGLcqkkYxSz+0j0/nRi38vM3gpniDwAaGxtx7bXXYs6cORg5cqQJKyQId0ECkLCMnTt34tBDD834c0EQsHbtWtTX12PBggVoaWnB8OHDUVdXh5qaGtvHGKVOYkgnBhOJBKKRCPxffIHAsmWtkcHPPpPfQ/J6IZ51FoQxY5AYNQro2tXWczBCvu1CUpsYzB6LxppZCrFLW5IkhMNh3TY2TIynfv5OsfcxW/wtXboUV1xxBV577TVceOGFJqyQINwHCUDCEQiCgPfff18Wg3v27MGwYcNQV1eHIUOGIBgM2r6eVDHIIiapDRHc5s3wLlyIksZGeD7+WH5c4jiI/fu3zieurYV02GG2noMWnGYXYvZYtEK26FF6GJr1pcmOsXRqMasWlfH222/jsssuw0svvYSLL77YhBUShDshAUg4DlEU8eGHH2LevHlYsGABdu3ahaFDh6Kurg5Dhw5FRUWFrethnazKjtFMmyH31VdyzaD3739Pfp++fVsbSOrqIB15pJ2nkBWnmyCn2stoFSNmCwgnYYX4S3eMfDWRmP27W7NmDX75y1/iueeew+WXX+64a50g7IQEIOFoRFHERx99hPr6esyfPx87duzAkCFDUFdXh2HDhqFdu3aWr4E1RLDIWCKRQDwezxkZ4f73v1Yh2NgIz/r14BR/auKpp7bWDNbWQjr+eMvPIRNuM0HWKkYK2Z/RDvGX7pgsVa+cwmNFR7fZ4u9vf/sbfv7zn+OJJ57ANddcQ+KPKHpIABKuQRRFfPzxx6ivr0dDQwO2bduGmpoa1NbWYvjw4TjooINMvannaojQFJnauRMlS5bAu2ABPGvXgmN+hADEE06AUFuLRG0tpFNOAWzamNxuhZJJjDAxaKZdiNNwgnDP1kRiNM1utvjbsGEDamtr8fDDD+Omm24i8UcQIAFIuBRJkvDvf/9bjgx+8cUX+NnPfoba2lqMHDkSHTt2NHSTZzVxgDqPv3Ri0Ov1orS0tO1rd++Gd+nS1prB1avB/dSBDADiUUfJaWLx9NMtE4OZRru5lVR7E57nwXEcKioqCq7b1wniLxU1Y+nUYrb4+8c//oGRI0fi7rvvxsSJE0n8EcRPkAAkXI8kSdi8ebMsBj/55BOce+65GDNmDEaOHImDDz5Y003faE2cpjTl3r3w/tRN7H37bXCx2IH36d79gBisrgZMimKpHe3mRljUlud5lJaWQhRF13ndZcOJ4i8deptI2LVplvj717/+heHDh+PWW2/FHXfcQeKPIBSQACQKCkmSsGXLFsybNw/z58/HP//5T5x99tmoq6vDqFGj0KVLl6ybgNmzYXOlKZNoaYF3xYrWJpIVK8CFQgfep2tXCKNHt4rBgQMBnSm2Qu6GTWdjY2ZkKt+IoohwOOy6ucWZouOpfwNmi7/PPvsMw4YNw4033oh7773XVb9rgrADEoBEwSJJErZu3SpHBjdu3Ij+/fujrq4OtbW16Nq1a9KmEA6HIYqiZWnR1DRlVjEYicC7cmWrGFy2DNy+fQfep3NnCCNHIlFXB/HccwGVay3khgi1KXs1Xo9OhIk/t6fsM30hYo+b9cXkyy+/xAUXXIBx48ZhypQpjv7dEkS+IAFIFAWSJGH79u1oaGjA/Pnz8f777+PMM89EbW0tamtrsXz5crzwwgt49913bemozDQfN60YjMXgWb0aJQsXwrtkCbg9ew68T4cOEIYPb/UaPO88IMParRrt5gT0ehg6yesuG25v1skE+xuIRqMIh8Pw+/2yADTyBWXr1q244IIL8Itf/AJPPPFEwV3vBGEWJACJokOSJOzYsQPz589HfX091q5dC6/XiyuvvBITJ07E4YcfbqsA0DSfNR6H5733Wo2nFy0C9+23B96nogLCBRe0isHzzwfKy20d7ZYP2AQMj8djyMBaUxOPjRSq+GMo61GZxZKRVP327dtxwQUXYPjw4Zg+fXrBXe8EYSYkAImiJR6P47rrrsPbb7+NK664AuvWrcN7772HXr16oa6uDnV1dejZs6ftYlAZmcoqBgUBnvXrW9PEixbBs2PHgfcJBCAMGYLI8OHgzz8f/hy1j27EKh+8fBofKyl08ceif+nSvnqiszt37sTQoUMxaNAgvPDCCyT+CCIHJACJokQURYwePRr/+9//sGzZMnTr1g2SJOG7777DggUL0NDQgKamJpx00kmyGDz66KOdKwZFEZ6NG+FdsKB1PvG2bQfep6wM4nnnIVFbC2HECKBTJ9vOwSrs6obVVLdpIsUs/lJRzihWRmeV5tO7du3CsGHDcMYZZ2DWrFm21bjOmDEDU6dORXNzM3r16oVnn30W/fr1y/j8vXv34ve//z3mz5+PPXv24IgjjsC0adMwfPhwW9ZLEEpIABJFS2NjI372s5+hffv2bX4mSRL27NmDxsZG1NfX45133sFxxx2H2tpa1NXV4fjjj8+rGASA0tLStKa7oiAg/uGH8C9ZAt+SJfB8+eWB9ykpgXjOOUiMGQNh5EigSxfbzsEszO7UVoumVL0BSPxlRtlE8vrrr+OVV17B4MGDsWjRIpx22ml44403bOtunzNnDsaOHYuZM2eiuroa06ZNw7x58/D555+jS5q/K57nMXDgQHTp0gV33XUXqqqq8PXXX6NDhw7o1auXLWsmCCUkAAkiB5IkYe/evVi4cCEaGhrw9ttv48gjj0RtbS3GjBmDE0880fZ0E9sE4z+ZSDMhArR2+8qRMUkC99lnrTWDCxbA88knB87L44E4cGCr12BtLaRu3Ww9Bz04RRxlis4anYLBzq8QPRoBY+Ivld27d2Pu3Ll4+OGHsW/fPhx11FEYM2YM6urqUF1dbfnfZHV1Nc444wxMnz4dQKs47d69OyZMmIA77rijzfNnzpyJqVOnYvPmzQX5uyXcBwlAgtDIjz/+iMWLF6OhoQErVqxA9+7dZTF4yimn2C4GmRCJxWKIRqMIBAKy1Uub+cRbtrTWDC5cCO9HHyW/T3W1bDwtHXGEnaegCqeIv1TM8hpk4qjQxZ9Z5/fjjz9i9OjR6NKlC1577TWsWbMGjY2NWLx4MS6++GI899xzJqw6PTzPIxgMor6+HnV1dfLj48aNk78spjJ8+HB06tQJwWAQCxcuxCGHHIJLL70Ut99+e8HZMhHugAQgQRhg//79WLJkCRoaGrB8+XJUVlbKYvC0006zTQyyzdXr9cLj8ajyueO+/rpVCC5cCO/77yf9TDjttANi8JhjbDmHbLhJHKXzGmSRwUxi0E3npwezz2///v0YM2YMysvLsXjx4qQmoHg8jn379uHggw82fJxMfPPNN6iqqsK6devQv39/+fHbbrsNa9aswQcffNDmNccffzy2bduGyy67DDfeeCO2bNmCG2+8ETfffDPuvfdey9ZKEJkgAUgQJtHS0oI333wTDQ0NWLZsGTp16oTRo0fjwgsvRN++fS0Tg5lGu2kRItw338C7aFFrA8nateBEUf6ZeNJJSNTVtaaJTzzRsvnEmXDz6DrWwBCPxzN2s5L400Y4HMaFF14IjuOwbNkylJeXm7BKbegRgMceeyyi0Si2bt0qR/yefPJJTJ06FTt37rRt7QTBIAFIEBYQDoexYsUKNDQ0YMmSJWjXrp3cQFJdXW1aykftaDc1QkTm22/hXbIEJY2N8KxZA+6ntCYAiMccA6GuDonaWki9e1suBpn4K4TRdem8BgHI01kKUfyZXdMYiURw0UUXIRKJYPny5WjXrp0Jq9SOnhTwueeei9LSUqxcuVJ+7M0338Tw4cMRi8UcVdZAFAdklEQQFhAMBjFmzBi8/vrraG5uxowZM7B//3786le/wnHHHYdJkybh3XfflWvG9BCLxcDzPAKBQE5x5PV6UVZWhvLycgSDQXi9XsTjcYRCIUQiEVkYAgC6dIFw1VWILVqEyNatiD3/PIRhwyCVlcHz5ZconToVgbPOgv/kk1F6113wbNgAKCKGZsHzfMGIPwDweDwoKytDMBhEMBgE0Bo1FkUR8XgcPM9DtOBzzBdmi79YLIbLL78c+/btw9KlS/Mm/gCgrKwMffr0wapVq+THRFHEqlWrkiKCSgYOHIgtW7Yk/Y6/+OILHHrooST+iLxAEUCCsBGe57Fy5Uo0NDRg4cKFKCkpwahRozBmzBgMHDhQ9UZp1mg3TRMw9u2Dd/ny1iaSt94C99PsXQAQu3WTawbF/v0BgxFOFtksxLnFQHJk0+v1pvUaVPrcuQ2zG3bi8TjGjh2L7du3Y9WqVejkAC/LOXPmYNy4cXj++efRr18/TJs2DXPnzsXmzZtRWVmJsWPHoqqqClOmTAEA/Pe//8VJJ52EcePGYcKECfjyyy9x1VVX4eabb8bvf//7PJ8NUYyQACSIPBGPx9HU1IT6+no0NjZCFEWMHDkSY8aMwTnnnJN247RytJumCRihELxvv90qBt98E1xLy4E1HnIIEqNHQ6ithXjOOYDG6E8sFpPTom4VQNnIlta2y2vQSswWf4lEAldddRU2b96M1atX45BDDjFhleYwffp02Qi6d+/eeOaZZ1BdXQ0AGDRoEHr06IFZs2bJz1+/fj0mTpyITZs2oaqqCldffTV1ARN5gwQgkRWtTvfz5s3D3XffjW3btuGYY47BY489Ri73KkgkEnj33Xcxb948NDY2IhaLYeTIkairq8PgwYPh8/mwd+9e/OUvf8EVV1yBYDBoqRG10nA35wSMaBTed95pFYNLl4Lbu1f+kdSpE4QRI5Coq4M4eDCQw7g5FoshkUgU5NxiQFtNo1Veg1ZitvgTBAHXX389PvroI6xevRpdu3Y1YZUEQQAkAIksaHW6X7duHc455xxMmTIFI0eOxBtvvIHHHnsMH330EU4++eQ8nIE7EQQBa9euRX19PRYsWICWlhb87Gc/w8aNG3HMMcegvr7e1pohTePQeB6eNWtQsnAhvIsXg9u9+8D7tG8PYdgwCHV1EIYMAQKBpJealdZ2KkYaWpgYTGf+rcVr0ErMFn+iKGLChAl47733sGbNGlRVVZmwSoIgGCQAiYxodbq/6KKLEAqFsGTJEvmxM888E71798bMmTNtW3chIQgCGhoacN1110EQBACthrJ1dXUYMmSI3ExgF5rEYCIBz9/+JnsNepqbD7xPMAjhggsg1NYicf75iJaWWpLWdgpm1zTq8Rq0EivE36233ooVK1Zg9erV6NGjh/FFEgSRROHdaQlT4HkeGzduRE1NjfyYx+NBTU0N1q9fn/Y169evT3o+AAwdOjTj84nc/Pvf/8bNN9+Mq666Cj/88ANWrlyJ7t27Y/LkyejRowcuv/xyNDQ0oEVRg2clHMehtLQUgUAA5eXlKC0thSAICIfDCIVC4HleFqooKYF47rmIP/kkol9+ieiqVYiPHw+xe3dw4TBK5s+Hb9w4BHv0QMWvf432CxfCs2+fLedhJ1Y0tHi9Xvh8PpSXl8uimef59F3dFiOKouni76677sLSpUuxcuVKEn8EYREkAIm07N69G4IgoLKyMunxyspKNCsiOUqam5s1PZ/IzeTJk3HLLbfgiSeeQElJCaqrq/GHP/wBX375JZqamnDMMcfgwQcfRM+ePXHppZdi7ty52L9/vy1rSxWDZWVlshgIhUKIxWIHxKDHA/HMMxF/7DFEP/sM0ffeAz9pEoSePcHFYvAtXw7ftdci0KMHfHV18L7yCqBIH7sVO7qZc1n8WGkvI4oiwuGwaeJPkiQ88MADmDdvHlauXImjjjrKhFUSBJEOZ1YSEwQBAJg/f35aaxiPx4O+ffuib9++eOSRR/Dxxx+jvr4ejz32GG644QbU1NSgtrYWw4cPx0EHHWR5WpCJwdLS0qTmhUgk0raTleMgnHYaWo4/HtyddyLwn/+gdOFCeBsb4fnss9bu4rffhuT1QjzrrFbj6VGjgEMPtfQczCYfVjbMa5CJcZaq53k+e7peB1aIv0cffRSzZs3C6tWrcdxxxxl+T4IgMkMRQCItnTt3htfrxa5du5Ie37VrV8ZOvK5du2p6PpEbNb6AHo8HvXv3xkMPPYRPP/0UGzZswOmnn46nn34aPXv2xC9+8Qu8+uqr2LNnjy1pQSb4/H4/ysvL4fP5IEmSHBmMRCLYv38/OI6DPxAATjkF8cmTEf373xH56CPw994LsVcvcIIA75o1KJs4EYFjjoFvyBCUTJ8O7r//tfwcjOIEH0MmBtOl68PhcHK6XiMs0ltaWmqa+Hvqqafw3HPP4e2338ZJJ51k+D0JgsgONYEQGamurka/fv3w7LPPAmi96R9++OEYP358xiaQcDiMxYsXy48NGDAAp556KjWB5AFJkrB582bU19dj/vz5+OSTTzBo0CDU1dVh5MiROPjgg21tGJAkCfF4HC0tLZAkCT6fL2snK7d1a6u1zMKF8H74YdLPhL59ZeNp6cgjbTsHNThB/GWDNfKwKK1Wr0Em/kpKSuDLYeujdj0zZszAlClT8NZbb+GMM84w/J4EQeSGBCCREa1O9+vWrcO5556LRx99FCNGjMDs2bPxyCOPkA2MA5AkCVu2bMG8efMwf/58/POf/8TZZ5+Nuro6jBo1Cl26dLFcDKYKh3SdrBnF4P/+d6CbeN06cIrblnjqqUjU1UGorYV0/PGWnkMumIl1MBh0RTdzNq/BdL8HK8TfSy+9hHvuuQdvvvkmBgwYYPg9CYJQBwlAIitane7nzZuHyZMny0bQjz/+OBlBOwxJkrB161Y5Mrhx40b0798fY8aMwejRo9G1a1fTxSCzCSktLU0rHLSIQTQ3o2Tx4taawffeA6dIY4rHH99aM1hbC+mUUwAbI5yFYGKtjAym/h5YGt9M8ffqq6/i9ttvx+LFi3HuueeacAYEQaiFBCBBFDGSJGH79u1oaGjA/Pnz8f777+PMM89EbW0tamtrUVVVZVgMavWI0+Rxt3s3vEuXoqSxEZ7Vq8H9ZJIMAOKRR7amiceMgXj66ZaKwUIQf6kofw/MgNrv95syhUaSJMyePRu//e1v0djYiPPOO8+kVRMEoRYSgARBAGjdlHfs2IH58+ejoaEB69atQ58+fVBbW4u6ujocfvjhmjf+RCKBaDSqu1NUOf1CkiRZCKYVg3v3wvvmm611gytXgotG5R+J3btDGD26VQxWVwMmirRCFH9KRFGUfSZLSkogimL234MKGhoacMMNN2DevHkYNmyY2UsmCEIFJAAJgmiDJEnYuXMnFixYgIaGBrz33nvo1asX6urqUFdXh549e+bc+Jn48/l8qrqZc8FsTRKJRG4R0tIC74oVrXWDy5eDC4UOvE/Xrq1isLYW4llnAQbm6haD+ItEIvB6vfD7/fJjqb8H9rtQ8xksXrwYV111Fd544w3U1tZafQoEQWSg8O5YRFExY8YM9OjRA36/H9XV1diwYUPG57744os4++yz0bFjR3Ts2BE1NTVZn1/McByHbt264aabbsKqVauwY8cOXHvttXj33Xdx+umn46yzzsLUqVPx5ZdfprWWicfjpoo/4ICtSTAYzGh4LK+logLCz38O/tVXEfn6a8Rmz0bi4oshHXQQPM3NKH3hBfhHjEDgqKNQdtNN8Lz1FsDzmtYTjUYLWvyxmj+l+APS/x5S7WUyGU8vX74cV111FWbNmmWr+NNyn1Aye/ZscByHuro6axdIEHmAIoCEa5kzZw7Gjh2LmTNnorq6GtOmTcO8efPw+eefo0uXLm2ef9lll2HgwIEYMGAA/H4/HnvsMSxYsACffPIJDZpXiSRJ2LNnDxobG1FfX4933nkHxx13nJwmPv744zFr1ix88sknePTRR1FiILqmltSIVFbDY56HZ/VqlDQ2wrt0Kbjvvz9wbh06QBg+HEJdHYTzzgMUoieVaDQKQRAKWvyFw+E24i/Xa5Q1gxzHYc+ePfjuu+9w2mmnYfXq1bj44ovx/PPP49JLL7XNgkjrfYKxbds2nHXWWTjyyCPRqVMnNDY22rJegrALEoCEa6mursYZZ5yB6dOnA2gVAt27d8eECRPS+hSmIggCOnbsiOnTp2Ps2LFWL7fgkCQJe/fuxcKFC9HQ0IC3334bHTp0wA8//ICnnnoKY8eOtV0cKadfCIKQXQwmEvC89x68CxeiZOFCcN9+e+DcKiogXHBBqxg8/3ygvFz+WTGIv0gkAo/Ho1r8pXuPRCKBRYsW4YYbbkB5eTl++OEH/O53v8ODDz5oyxcDhp77hCAIOOecc3DVVVfhvffew969e0kAEgVH4d29iKKA53ls3LgRNTU18mMejwc1NTVYv369qvcIh8OIx+Po1KmTVcssaDiOQ8eOHXHFFVdg0aJF+L//+z+0tLTgzDPPxK233oo+ffrgvvvuwz//+U/LZtGmomb6hbyWkhKIgwcjPm0aIlu2IPrWW4jfeCPEqipwLS0oqa+H79e/RuCII1B2ySXwzJmD6LffQhAE1/j8acUM8QccGA3485//HPPmzUMoFELfvn3x4osv4rDDDsP111+PpqYm8xaeAb33iQceeABdunTB1VdfbfkaCSJfFN4djCgKdu/eDUEQUFlZmfR4ZWUlmpubVb3H7bffjm7duiVtDoR2JEnCnXfeiRdeeAHr1q3DmjVrsGvXLtx///3YunUrhgwZgl69emHy5MnYuHGjbWKQiRBVYtDrhThwIOJTpyK6eTOiTU2I//a3EHv2BBeJoGTRIvivugodjzsOHceORcnrrwN79thyHnbBxB/Hcab4/AHAxo0bcckll+Dhhx/G3/72NzQ3N+Ovf/0rSktLsWzZMlOOkQ0994m1a9fiT3/6E1588UXT1yNJEmpqajB06NA2P3vuuefQoUMH/O9//zP9uASRDvvi8AThIB599FHMnj0bTU1NhiIdRGvDx86dO/Hee+/h2GOPBQC0a9cOF198MS6++GK0tLTgzTffRENDA0aMGIGDDz4Yo0ePxpgxY9C3b19bImlMDJaWlibVqvE8L/+MdbPC44F4xhkQzzgD8YceAvfPf0JqaEDZ4sUo+fJLlCxfjpLlyyGVlEA855xW4+mRI4EUkeEmlOLP7/ebUp/3z3/+E7W1tfj973+Pm2++WZ4yMnjwYAwePNiEVZvP/v37cfnll+PFF19E586dTX9/juPw5z//Gaeccgqef/55/OY3vwEAbN26Fbfddhv++Mc/4rDDDjP9uASRDqoBJFwJz/MIBoOor69P6tAbN26cXJeWiT/84Q946KGHsHLlSvTt29eG1RKMcDiMFStWoKGhAUuWLEH79u0xevRo1NXVobq62vbZubnm4kqShGg0CkmSWmv+Nm+Gt7Gx1Xj63/8+8D4eD8SBA1uNp2trIXXrZut5GMEK8ffpp5/iggsuwC233ILJkyfbOnNaidb7xKZNm3DaaaclXYcsSuzxePD555/jqKOOMryuV155BePHj8fHH3+MHj164LzzzkOHDh0wf/58w+9NEGohAUi4lurqavTr1w/PPvssgNYb9eGHH47x48dnLO5+/PHH8fDDD2PFihU488wz7VwukUI0GsVbb72FhoYGLF68GH6/XxaDAwYMsLVRAGg7FxeA3EhSUVHRdj7xli2tptMLF8L70UdJPxOqq1vFYF0dpCOOsO0ctGKF+Pv8888xbNgwXHPNNXjwwQfzJv4YWu4T0WgUW7ZsSXps8uTJ2L9/P55++mkce+yxugzN01FXV4cff/wRF154IR588EF88sknOOSQQ0x5b4JQAwlAwrXMmTMH48aNw/PPP49+/fph2rRpmDt3LjZv3ozKykqMHTsWVVVVmDJlCgDgsccewz333IM33ngDAwcOlN+noqICFRUV+ToNAq2RmpUrV6KhoQELFy5ESUkJRo0ahTFjxmDgwIGmeQmqRRRFhEIhJBIJlJaWypFBZnicCrd9e6sQbGyE9/33k34mnHbaATF4zDF2nUJOrBB///nPf3DBBRfg0ksvxWOPPeaIRhmt94lUrrjiCku6gL/99lucdNJJ2LNnDxoaGshrkLAdEoCEq5k+fTqmTp2K5uZm9O7dG8888wyqq6sBAIMGDUKPHj0wa9YsAECPHj3w9ddft3mPe++9F/fdd5+NqyayEY/H0dTUhPr6ejQ2NkIURYwcORJjxozBOeecY1oEJhNMGAFAIBAAkDySDkBSmrhNZHDnTngXLYK3sRGetWvBKZpexBNPRGLMmNY08YknWjqfOBsstQ3ANPG3bds2DBs2DKNHj8bTTz/tCPHH0HKfSMUqAQi0RhcbGxvxb0U5AUHYBQlAgiAcSyKRwLvvvot58+ahsbERsVgMI0eORF1dHQYPHmxatypDTVRMmSaWJCmrGMS338K7dGlrzWBTE7ifUssAIB5zDITaWiTq6iD17m2bGEytazRD/O3YsQPnn38+zj//fPzxj390lPhzMvfddx8aGxuxadOmfC+FKEJIABIE4QoEQcDatWtRX1+PBQsWoKWlBSNGjEBtbS1qamoMd3PrSYlqEoM//ADv0qWtqeJVq8DFYvKPxCOOaE0TjxkDsW9fwCIBZYX4a25uxtChQ3HWWWfhpZdesr2Rx82QACTyCQlAgiBchyAIeP/992Ux+MMPP+CCCy5AXV0dhgwZgmAwqOn9zKiHSycGWc1gm/fbtw/e5ctbxeCKFeB+SjkDgNitm9xNLA4YAJgkqKwQf99++y2GDx+O3r1749VXX7W9ccftkAAk8gkJQIIgXI0oivjwww8xb948LFiwALt27cLQoUMxZswYDB06FOWKMW7psKIZQlkzKEmSLATTisFwGN6334Z3wQJ4ly8Ht3//gbUdcggSo0e3isFzzgF0NsNYIf6+//57jBgxAscccwxmz55te6NOIUACkMgnJAAJwmJmzJghF6D36tULzz77LPr165fzdbNnz8Yll1yC2tpamkOqElEU8dFHH6G+vh7z58/Hjh07MGTIENTV1WHYsGFo165dm+dHo1FTxV+6NbHIoCiK2cVgNArP6tUoWbAA3mXLwP3wg/wjqVMnCCNGIFFXB3HwYEBl/aMV4m/v3r0YOXIkDjvsMNTX11vemEMQhPmQACQIC5kzZw7Gjh2LmTNnorq6GtOmTcO8efPw+eefo0uXLhlft23bNpx11lk48sgj0alTJxKAOhBFER9//DHq6+vR0NCAbdu2oaamBrW1tRgxYgQikQguueQSPPvsszjppJNs8atLJwa9Xq9sNZNEPA7PmjXwLlyIkkWLwO3eLf9Iat8ewrBhEOrqINTUAFlS3tFoFKIomib+9u3bh9raWnTs2BGNjY00SYcgXAoJQIKwkOrqapxxxhmYPn06gFYB0L17d0yYMCGjWbUgCDjnnHNw1VVX4b333rPMgqKYkCQJ//73v+XI4Oeffw6fz4cTTjgBc+fOxSGHHGK7YXGqGPR4PHJksE0XrSDA87e/tdYMLlwIz86dB84tGIQwdGirGBw6FFBEOc0Wf6FQCBdeeCFKS0uxdOlS2SaHIAj3QQKQICxC77i6e++9Fx9//DEWLFhgqQdZsfLf//4XZ599Njp27AhJkvDpp59i0KBBqKurw8iRI3HwwQfnTQyy2sGsYlAU4dmwQZ5C4tm+/cCPTjwR0Q8/BNAq/gRBQDAYNOV8IpEIfvGLXyCRSODNN98k83SCcDlk1kQQFrF7924IgoDKysqkxysrK9Hc3Jz2NWvXrsWf/vQnvPjii3YssejYvn07Bg0ahCFDhmDjxo34xz/+gU8++QSDBw/Gn//8Zxx11FEYNWoUXnrpJezatQt2fT/2eDwoKytDIBBAeXk5SktLIQgCwuEwwuEweJ6XZ9LC44F45pmIP/ooop9+iuh77yH+u99BPPpoCBdcAMB88ReNRnHppZciEolgyZIlJP4IogAgAUgQDmH//v24/PLL8eKLL6Jz5875Xk5BsnXrVowePRrPP/88PB4POI7DMcccgzvvvBMbNmzA559/jgsuuABvvPEGjj32WAwbNgzPP/88du7caZsY5DgOpaWl6sQgx0E8/XTEH3gA0U2bEJ882XTxx/M8xo4di++//x5vvvkmDjroIMPvSRBE/qEUMEFYhNYU8KZNm3DaaaclGemyjd7j8eDzzz/HUUcdZcvaix1JkrB9+3Y0NDRg/vz5eP/993HmmWeitrYWtbW1qKqqsj1NLEmSXDMoCIIsFFkjCXAg8hcIBEyZxhGPx3HFFVfgq6++wjvvvIODDz7Y8HsSBOEMSAAShIVUV1ejX79+ePbZZwG0CrrDDz8c48ePb9MEEo1GsWXLlqTHJk+ejP379+Ppp5/GscceS3YbeUCSJOzYsQPz589HQ0MD1q1bhz59+qC2thZ1dXU4/PDD8yYGmfk0x3EQBAEAUFFRYYr4SyQSuO666/Dxxx+jqakpa9c6QRDugwQgQVjInDlzMG7cODz//PPo168fpk2bhrlz52Lz5s2orKzE2LFjUVVVhSlTpqR9PTWBOAtJkrBz504sWLAADQ0NeO+999C7d2/U1dWhtrYWPXv2zIsYDIfDiEajckRQOZJOD4Ig4KabbsL777+PNWvW4NBDDzV51QRB5Bua20MQFnLRRRfhu+++wz333IPm5mb07t0by5cvlxtDtm/fbkq0hrAHjuPQrVs33HTTTbjxxhvx3XffyWLw/vvvx0knnYS6ujrU1dXh6KOPtkUM8jwPAOjYsaMcCUwkEvJ0E61iUBRFTJw4EX/729+wevVqEn8EUaBQBJAgCMIgkiRhz549aGxsRH19Pd555x0cd9xxshg87rjjLBGDsVgMiUQibc2fJElJ84kBJNUMpluPKIq4/fbbsWTJEjQ1NaFnz56mrzkbWqbmvPjii3j11Vfx73//GwDQp08fPPLII6qm7BAEQQKQIAjCVCRJkpt8Ghoa8Pbbb+Ooo45CbW0txowZgxNOOMGUqG828ZcOZc2gJElyZBAASkpKIIoi7r77bsydOxdNTU045phjDK9RC1qn5lx22WUYOHAgBgwYAL/fj8ceewwLFizAJ598gqqqKlvXThBuhAQgQRCEhfz4449YvHgxGhoasGLFCnTv3l0Wg6eccoouMcjzvNxlruf1TAju2bMH1dXV+NnPfgZBELB27Vo0NTXhhBNO0PyeRtEzNUeJIAjo2LEjpk+fjrFjx1q9XIJwPVR8RBAEYSEHHXQQfv3rX2PBggXYtWsX7r//fmzduhVDhgxBr169MHnyZGzcuPGAt18OjIo/APB6vfD5fOjatSvq6+vxzTffYOHChdi/fz/uu+8+zJ07Fy0tLbreWw88z2Pjxo2oqamRH/N4PKipqcH69etVvUc4HEY8HkenTp2sWiZBFBQkAAmCANBaf9WjRw/4/X5UV1djw4YNWZ+/d+9e3HTTTTj00EPh8/lw7LHHYtmyZTat1p20a9cOF198MebNm4fm5mY8+uij+OabbzBixAiccsopsiF1JjFohvhLZf369fj000/x/vvvY/369TjuuONw33334ZBDDsk4scZs9EzNSeX2229Ht27dkkQkQRCZoS5ggiAwZ84cTJo0Kan+aujQoRnrr3iex5AhQ9ClSxfU19ejqqoKX3/9NTp06GD/4l1KRUUFfvnLX+KXv/wlwuEwVqxYgYaGBtTV1aF9+/YYPXo06urqUF1dDa/Xi2nTpuHkk0/G4MGDTRF/kiRh5syZeOyxx7BixQr07dsXANCrVy888MAD+PLLL9G1a1fDx7GDRx99FLNnz0ZTUxP8fn++l0MQroBqAAmC0Fx/NXPmTEydOhWbN29GaWmp3cstaKLRKN566y00NDRg8eLFCAQCOOKII/Cvf/0LS5YswRlnnGH4GJIk4c9//jPuuusuLFu2DGeddZYJK9eP1qk5Sv7whz/goYcewsqVK2URSxBEbigFTBBFjp76q0WLFqF///646aabUFlZiZNPPhmPPPKIPI2C0I/f78fo0aPxyiuvoLm5GSNHjsTGjRtRUlKCiy66CLfccguampoQj8d1vb8kSXj99ddx5513YtGiRXkXfwBQVlaGPn36YNWqVfJjoihi1apV6N+/f8bXPf7443jwwQexfPlyEn8EoRESgARR5Oipv/rqq69QX18PQRCwbNky3H333XjiiSfw0EMP2bHkouHFF1/EnDlz8N577+Hbb7/Fa6+9Bo/HgyuvvBJHH300brrpJqxcuVI2g86FJEmYN28efve736GhoQGDBg2y9gQ0MGnSJLz44ot45ZVX8Nlnn+GGG25AKBTClVdeCQAYO3Ys7rzzTvn5jz32GO6++268/PLL6NGjB5qbm9Hc3Gxr8wpBuBqJIIiiZseOHRIAad26dUmP/9///Z/Ur1+/tK855phjpO7du0uJREJ+7IknnpC6du1q6VqLiW+//VY67LDDpPXr17f5WTwel1atWiVdf/31UteuXaVOnTpJY8eOlebPny/t2bNHCoVCaf/5y1/+IpWXl0uLFy/Owxnl5tlnn5UOP/xwqaysTOrXr5/0/vvvyz8799xzpXHjxsn/f8QRR0gA2vxz77332r9wgnAhVANIEEWOnvqrc889F6WlpVi5cqX82Jtvvonhw4cjFouhrKzMjqUXPNFoNGdTA/Pvq6+vx4IFC9DS0oIRI0agtrYWNTU18uuXLFmCK6+8Eq+99houvPBCO5ZPEISDoRQwQRQ5euqvBg4ciC1btiTZlXzxxRc49NBDSfyZiJqOVq/Xi3PPPRfPPvssvv76ayxduhRdunTBbbfdhp49e+LKK6/Egw8+iCuvvBJ/+tOfSPwRBAGAuoAJgkCrDcy4cePw/PPPo1+/fpg2bRrmzp2LzZs3o7KyEmPHjkVVVRWmTJkCAPjvf/+Lk046CePGjcOECRPw5Zdf4qqrrsLNN9+M3//+93k+GwJoFfEffvgh5s6dixkzZmDixIl45JFHLJlJTBCE+yABSBAEAGD69OmYOnUqmpub0bt3bzzzzDOorq4GAAwaNAg9evTArFmz5OevX78eEydOxKZNm1BVVYWrr74at99+O7xeb57OgMhELBZDaWmpaebRBEG4HxKABEEQBEEQRQZ9HSQIgiAIgigySAASBEEQBEEUGSQACYIgCIIgigwSgAThQARBwIABA9pYdvz444/o3r170XfazpgxAz169IDf70d1dTU2bNiQ9fnTpk3Dcccdh0AggO7du2PixImIRqM2rZYgCMJ5kAAkCAfi9Xoxa9YsLF++HH/5y1/kxydMmIBOnTrh3nvvzePq8sucOXMwadIk3Hvvvfjoo4/Qq1cvDB06FN9++23a57/xxhu44447cO+99+Kzzz7Dn/70J8yZMwd33XWXzSsnCIJwDtQFTBAO5plnnsF9992HTz75BBs2bMAvf/lLfPjhh+jVq1e+l5Y3qqurccYZZ2D69OkAWv3uunfvjgkTJuCOO+5o8/zx48fjs88+SzK6/t3vfocPPvgAa9eutW3dBEEQToIigAThYCZMmIBevXrh8ssvx3XXXYd77rmnqMUfz/PYuHEjampq5Mc8Hg9qamqwfv36tK8ZMGAANm7cKKeJv/rqKyxbtgzDhw+3Zc0EQRBOpCTfCyAIIjMcx+GPf/wjTjjhBJxyyilpI1zFxO7duyEIAiorK5Mer6ysxObNm9O+5tJLL8Xu3btx1llnQZIkJBIJXH/99ZQCJgiiqKEIIEE4nJdffhnBYBBbt27F//73v3wvx3U0NTXhkUcewXPPPYePPvoI8+fPx9KlS/Hggw/me2kEQRB5gwQgQTiYdevW4amnnsKSJUvQr18/XH311Sjmst3OnTvD6/Vi165dSY/v2rULXbt2Tfuau+++G5dffjmuueYanHLKKRgzZgweeeQRTJkyBaIo2rHsgkFr9/W8efNw/PHHw+/345RTTsGyZctsWilBELkgAUgQDiUcDuOKK67ADTfcgMGDB+NPf/oTNmzYgJkzZ+Z7aXmjrKwMffr0SWroEEURq1atQv/+/dO+JhwOt5mBy+YVF7OY1orW7ut169bhkksuwdVXX41//OMfqKurQ11dHf7973/bvHKCINIiEQThSG6++Wbp6KOPlkKhkPzYzJkzpYqKCmnr1q35W1iemT17tuTz+aRZs2ZJn376qXTddddJHTp0kJqbmyVJkqTLL79cuuOOO+Tn33vvvVK7du2kv/71r9JXX30lvfXWW9JRRx0l/epXv8rXKbiSfv36STfddJP8/4IgSN26dZOmTJmS9vm/+tWvpBEjRiQ9Vl1dLf3mN7+xdJ0EQaiDmkAIwoGsWbMGM2bMQFNTE4LBoPz4b37zG8yfPx9XX301Vq5cCY7j8rjK/HDRRRfhu+++wz333IPm5mb07t0by5cvlxtDtm/fnhTxmzx5MjiOw+TJk7Fjxw4ccsghGDVqFB5++OF8nYLrYN3Xd955p/xYru7r9evXY9KkSUmPDR06FI2NjVYulSAIlZAPIEEQBJGVb775BlVVVVi3bl1Sqv22227DmjVr8MEHH7R5TVlZGV555RVccskl8mPPPfcc7r///jY1nARB2A/VABIEQRAEQRQZJAAJgiCIrOjpvu7ataum5xMEYS8kAAmCIIis6Om+7t+/f9LzAeDtt9/O+HyCIOyFBCBBEIRFvPvuuxg1ahS6desGjuNUNUA0NTXh9NNPh8/nw9FHH41Zs2ZZvk41TJo0CS+++CJeeeUVfPbZZ7jhhhsQCoVw5ZVXAgDGjh2b1CRyyy23YPny5XjiiSewefNm3Hffffj73/+O8ePH5+sUCIJQQAKQIAjCIkKhEHr16oUZM2aoev7WrVsxYsQIDB48GJs2bcJvf/tbXHPNNVixYoXFK83NRRddhD/84Q+455570Lt3b2zatKlN9/XOnTvl5w8YMABvvPEGXnjhBfTq1Qv19fVobGzEySefnK9TIAhCAXUBEwRB2ADHcViwYAHq6uoyPuf222/H0qVLk8ySL774YuzduxfLly+3YZUEQRQLFAEkCIJwCOvXr0dNTU3SY0OHDs3otUcQBKEXEoAEQRAOobm5WU6pMiorK7Fv3z5EIpE8rYogiEKEBCBBEARBEESRQQKQIAjCIWTyzmvfvj0CgUCeVkUQRCFCApAgCMIhkHceQRB2QQKQIAjCIlpaWrBp0yZs2rQJQKvNy6ZNm7B9+3YAwJ133omxY8fKz7/++uvx1Vdf4bbbbsPmzZvx3HPPYe7cuZg4cWI+lk8QRAFDNjAEQRAW0dTUhMGDB7d5fNy4cfj/9uyYBqIYBqLgAgk4UwiAcAmUoEgdKL8+Atd4pl/J5ZO8905V5b2Xc87PZs6Ze2/GGFlrpar+dzTQggAEAGjGCxgAoBkBCADQjAAEAGhGAAIANPMByUt2KS9jK0QAAAAASUVORK5CYII=", + "text/html": [ + "\n", + "
\n", + "
\n", + " Figure\n", + "
\n", + " \n", + "
\n", + " " + ], + "text/plain": [ + "Canvas(toolbar=Toolbar(toolitems=[('Home', 'Reset original view', 'home', 'home'), ('Back', 'Back to previous …" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "global_frame = ahrs.DCM() # An empty DCM is initialized as the global frame\n", + "print(\"Global frame:\")\n", + "print(global_frame.view())\n", + "plot3(frames=global_frame)" + ] + }, + { + "cell_type": "markdown", + "id": "8b1e60ee-28d2-4156-98ba-51dfe4511f96", + "metadata": {}, + "source": [ + "As you can see, any frame in 3D can be visualized with three orthogonal axes of length one. The X-, Y-, and Z-axis are represented with red, green and blue color, respectively.\n", + "\n", + "Each axis is described in the columns of the DCM:\n", + "\n", + "$$\n", + "\\begin{bmatrix}\n", + " \\color{red}{|} & \\color{green}{|} & \\color{blue}{|} \\\\\n", + " \\color{red}{X} & \\color{green}{Y} & \\color{blue}{Z} \\\\\n", + " \\color{red}{|} & \\color{green}{|} & \\color{blue}{|}\n", + " \\end{bmatrix}\n", + "$$\n", + "\n", + "To make it easier. Imagine:\n", + "\n", + "- The first column describes the three-dimensional postition of the X-axis tip (red)\n", + "- The second column describes the three-dimensional postition of the Y-axis tip (green)\n", + "- The third column describes the three-dimensional postition of the Z-axis tip (blue)\n", + "\n", + "Go back up and see that the visualized frame actually describes the columns of the global frame.\n", + "\n", + "$$\n", + "\\begin{array}{lcr}\n", + "X = \\begin{bmatrix} 1 \\\\ 0 \\\\ 0 \\end{bmatrix} &\n", + "Y = \\begin{bmatrix} 0 \\\\ 1 \\\\ 0 \\end{bmatrix} &\n", + "Z = \\begin{bmatrix} 0 \\\\ 0 \\\\ 1 \\end{bmatrix}\n", + "\\end{array}\n", + "$$\n", + "\n", + "The class `DCM` works in radians. If you want to use degrees, you can transform your values with the helper constant `DEG2RAD`.\n", + "\n", + "Now let's built a matrix describing a rotation of 45° about the Z-axis, and confirm that its elements describe the position of each Axis' tip." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "id": "fd6e95f1-3c8c-4e65-bd2e-ad0bac57a2ef", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Rotation of 45° about global frame's Z-axis:\n", + "[[ 0.70710678 -0.70710678 0. ]\n", + " [ 0.70710678 0.70710678 0. ]\n", + " [ 0. 0. 1. ]]\n" + ] + }, + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "3600367061b3430ab0636f066888825c", + "version_major": 2, + "version_minor": 0 + }, + "image/png": "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", + "text/html": [ + "\n", + "
\n", + "
\n", + " Figure\n", + "
\n", + " \n", + "
\n", + " " + ], + "text/plain": [ + "Canvas(toolbar=Toolbar(toolitems=[('Home', 'Reset original view', 'home', 'home'), ('Back', 'Back to previous …" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "rotated_frame = ahrs.DCM(z=45.0*ahrs.DEG2RAD) # DCM rotated 45 degrees (see helper constant) about the Z-axis\n", + "print(\"Rotation of 45° about global frame's Z-axis:\")\n", + "print(rotated_frame.view())\n", + "plot3(frames=rotated_frame)" + ] + }, + { + "cell_type": "markdown", + "id": "30224465-8620-406d-8157-a63339686b97", + "metadata": {}, + "source": [ + "You see the Z-axis (blue) remains unchanged, while the other points rotate around it, as expected.\n", + "\n", + "The class `DCM` is derived from [NumPy arrays](https://numpy.org/doc/stable/reference/generated/numpy.array.html), and its attributes and methods are kept.\n", + "\n", + "The DCM's characteristics in SO(3) are conveniently added. Operations between DCMs yield DCMs too.\n", + "\n", + "You can also build the DCM, by giving it any valid $3\\times 3$ orthogonal matrix in SO(3). It will fail if it is not valid." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "id": "21b79f46-02ce-4582-8d47-06a0384e786d", + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "DCM([[ 0.70710678, -0.70710678, 0. ],\n", + " [ 0.70710678, 0.70710678, 0. ],\n", + " [ 0. , 0. , 1. ]])" + ] + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "valid_rotation = ahrs.DCM(np.array([[np.sqrt(2)/2, -np.sqrt(2)/2, 0], [np.sqrt(2)/2, np.sqrt(2)/2, 0], [0, 0, 1]]))\n", + "valid_rotation.view()" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "id": "2742fc20-8554-430f-b381-7305e43786d4", + "metadata": {}, + "outputs": [ + { + "ename": "ValueError", + "evalue": "Given attitude is not in SO(3)", + "output_type": "error", + "traceback": [ + "\u001b[1;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[1;31mValueError\u001b[0m Traceback (most recent call last)", + "Cell \u001b[1;32mIn[6], line 1\u001b[0m\n\u001b[1;32m----> 1\u001b[0m invalid_rotation \u001b[38;5;241m=\u001b[39m \u001b[43mahrs\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mDCM\u001b[49m\u001b[43m(\u001b[49m\u001b[43mnp\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43marray\u001b[49m\u001b[43m(\u001b[49m\u001b[43m[\u001b[49m\u001b[43m[\u001b[49m\u001b[38;5;241;43m0\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m1\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m2\u001b[39;49m\u001b[43m]\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43m[\u001b[49m\u001b[38;5;241;43m3\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m4\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m5\u001b[39;49m\u001b[43m]\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43m[\u001b[49m\u001b[38;5;241;43m6\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m7\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m8\u001b[39;49m\u001b[43m]\u001b[49m\u001b[43m]\u001b[49m\u001b[43m)\u001b[49m\u001b[43m)\u001b[49m\n", + "File \u001b[1;32mD:\\Projects\\ahrs\\ahrs\\common\\dcm.py:427\u001b[0m, in \u001b[0;36mDCM.__new__\u001b[1;34m(subtype, array, **kwargs)\u001b[0m\n\u001b[0;32m 425\u001b[0m array \u001b[38;5;241m=\u001b[39m DCM\u001b[38;5;241m.\u001b[39mfrom_axisangle(DCM, np\u001b[38;5;241m.\u001b[39marray(ax), ang)\n\u001b[0;32m 426\u001b[0m _assert_numerical_iterable(array, \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mDirection Cosine Matrix\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n\u001b[1;32m--> 427\u001b[0m \u001b[43m_assert_SO3\u001b[49m\u001b[43m(\u001b[49m\u001b[43marray\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[38;5;124;43mDirection Cosine Matrix\u001b[39;49m\u001b[38;5;124;43m\"\u001b[39;49m\u001b[43m)\u001b[49m\n\u001b[0;32m 428\u001b[0m \u001b[38;5;66;03m# Create the ndarray instance of type DCM. This will call the standard\u001b[39;00m\n\u001b[0;32m 429\u001b[0m \u001b[38;5;66;03m# ndarray constructor, but return an object of type DCM.\u001b[39;00m\n\u001b[0;32m 430\u001b[0m obj \u001b[38;5;241m=\u001b[39m \u001b[38;5;28msuper\u001b[39m(DCM, subtype)\u001b[38;5;241m.\u001b[39m\u001b[38;5;21m__new__\u001b[39m(subtype, array\u001b[38;5;241m.\u001b[39mshape, \u001b[38;5;28mfloat\u001b[39m, array)\n", + "File \u001b[1;32mD:\\Projects\\ahrs\\ahrs\\common\\dcm.py:108\u001b[0m, in \u001b[0;36m_assert_SO3\u001b[1;34m(array, R_name)\u001b[0m\n\u001b[0;32m 106\u001b[0m in_SO3 \u001b[38;5;241m&\u001b[39m\u001b[38;5;241m=\u001b[39m np\u001b[38;5;241m.\u001b[39mallclose([x\u001b[38;5;129m@x\u001b[39m\u001b[38;5;241m.\u001b[39mT \u001b[38;5;28;01mfor\u001b[39;00m x \u001b[38;5;129;01min\u001b[39;00m array], np\u001b[38;5;241m.\u001b[39midentity(\u001b[38;5;241m3\u001b[39m))\n\u001b[0;32m 107\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m \u001b[38;5;129;01mnot\u001b[39;00m in_SO3:\n\u001b[1;32m--> 108\u001b[0m \u001b[38;5;28;01mraise\u001b[39;00m \u001b[38;5;167;01mValueError\u001b[39;00m(\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mGiven attitude is not in SO(3)\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n", + "\u001b[1;31mValueError\u001b[0m: Given attitude is not in SO(3)" + ] + } + ], + "source": [ + "invalid_rotation = ahrs.DCM(np.array([[0, 1, 2], [3, 4, 5], [6, 7, 8]]))" + ] + }, + { + "cell_type": "markdown", + "id": "ae9d3c35-0dce-4037-a145-9be9e5509c31", + "metadata": {}, + "source": [ + "### Euler Angles\n", + "\n", + "DCMs can be built in different ways, the most famous one is through Euler Angles.\n", + "\n", + "These angles, first introduced by [Leonhard Euler](https://en.wikipedia.org/wiki/Leonhard_Euler) are three angles describing the orientation of an object with respect to a fixed coordinate system.\n", + "\n", + "Three composed (chained) **elemental rotations** are always sufficient to reach any frame in 3D space. In this case, we can build each rotation separately with our class `DCM` by setting it in its constructor.\n", + "\n", + "The chained multiplication of these orientations yields a final composed orientation.\n", + "\n", + "Because the rotation operations are **always with respect to the initial global frame**, it is called an **[Extrinsic rotation](https://en.wikipedia.org/wiki/Euler_angles#Conventions_by_extrinsic_rotations)**." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "id": "4ede2c84-c356-4055-addc-92d8fccc590d", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Rotation of 10 degrees about X-axis:\n", + "[[ 1. 0. 0. ]\n", + " [ 0. 0.98480775 -0.17364818]\n", + " [ 0. 0.17364818 0.98480775]]\n", + "Rotation of 20 degrees about Y-axis:\n", + "[[ 0.93969262 0. 0.34202014]\n", + " [ 0. 1. 0. ]\n", + " [-0.34202014 0. 0.93969262]]\n", + "Rotation of 30 degrees about Z-axis:\n", + "[[ 0.8660254 -0.5 0. ]\n", + " [ 0.5 0.8660254 0. ]\n", + " [ 0. 0. 1. ]]\n" + ] + }, + { + "ename": "NameError", + "evalue": "name 'rotation' is not defined", + "output_type": "error", + "traceback": [ + "\u001b[1;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[1;31mNameError\u001b[0m Traceback (most recent call last)", + "Cell \u001b[1;32mIn[7], line 14\u001b[0m\n\u001b[0;32m 10\u001b[0m \u001b[38;5;66;03m# New rotation matrix from products of rotations about X-, Y-, and Z-axis, respectively.\u001b[39;00m\n\u001b[0;32m 11\u001b[0m \u001b[38;5;66;03m# Order of matrix multiplication is right to left: x --> y --> z\u001b[39;00m\n\u001b[0;32m 12\u001b[0m orientation \u001b[38;5;241m=\u001b[39m ahrs\u001b[38;5;241m.\u001b[39mDCM(z\u001b[38;5;241m=\u001b[39m\u001b[38;5;241m30.0\u001b[39m\u001b[38;5;241m*\u001b[39mahrs\u001b[38;5;241m.\u001b[39mDEG2RAD) \u001b[38;5;241m@\u001b[39m ahrs\u001b[38;5;241m.\u001b[39mDCM(y\u001b[38;5;241m=\u001b[39m\u001b[38;5;241m20.0\u001b[39m\u001b[38;5;241m*\u001b[39mahrs\u001b[38;5;241m.\u001b[39mDEG2RAD) \u001b[38;5;241m@\u001b[39m ahrs\u001b[38;5;241m.\u001b[39mDCM(x\u001b[38;5;241m=\u001b[39m\u001b[38;5;241m10.0\u001b[39m\u001b[38;5;241m*\u001b[39mahrs\u001b[38;5;241m.\u001b[39mDEG2RAD)\n\u001b[1;32m---> 14\u001b[0m \u001b[38;5;28mprint\u001b[39m(\u001b[38;5;124mf\u001b[39m\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mRotation Matrix \u001b[39m\u001b[38;5;132;01m{\u001b[39;00m\u001b[38;5;28mtype\u001b[39m(\u001b[43mrotation\u001b[49m)\u001b[38;5;132;01m}\u001b[39;00m\u001b[38;5;124m:\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n\u001b[0;32m 15\u001b[0m \u001b[38;5;28mprint\u001b[39m(orientation)\n", + "\u001b[1;31mNameError\u001b[0m: name 'rotation' is not defined" + ] + } + ], + "source": [ + "print(\"Rotation of 10 degrees about X-axis:\")\n", + "print(ahrs.DCM(x=10.0*ahrs.DEG2RAD))\n", + "\n", + "print(\"Rotation of 20 degrees about Y-axis:\")\n", + "print(ahrs.DCM(y=20.0*ahrs.DEG2RAD))\n", + "\n", + "print(\"Rotation of 30 degrees about Z-axis:\")\n", + "print(ahrs.DCM(z=30.0*ahrs.DEG2RAD))\n", + "\n", + "# New rotation matrix from products of rotations about X-, Y-, and Z-axis, respectively.\n", + "# Order of matrix multiplication is right to left: x --> y --> z\n", + "orientation = ahrs.DCM(z=30.0*ahrs.DEG2RAD) @ ahrs.DCM(y=20.0*ahrs.DEG2RAD) @ ahrs.DCM(x=10.0*ahrs.DEG2RAD)\n", + "\n", + "print(f\"Rotation Matrix {type(orientation)}:\")\n", + "print(orientation)" + ] + }, + { + "cell_type": "markdown", + "id": "505fe5be-25d4-4407-9ec1-365688d8834a", + "metadata": {}, + "source": [ + "This proces can be simplified at creation of the DCM object setting the [Euler angles](https://en.wikipedia.org/wiki/Euler_angles) tuple:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "3b2f1a04-6dd1-4e94-a53f-de1c28c22cf2", + "metadata": {}, + "outputs": [], + "source": [ + "orientation = ahrs.DCM( euler=('zyx', np.array([30.0, 20.0, 10.0])*ahrs.DEG2RAD) )\n", + "orientation.view()" + ] + }, + { + "cell_type": "markdown", + "id": "5179869a-9b87-47bb-9ffa-09eb62017e28", + "metadata": {}, + "source": [ + "As you can see, for the Euler angles we tried to match the mathematical order of multiplication from right to left.\n", + "\n", + "The custom class [DCM](https://ahrs.readthedocs.io/en/latest/dcm/classDCM.html) includes the basic attributes describing the mathematical properties of a DCM." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "046c9a46-5b4b-4e5c-a4f8-e4e9c40afa7e", + "metadata": {}, + "outputs": [], + "source": [ + "attribute_list = ['T', 'I', 'inv', 'det', 'determinant', 'fro', 'frobenius', 'adj', 'adjugate', 'log']\n", + "for attribute_name in attribute_list:\n", + " print(f\"rotation.{attribute_name} =\")\n", + " print(orientation.__getattribute__(attribute_name), '\\n')" + ] + }, + { + "cell_type": "markdown", + "id": "151705fa-e3ca-40ef-85e0-8674bbcadcb6", + "metadata": {}, + "source": [ + "For a full detail of its properties, see its [documentation](https://ahrs.readthedocs.io/en/latest/dcm/classDCM.html).\n", + "\n", + "On top of that, it has a plethora of methods that help us to get extra information." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "5eedfc5e-b40b-47cc-ba29-eae8f89491bc", + "metadata": {}, + "outputs": [], + "source": [ + "# List all DCM methods and the first descriptive line from each docstring\n", + "from tools import describe_methods\n", + "describe_methods(orientation)" + ] + }, + { + "cell_type": "markdown", + "id": "e471d56e-3e2a-4017-bc15-187e76bd156a", + "metadata": {}, + "source": [ + "Have a look at the documentation of the class [DCM](https://ahrs.readthedocs.io/en/latest/dcm/classDCM.html) for more details about the most important methods." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "24b6846f-a106-45d4-9243-c04fdad77857", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.11.2" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/notebooks/tools.py b/notebooks/tools.py new file mode 100644 index 0000000..c4a8127 --- /dev/null +++ b/notebooks/tools.py @@ -0,0 +1,380 @@ +# -*- coding: utf-8 -*- +""" +Tools for the Juypter notebooks used to showcase the functionality of the +package. + +Many funcitons are based on the ones included in the Python package `ezview` +available in the repository https://https://github.com/Mayitzin/ezview +""" + +import copy +import numpy as np +import matplotlib.pyplot as plt + +plt.rcParams['grid.color'] = (0.5, 0.5, 0.5, 0.1) # Light grey grid + +def hex_to_int(color: str) -> tuple: + """Convert a hex color to a tuple of integers.""" + a = color.lstrip('#') + return tuple(int(a[i:i+2], 16) for i in (0, 2, 4, 6)) + +def hex_to_float(color: str) -> tuple: + """Convert a hex color to a tuple of floats.""" + a = color.lstrip('#') + return tuple(int(a[i:i+2], 16)/255.0 for i in (0, 2, 4, 6)) + +COLORS = [ + "#FF0000FF", "#00AA00FF", "#0000FFFF", "#999933FF", + "#FF8888FF", "#88AA88FF", "#8888FFFF", "#999955FF", + "#660000FF", "#005500FF", "#000088FF", "#666600FF"] +COLORS_INTS = [hex_to_int(c) for c in COLORS] +COLORS_FLOATS = [hex_to_float(c) for c in COLORS] + +def describe_methods(obj): + """Return the description of the methods of an object.""" + for method_name in [x for x in dir(obj) if hasattr(obj.__getattribute__(x), '__call__') and not x.startswith('__')]: + method_description = '' + method_docstring = getattr(obj, method_name).__doc__ + if isinstance(method_docstring, str): + method_description = method_docstring.split('\n')[1].strip() + if len(method_description) < 1: + method_description = [x.strip() for x in method_docstring.split('\n') if len(x) > 0][1] + print(f"DCM.{method_name+'()': <20} {method_description.replace(':meth:', '')}") + +def plot(*data, **kw): + """ + Plot time-series data. + + Parameters + ---------- + data : array + Arrays with the contents of data to plot. They could be 1- (single line) + or 2-dimensional. + title : int or str + Window title as number or label. + subtitles : list + List of strings of the titles of each subplot. + labels : list + List of labels that will be displayed in each subplot's legend. + xlabels : list + List of strings of the labels of each subplot's X-axis. + ylabels : list + List of strings of the labels of each subplot's Y-axis. + yscales : str + List of strings of the scales of each subplot's Y-axis. It supports + matlabs defaults values: "linear", "log", "symlog" and "logit" + + """ + title = kw.get("title") + subtitles = kw.get("subtitles") + labels = kw.get("labels") + xlabels = kw.get("xlabels") + ylabels = kw.get("ylabels") + yscales = kw.get("yscales") + index = kw.get("index") + indices = kw.get("indices") + shades_spans = kw.get("shaded") + num_subplots = len(data) # Number of given arrays + # Create figure with vertically stacked subplots + fig, axs = plt.subplots( + num_subplots, + 1, + num=title, + squeeze=False, + sharex=kw.get('sharex', "indices" not in kw), + sharey=kw.get('sharey', False) + ) + for i, array in enumerate(data): + array = np.copy(array) + if array.ndim > 2: + raise ValueError(f"Data array {i} has more than 2 dimensions.") + if array.ndim < 2: + # Plot a single line in the subplot (1-dimensional array) + label = labels[i][0] if labels else None + index = index if index is not None else np.arange(array.shape[0]) + axs[i, 0].plot(index, array, color=COLORS[0], lw=0.5, ls='-', label=label) + else: + # Plot multiple lines in the subplot (2-dimensional array) + array_sz = array.shape + if array_sz[0] > array_sz[1]: + # Transpose array if it has more rows than columns + array = array.T + index = indices[i] if indices is not None else np.arange(array_sz[0]) + for j, row in enumerate(array): + label = None + if labels: + if len(labels[i]) == len(array): + label = labels[i][j] + axs[i, 0].plot(index, row, color=COLORS[j], lw=0.5, ls='-', label=label) + axs[i, 0].grid(axis='y') + if subtitles: + axs[i, 0].set_title(subtitles[i]) + if xlabels: + axs[i, 0].set_xlabel(xlabels[i]) + if ylabels: + axs[i, 0].set_ylabel(ylabels[i]) + if yscales: + axs[i, 0].set_yscale(yscales[i]) + if shades_spans is not None: + # Add shaded areas + try: + if isinstance(shades_spans, (list, np.ndarray)): + current_spans = shades_spans[i] if np.copy(shades_spans).ndim > 2 else shades_spans + for s in current_spans: + axs[i, 0].axvspan(s[0], s[1], color='gray', alpha=0.1) + elif isinstance(shades_spans, dict): + # Add shades AND their corresponding labels + for k, v in shades_spans.items(): + span = [v['start'], v['stop']] + axs[i, 0].axvspan(span[0], span[1], color='gray', alpha=0.1) + axs[i, 0].text(int(np.mean(span)), max(array), k, ha='center') + except: + print("No spans were given") + if labels: + if len(labels[i]) > 0: + axs[i, 0].legend(loc='lower right') + fig.tight_layout() + plt.show() + +def ellipsoid(center: np.ndarray = None, axes: np.ndarray = None, num_points: int = 20) -> tuple: + """ + Return the mesh of an ellipsoid. + + Parameters + ---------- + center : numpy.ndarray, optional + 3-element array with the ellipsoid's center. Default is [0, 0, 0]. + axes : numpy.ndarray, optional + 3-element array with the ellipsoid's main axes lengths. Default is + [1, 1, 1]. + num_points : int, optional + Number of points to use in the mesh. Default is 20. + + Returns + ------- + tuple + Tuple with the mesh of the ellipsoid in the form (x, y, z). + + """ + if center is None: + center = np.zeros(3) + if axes is None: + axes = np.ones(3) + if not isinstance(center, (np.ndarray, list, tuple)): + raise TypeError("Center must be a 3-element array.") + if not isinstance(axes, (np.ndarray, list, tuple)): + raise TypeError("Axes must be a 3-element array.") + # Create ellipsoid mesh + cx, cy, cz = center + sx, sy, sz = axes + u, v = np.mgrid[0:2*np.pi:complex(num_points), 0:np.pi:complex(num_points)] + x = sx * np.cos(u)*np.sin(v) + cx + y = sy * np.sin(u)*np.sin(v) + cy + z = sz * np.cos(v) + cz + return x, y, z + +def frame(dcm: np.ndarray = None, position: np.ndarray = None, scale: float = 1.0) -> list: + """ + Return the coordinates of an orthogonal frame. + + Parameters + ---------- + dcm : numpy.ndarray, optional + 3-by-3 array with the frame's axes. Default is the identity matrix. + position : numpy.ndarray, optional + 3-element array with the frame's origin. Default is [0, 0, 0]. + scale : float, optional + Scale factor for the frame's axes. Default is 1.0. + + """ + if dcm is None: + dcm = np.identity(3) + if position is None: + position = np.zeros(3) + f_coords = [] + for column_index in range(3): + axis_end = dcm[:, column_index]*scale + position + f_coords.append(np.c_[position, axis_end]) + return f_coords + + +def add_ellipsoid(ax, params: list | dict, num_points: int = 20, color = 'k', lw = 0.5, **kwargs) -> None: + """ + Add a ellipsoid to an existing 3D plot. + + Parameters + ---------- + ax : matplotlib.axes.Axes3D + 3D axis where the ellipsoid will be added. + params : list or dict. + List or dictionary with the parameters to draw an ellipsoid. If a list + is given, it must be of the form [[a, b, c], [x, y, z]], where a, b, c + are the coordinates of the ellipsoid's center, and x, y, z are the + ellipsoid's main axes lengths. If a dictionary is given, it must be of + the form {'center': [a, b, c], 'axes': [x, y, z]} + num_points : int, optional + Number of points, per axis, to use in the mesh. Default is 20. + color : str, optional + Color of the ellipsoid. Default is 'k'. + lw : float, optional + Line width of the ellipsoid. Default is 0.5. + + """ + if isinstance(params, (list, tuple, np.ndarray)): + center, axes = params + elif isinstance(params, dict): + center = params.get("center", np.zeros(3)) + axes = params.get("axes", np.ones(3)) + else: + raise TypeError("Unknown type for 'sphere'. Try a list or a dict.") + # Extract only the expected parameters from kwargs + expected_params = {'num_points': num_points, 'color': color, 'lw': lw, 'alpha': 0.5} + for key in expected_params: + if key in kwargs: + expected_params[key] = kwargs[key] + x, y, z = ellipsoid(center=center, axes=axes, num_points=expected_params['num_points']) # Ellipsoid mesh + ax.plot_wireframe(x, y, z, color=expected_params['color'], lw=expected_params['lw'], alpha=expected_params['alpha']) + +def add_frame(ax, dcm: np.ndarray, position = None, color: str | list = None, scale: float = 1.0, lw: float = 1.5, **kwargs) -> None: + """ + Add a frame to an existing 3D plot. + + Parameters + ---------- + ax : mpl_toolkits.mplot3d.axes3d.Axes3D + 3D axis where the frame will be added. + frame : numpy.ndarray + 3-by-3 array with the frame's axes. Each row is a vector. + position : numpy.ndarray, optional + 3-element array with the frame's position. Default is [0, 0, 0]. + color : str or list of strings, optional + Color of the frame. Default is None, which iterates over RGB. + scale : float, optional + Scale factor of the frame. Default is 1.0 + lw : float, optional + Line width of the frame. Default is 1.5 + + """ + if not hasattr(ax, 'plot'): + raise TypeError("The given axis is not a 3D plot item.") + colors = ([color]*3 if isinstance(color, str) else color) if color is not None else COLORS[:3] + # Extract only the expected parameters from kwargs + expected_params = {'scale': scale, 'lw': lw} + for key in expected_params: + if key in kwargs: + expected_params[key] = kwargs[key] + frame_coords = frame(dcm, position, scale) + for axis in frame_coords: + ax.plot(*axis, color=colors.pop(0), lw=lw) + +def add_items(ax, **kwargs) -> None: + """ + Add items to an existing 3D plot. + + Parameters + ---------- + ax : mpl_toolkits.mplot3d.axes3d.Axes3D + 3D axis where the items will be added. + kwargs : dict + Dictionary with the items to be added. The keys are the items' types, + and the values are the items' data and parameters. + + """ + if 'scatter' in kwargs: + data = kwargs['scatter'] + if isinstance(data, (list, tuple, np.ndarray)): + if isinstance(data, np.ndarray): + data = data.T + ax.scatter(*data) + elif isinstance(data, dict): + scatter_dict = copy.deepcopy(data) + for k, v in scatter_dict.items(): + points = v.pop('data') # Get N-by-3 numpy array from dict + ax.scatter(*points.T, **v) + else: + raise TypeError(f"Unknown type for 'scatter': {type(data)}. Try an array, list or dict.") + if 'lines' in kwargs: + data = kwargs['lines'] + if isinstance(data, (list, tuple, np.ndarray)): + if isinstance(data, np.ndarray): + data = data.T + ax.plot(*data) + elif isinstance(data, dict): + lines_dict = copy.deepcopy(data) + for k, v in lines_dict.items(): + lines = v.pop('data') # Get N-by-3 numpy array from dict + ax.plot(*lines.T, **v) + else: + raise TypeError(f"Unknown type for 'lines': {type(data)}. Try an array, list or dict.") + if 'frames' in kwargs: + if isinstance(kwargs['frames'], dict): + # Frames given as dictionary of dictionaries with each frame's attitude and position + for k, v in kwargs['frames'].items(): + data = v.copy() + add_frame(ax, dcm=data['attitude'], position=data.pop('position'), **data) + elif isinstance(kwargs['frames'], list): + # Frames given as list of frames. + for frame_idx, frame_item in enumerate(kwargs['frames']): + np_frame = np.copy(frame_item) + if np_frame.shape == (3, 3): + add_frame(ax, dcm=np_frame) + elif np_frame.shape == (3, 4): + add_frame(ax, dcm=np_frame[:, :3], position=np_frame[:, 3]) + else: + raise ValueError(f"Unknown shape for frame {frame_idx}: {np_frame.shape}") + elif isinstance(kwargs['frames'], np.ndarray): + # 3-dimensional array with the frames' data + if kwargs['frames'].ndim == 2: + np_frame = np.copy(kwargs['frames']) + if np_frame.shape == (3, 3): + add_frame(ax, dcm=np_frame) + elif np_frame.shape == (3, 4): + add_frame(ax, dcm=np_frame[:, :3], position=np_frame[:, 3]) + else: + raise ValueError(f"Unknown shape for frame: {np_frame.shape}") + elif kwargs['frames'].ndim == 3: + for frame_idx, frame_item in enumerate(kwargs['frames']): + np_frame = np.copy(frame_item) + if np_frame.shape == (3, 3): + add_frame(ax, dcm=np_frame) + elif np_frame.shape == (3, 4): + add_frame(ax, dcm=np_frame[:, :3], position=np_frame[:, 3]) + else: + raise ValueError(f"Unknown shape for frame {frame_idx}: {np_frame.shape}") + else: + raise ValueError(f"Frames must be a 2D or 3D numpy array. Got shape {kwargs['frames'].shape}") + else: + raise TypeError(f"Unknown type for 'frames': {type(kwargs['frames'])}. Try a list or dict.") + if 'ellipsoids' in kwargs: + for k, v in kwargs['ellipsoids'].items(): + add_ellipsoid(ax, v, **v) + +def plot3(**kwargs) -> None | tuple: + """ + Plot 3-dimensional data in a cartesian coordinate system. + + Parameters + ---------- + show : bool, optional + Show the plot after creating it. Default is True. Otherwise, the plot + Figure and Axes objects are returned. + + """ + # Build the plot + fig = plt.figure() + ax = fig.add_subplot(projection='3d') + + # Add items + add_items(ax, **kwargs) + + # Set properties of plot + plt.tight_layout() + ax.set_xlabel('X') + ax.set_ylabel('Y') + ax.set_zlabel('Z') + ax.set_aspect('equal') # Added in matplotlib 3.6 + + # Show or return the plot + if not kwargs.get('show', True): + return fig, ax + plt.show() From cfaf62cd67afc073ad8b77501555aea3fbe778a3 Mon Sep 17 00:00:00 2001 From: Mayitzin Date: Tue, 1 Oct 2024 14:38:41 +0200 Subject: [PATCH 15/15] Update output of notebook, and add .ipynb_checkpoints to .gitignore --- .gitignore | 1 + notebooks/Showcase.ipynb | 169 ++++++++++++++++++++++++++++++++++----- 2 files changed, 150 insertions(+), 20 deletions(-) diff --git a/.gitignore b/.gitignore index 9ed7c6f..1601ee5 100644 --- a/.gitignore +++ b/.gitignore @@ -11,6 +11,7 @@ *.DS_Store build/* dist/* +*/.ipynb_checkpoints/* # test-related .coverage diff --git a/notebooks/Showcase.ipynb b/notebooks/Showcase.ipynb index 7b1ac6d..1268058 100644 --- a/notebooks/Showcase.ipynb +++ b/notebooks/Showcase.ipynb @@ -126,7 +126,7 @@ { "data": { "application/vnd.jupyter.widget-view+json": { - "model_id": "af951b8628e04da1a5dd3dc9308a7701", + "model_id": "63a32ec81389462e8170cc5fd8e872e8", "version_major": 2, "version_minor": 0 }, @@ -213,7 +213,7 @@ { "data": { "application/vnd.jupyter.widget-view+json": { - "model_id": "3600367061b3430ab0636f066888825c", + "model_id": "42d1864a7bcd4bc99dd0cd9e91adedb7", "version_major": 2, "version_minor": 0 }, @@ -344,18 +344,11 @@ "Rotation of 30 degrees about Z-axis:\n", "[[ 0.8660254 -0.5 0. ]\n", " [ 0.5 0.8660254 0. ]\n", - " [ 0. 0. 1. ]]\n" - ] - }, - { - "ename": "NameError", - "evalue": "name 'rotation' is not defined", - "output_type": "error", - "traceback": [ - "\u001b[1;31m---------------------------------------------------------------------------\u001b[0m", - "\u001b[1;31mNameError\u001b[0m Traceback (most recent call last)", - "Cell \u001b[1;32mIn[7], line 14\u001b[0m\n\u001b[0;32m 10\u001b[0m \u001b[38;5;66;03m# New rotation matrix from products of rotations about X-, Y-, and Z-axis, respectively.\u001b[39;00m\n\u001b[0;32m 11\u001b[0m \u001b[38;5;66;03m# Order of matrix multiplication is right to left: x --> y --> z\u001b[39;00m\n\u001b[0;32m 12\u001b[0m orientation \u001b[38;5;241m=\u001b[39m ahrs\u001b[38;5;241m.\u001b[39mDCM(z\u001b[38;5;241m=\u001b[39m\u001b[38;5;241m30.0\u001b[39m\u001b[38;5;241m*\u001b[39mahrs\u001b[38;5;241m.\u001b[39mDEG2RAD) \u001b[38;5;241m@\u001b[39m ahrs\u001b[38;5;241m.\u001b[39mDCM(y\u001b[38;5;241m=\u001b[39m\u001b[38;5;241m20.0\u001b[39m\u001b[38;5;241m*\u001b[39mahrs\u001b[38;5;241m.\u001b[39mDEG2RAD) \u001b[38;5;241m@\u001b[39m ahrs\u001b[38;5;241m.\u001b[39mDCM(x\u001b[38;5;241m=\u001b[39m\u001b[38;5;241m10.0\u001b[39m\u001b[38;5;241m*\u001b[39mahrs\u001b[38;5;241m.\u001b[39mDEG2RAD)\n\u001b[1;32m---> 14\u001b[0m \u001b[38;5;28mprint\u001b[39m(\u001b[38;5;124mf\u001b[39m\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mRotation Matrix \u001b[39m\u001b[38;5;132;01m{\u001b[39;00m\u001b[38;5;28mtype\u001b[39m(\u001b[43mrotation\u001b[49m)\u001b[38;5;132;01m}\u001b[39;00m\u001b[38;5;124m:\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n\u001b[0;32m 15\u001b[0m \u001b[38;5;28mprint\u001b[39m(orientation)\n", - "\u001b[1;31mNameError\u001b[0m: name 'rotation' is not defined" + " [ 0. 0. 1. ]]\n", + "Rotation Matrix :\n", + "[[ 0.81379768 -0.44096961 0.37852231]\n", + " [ 0.46984631 0.88256412 0.01802831]\n", + " [-0.34202014 0.16317591 0.92541658]]\n" ] } ], @@ -387,10 +380,23 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 8, "id": "3b2f1a04-6dd1-4e94-a53f-de1c28c22cf2", "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "DCM([[ 0.81379768, -0.44096961, 0.37852231],\n", + " [ 0.46984631, 0.88256412, 0.01802831],\n", + " [-0.34202014, 0.16317591, 0.92541658]])" + ] + }, + "execution_count": 8, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "orientation = ahrs.DCM( euler=('zyx', np.array([30.0, 20.0, 10.0])*ahrs.DEG2RAD) )\n", "orientation.view()" @@ -408,10 +414,59 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 9, "id": "046c9a46-5b4b-4e5c-a4f8-e4e9c40afa7e", "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "rotation.T =\n", + "[[ 0.81379768 0.46984631 -0.34202014]\n", + " [-0.44096961 0.88256412 0.16317591]\n", + " [ 0.37852231 0.01802831 0.92541658]] \n", + "\n", + "rotation.I =\n", + "[[ 0.81379768 0.46984631 -0.34202014]\n", + " [-0.44096961 0.88256412 0.16317591]\n", + " [ 0.37852231 0.01802831 0.92541658]] \n", + "\n", + "rotation.inv =\n", + "[[ 0.81379768 0.46984631 -0.34202014]\n", + " [-0.44096961 0.88256412 0.16317591]\n", + " [ 0.37852231 0.01802831 0.92541658]] \n", + "\n", + "rotation.det =\n", + "1.0000000000000002 \n", + "\n", + "rotation.determinant =\n", + "1.0000000000000002 \n", + "\n", + "rotation.fro =\n", + "1.7320508075688772 \n", + "\n", + "rotation.frobenius =\n", + "1.7320508075688772 \n", + "\n", + "rotation.adj =\n", + "[[ 0.81379768 0.46984631 -0.34202014]\n", + " [-0.44096961 0.88256412 0.16317591]\n", + " [ 0.37852231 0.01802831 0.92541658]] \n", + "\n", + "rotation.adjugate =\n", + "[[ 0.81379768 0.46984631 -0.34202014]\n", + " [-0.44096961 0.88256412 0.16317591]\n", + " [ 0.37852231 0.01802831 0.92541658]] \n", + "\n", + "rotation.log =\n", + "[[ 0. 0.48647923 -0.38485157]\n", + " [-0.48647923 0. 0.07752532]\n", + " [ 0.38485157 -0.07752532 0. ]] \n", + "\n" + ] + } + ], "source": [ "attribute_list = ['T', 'I', 'inv', 'det', 'determinant', 'fro', 'frobenius', 'adj', 'adjugate', 'log']\n", "for attribute_name in attribute_list:\n", @@ -431,10 +486,84 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 10, "id": "5eedfc5e-b40b-47cc-ba29-eae8f89491bc", "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "DCM.all() Returns True if all elements evaluate to True.\n", + "DCM.any() Returns True if any of the elements of `a` evaluate to True.\n", + "DCM.argmax() Return indices of the maximum values along the given axis.\n", + "DCM.argmin() Return indices of the minimum values along the given axis.\n", + "DCM.argpartition() Returns the indices that would partition this array.\n", + "DCM.argsort() Returns the indices that would sort this array.\n", + "DCM.astype() Copy of the array, cast to a specified type.\n", + "DCM.byteswap() Swap the bytes of the array elements\n", + "DCM.choose() Use an index array to construct a new array from a set of choices.\n", + "DCM.clip() Return an array whose values are limited to ``[min, max]``.\n", + "DCM.compress() Return selected slices of this array along given axis.\n", + "DCM.conj() Complex-conjugate all elements.\n", + "DCM.conjugate() Return the complex conjugate, element-wise.\n", + "DCM.copy() Return a copy of the array.\n", + "DCM.cumprod() Return the cumulative product of the elements along the given axis.\n", + "DCM.cumsum() Return the cumulative sum of the elements along the given axis.\n", + "DCM.diagonal() Return specified diagonals. In NumPy 1.9 the returned array is a\n", + "DCM.dot() \n", + "DCM.dump() Dump a pickle of the array to the specified file.\n", + "DCM.dumps() Returns the pickle of the array as a string.\n", + "DCM.fill() Fill the array with a scalar value.\n", + "DCM.flatten() Return a copy of the array collapsed into one dimension.\n", + "DCM.from_axang() Synonym of method `from_axisangle`.\n", + "DCM.from_axisangle() DCM from axis-angle representation\n", + "DCM.from_q() Synonym of method `from_quaternion`.\n", + "DCM.from_quaternion() DCM from given quaternion\n", + "DCM.getfield() Returns a field of the given array as a certain type.\n", + "DCM.item() Copy an element of an array to a standard Python scalar and return it.\n", + "DCM.itemset() Insert scalar into an array (scalar is cast to array's dtype, if possible)\n", + "DCM.max() Return the maximum along a given axis.\n", + "DCM.mean() Returns the average of the array elements along given axis.\n", + "DCM.min() Return the minimum along a given axis.\n", + "DCM.newbyteorder() Return the array with the same data viewed with a different byte order.\n", + "DCM.nonzero() Return the indices of the elements that are non-zero.\n", + "DCM.ode() Ordinary Differential Equation of the DCM.\n", + "DCM.partition() Rearranges the elements in the array in such a way that the value of the\n", + "DCM.prod() Return the product of the array elements over the given axis\n", + "DCM.ptp() Peak to peak (maximum - minimum) value along a given axis.\n", + "DCM.put() Set ``a.flat[n] = values[n]`` for all `n` in indices.\n", + "DCM.ravel() Return a flattened array.\n", + "DCM.repeat() Repeat elements of an array.\n", + "DCM.reshape() Returns an array containing the same data with a new shape.\n", + "DCM.resize() Change shape and size of array in-place.\n", + "DCM.round() Return `a` with each element rounded to the given number of decimals.\n", + "DCM.searchsorted() Find indices where elements of v should be inserted in a to maintain order.\n", + "DCM.setfield() Put a value into a specified place in a field defined by a data-type.\n", + "DCM.setflags() Set array flags WRITEABLE, ALIGNED, WRITEBACKIFCOPY,\n", + "DCM.sort() Sort an array in-place. Refer to `numpy.sort` for full documentation.\n", + "DCM.squeeze() Remove axes of length one from `a`.\n", + "DCM.std() Returns the standard deviation of the array elements along given axis.\n", + "DCM.sum() Return the sum of the array elements over the given axis.\n", + "DCM.swapaxes() Return a view of the array with `axis1` and `axis2` interchanged.\n", + "DCM.take() Return an array formed from the elements of `a` at the given indices.\n", + "DCM.to_angles() Synonym of method `to_rpy`.\n", + "DCM.to_axang() Synonym of method `to_axisangle`.\n", + "DCM.to_axisangle() Return axis-angle representation of the DCM.\n", + "DCM.to_q() Synonym of method `to_quaternion`.\n", + "DCM.to_quaternion() Quaternion from Direction Cosine Matrix.\n", + "DCM.to_rpy() Roll-Pitch-Yaw Angles from DCM\n", + "DCM.tobytes() Construct Python bytes containing the raw data bytes in the array.\n", + "DCM.tofile() Write array to a file as text or binary (default).\n", + "DCM.tolist() Return the array as an ``a.ndim``-levels deep nested list of Python scalars.\n", + "DCM.tostring() A compatibility alias for `tobytes`, with exactly the same behavior.\n", + "DCM.trace() Return the sum along diagonals of the array.\n", + "DCM.transpose() Returns a view of the array with axes transposed.\n", + "DCM.var() Returns the variance of the array elements, along given axis.\n", + "DCM.view() New view of array with the same data.\n" + ] + } + ], "source": [ "# List all DCM methods and the first descriptive line from each docstring\n", "from tools import describe_methods\n",