From 76e86cf937c586e19f300b7aafc95fb2b8121847 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 14:46:54 -0500 Subject: [PATCH 001/388] Initial commit. --- .gitignore | 1 + CMakeLists.txt | 17 ++ LICENSE | 28 +++ matrix/Dcm.hpp | 64 ++++++ matrix/Euler.hpp | 61 +++++ matrix/Matrix.hpp | 472 ++++++++++++++++++++++++++++++++++++++ matrix/Quaternion.hpp | 89 +++++++ matrix/Vector.hpp | 52 +++++ matrix/Vector3.hpp | 46 ++++ test/CMakeLists.txt | 20 ++ test/dcm.cpp | 13 ++ test/euler.cpp | 15 ++ test/inverse.cpp | 30 +++ test/matrixAssignment.cpp | 29 +++ test/matrixMult.cpp | 26 +++ test/matrixScalarMult.cpp | 18 ++ test/quaternion.cpp | 15 ++ test/setIdentity.cpp | 25 ++ test/transpose.cpp | 18 ++ test/vector.cpp | 13 ++ test/vector3.cpp | 13 ++ test/vectorAssignment.cpp | 28 +++ 22 files changed, 1093 insertions(+) create mode 100644 .gitignore create mode 100644 CMakeLists.txt create mode 100644 LICENSE create mode 100644 matrix/Dcm.hpp create mode 100644 matrix/Euler.hpp create mode 100644 matrix/Matrix.hpp create mode 100644 matrix/Quaternion.hpp create mode 100644 matrix/Vector.hpp create mode 100644 matrix/Vector3.hpp create mode 100644 test/CMakeLists.txt create mode 100644 test/dcm.cpp create mode 100644 test/euler.cpp create mode 100644 test/inverse.cpp create mode 100644 test/matrixAssignment.cpp create mode 100644 test/matrixMult.cpp create mode 100644 test/matrixScalarMult.cpp create mode 100644 test/quaternion.cpp create mode 100644 test/setIdentity.cpp create mode 100644 test/transpose.cpp create mode 100644 test/vector.cpp create mode 100644 test/vector3.cpp create mode 100644 test/vectorAssignment.cpp diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000000..a5309e6b90 --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +build*/ diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000000..6cb01964c6 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 2.8) + +project(matrix CXX) + +list(APPEND CMAKE_CXX_FLAGS + -Wall + -Weffc++ + -Wfatal-errors + ) + +string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") + +enable_testing() + +include_directories(matrix) + +add_subdirectory(test) diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000000..1d5f729548 --- /dev/null +++ b/LICENSE @@ -0,0 +1,28 @@ +Copyright (c) 2015, James Goppert +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of ocr nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp new file mode 100644 index 0000000000..8222e356d2 --- /dev/null +++ b/matrix/Dcm.hpp @@ -0,0 +1,64 @@ +/** + * @file Dcm.hpp + * + * A direction cosine matrix class. + * + * @author James Goppert + */ + +#pragma once + +#include +#include +#include + +namespace matrix +{ + +template +class Quaternion; + +template +class Dcm : public Matrix +{ +public: + virtual ~Dcm() {}; + + typedef Matrix Vector3; + + Dcm() : Matrix() + { + } + + Dcm(const Quaternion & q) { + // TODO + Dcm &c = *this; + c(0, 0) = 0; + c(0, 1) = 0; + c(0, 2) = 0; + c(1, 0) = 0; + c(1, 1) = 0; + c(1, 2) = 0; + c(2, 0) = 0; + c(2, 1) = 0; + c(2, 2) = 0; + } + + Dcm(const Euler & e) { + // TODO + Dcm &c = *this; + c(0, 0) = 0; + c(0, 1) = 0; + c(0, 2) = 0; + c(1, 0) = 0; + c(1, 1) = 0; + c(1, 2) = 0; + c(2, 0) = 0; + c(2, 1) = 0; + c(2, 2) = 0; + } +}; + +typedef Dcm Dcmf; + +}; // namespace matrix diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp new file mode 100644 index 0000000000..d6a7178f89 --- /dev/null +++ b/matrix/Euler.hpp @@ -0,0 +1,61 @@ +/** + * @file Euler.hpp + * + * Euler angle tait-bryan body 3-2-1 + * + * @author James Goppert + */ + +#pragma once +#include +#include +#include + +namespace matrix +{ + +template +class Dcm; + +template +class Quaternion; + +template +class Euler : public Vector +{ +public: + virtual ~Euler() {}; + + Euler() : Vector() + { + } + + Euler(Type roll, Type pitch, Type yaw) : Vector() + { + Euler &v(*this); + v(0) = roll; + v(1) = pitch; + v(2) = yaw; + } + + Euler(const Dcm & dcm) { + // TODO + Euler &e = *this; + e(0) = 0; + e(1) = 0; + e(2) = 0; + } + + Euler(const Quaternion & q) { + // TODO + Euler &e = *this; + e(0) = 0; + e(1) = 0; + e(2) = 0; + } + +}; + +typedef Euler Eulerf; + +}; // namespace matrix diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp new file mode 100644 index 0000000000..ee94b6020a --- /dev/null +++ b/matrix/Matrix.hpp @@ -0,0 +1,472 @@ +/** + * @file Matrix.hpp + * + * A simple matrix template library. + * + * @author James Goppert + */ + +#pragma once + +#include +#include +#include +#include +#include + +namespace matrix +{ + +template +class Matrix +{ + +protected: + Type _data[M][N]; + size_t _rows; + size_t _cols; + +public: + + virtual ~Matrix() {}; + + Matrix() : + _data(), + _rows(M), + _cols(N) + { + } + + Matrix(const Type *data) : + _data(), + _rows(M), + _cols(N) + { + memcpy(_data, data, sizeof(_data)); + } + + Matrix(const Matrix &other) : + _data(), + _rows(M), + _cols(N) + { + memcpy(_data, other._data, sizeof(_data)); + } + + /** + * Accessors/ Assignment etc. + */ + + Type *data() + { + return _data[0]; + } + + inline size_t rows() const + { + return _rows; + } + + inline size_t cols() const + { + return _rows; + } + + inline Type operator()(size_t i, size_t j) const + { + return _data[i][j]; + } + + inline Type &operator()(size_t i, size_t j) + { + return _data[i][j]; + } + + /** + * Matrix Operations + */ + + // this might use a lot of programming memory + // since it instantiates a class for every + // required mult pair, but it provides + // compile time size_t checking + template + Matrix operator*(const Matrix &other) const + { + const Matrix &self = *this; + Matrix res; + res.setZero(); + + for (size_t i = 0; i < M; i++) { + for (size_t k = 0; k < P; k++) { + for (size_t j = 0; j < N; j++) { + res(i, k) += self(i, j) * other(j, k); + } + } + } + + return res; + } + + Matrix operator+(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) + other(i, j); + } + } + + return res; + } + + bool operator==(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + if (self(i , j) != other(i, j)) { + return false; + } + } + } + + return true; + } + + operator Type(); + + Matrix operator-(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) - other(i, j); + } + } + + return res; + } + + void operator+=(const Matrix &other) + { + Matrix &self = *this; + self = self + other; + } + + void operator-=(const Matrix &other) + { + Matrix &self = *this; + self = self - other; + } + + void operator*=(const Matrix &other) + { + Matrix &self = *this; + self = self * other; + } + + /** + * Scalar Operations + */ + + Matrix operator*(Type scalar) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) * scalar; + } + } + + return res; + } + + Matrix operator+(Type scalar) const + { + Matrix res; + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) + scalar; + } + } + + return res; + } + + void operator*=(Type scalar) + { + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) = self(i, j) * scalar; + } + } + } + + void operator/=(Type scalar) + { + Matrix &self = *this; + self = self * (1.0f / scalar); + } + + /** + * Misc. Functions + */ + + void print() + { + Matrix &self = *this; + printf("\n"); + + for (size_t i = 0; i < M; i++) { + printf("["); + + for (size_t j = 0; j < N; j++) { + printf("%10g\t", double(self(i, j))); + } + + printf("]\n"); + } + } + + Matrix transpose() const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(j, i) = self(i, j); + } + } + + return res; + } + + + // tranpose alias + inline Matrix T() const + { + return transpose(); + } + + Matrix expm(float dt, size_t n) const + { + Matrix res; + res.setIdentity(); + Matrix A_pow = *this; + float k_fact = 1; + size_t k = 1; + + while (k < n) { + res += A_pow * (float(pow(dt, k)) / k_fact); + + if (k == n) { break; } + + A_pow *= A_pow; + k_fact *= k; + k++; + } + + return res; + } + + Matrix diagonal() const + { + Matrix res; + // force square for now + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i, i); + } + + return res; + } + + void setZero() + { + memset(_data, 0, sizeof(_data)); + } + + void setIdentity() + { + setZero(); + Matrix &self = *this; + + for (size_t i = 0; i < M and i < N; i++) { + self(i, i) = 1; + } + } + + inline void swapRows(size_t a, size_t b) + { + if (a == b) { return; } + + Matrix &self = *this; + + for (size_t j = 0; j < cols(); j++) { + Type tmp = self(a, j); + self(a, j) = self(b, j); + self(b, j) = tmp; + } + } + + inline void swapCols(size_t a, size_t b) + { + if (a == b) { return; } + + Matrix &self = *this; + + for (size_t i = 0; i < rows(); i++) { + Type tmp = self(i, a); + self(i, a) = self(i, b); + self(i, b) = tmp; + } + } + + /** + * inverse based on LU factorization with partial pivotting + */ + Matrix inverse() const + { + Matrix L; + L.setIdentity(); + const Matrix &A = (*this); + Matrix U = A; + Matrix P; + P.setIdentity(); + + //printf("A:\n"); A.print(); + + // for all diagonal elements + for (size_t n = 0; n < N; n++) { + + // if diagonal is zero, swap with row below + if (fabsf(U(n, n)) < 1e-8f) { + //printf("trying pivot for row %d\n",n); + for (size_t i = 0; i < N; i++) { + if (i == n) { continue; } + + //printf("\ttrying row %d\n",i); + if (fabsf(U(i, n)) > 1e-8f) { + //printf("swapped %d\n",i); + U.swapRows(i, n); + P.swapRows(i, n); + } + } + } + +#ifdef MATRIX_ASSERT + //printf("A:\n"); A.print(); + //printf("U:\n"); U.print(); + //printf("P:\n"); P.print(); + //fflush(stdout); + ASSERT(fabsf(U(n, n)) > 1e-8f); +#endif + + // failsafe, return zero matrix + if (fabsf(U(n, n)) < 1e-8f) { + Matrix zero; + zero.setZero(); + return zero; + } + + // for all rows below diagonal + for (size_t i = (n + 1); i < N; i++) { + L(i, n) = U(i, n) / U(n, n); + + // add i-th row and n-th row + // multiplied by: -a(i,n)/a(n,n) + for (size_t k = n; k < N; k++) { + U(i, k) -= L(i, n) * U(n, k); + } + } + } + + //printf("L:\n"); L.print(); + //printf("U:\n"); U.print(); + + // solve LY=P*I for Y by forward subst + Matrix Y = P; + + // for all columns of Y + for (size_t c = 0; c < N; c++) { + // for all rows of L + for (size_t i = 0; i < N; i++) { + // for all columns of L + for (size_t j = 0; j < i; j++) { + // for all existing y + // subtract the component they + // contribute to the solution + Y(i, c) -= L(i, j) * Y(j, c); + } + + // divide by the factor + // on current + // term to be solved + // Y(i,c) /= L(i,i); + // but L(i,i) = 1.0 + } + } + + //printf("Y:\n"); Y.print(); + + // solve Ux=y for x by back subst + Matrix X = Y; + + // for all columns of X + for (size_t c = 0; c < N; c++) { + // for all rows of U + for (size_t k = 0; k < N; k++) { + // have to go in reverse order + size_t i = N - 1 - k; + + // for all columns of U + for (size_t j = i + 1; j < N; j++) { + // for all existing x + // subtract the component they + // contribute to the solution + X(i, c) -= U(i, j) * X(j, c); + } + + // divide by the factor + // on current + // term to be solved + X(i, c) /= U(i, i); + } + } + + //printf("X:\n"); X.print(); + return X; + } + + // inverse alias + inline Matrix I() const + { + return inverse(); + } + +}; + +template <> +Matrix::operator float() +{ + return (*this)(0,0); +} + +typedef Matrix Matrix3f; + +}; // namespace matrix diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp new file mode 100644 index 0000000000..91b344cd3d --- /dev/null +++ b/matrix/Quaternion.hpp @@ -0,0 +1,89 @@ +/** + * @file Matrix.hpp + * + * A quaternion class. + * + * @author James Goppert + */ + +#pragma once +#include +#include +#include + +namespace matrix +{ + +template +class Dcm; + +template +class Euler; + +template +class Quaternion : public Vector +{ +public: + virtual ~Quaternion() {}; + + Quaternion() : Vector() + { + // TODO + Quaternion &q = *this; + q(0) = 1; + q(1) = 0; + q(2) = 0; + q(3) = 0; + } + + Quaternion(const Dcm & dcm) { + // TODO + Quaternion &q = *this; + q(0) = 0; + q(1) = 0; + q(2) = 0; + q(3) = 0; + } + + Quaternion(const Euler & e) { + // TODO + Quaternion &q = *this; + q(0) = 0; + q(1) = 0; + q(2) = 0; + q(3) = 0; + } + + Quaternion(Type a, Type b, Type c, Type d) : Vector() + { + // TODO + Quaternion &q = *this; + q(0) = a; + q(1) = b; + q(2) = c; + q(3) = d; + } + + Quaternion operator*(const Quaternion &q) const + { + // TODO + const Quaternion &p = *this; + Quaternion r; + r(0) = 0; + r(1) = 0; + r(2) = 0; + r(3) = 0; + return r; + } + + Matrix derivative() const { + // TODO + Matrix d; + return d; + } + +}; + +typedef Quaternion Quatf; + +}; // namespace matrix diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp new file mode 100644 index 0000000000..3f8731bfc1 --- /dev/null +++ b/matrix/Vector.hpp @@ -0,0 +1,52 @@ +/** + * @file Vector.hpp + * + * Vector class. + * + * @author James Goppert + */ + +#pragma once +#include + +namespace matrix +{ + +template +class Vector : public Matrix +{ +public: + virtual ~Vector() {}; + + Vector() : Matrix() + { + } + + inline Type operator()(size_t i) const + { + const Matrix &v = *this; + return v(i, 0); + } + + inline Type &operator()(size_t i) + { + Matrix &v = *this; + return v(i, 0); + } + + Type dot(const Vector & b) { + Vector &a(*this); + Type r = 0; + for (int i = 0; i<3; i++) { + r += a(i)*b(i); + } + return r; + } + + Type norm() { + Vector &a(*this); + return sqrt(a.dot(a)); + } +}; + +}; // namespace matrix diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp new file mode 100644 index 0000000000..ff4d87208c --- /dev/null +++ b/matrix/Vector3.hpp @@ -0,0 +1,46 @@ +/** + * @file Vector3.hpp + * + * 3D vector class. + * + * @author James Goppert + */ + +#pragma once +#include + +namespace matrix +{ + +template +class Vector3 : public Vector +{ +public: + virtual ~Vector3() {}; + + Vector3() : Vector() + { + } + + Vector3(Type x, Type y, Type z) : Vector() + { + Vector3 &v(*this); + v(0) = x; + v(1) = y; + v(2) = z; + } + + Vector3 cross(const Vector3 & b) { + // TODO + Vector3 &a(*this); + Vector3 c; + c(0) = 0; + c(1) = 0; + c(2) = 0; + return c; + } +}; + +typedef Vector3 Vector3f; + +}; // namespace matrix diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt new file mode 100644 index 0000000000..4c37fe51c9 --- /dev/null +++ b/test/CMakeLists.txt @@ -0,0 +1,20 @@ +set(tests + setIdentity + inverse + matrixMult + vectorAssignment + matrixAssignment + matrixScalarMult + transpose + quaternion + dcm + vector + vector3 + euler + ) + +foreach(test ${tests}) + add_executable(${test} + ${test}.cpp) + add_test(${test} ${test}) +endforeach() diff --git a/test/dcm.cpp b/test/dcm.cpp new file mode 100644 index 0000000000..aa150a3552 --- /dev/null +++ b/test/dcm.cpp @@ -0,0 +1,13 @@ +#include "Dcm.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + Dcmf dcm; + Quatf q = Quatf(dcm); + Eulerf e = Eulerf(dcm); + return 0; +} diff --git a/test/euler.cpp b/test/euler.cpp new file mode 100644 index 0000000000..d5b3a4c30b --- /dev/null +++ b/test/euler.cpp @@ -0,0 +1,15 @@ +#include "Euler.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + Eulerf e; + float dp = e.T()*e; + Dcmf dcm = Dcmf(e); + Quatf q = Quatf(e); + float n = e.norm(); + return 0; +} diff --git a/test/inverse.cpp b/test/inverse.cpp new file mode 100644 index 0000000000..73f7c0b432 --- /dev/null +++ b/test/inverse.cpp @@ -0,0 +1,30 @@ +#include "Matrix.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; + Matrix3f A(data); + Matrix3f A_I = A.inverse(); + float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; + Matrix3f A_I_check(data_check); + (void)A_I; + assert(A_I == A_I_check); + + // stess test + static const size_t n = 100; + Matrix A_large; + A_large.setIdentity(); + Matrix A_large_I; + A_large_I.setZero(); + + for (size_t i = 0; i < 100; i++) { + A_large_I = A_large.inverse(); + assert(A_large == A_large_I); + } + + return 0; +} diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp new file mode 100644 index 0000000000..5a625d0cc1 --- /dev/null +++ b/test/matrixAssignment.cpp @@ -0,0 +1,29 @@ +#include "Matrix.hpp" +#include + +using namespace matrix; + +int main() +{ + Matrix3f m; + m.setZero(); + m(0, 0) = 1; + m(0, 1) = 2; + m(0, 2) = 3; + m(1, 0) = 4; + m(1, 1) = 5; + m(1, 2) = 6; + m(2, 0) = 7; + m(2, 1) = 8; + m(2, 2) = 9; + + m.print(); + + float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; + Matrix3f m2(data); + m2.print(); + + assert(m == m2); + + return 0; +} diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp new file mode 100644 index 0000000000..7b42d947d4 --- /dev/null +++ b/test/matrixMult.cpp @@ -0,0 +1,26 @@ +#include "Matrix.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; + Matrix3f A(data); + float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; + Matrix3f A_I(data_check); + Matrix3f I; + I.setIdentity(); + A.print(); + A_I.print(); + Matrix3f R = A * A_I; + R.print(); + assert(R == I); + + Matrix3f R2 = A; + R2 *= A_I; + R2.print(); + assert(R2 == I); + return 0; +} diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp new file mode 100644 index 0000000000..78bdb5b27f --- /dev/null +++ b/test/matrixScalarMult.cpp @@ -0,0 +1,18 @@ +#include "Matrix.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; + Matrix3f A(data); + A = A * 2; + float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; + Matrix3f A_check(data_check); + A.print(); + A_check.print(); + assert(A == A_check); + return 0; +} diff --git a/test/quaternion.cpp b/test/quaternion.cpp new file mode 100644 index 0000000000..40c36adf58 --- /dev/null +++ b/test/quaternion.cpp @@ -0,0 +1,15 @@ +#include "Quaternion.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + Quatf p(1, 0, 0, 0); + Quatf q(0, 1, 0, 0); + Quatf r = p*q; + Dcmf dcm = Dcmf(p); + Eulerf e = Eulerf(p); + return 0; +} diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp new file mode 100644 index 0000000000..f80e437939 --- /dev/null +++ b/test/setIdentity.cpp @@ -0,0 +1,25 @@ +#include "Matrix.hpp" +#include + +using namespace matrix; + +int main() +{ + Matrix3f A; + A.setIdentity(); + assert(A.rows() == 3); + assert(A.cols() == 3); + + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + if (i == j) { + assert(A(i, j) == 1); + + } else { + assert(A(i, j) == 0); + } + } + } + + return 0; +} diff --git a/test/transpose.cpp b/test/transpose.cpp new file mode 100644 index 0000000000..3623fc1f9a --- /dev/null +++ b/test/transpose.cpp @@ -0,0 +1,18 @@ +#include "Matrix.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + float data[9] = {1, 2, 3, 4, 5, 6}; + Matrix A(data); + Matrix A_T = A.transpose(); + float data_check[9] = {1, 4, 2, 5, 3, 6}; + Matrix A_T_check(data_check); + A_T.print(); + A_T_check.print(); + assert(A_T == A_T_check); + return 0; +} diff --git a/test/vector.cpp b/test/vector.cpp new file mode 100644 index 0000000000..3da9f8a01a --- /dev/null +++ b/test/vector.cpp @@ -0,0 +1,13 @@ +#include "Vector.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + Vector v; + float n = v.norm(); + float r = v.dot(v); + return 0; +} diff --git a/test/vector3.cpp b/test/vector3.cpp new file mode 100644 index 0000000000..f79186504e --- /dev/null +++ b/test/vector3.cpp @@ -0,0 +1,13 @@ +#include "Vector3.hpp" +#include +#include + +using namespace matrix; + +int main() +{ + Vector3f a(1, 0, 0); + Vector3f b(0, 1, 0); + Vector3f c = a.cross(b); + return 0; +} diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp new file mode 100644 index 0000000000..7d7c7a36a4 --- /dev/null +++ b/test/vectorAssignment.cpp @@ -0,0 +1,28 @@ +#include "Vector3.hpp" +#include + +using namespace matrix; + +int main() +{ + Vector3f v; + v(0) = 1; + v(1) = 2; + v(2) = 3; + + v.print(); + + assert(v(0) == 1); + assert(v(1) == 2); + assert(v(2) == 3); + + Vector3f v2(4, 5, 6); + + v2.print(); + + assert(v2(0) == 4); + assert(v2(1) == 5); + assert(v2(2) == 6); + + return 0; +} From a36ff9f1e5714cf116bbd8b4d6379de31ed2e186 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 19:38:31 -0500 Subject: [PATCH 002/388] Formatting and added Scalar. --- .gitignore | 1 + CMakeLists.txt | 14 + matrix/Dcm.hpp | 77 ++-- matrix/Euler.hpp | 79 ++-- matrix/Matrix.hpp | 827 +++++++++++++++++++------------------- matrix/Quaternion.hpp | 126 +++--- matrix/Scalar.hpp | 46 +++ matrix/Vector.hpp | 52 +-- matrix/Vector3.hpp | 41 +- test/dcm.cpp | 8 +- test/euler.cpp | 15 +- test/inverse.cpp | 36 +- test/matrixAssignment.cpp | 34 +- test/matrixMult.cpp | 32 +- test/matrixScalarMult.cpp | 18 +- test/quaternion.cpp | 12 +- test/setIdentity.cpp | 26 +- test/transpose.cpp | 18 +- test/vector.cpp | 10 +- test/vector3.cpp | 8 +- test/vectorAssignment.cpp | 28 +- 21 files changed, 811 insertions(+), 697 deletions(-) create mode 100644 matrix/Scalar.hpp diff --git a/.gitignore b/.gitignore index a5309e6b90..f1feb3e425 100644 --- a/.gitignore +++ b/.gitignore @@ -1 +1,2 @@ build*/ +*.orig diff --git a/CMakeLists.txt b/CMakeLists.txt index 6cb01964c6..6a297b7ce0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,9 +2,15 @@ cmake_minimum_required(VERSION 2.8) project(matrix CXX) +if (NOT CMAKE_BUILD_TYPE) + set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) + message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") +endif() + list(APPEND CMAKE_CXX_FLAGS -Wall -Weffc++ + #-Werror -Wfatal-errors ) @@ -15,3 +21,11 @@ enable_testing() include_directories(matrix) add_subdirectory(test) + +add_custom_target(format + COMMAND astyle --recursive + ${CMAKE_SOURCE_DIR}/matrix/*.*pp + ${CMAKE_SOURCE_DIR}/test/*.*pp + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + VERBATIM + ) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 8222e356d2..e13a84931c 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -22,41 +22,56 @@ template class Dcm : public Matrix { public: - virtual ~Dcm() {}; + virtual ~Dcm() {}; - typedef Matrix Vector3; + typedef Matrix Vector3; - Dcm() : Matrix() - { - } + Dcm() : Matrix() + { + } - Dcm(const Quaternion & q) { - // TODO - Dcm &c = *this; - c(0, 0) = 0; - c(0, 1) = 0; - c(0, 2) = 0; - c(1, 0) = 0; - c(1, 1) = 0; - c(1, 2) = 0; - c(2, 0) = 0; - c(2, 1) = 0; - c(2, 2) = 0; - } + Dcm(const Quaternion & q) { + Dcm &dcm = *this; + Type a = q(0); + Type b = q(1); + Type c = q(2); + Type d = q(3); + Type aSq = a*a; + Type bSq = b*b; + Type cSq = c*c; + Type dSq = d*d; + dcm(0, 0) = aSq + bSq - cSq - dSq; + dcm(0, 1) = 2 * (b * c - a * d); + dcm(0, 2) = 2 * (a * c + b * d); + dcm(1, 0) = 2 * (b * c + a * d); + dcm(1, 1) = aSq - bSq + cSq - dSq; + dcm(1, 2) = 2 * (c * d - a * b); + dcm(2, 0) = 2 * (b * d - a * c); + dcm(2, 1) = 2 * (a * b + c * d); + dcm(2, 2) = aSq - bSq - cSq + dSq; + } - Dcm(const Euler & e) { - // TODO - Dcm &c = *this; - c(0, 0) = 0; - c(0, 1) = 0; - c(0, 2) = 0; - c(1, 0) = 0; - c(1, 1) = 0; - c(1, 2) = 0; - c(2, 0) = 0; - c(2, 1) = 0; - c(2, 2) = 0; - } + Dcm(const Euler & euler) { + Dcm &dcm = *this; + Type cosPhi = cosf(euler.phi()); + Type sinPhi = sinf(euler.phi()); + Type cosThe = cosf(euler.theta()); + Type sinThe = sinf(euler.theta()); + Type cosPsi = cosf(euler.psi()); + Type sinPsi = sinf(euler.psi()); + + dcm(0, 0) = cosThe * cosPsi; + dcm(0, 1) = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; + dcm(0, 2) = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; + + dcm(1, 0) = cosThe * sinPsi; + dcm(1, 1) = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; + dcm(1, 2) = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; + + dcm(2, 0) = -sinThe; + dcm(2, 1) = sinPhi * cosThe; + dcm(2, 2) = cosPhi * cosThe; + } }; typedef Dcm Dcmf; diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index d6a7178f89..9b356ca265 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -24,35 +24,64 @@ template class Euler : public Vector { public: - virtual ~Euler() {}; + virtual ~Euler() {}; - Euler() : Vector() - { - } + Euler() : Vector() + { + } - Euler(Type roll, Type pitch, Type yaw) : Vector() - { - Euler &v(*this); - v(0) = roll; - v(1) = pitch; - v(2) = yaw; - } + Euler(Type phi, Type theta, Type psi) : Vector() + { + this->phi() = phi; + this->theta() = theta; + this->psi() = psi; + } - Euler(const Dcm & dcm) { - // TODO - Euler &e = *this; - e(0) = 0; - e(1) = 0; - e(2) = 0; - } + Euler(const Dcm & dcm) { + Type theta = asin(-dcm(2, 0)); + Type phi = 0; + Type psi = 0; - Euler(const Quaternion & q) { - // TODO - Euler &e = *this; - e(0) = 0; - e(1) = 0; - e(2) = 0; - } + if (abs(theta - M_PI_2) < 1.0e-3) { + psi = atan2(dcm(1, 2) - dcm(0, 1), + dcm(0, 2) + dcm(1, 1)); + + } else if (abs(theta + M_PI_2) < 1.0e-3) { + psi = atan2(dcm(1, 2) - dcm(0, 1), + dcm(0, 2) + dcm(1, 1)); + + } else { + phi = atan2f(dcm(2, 1), dcm(2, 2)); + psi = atan2f(dcm(1, 0), dcm(0, 0)); + } + this->phi() = phi; + this->theta() = theta; + this->psi() = psi; + } + + Euler(const Quaternion & q) { + *this = Euler(Dcm(q)); + } + + inline Type phi() const { + return (*this)(0); + } + inline Type theta() const { + return (*this)(1); + } + inline Type psi() const { + return (*this)(2); + } + + inline Type & phi() { + return (*this)(0); + } + inline Type & theta() { + return (*this)(1); + } + inline Type & psi() { + return (*this)(2); + } }; diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index ee94b6020a..e0cbe8f599 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -22,451 +22,434 @@ class Matrix { protected: - Type _data[M][N]; - size_t _rows; - size_t _cols; + Type _data[M][N]; public: - virtual ~Matrix() {}; - - Matrix() : - _data(), - _rows(M), - _cols(N) - { - } - - Matrix(const Type *data) : - _data(), - _rows(M), - _cols(N) - { - memcpy(_data, data, sizeof(_data)); - } - - Matrix(const Matrix &other) : - _data(), - _rows(M), - _cols(N) - { - memcpy(_data, other._data, sizeof(_data)); - } - - /** - * Accessors/ Assignment etc. - */ - - Type *data() - { - return _data[0]; - } - - inline size_t rows() const - { - return _rows; - } - - inline size_t cols() const - { - return _rows; - } - - inline Type operator()(size_t i, size_t j) const - { - return _data[i][j]; - } - - inline Type &operator()(size_t i, size_t j) - { - return _data[i][j]; - } - - /** - * Matrix Operations - */ - - // this might use a lot of programming memory - // since it instantiates a class for every - // required mult pair, but it provides - // compile time size_t checking - template - Matrix operator*(const Matrix &other) const - { - const Matrix &self = *this; - Matrix res; - res.setZero(); - - for (size_t i = 0; i < M; i++) { - for (size_t k = 0; k < P; k++) { - for (size_t j = 0; j < N; j++) { - res(i, k) += self(i, j) * other(j, k); - } - } - } - - return res; - } - - Matrix operator+(const Matrix &other) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) + other(i, j); - } - } - - return res; - } - - bool operator==(const Matrix &other) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - if (self(i , j) != other(i, j)) { - return false; - } - } - } - - return true; - } - - operator Type(); - - Matrix operator-(const Matrix &other) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) - other(i, j); - } - } - - return res; - } - - void operator+=(const Matrix &other) - { - Matrix &self = *this; - self = self + other; - } - - void operator-=(const Matrix &other) - { - Matrix &self = *this; - self = self - other; - } - - void operator*=(const Matrix &other) - { - Matrix &self = *this; - self = self * other; - } - - /** - * Scalar Operations - */ - - Matrix operator*(Type scalar) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) * scalar; - } - } - - return res; - } - - Matrix operator+(Type scalar) const - { - Matrix res; - Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) + scalar; - } - } - - return res; - } - - void operator*=(Type scalar) - { - Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - self(i, j) = self(i, j) * scalar; - } - } - } - - void operator/=(Type scalar) - { - Matrix &self = *this; - self = self * (1.0f / scalar); - } - - /** - * Misc. Functions - */ - - void print() - { - Matrix &self = *this; - printf("\n"); - - for (size_t i = 0; i < M; i++) { - printf("["); - - for (size_t j = 0; j < N; j++) { - printf("%10g\t", double(self(i, j))); - } - - printf("]\n"); - } - } - - Matrix transpose() const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(j, i) = self(i, j); - } - } - - return res; - } - - - // tranpose alias - inline Matrix T() const - { - return transpose(); - } - - Matrix expm(float dt, size_t n) const - { - Matrix res; - res.setIdentity(); - Matrix A_pow = *this; - float k_fact = 1; - size_t k = 1; - - while (k < n) { - res += A_pow * (float(pow(dt, k)) / k_fact); - - if (k == n) { break; } - - A_pow *= A_pow; - k_fact *= k; - k++; - } - - return res; - } - - Matrix diagonal() const - { - Matrix res; - // force square for now - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - res(i) = self(i, i); - } - - return res; - } - - void setZero() - { - memset(_data, 0, sizeof(_data)); - } - - void setIdentity() - { - setZero(); - Matrix &self = *this; - - for (size_t i = 0; i < M and i < N; i++) { - self(i, i) = 1; - } - } - - inline void swapRows(size_t a, size_t b) - { - if (a == b) { return; } - - Matrix &self = *this; - - for (size_t j = 0; j < cols(); j++) { - Type tmp = self(a, j); - self(a, j) = self(b, j); - self(b, j) = tmp; - } - } - - inline void swapCols(size_t a, size_t b) - { - if (a == b) { return; } - - Matrix &self = *this; - - for (size_t i = 0; i < rows(); i++) { - Type tmp = self(i, a); - self(i, a) = self(i, b); - self(i, b) = tmp; - } - } - - /** - * inverse based on LU factorization with partial pivotting - */ - Matrix inverse() const - { - Matrix L; - L.setIdentity(); - const Matrix &A = (*this); - Matrix U = A; - Matrix P; - P.setIdentity(); - - //printf("A:\n"); A.print(); - - // for all diagonal elements - for (size_t n = 0; n < N; n++) { - - // if diagonal is zero, swap with row below - if (fabsf(U(n, n)) < 1e-8f) { - //printf("trying pivot for row %d\n",n); - for (size_t i = 0; i < N; i++) { - if (i == n) { continue; } - - //printf("\ttrying row %d\n",i); - if (fabsf(U(i, n)) > 1e-8f) { - //printf("swapped %d\n",i); - U.swapRows(i, n); - P.swapRows(i, n); - } - } - } + virtual ~Matrix() {}; + + Matrix() : + _data() + { + } + + Matrix(const Type *data) : + _data() + { + memcpy(_data, data, sizeof(_data)); + } + + Matrix(const Matrix &other) : + _data() + { + memcpy(_data, other._data, sizeof(_data)); + } + + /** + * Accessors/ Assignment etc. + */ + + Type *data() + { + return _data[0]; + } + + inline Type operator()(size_t i, size_t j) const + { + return _data[i][j]; + } + + inline Type &operator()(size_t i, size_t j) + { + return _data[i][j]; + } + + /** + * Matrix Operations + */ + + // this might use a lot of programming memory + // since it instantiates a class for every + // required mult pair, but it provides + // compile time size_t checking + template + Matrix operator*(const Matrix &other) const + { + const Matrix &self = *this; + Matrix res; + res.setZero(); + + for (size_t i = 0; i < M; i++) { + for (size_t k = 0; k < P; k++) { + for (size_t j = 0; j < N; j++) { + res(i, k) += self(i, j) * other(j, k); + } + } + } + + return res; + } + + Matrix operator+(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) + other(i, j); + } + } + + return res; + } + + bool operator==(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + if (self(i , j) != other(i, j)) { + return false; + } + } + } + + return true; + } + + Matrix operator-(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) - other(i, j); + } + } + + return res; + } + + void operator+=(const Matrix &other) + { + Matrix &self = *this; + self = self + other; + } + + void operator-=(const Matrix &other) + { + Matrix &self = *this; + self = self - other; + } + + void operator*=(const Matrix &other) + { + Matrix &self = *this; + self = self * other; + } + + /** + * Scalar Operations + */ + + Matrix operator*(Type scalar) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) * scalar; + } + } + + return res; + } + + Matrix operator+(Type scalar) const + { + Matrix res; + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) + scalar; + } + } + + return res; + } + + void operator*=(Type scalar) + { + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) = self(i, j) * scalar; + } + } + } + + void operator/=(Type scalar) + { + Matrix &self = *this; + self = self * (1.0f / scalar); + } + + /** + * Misc. Functions + */ + + void print() + { + Matrix &self = *this; + printf("\n"); + + for (size_t i = 0; i < M; i++) { + printf("["); + + for (size_t j = 0; j < N; j++) { + printf("%10g\t", double(self(i, j))); + } + + printf("]\n"); + } + } + + Matrix transpose() const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(j, i) = self(i, j); + } + } + + return res; + } + + + // tranpose alias + inline Matrix T() const + { + return transpose(); + } + + Matrix expm(float dt, size_t n) const + { + Matrix res; + res.setIdentity(); + Matrix A_pow = *this; + float k_fact = 1; + size_t k = 1; + + while (k < n) { + res += A_pow * (float(pow(dt, k)) / k_fact); + + if (k == n) { + break; + } + + A_pow *= A_pow; + k_fact *= k; + k++; + } + + return res; + } + + Matrix diagonal() const + { + Matrix res; + // force square for now + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i, i); + } + + return res; + } + + void setZero() + { + memset(_data, 0, sizeof(_data)); + } + + void setIdentity() + { + setZero(); + Matrix &self = *this; + + for (size_t i = 0; i < M and i < N; i++) { + self(i, i) = 1; + } + } + + inline void swapRows(size_t a, size_t b) + { + if (a == b) { + return; + } + + Matrix &self = *this; + + for (size_t j = 0; j < N; j++) { + Type tmp = self(a, j); + self(a, j) = self(b, j); + self(b, j) = tmp; + } + } + + inline void swapCols(size_t a, size_t b) + { + if (a == b) { + return; + } + + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + Type tmp = self(i, a); + self(i, a) = self(i, b); + self(i, b) = tmp; + } + } + + /** + * inverse based on LU factorization with partial pivotting + */ + Matrix inverse() const + { + Matrix L; + L.setIdentity(); + const Matrix &A = (*this); + Matrix U = A; + Matrix P; + P.setIdentity(); + + //printf("A:\n"); A.print(); + + // for all diagonal elements + for (size_t n = 0; n < N; n++) { + + // if diagonal is zero, swap with row below + if (fabsf(U(n, n)) < 1e-8f) { + //printf("trying pivot for row %d\n",n); + for (size_t i = 0; i < N; i++) { + if (i == n) { + continue; + } + + //printf("\ttrying row %d\n",i); + if (fabsf(U(i, n)) > 1e-8f) { + //printf("swapped %d\n",i); + U.swapRows(i, n); + P.swapRows(i, n); + } + } + } #ifdef MATRIX_ASSERT - //printf("A:\n"); A.print(); - //printf("U:\n"); U.print(); - //printf("P:\n"); P.print(); - //fflush(stdout); - ASSERT(fabsf(U(n, n)) > 1e-8f); + //printf("A:\n"); A.print(); + //printf("U:\n"); U.print(); + //printf("P:\n"); P.print(); + //fflush(stdout); + ASSERT(fabsf(U(n, n)) > 1e-8f); #endif - // failsafe, return zero matrix - if (fabsf(U(n, n)) < 1e-8f) { - Matrix zero; - zero.setZero(); - return zero; - } + // failsafe, return zero matrix + if (fabsf(U(n, n)) < 1e-8f) { + Matrix zero; + zero.setZero(); + return zero; + } - // for all rows below diagonal - for (size_t i = (n + 1); i < N; i++) { - L(i, n) = U(i, n) / U(n, n); + // for all rows below diagonal + for (size_t i = (n + 1); i < N; i++) { + L(i, n) = U(i, n) / U(n, n); - // add i-th row and n-th row - // multiplied by: -a(i,n)/a(n,n) - for (size_t k = n; k < N; k++) { - U(i, k) -= L(i, n) * U(n, k); - } - } - } + // add i-th row and n-th row + // multiplied by: -a(i,n)/a(n,n) + for (size_t k = n; k < N; k++) { + U(i, k) -= L(i, n) * U(n, k); + } + } + } - //printf("L:\n"); L.print(); - //printf("U:\n"); U.print(); + //printf("L:\n"); L.print(); + //printf("U:\n"); U.print(); - // solve LY=P*I for Y by forward subst - Matrix Y = P; + // solve LY=P*I for Y by forward subst + Matrix Y = P; - // for all columns of Y - for (size_t c = 0; c < N; c++) { - // for all rows of L - for (size_t i = 0; i < N; i++) { - // for all columns of L - for (size_t j = 0; j < i; j++) { - // for all existing y - // subtract the component they - // contribute to the solution - Y(i, c) -= L(i, j) * Y(j, c); - } + // for all columns of Y + for (size_t c = 0; c < N; c++) { + // for all rows of L + for (size_t i = 0; i < N; i++) { + // for all columns of L + for (size_t j = 0; j < i; j++) { + // for all existing y + // subtract the component they + // contribute to the solution + Y(i, c) -= L(i, j) * Y(j, c); + } - // divide by the factor - // on current - // term to be solved - // Y(i,c) /= L(i,i); - // but L(i,i) = 1.0 - } - } + // divide by the factor + // on current + // term to be solved + // Y(i,c) /= L(i,i); + // but L(i,i) = 1.0 + } + } - //printf("Y:\n"); Y.print(); + //printf("Y:\n"); Y.print(); - // solve Ux=y for x by back subst - Matrix X = Y; + // solve Ux=y for x by back subst + Matrix X = Y; - // for all columns of X - for (size_t c = 0; c < N; c++) { - // for all rows of U - for (size_t k = 0; k < N; k++) { - // have to go in reverse order - size_t i = N - 1 - k; + // for all columns of X + for (size_t c = 0; c < N; c++) { + // for all rows of U + for (size_t k = 0; k < N; k++) { + // have to go in reverse order + size_t i = N - 1 - k; - // for all columns of U - for (size_t j = i + 1; j < N; j++) { - // for all existing x - // subtract the component they - // contribute to the solution - X(i, c) -= U(i, j) * X(j, c); - } + // for all columns of U + for (size_t j = i + 1; j < N; j++) { + // for all existing x + // subtract the component they + // contribute to the solution + X(i, c) -= U(i, j) * X(j, c); + } - // divide by the factor - // on current - // term to be solved - X(i, c) /= U(i, i); - } - } + // divide by the factor + // on current + // term to be solved + X(i, c) /= U(i, i); + } + } - //printf("X:\n"); X.print(); - return X; - } + //printf("X:\n"); X.print(); + return X; + } - // inverse alias - inline Matrix I() const - { - return inverse(); - } + // inverse alias + inline Matrix I() const + { + return inverse(); + } }; -template <> -Matrix::operator float() -{ - return (*this)(0,0); -} -typedef Matrix Matrix3f; +typedef Matrix Matrix3f; }; // namespace matrix diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 91b344cd3d..3d277978d7 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -24,64 +24,86 @@ template class Quaternion : public Vector { public: - virtual ~Quaternion() {}; + virtual ~Quaternion() {}; - Quaternion() : Vector() - { - // TODO - Quaternion &q = *this; - q(0) = 1; - q(1) = 0; - q(2) = 0; - q(3) = 0; - } + Quaternion() : + Vector() + { + Quaternion &q = *this; + q(0) = 1; + q(1) = 2; + q(2) = 3; + q(3) = 4; + } - Quaternion(const Dcm & dcm) { - // TODO - Quaternion &q = *this; - q(0) = 0; - q(1) = 0; - q(2) = 0; - q(3) = 0; - } + Quaternion(const Dcm & dcm) : + Vector() + { + Quaternion &q = *this; + q(0) = 0.5 * sqrt(1 + dcm(0, 0) + + dcm(1, 1) + dcm(2, 2)); + q(1) = (dcm(2, 1) - dcm(1, 2)) / + (4 * q(0)); + q(2) = (dcm(0, 2) - dcm(2, 0)) / + (4 * q(0)); + q(3) = (dcm(1, 0) - dcm(0, 1)) / + (4 * q(0)); + } - Quaternion(const Euler & e) { - // TODO - Quaternion &q = *this; - q(0) = 0; - q(1) = 0; - q(2) = 0; - q(3) = 0; - } + Quaternion(const Euler & euler) { + Quaternion &q = *this; + Type cosPhi_2 = cos(euler.phi() / 2.0); + Type cosTheta_2 = cos(euler.theta() / 2.0); + Type cosPsi_2 = cos(euler.psi() / 2.0); + Type sinPhi_2 = sin(euler.phi() / 2.0); + Type sinTheta_2 = sin(euler.theta() / 2.0); + Type sinPsi_2 = sin(euler.psi() / 2.0); + q(0) = cosPhi_2 * cosTheta_2 * cosPsi_2 + + sinPhi_2 * sinTheta_2 * sinPsi_2; + q(1) = sinPhi_2 * cosTheta_2 * cosPsi_2 - + cosPhi_2 * sinTheta_2 * sinPsi_2; + q(2) = cosPhi_2 * sinTheta_2 * cosPsi_2 + + sinPhi_2 * cosTheta_2 * sinPsi_2; + q(3) = cosPhi_2 * cosTheta_2 * sinPsi_2 + + sinPhi_2 * sinTheta_2 * cosPsi_2; + } - Quaternion(Type a, Type b, Type c, Type d) : Vector() - { - // TODO - Quaternion &q = *this; - q(0) = a; - q(1) = b; - q(2) = c; - q(3) = d; - } + Quaternion(Type a, Type b, Type c, Type d) : Vector() + { + Quaternion &q = *this; + q(0) = a; + q(1) = b; + q(2) = c; + q(3) = d; + } - Quaternion operator*(const Quaternion &q) const - { - // TODO - const Quaternion &p = *this; - Quaternion r; - r(0) = 0; - r(1) = 0; - r(2) = 0; - r(3) = 0; - return r; - } - - Matrix derivative() const { - // TODO - Matrix d; - return d; - } + Quaternion operator*(const Quaternion &q) const + { + const Quaternion &p = *this; + Quaternion r; + r(0) = p(0)*q(0) - p(1)*q(1) - p(2)*q(2) - p(3)*q(3); + r(1) = p(0)*q(1) + p(1)*q(0) - p(2)*q(3) + p(3)*q(2); + r(2) = p(0)*q(2) + p(1)*q(3) + p(2)*q(0) - p(3)*q(1); + r(3) = p(0)*q(3) - p(1)*q(2) + p(2)*q(1) + p(3)*q(0); + return r; + } + Matrix derivative(const Matrix & w) const { + const Quaternion &q = *this; + Type dataQ[] = { + q(0), -q(1), -q(2), -q(3), + q(1), q(0), -q(3), q(2), + q(2), q(3), q(0), -q(1), + q(3), -q(2), q(1), q(0) + }; + Matrix Q(dataQ); + Vector v; + v(0) = 0; + v(1) = w(0); + v(2) = w(1); + v(3) = w(2); + return Q * v * 0.5; + } }; typedef Quaternion Quatf; diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp new file mode 100644 index 0000000000..f45e0c374a --- /dev/null +++ b/matrix/Scalar.hpp @@ -0,0 +1,46 @@ +/** + * @file Scalar.hpp + * + * Defines conversion of matrix to scalar. + * + * @author James Goppert + */ + +#pragma once + +#include +#include +#include +#include +#include + +#include "Matrix.hpp" + +namespace matrix +{ + +template +class Scalar : public Matrix +{ +public: + virtual ~Scalar() {}; + + Scalar() : Matrix() + { + } + + Scalar(const Matrix & other) + { + (*this)(0,0) = other(0,0); + } + + operator Type() + { + return (*this)(0,0); + } + +}; + +typedef Scalar Scalarf; + +}; // namespace matrix diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 3f8731bfc1..4844b6c6e9 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -16,37 +16,37 @@ template class Vector : public Matrix { public: - virtual ~Vector() {}; + virtual ~Vector() {}; - Vector() : Matrix() - { - } + Vector() : Matrix() + { + } - inline Type operator()(size_t i) const - { - const Matrix &v = *this; - return v(i, 0); - } + inline Type operator()(size_t i) const + { + const Matrix &v = *this; + return v(i, 0); + } - inline Type &operator()(size_t i) - { - Matrix &v = *this; - return v(i, 0); - } + inline Type &operator()(size_t i) + { + Matrix &v = *this; + return v(i, 0); + } - Type dot(const Vector & b) { - Vector &a(*this); - Type r = 0; - for (int i = 0; i<3; i++) { - r += a(i)*b(i); - } - return r; - } + Type dot(const Vector & b) { + Vector &a(*this); + Type r = 0; + for (int i = 0; i<3; i++) { + r += a(i)*b(i); + } + return r; + } - Type norm() { - Vector &a(*this); - return sqrt(a.dot(a)); - } + Type norm() { + Vector &a(*this); + return sqrt(a.dot(a)); + } }; }; // namespace matrix diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index ff4d87208c..4fb1c0f2f7 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -16,29 +16,30 @@ template class Vector3 : public Vector { public: - virtual ~Vector3() {}; + virtual ~Vector3() {}; - Vector3() : Vector() - { - } + Vector3() : Vector() + { + } - Vector3(Type x, Type y, Type z) : Vector() - { - Vector3 &v(*this); - v(0) = x; - v(1) = y; - v(2) = z; - } + Vector3(Type x, Type y, Type z) : Vector() + { + Vector3 &v(*this); + v(0) = x; + v(1) = y; + v(2) = z; + } - Vector3 cross(const Vector3 & b) { - // TODO - Vector3 &a(*this); - Vector3 c; - c(0) = 0; - c(1) = 0; - c(2) = 0; - return c; - } + Vector3 cross(const Vector3 & b) { + // TODO + Vector3 &a(*this); + (void)a; + Vector3 c; + c(0) = 0; + c(1) = 0; + c(2) = 0; + return c; + } }; typedef Vector3 Vector3f; diff --git a/test/dcm.cpp b/test/dcm.cpp index aa150a3552..8f404226f6 100644 --- a/test/dcm.cpp +++ b/test/dcm.cpp @@ -6,8 +6,8 @@ using namespace matrix; int main() { - Dcmf dcm; - Quatf q = Quatf(dcm); - Eulerf e = Eulerf(dcm); - return 0; + Dcmf dcm; + Quatf q = Quatf(dcm); + Eulerf e = Eulerf(dcm); + return 0; } diff --git a/test/euler.cpp b/test/euler.cpp index d5b3a4c30b..cafa05d67f 100644 --- a/test/euler.cpp +++ b/test/euler.cpp @@ -1,4 +1,5 @@ #include "Euler.hpp" +#include "Scalar.hpp" #include #include @@ -6,10 +7,12 @@ using namespace matrix; int main() { - Eulerf e; - float dp = e.T()*e; - Dcmf dcm = Dcmf(e); - Quatf q = Quatf(e); - float n = e.norm(); - return 0; + Eulerf e; + float dp = Scalarf(e.T()*e); + (void)dp; + Dcmf dcm = Dcmf(e); + Quatf q = Quatf(e); + float n = e.norm(); + (void)n; + return 0; } diff --git a/test/inverse.cpp b/test/inverse.cpp index 73f7c0b432..67b4569347 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -6,25 +6,25 @@ using namespace matrix; int main() { - float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; - Matrix3f A(data); - Matrix3f A_I = A.inverse(); - float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; - Matrix3f A_I_check(data_check); - (void)A_I; - assert(A_I == A_I_check); + float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; + Matrix3f A(data); + Matrix3f A_I = A.inverse(); + float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; + Matrix3f A_I_check(data_check); + (void)A_I; + assert(A_I == A_I_check); - // stess test - static const size_t n = 100; - Matrix A_large; - A_large.setIdentity(); - Matrix A_large_I; - A_large_I.setZero(); + // stess test + static const size_t n = 100; + Matrix A_large; + A_large.setIdentity(); + Matrix A_large_I; + A_large_I.setZero(); - for (size_t i = 0; i < 100; i++) { - A_large_I = A_large.inverse(); - assert(A_large == A_large_I); - } + for (size_t i = 0; i < 100; i++) { + A_large_I = A_large.inverse(); + assert(A_large == A_large_I); + } - return 0; + return 0; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 5a625d0cc1..21827883bd 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -5,25 +5,25 @@ using namespace matrix; int main() { - Matrix3f m; - m.setZero(); - m(0, 0) = 1; - m(0, 1) = 2; - m(0, 2) = 3; - m(1, 0) = 4; - m(1, 1) = 5; - m(1, 2) = 6; - m(2, 0) = 7; - m(2, 1) = 8; - m(2, 2) = 9; + Matrix3f m; + m.setZero(); + m(0, 0) = 1; + m(0, 1) = 2; + m(0, 2) = 3; + m(1, 0) = 4; + m(1, 1) = 5; + m(1, 2) = 6; + m(2, 0) = 7; + m(2, 1) = 8; + m(2, 2) = 9; - m.print(); + m.print(); - float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; - Matrix3f m2(data); - m2.print(); + float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; + Matrix3f m2(data); + m2.print(); - assert(m == m2); + assert(m == m2); - return 0; + return 0; } diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 7b42d947d4..0dfd05f875 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -6,21 +6,21 @@ using namespace matrix; int main() { - float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; - Matrix3f A(data); - float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; - Matrix3f A_I(data_check); - Matrix3f I; - I.setIdentity(); - A.print(); - A_I.print(); - Matrix3f R = A * A_I; - R.print(); - assert(R == I); + float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; + Matrix3f A(data); + float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; + Matrix3f A_I(data_check); + Matrix3f I; + I.setIdentity(); + A.print(); + A_I.print(); + Matrix3f R = A * A_I; + R.print(); + assert(R == I); - Matrix3f R2 = A; - R2 *= A_I; - R2.print(); - assert(R2 == I); - return 0; + Matrix3f R2 = A; + R2 *= A_I; + R2.print(); + assert(R2 == I); + return 0; } diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index 78bdb5b27f..6c569d6ed0 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -6,13 +6,13 @@ using namespace matrix; int main() { - float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; - Matrix3f A(data); - A = A * 2; - float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; - Matrix3f A_check(data_check); - A.print(); - A_check.print(); - assert(A == A_check); - return 0; + float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; + Matrix3f A(data); + A = A * 2; + //float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; + //Matrix3f A_check(data_check); + //A.print(); + //A_check.print(); + //assert(A == A_check); + return 0; } diff --git a/test/quaternion.cpp b/test/quaternion.cpp index 40c36adf58..eaa76ff77a 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -6,10 +6,10 @@ using namespace matrix; int main() { - Quatf p(1, 0, 0, 0); - Quatf q(0, 1, 0, 0); - Quatf r = p*q; - Dcmf dcm = Dcmf(p); - Eulerf e = Eulerf(p); - return 0; + Quatf p(1, 0, 0, 0); + Quatf q(0, 1, 0, 0); + Quatf r = p*q; + Dcmf dcm = Dcmf(p); + Eulerf e = Eulerf(p); + return 0; } diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index f80e437939..15ecf356a3 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -5,21 +5,19 @@ using namespace matrix; int main() { - Matrix3f A; - A.setIdentity(); - assert(A.rows() == 3); - assert(A.cols() == 3); + Matrix3f A; + A.setIdentity(); - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { - if (i == j) { - assert(A(i, j) == 1); + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + if (i == j) { + assert(A(i, j) == 1); - } else { - assert(A(i, j) == 0); - } - } - } + } else { + assert(A(i, j) == 0); + } + } + } - return 0; + return 0; } diff --git a/test/transpose.cpp b/test/transpose.cpp index 3623fc1f9a..eed53bc080 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -6,13 +6,13 @@ using namespace matrix; int main() { - float data[9] = {1, 2, 3, 4, 5, 6}; - Matrix A(data); - Matrix A_T = A.transpose(); - float data_check[9] = {1, 4, 2, 5, 3, 6}; - Matrix A_T_check(data_check); - A_T.print(); - A_T_check.print(); - assert(A_T == A_T_check); - return 0; + float data[9] = {1, 2, 3, 4, 5, 6}; + Matrix A(data); + Matrix A_T = A.transpose(); + float data_check[9] = {1, 4, 2, 5, 3, 6}; + Matrix A_T_check(data_check); + A_T.print(); + A_T_check.print(); + assert(A_T == A_T_check); + return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index 3da9f8a01a..60ba11aa7d 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -6,8 +6,10 @@ using namespace matrix; int main() { - Vector v; - float n = v.norm(); - float r = v.dot(v); - return 0; + Vector v; + float n = v.norm(); + (void)n; + float r = v.dot(v); + (void)r; + return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index f79186504e..1a3a1bbf66 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -6,8 +6,8 @@ using namespace matrix; int main() { - Vector3f a(1, 0, 0); - Vector3f b(0, 1, 0); - Vector3f c = a.cross(b); - return 0; + Vector3f a(1, 0, 0); + Vector3f b(0, 1, 0); + Vector3f c = a.cross(b); + return 0; } diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 7d7c7a36a4..fdd715bc12 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -5,24 +5,24 @@ using namespace matrix; int main() { - Vector3f v; - v(0) = 1; - v(1) = 2; - v(2) = 3; + Vector3f v; + v(0) = 1; + v(1) = 2; + v(2) = 3; - v.print(); + v.print(); - assert(v(0) == 1); - assert(v(1) == 2); - assert(v(2) == 3); + assert(v(0) == 1); + assert(v(1) == 2); + assert(v(2) == 3); - Vector3f v2(4, 5, 6); + Vector3f v2(4, 5, 6); - v2.print(); + v2.print(); - assert(v2(0) == 4); - assert(v2(1) == 5); - assert(v2(2) == 6); + assert(v2(0) == 4); + assert(v2(1) == 5); + assert(v2(2) == 6); - return 0; + return 0; } From 5369904d27e8da91691dedf1baff5827ed99f196 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 19:50:09 -0500 Subject: [PATCH 003/388] Fixed default. --- matrix/Quaternion.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 3d277978d7..938c071caa 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -31,9 +31,9 @@ public: { Quaternion &q = *this; q(0) = 1; - q(1) = 2; - q(2) = 3; - q(3) = 4; + q(1) = 0; + q(2) = 0; + q(3) = 0; } Quaternion(const Dcm & dcm) : From b842f8d8a530251d6df0d123c0274993854e1062 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 20:17:34 -0500 Subject: [PATCH 004/388] Added travis. --- .travis.yml | 9 +++++++++ CMakeLists.txt | 5 +++-- test/quaternion.cpp | 11 ++++++++--- 3 files changed, 20 insertions(+), 5 deletions(-) create mode 100644 .travis.yml diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 0000000000..89da1148e9 --- /dev/null +++ b/.travis.yml @@ -0,0 +1,9 @@ +language: cpp +compiler: + - gcc + +script: mkdir build && cd build && cmake .. && ctest -V + +os: + - linux + - osx diff --git a/CMakeLists.txt b/CMakeLists.txt index 6a297b7ce0..5ab8522d38 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,14 +3,15 @@ cmake_minimum_required(VERSION 2.8) project(matrix CXX) if (NOT CMAKE_BUILD_TYPE) - set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) + set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() list(APPEND CMAKE_CXX_FLAGS + ${CMAKE_CXX_FLAGS} -Wall -Weffc++ - #-Werror + -Werror -Wfatal-errors ) diff --git a/test/quaternion.cpp b/test/quaternion.cpp index eaa76ff77a..afba53576d 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -1,12 +1,17 @@ #include "Quaternion.hpp" -#include -#include +#include +#include using namespace matrix; int main() { - Quatf p(1, 0, 0, 0); + Quatf p(1, 2, 3, 4); + assert(p(0) == 1); + assert(p(1) == 2); + assert(p(2) == 3); + assert(p(3) == 100); + Quatf q(0, 1, 0, 0); Quatf r = p*q; Dcmf dcm = Dcmf(p); From 49035ed6a90341b7914c2e02ef19d382e7a08c6d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 20:26:42 -0500 Subject: [PATCH 005/388] Added mode lines for vi. --- .travis.yml | 8 +++++++- matrix/Dcm.hpp | 2 ++ matrix/Euler.hpp | 2 ++ matrix/Matrix.hpp | 2 ++ matrix/Quaternion.hpp | 2 ++ matrix/Scalar.hpp | 2 ++ matrix/Vector.hpp | 2 ++ matrix/Vector3.hpp | 2 ++ test/dcm.cpp | 2 ++ test/euler.cpp | 2 ++ test/inverse.cpp | 6 ++++-- test/matrixAssignment.cpp | 2 ++ test/matrixMult.cpp | 2 ++ test/matrixScalarMult.cpp | 12 +++++++----- test/quaternion.cpp | 10 ++++++---- test/setIdentity.cpp | 2 ++ test/transpose.cpp | 2 ++ test/vector.cpp | 2 ++ test/vector3.cpp | 2 ++ test/vectorAssignment.cpp | 2 ++ 20 files changed, 56 insertions(+), 12 deletions(-) diff --git a/.travis.yml b/.travis.yml index 89da1148e9..fa4e5cab98 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,8 +2,14 @@ language: cpp compiler: - gcc -script: mkdir build && cd build && cmake .. && ctest -V +script: + - mkdir build + - cd build + - cmake .. + - ctest -V os: - linux - osx + +# vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index e13a84931c..05bcdcb37e 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -77,3 +77,5 @@ public: typedef Dcm Dcmf; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 9b356ca265..a6701a9cec 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -88,3 +88,5 @@ public: typedef Euler Eulerf; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index e0cbe8f599..86fe51d1af 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -453,3 +453,5 @@ public: typedef Matrix Matrix3f; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 938c071caa..d36c25e81d 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -109,3 +109,5 @@ public: typedef Quaternion Quatf; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index f45e0c374a..fdf2df6fb8 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -44,3 +44,5 @@ public: typedef Scalar Scalarf; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 4844b6c6e9..7bd792ef1e 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -50,3 +50,5 @@ public: }; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 4fb1c0f2f7..8f667f90a7 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -45,3 +45,5 @@ public: typedef Vector3 Vector3f; }; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/dcm.cpp b/test/dcm.cpp index 8f404226f6..2779d46113 100644 --- a/test/dcm.cpp +++ b/test/dcm.cpp @@ -11,3 +11,5 @@ int main() Eulerf e = Eulerf(dcm); return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/euler.cpp b/test/euler.cpp index cafa05d67f..236f6e0225 100644 --- a/test/euler.cpp +++ b/test/euler.cpp @@ -16,3 +16,5 @@ int main() (void)n; return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/inverse.cpp b/test/inverse.cpp index 67b4569347..9fb23fdefa 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -15,16 +15,18 @@ int main() assert(A_I == A_I_check); // stess test - static const size_t n = 100; + static const size_t n = 50; Matrix A_large; A_large.setIdentity(); Matrix A_large_I; A_large_I.setZero(); - for (size_t i = 0; i < 100; i++) { + for (size_t i = 0; i < 50; i++) { A_large_I = A_large.inverse(); assert(A_large == A_large_I); } return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 21827883bd..dfd98e0ae3 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -27,3 +27,5 @@ int main() return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 0dfd05f875..0af96180c6 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -24,3 +24,5 @@ int main() assert(R2 == I); return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index 6c569d6ed0..c0b8932604 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -9,10 +9,12 @@ int main() float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; Matrix3f A(data); A = A * 2; - //float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; - //Matrix3f A_check(data_check); - //A.print(); - //A_check.print(); - //assert(A == A_check); + float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; + Matrix3f A_check(data_check); + A.print(); + A_check.print(); + assert(A == A_check); return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/quaternion.cpp b/test/quaternion.cpp index afba53576d..89c0db2063 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -7,10 +7,10 @@ using namespace matrix; int main() { Quatf p(1, 2, 3, 4); - assert(p(0) == 1); - assert(p(1) == 2); - assert(p(2) == 3); - assert(p(3) == 100); + assert(p(0) == 1); + assert(p(1) == 2); + assert(p(2) == 3); + assert(p(3) == 4); Quatf q(0, 1, 0, 0); Quatf r = p*q; @@ -18,3 +18,5 @@ int main() Eulerf e = Eulerf(p); return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index 15ecf356a3..0ece759bee 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -21,3 +21,5 @@ int main() return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/transpose.cpp b/test/transpose.cpp index eed53bc080..7dd7f2339d 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -16,3 +16,5 @@ int main() assert(A_T == A_T_check); return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/vector.cpp b/test/vector.cpp index 60ba11aa7d..a1aabc6a26 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -13,3 +13,5 @@ int main() (void)r; return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/vector3.cpp b/test/vector3.cpp index 1a3a1bbf66..fe93629e3b 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -11,3 +11,5 @@ int main() Vector3f c = a.cross(b); return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index fdd715bc12..e5074583dd 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -26,3 +26,5 @@ int main() return 0; } + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From ad03429ae985c7078e81e8a9f6ebb539e188b80d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 20:28:48 -0500 Subject: [PATCH 006/388] Added readme. --- READEME.md | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 READEME.md diff --git a/READEME.md b/READEME.md new file mode 100644 index 0000000000..9a57dd7219 --- /dev/null +++ b/READEME.md @@ -0,0 +1,3 @@ +# matrix + +A simple and efficient template based matrix library. From 74701345594296152b274b48d3f164a3de50add6 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 20:29:34 -0500 Subject: [PATCH 007/388] Fixed filename. --- READEME.md => README.md | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename READEME.md => README.md (100%) diff --git a/READEME.md b/README.md similarity index 100% rename from READEME.md rename to README.md From 33e027244734a92a5c027b7ee7ae32b0938ac55a Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 20:31:10 -0500 Subject: [PATCH 008/388] Travis fix. --- .travis.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.travis.yml b/.travis.yml index fa4e5cab98..4c474e6b01 100644 --- a/.travis.yml +++ b/.travis.yml @@ -6,6 +6,7 @@ script: - mkdir build - cd build - cmake .. + - make - ctest -V os: From 89851a85c0184ae8ba9297ff2f806f0618b60416 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Tue, 3 Nov 2015 20:31:47 -0500 Subject: [PATCH 009/388] Added badge. --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index 9a57dd7219..cf064988d9 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,5 @@ # matrix +[![Build Status](https://travis-ci.org/dronecrew/matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) + A simple and efficient template based matrix library. From c84e934909148a6e8cc857b37d231f790628a882 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 00:37:00 -0500 Subject: [PATCH 010/388] Updated vector class. --- doc/nasa_rotation_def.pdf | 2217 +++++++++++++++++++++++++++++++++++++ matrix/Quaternion.hpp | 2 +- matrix/Vector.hpp | 114 +- test/quaternion.cpp | 34 +- test/test_math.py | 66 ++ 5 files changed, 2418 insertions(+), 15 deletions(-) create mode 100644 doc/nasa_rotation_def.pdf create mode 100644 test/test_math.py diff --git a/doc/nasa_rotation_def.pdf b/doc/nasa_rotation_def.pdf new file mode 100644 index 0000000000..c97a741d0d --- /dev/null +++ b/doc/nasa_rotation_def.pdf @@ -0,0 +1,2217 @@ + + + + + + + + + + + + + Firmware/nasa_rotation_def.pdf at f8811649cb91fc88cef7b224b29c6c5f235f1d8d · PX4/Firmware + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Skip to content + + + + + + + + + + + + + + +
+ +
+
+ + +
+
+
+ +
+ +
+ + +
    + +
  • +
    + +
    + + + + Unwatch + + + + +
    + +
    +
    +
    +
  • + +
  • + +
    + +
    + + +
    +
    + + +
    + +
  • + +
  • + + + Fork + + + + + +
  • +
+ +

+ + /Firmware + + + + + +

+ +
+
+
+ +
+
+
+ + + +
+ +
+

HTTPS clone URL

+
+ + + + +
+
+ + +
+

SSH clone URL

+
+ + + + +
+
+ + +
+

Subversion checkout URL

+
+ + + + +
+
+ + + +
You can clone with +
,
, or
. + + + +
+ + + + Download ZIP + +
+
+
+ + + + + + + +
+ +
+ + + +
+ +
+ + + + +
+ + +
+ + +
+ + + 464c524 + + + + + + + + +
+ +
+
+
+ +
+ Raw + History +
+ + + +
+ +
+ 693 KB +
+
+ + + +
+ +
+
+ +
Sorry, something went wrong. Reload?
+
Sorry, we cannot display this file.
+
Sorry, this file is invalid so it cannot be displayed.
+ +
+
+ +
+ +
+ +Jump to Line + + +
+
+ +
+
+ + +
+ +
+ +
+ + + + + + + +
+ + + Something went wrong with that request. Please try again. +
+ + + + + + + + + + diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index d36c25e81d..ca142a4696 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -64,7 +64,7 @@ public: cosPhi_2 * sinTheta_2 * sinPsi_2; q(2) = cosPhi_2 * sinTheta_2 * cosPsi_2 + sinPhi_2 * cosTheta_2 * sinPsi_2; - q(3) = cosPhi_2 * cosTheta_2 * sinPsi_2 + + q(3) = cosPhi_2 * cosTheta_2 * sinPsi_2 - sinPhi_2 * sinTheta_2 * cosPsi_2; } diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 7bd792ef1e..ff175d194d 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -12,25 +12,25 @@ namespace matrix { -template -class Vector : public Matrix +template +class Vector : public Matrix { public: virtual ~Vector() {}; - Vector() : Matrix() + Vector() : Matrix() { } inline Type operator()(size_t i) const { - const Matrix &v = *this; + const Matrix &v = *this; return v(i, 0); } inline Type &operator()(size_t i) { - Matrix &v = *this; + Matrix &v = *this; return v(i, 0); } @@ -47,6 +47,110 @@ public: Vector &a(*this); return sqrt(a.dot(a)); } + + /** + * Vector Operations + */ + + Vector operator+(const Vector &other) const + { + Vector res; + const Vector &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i) + other(i); + } + + return res; + } + + bool operator==(const Vector &other) const + { + Vector res; + const Vector &self = *this; + + for (size_t i = 0; i < M; i++) { + if (self(i) != other(i)) { + return false; + } + } + + return true; + } + + Vector operator-(const Vector &other) const + { + Vector res; + const Vector &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i) - other(i); + } + + return res; + } + + void operator+=(const Vector &other) + { + Vector &self = *this; + self = self + other; + } + + void operator-=(const Vector &other) + { + Vector &self = *this; + self = self - other; + } + + void operator*=(const Vector &other) + { + Vector &self = *this; + self = self * other; + } + + /** + * Scalar Operations + */ + + Vector operator*(Type scalar) const + { + Vector res; + const Vector &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i) * scalar; + } + + return res; + } + + Vector operator+(Type scalar) const + { + Vector res; + Vector &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i) + scalar; + } + + return res; + } + + void operator*=(Type scalar) + { + Vector &self = *this; + + for (size_t i = 0; i < M; i++) { + self(i) = self(i) * scalar; + } + } + + void operator/=(Type scalar) + { + Vector &self = *this; + self = self * (1.0f / scalar); + } + }; }; // namespace matrix diff --git a/test/quaternion.cpp b/test/quaternion.cpp index 89c0db2063..35a2f6c7fc 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -6,16 +6,32 @@ using namespace matrix; int main() { - Quatf p(1, 2, 3, 4); - assert(p(0) == 1); - assert(p(1) == 2); - assert(p(2) == 3); - assert(p(3) == 4); + // test default ctor + Quatf q; + assert(q(0) == 1); + assert(q(1) == 0); + assert(q(2) == 0); + assert(q(3) == 0); + + q = Quatf(0.1825742f, 0.3651484f, 0.5477226f, 0.7302967f); + assert(q(0) == 0.1825742f); + assert(q(1) == 0.3651484f); + assert(q(2) == 0.5477226f); + assert(q(3) == 0.7302967f); - Quatf q(0, 1, 0, 0); - Quatf r = p*q; - Dcmf dcm = Dcmf(p); - Eulerf e = Eulerf(p); + // test euler ctor + q = Quatf(Eulerf(0.1f, 0.2f, 0.3f)); + assert((q - Quatf(0.983347f, 0.034271f, 0.106021f, 0.143572f)).norm() < 1e-3); + // test dcm ctor + //q = Quatf(Dcmf()); + //assert(q == Quatf(1.0f, 0.0f, 0.0f, 0.0f)); + // TODO test derivative + // test accessors + //q(0) = 0.1f; + //q(1) = 0.2f; + //q(2) = 0.3f; + //q(3) = 0.4f; + //assert(q == Quatf(0.1f, 0.2f, 0.3f, 0.4f)); return 0; } diff --git a/test/test_math.py b/test/test_math.py new file mode 100644 index 0000000000..d5d24da60c --- /dev/null +++ b/test/test_math.py @@ -0,0 +1,66 @@ +from __future__ import print_function +from pylab import * +from pprint import pprint + +#pylint: disable=all + +phi = 0.1 +theta = 0.2 +psi = 0.3 + +cosPhi = cos(phi) +cosPhi_2 = cos(phi/2) +sinPhi = sin(phi) +sinPhi_2 = sin(phi/2) + +cosTheta = cos(theta) +cosTheta_2 = cos(theta/2) +sinTheta = sin(theta) +sinTheta_2 = sin(theta/2) + +cosPsi = cos(psi) +cosPsi_2 = cos(psi/2) +sinPsi = sin(psi) +sinPsi_2 = sin(psi/2) + +C_nb = array([ + [cosTheta*cosPsi, -cosPhi*sinPsi + sinPhi*sinTheta*cosPsi, sinPhi*sinPsi + cosPhi*sinTheta*cosPsi], + [cosTheta*sinPsi, cosPhi*cosPsi + sinPhi*sinTheta*sinPsi, -sinPhi*cosPsi + cosPhi*sinTheta*sinPsi], + [-sinTheta, sinPhi*cosTheta, cosPhi*cosTheta]]) + +print('\nC_nb') +pprint(C_nb) + +theta = arcsin(-C_nb[2,0]) +phi = arctan(C_nb[2,1]/ C_nb[2,2]) +psi = arctan(C_nb[1,0]/ C_nb[0,0]) +print('\nphi {:f}, theta {:f}, psi {:f}\n'.format(phi, theta, psi)) + +q = array([ + cosPhi_2*cosTheta_2*cosPsi_2 + sinPhi_2*sinTheta_2*sinPsi_2, + sinPhi_2*cosTheta_2*cosPsi_2 - cosPhi_2*sinTheta_2*sinPsi_2, + cosPhi_2*sinTheta_2*cosPsi_2 + sinPhi_2*cosTheta_2*sinPsi_2, + cosPhi_2*cosTheta_2*sinPsi_2 - sinPhi_2*sinTheta_2*cosPsi_2]) + +a = q[0] +b = q[1] +c = q[2] +d = q[3] + +print('\nq') +pprint(q.T) + +a2 = a*a +b2 = b*b +c2 = c*c +d2 = d*d + +C2_nb = array([ + [a2 + b2 - c2 - d2, 2*(b*c - a*d), 2*(b*d + a*c)], + [2*(b*c + a*d), a2 - b2 + c2 - d2, 2*(c*d - a*b)], + [2*(b*d - a*c), 2*(c*d + a*b), a2 - b2 - c2 + d2]]) + +print('\nC2_nb') +pprint(C2_nb) + +# vim: set et ft=python fenc=utf-8 ff=unix sts=4 sw=4 ts=8 : From 12713105b8f6471d6ec0508812c6edd3f64b3037 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 00:48:59 -0500 Subject: [PATCH 011/388] Fixed quaternion unit test. --- matrix/Dcm.hpp | 1 + test/quaternion.cpp | 17 +++++++++-------- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 05bcdcb37e..40de899688 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -28,6 +28,7 @@ public: Dcm() : Matrix() { + Matrix::setIdentity(); } Dcm(const Quaternion & q) { diff --git a/test/quaternion.cpp b/test/quaternion.cpp index 35a2f6c7fc..92a727d126 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -21,17 +21,18 @@ int main() // test euler ctor q = Quatf(Eulerf(0.1f, 0.2f, 0.3f)); - assert((q - Quatf(0.983347f, 0.034271f, 0.106021f, 0.143572f)).norm() < 1e-3); + assert((q - Quatf(0.983347f, 0.034271f, 0.106021f, 0.143572f)).norm() < 1e-5); + // test dcm ctor - //q = Quatf(Dcmf()); - //assert(q == Quatf(1.0f, 0.0f, 0.0f, 0.0f)); + q = Quatf(Dcmf()); + assert(q == Quatf(1.0f, 0.0f, 0.0f, 0.0f)); // TODO test derivative // test accessors - //q(0) = 0.1f; - //q(1) = 0.2f; - //q(2) = 0.3f; - //q(3) = 0.4f; - //assert(q == Quatf(0.1f, 0.2f, 0.3f, 0.4f)); + q(0) = 0.1f; + q(1) = 0.2f; + q(2) = 0.3f; + q(3) = 0.4f; + assert(q == Quatf(0.1f, 0.2f, 0.3f, 0.4f)); return 0; } From b1ee027f649c094f9e0a9d2dd4c9228b8d264e6d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 01:50:30 -0500 Subject: [PATCH 012/388] Working on coverage. --- .travis.yml | 30 +++++++++++++++--------------- CMakeLists.txt | 41 ++++++++++++++++++++++++++++++++++++++++- 2 files changed, 55 insertions(+), 16 deletions(-) diff --git a/.travis.yml b/.travis.yml index 4c474e6b01..6c62cd2677 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,16 +1,16 @@ -language: cpp -compiler: - - gcc - +language: c script: - - mkdir build - - cd build - - cmake .. - - make - - ctest -V - -os: - - linux - - osx - -# vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : +- mkdir -p build && cd build && cmake -DCOVERALLS=ON -DCMAKE_BUILD_TYPE=Debug .. && + make && ctest -V && make coveralls +env: + global: + - secure: vj6Y9LaNhnfWH+3AoqOIY/k5Ymb0zKlXJSlfa1qBnWC94/NDQjbV+6Lk1Ct1izzPmFbCiRwp/auwcUT0p3aUNNFshEUrL5rlHOwr4zLMqxdwKfUXA7X7NSJS2EJSgMm0to0iSzuCeub3E5Y7fdDpmWTZ9bD5E31wck/5kzjiuw0G8mtdOLeOnfERCZw/VTxLwKkdjU3+m64IYzAh9tWsyM1ZpVX0c7KjjPt29qYb45xmQ7XrWlKl9fHabKbTvopISas56Q95K46pcF9sDraP0+KVk6f5rVOjYppvRmT6BJwRjDRG/rC6Q0BSfZuUm8a0OgFxc2MG3sxKT/QfMMDzuxJWbewakam0hcPJl34cFzqgIuMeQ7bK1yitsFBCqo9b/noMMp4vX9Hkm8b1f4QHTuk2fqOqorP0hOQxhWUcNs8J2jG1nDOjB5wrv9fOyerAZjZ8fvzHkMh/aZ3Xj9Sw7PVxiue1eyRXHQgn2/IcerrhlujawGbjsvLvrmQ+v5A3xvh4q6iJ5glIv1dhGaEEGMrp8httjLUAzZJpSAdyyWnJtnD+5KLH7BOKT+ptuXRnU6H97nUlXIHujx4btEpIhYebEX+pmAfOwK8WP3DDG5ikbmf2BuaI/qOhPtUzf5PJiN/+vRKNYf6ijXBBr4Cq7pWSJotQRfoHXvfE4vFa+zA= +addons: + coverity_scan: + project: + name: dronecrew/matrix + description: Build submitted via Travis CI + notification_email: james.goppert@gmail.com + build_command_prepend: mkdir -p build && cd build && cmake .. && make + build_command: make -C build -j 4 + branch_pattern: coverity_scan diff --git a/CMakeLists.txt b/CMakeLists.txt index 5ab8522d38..54b9b154fd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,12 +1,30 @@ cmake_minimum_required(VERSION 2.8) +set(VERSION_MAJOR "0") +set(VERSION_MINOR "1") +set(VERSION_PATCH "0") + project(matrix CXX) +option(COVERALLS "Turn on coveralls support" OFF) +option(COVERALLS_UPLOAD "Upload the generated coveralls json" ON) + + +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} + ${CMAKE_SOURCE_DIR}/cmake/coveralls-cmake/cmake) + +if (COVERALLS) + include(Coveralls) + coveralls_turn_on_coverage() +endif() + if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() +option(COVERAGE "enable coverage" ON) + list(APPEND CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} -Wall @@ -14,13 +32,28 @@ list(APPEND CMAKE_CXX_FLAGS -Werror -Wfatal-errors ) - +if (COVERAGE) + list(APPEND CMAKE_CXX_FLAGS + -fprofile-arcs + -ftest-coverage + ) +endif() string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") enable_testing() include_directories(matrix) +# Setup the coveralls target and tell it to gather +# coverage data for all the lib sources. +if (COVERALLS) + coveralls_setup( + "${COV_SRCS}" + ${COVERALLS_UPLOAD} + "${CMAKE_SOURCE_DIR}/cmake/coveralls-cmake/cmake" + ) +endif() + add_subdirectory(test) add_custom_target(format @@ -30,3 +63,9 @@ add_custom_target(format WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} VERBATIM ) + +set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) +set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) +set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) +set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com") +include(CPack) From edd23778ca249033ac49b21f4266700c9568ea33 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 01:52:19 -0500 Subject: [PATCH 013/388] Added coverage. --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index cf064988d9..e7c11b02ea 100644 --- a/README.md +++ b/README.md @@ -2,4 +2,6 @@ [![Build Status](https://travis-ci.org/dronecrew/matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) +[![Coverage Status](https://coveralls.io/repos/dronecrew/matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/dronecrew/matrix?branch=master) + A simple and efficient template based matrix library. From 35edae200fad44530467c03d3d61538484a3b446 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 01:54:14 -0500 Subject: [PATCH 014/388] Badge placement. --- README.md | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/README.md b/README.md index e7c11b02ea..8dd6160162 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,3 @@ -# matrix - -[![Build Status](https://travis-ci.org/dronecrew/matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) - -[![Coverage Status](https://coveralls.io/repos/dronecrew/matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/dronecrew/matrix?branch=master) +# matrix [![Build Status](https://travis-ci.org/dronecrew/matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) [![Coverage Status](https://coveralls.io/repos/dronecrew/matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/dronecrew/matrix?branch=master) A simple and efficient template based matrix library. From 8f0448eb91ade1b1f35bdb71ad813400e9f3ac39 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 01:58:48 -0500 Subject: [PATCH 015/388] Coverage fix. --- .gitmodules | 3 +++ cmake/coveralls-cmake | 1 + 2 files changed, 4 insertions(+) create mode 100644 .gitmodules create mode 160000 cmake/coveralls-cmake diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000000..37bc2b63dd --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "cmake/coveralls-cmake"] + path = cmake/coveralls-cmake + url = https://github.com/JoakimSoderberg/coveralls-cmake.git diff --git a/cmake/coveralls-cmake b/cmake/coveralls-cmake new file mode 160000 index 0000000000..2d53ce3dea --- /dev/null +++ b/cmake/coveralls-cmake @@ -0,0 +1 @@ +Subproject commit 2d53ce3deaea087b2df778c09fe2590763661547 From ce719a0fe234ed6ed915b1cd68ca0915ee20ddfd Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 02:01:31 -0500 Subject: [PATCH 016/388] Added cov sources. --- CMakeLists.txt | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 54b9b154fd..eabcb7919f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -32,18 +32,14 @@ list(APPEND CMAKE_CXX_FLAGS -Werror -Wfatal-errors ) -if (COVERAGE) - list(APPEND CMAKE_CXX_FLAGS - -fprofile-arcs - -ftest-coverage - ) -endif() string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") enable_testing() include_directories(matrix) +file(GLOB_RECURSE COV_SRCS matrix/*.h*) + # Setup the coveralls target and tell it to gather # coverage data for all the lib sources. if (COVERALLS) From 9b90f223a4c2c208a1c498af634c58103972851a Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 02:51:42 -0500 Subject: [PATCH 017/388] Updated token. --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index 6c62cd2677..33cccab7bd 100644 --- a/.travis.yml +++ b/.travis.yml @@ -4,6 +4,8 @@ script: make && ctest -V && make coveralls env: global: + - export COVERALLS_SERVICE_NAME=travis-ci + - export COVERALLS_REPO_TOKEN=4MDwjIvimPGcxcHZQf0iS1aLHNfeQG9dN - secure: vj6Y9LaNhnfWH+3AoqOIY/k5Ymb0zKlXJSlfa1qBnWC94/NDQjbV+6Lk1Ct1izzPmFbCiRwp/auwcUT0p3aUNNFshEUrL5rlHOwr4zLMqxdwKfUXA7X7NSJS2EJSgMm0to0iSzuCeub3E5Y7fdDpmWTZ9bD5E31wck/5kzjiuw0G8mtdOLeOnfERCZw/VTxLwKkdjU3+m64IYzAh9tWsyM1ZpVX0c7KjjPt29qYb45xmQ7XrWlKl9fHabKbTvopISas56Q95K46pcF9sDraP0+KVk6f5rVOjYppvRmT6BJwRjDRG/rC6Q0BSfZuUm8a0OgFxc2MG3sxKT/QfMMDzuxJWbewakam0hcPJl34cFzqgIuMeQ7bK1yitsFBCqo9b/noMMp4vX9Hkm8b1f4QHTuk2fqOqorP0hOQxhWUcNs8J2jG1nDOjB5wrv9fOyerAZjZ8fvzHkMh/aZ3Xj9Sw7PVxiue1eyRXHQgn2/IcerrhlujawGbjsvLvrmQ+v5A3xvh4q6iJ5glIv1dhGaEEGMrp8httjLUAzZJpSAdyyWnJtnD+5KLH7BOKT+ptuXRnU6H97nUlXIHujx4btEpIhYebEX+pmAfOwK8WP3DDG5ikbmf2BuaI/qOhPtUzf5PJiN/+vRKNYf6ijXBBr4Cq7pWSJotQRfoHXvfE4vFa+zA= addons: coverity_scan: From ea66d09a8e07d30542bb93d5277f1c87ac3184a3 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 03:11:45 -0500 Subject: [PATCH 018/388] Added coverage source. --- CMakeLists.txt | 4 +--- test/coverage.cpp | 13 +++++++++++++ 2 files changed, 14 insertions(+), 3 deletions(-) create mode 100644 test/coverage.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index eabcb7919f..ad7d15b9a2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,8 +23,6 @@ if (NOT CMAKE_BUILD_TYPE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() -option(COVERAGE "enable coverage" ON) - list(APPEND CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} -Wall @@ -38,7 +36,7 @@ enable_testing() include_directories(matrix) -file(GLOB_RECURSE COV_SRCS matrix/*.h*) +file(GLOB_RECURSE COV_SRCS matrix/*.hpp test/*.cpp) # Setup the coveralls target and tell it to gather # coverage data for all the lib sources. diff --git a/test/coverage.cpp b/test/coverage.cpp new file mode 100644 index 0000000000..8a39945119 --- /dev/null +++ b/test/coverage.cpp @@ -0,0 +1,13 @@ +// dummy code to instantiate all templates for coverage + +#include +#include +#include +#include +#include +#include + +template Vector; +template Euler; +template Scalar; +template Matrix; From 6458c0477e64f803dc7acb571587c98c6795b599 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 03:16:41 -0500 Subject: [PATCH 019/388] Working on coverage for templates. --- CMakeLists.txt | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ad7d15b9a2..ddb34b493d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,27 +9,32 @@ project(matrix CXX) option(COVERALLS "Turn on coveralls support" OFF) option(COVERALLS_UPLOAD "Upload the generated coveralls json" ON) - -set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} - ${CMAKE_SOURCE_DIR}/cmake/coveralls-cmake/cmake) - -if (COVERALLS) - include(Coveralls) - coveralls_turn_on_coverage() -endif() - if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() -list(APPEND CMAKE_CXX_FLAGS +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} + ${CMAKE_SOURCE_DIR}/cmake/coveralls-cmake/cmake) + +set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} -Wall -Weffc++ -Werror -Wfatal-errors ) + +if (COVERALLS) + include(Coveralls) + coveralls_turn_on_coverage() + list(APPEND CMAKE_CXX_FLAGS + -fno-inline + -fno-inline-small-functions + -fno-default-inline + ) +endif() + string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") enable_testing() From 3477ff2adb3b9ce0366c4b014a90eb266586e0ef Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 03:29:01 -0500 Subject: [PATCH 020/388] Added coverage to build. --- matrix/Matrix.hpp | 11 ++++++++--- matrix/Vector.hpp | 11 ++++------- test/CMakeLists.txt | 5 +++++ test/coverage.cpp | 12 ++++++++---- 4 files changed, 25 insertions(+), 14 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 86fe51d1af..6c37e63bcd 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -14,9 +14,14 @@ #include #include +#include "Vector.hpp" + namespace matrix { +template +class Vector; + template class Matrix { @@ -173,7 +178,7 @@ public: Matrix operator+(Type scalar) const { Matrix res; - Matrix &self = *this; + const Matrix &self = *this; for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { @@ -265,9 +270,9 @@ public: return res; } - Matrix diagonal() const + Vector diagonal() const { - Matrix res; + Vector res; // force square for now const Matrix &self = *this; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index ff175d194d..b039b0d10a 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -12,6 +12,9 @@ namespace matrix { +template +class Matrix; + template class Vector : public Matrix { @@ -102,12 +105,6 @@ public: self = self - other; } - void operator*=(const Vector &other) - { - Vector &self = *this; - self = self * other; - } - /** * Scalar Operations */ @@ -127,7 +124,7 @@ public: Vector operator+(Type scalar) const { Vector res; - Vector &self = *this; + const Vector &self = *this; for (size_t i = 0; i < M; i++) { res(i) = self(i) + scalar; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 4c37fe51c9..fe8586b6be 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,3 +1,8 @@ +if (COVERALLS) + add_library(coverage + coverage.cpp) +endif() + set(tests setIdentity inverse diff --git a/test/coverage.cpp b/test/coverage.cpp index 8a39945119..6246833526 100644 --- a/test/coverage.cpp +++ b/test/coverage.cpp @@ -7,7 +7,11 @@ #include #include -template Vector; -template Euler; -template Scalar; -template Matrix; +namespace matrix { + +template class Vector; +template class Euler; +template class Scalar; +template class Matrix; + +}; From 88def6b54efc246b636c813c8bdd5a31194c186e Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 03:37:33 -0500 Subject: [PATCH 021/388] Made instantiation actual test program. --- test/CMakeLists.txt | 6 +----- test/{coverage.cpp => instantiation.cpp} | 8 +++++++- 2 files changed, 8 insertions(+), 6 deletions(-) rename test/{coverage.cpp => instantiation.cpp} (71%) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index fe8586b6be..e54387093a 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,8 +1,3 @@ -if (COVERALLS) - add_library(coverage - coverage.cpp) -endif() - set(tests setIdentity inverse @@ -16,6 +11,7 @@ set(tests vector vector3 euler + instantiation ) foreach(test ${tests}) diff --git a/test/coverage.cpp b/test/instantiation.cpp similarity index 71% rename from test/coverage.cpp rename to test/instantiation.cpp index 6246833526..c7edefe105 100644 --- a/test/coverage.cpp +++ b/test/instantiation.cpp @@ -7,11 +7,17 @@ #include #include -namespace matrix { +using namespace matrix; template class Vector; template class Euler; template class Scalar; template class Matrix; +int main() { + Vector v; + Euler e; + Scalar s; + Matrix m; + return 0; }; From abd0ef01430ebba60bc46c5d96c4438cef0543d8 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 03:39:35 -0500 Subject: [PATCH 022/388] Removed test files from coverage. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ddb34b493d..ed11ace281 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,7 +41,7 @@ enable_testing() include_directories(matrix) -file(GLOB_RECURSE COV_SRCS matrix/*.hpp test/*.cpp) +file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) # Setup the coveralls target and tell it to gather # coverage data for all the lib sources. From 4bf4611087cbf3e59388c6d4fed0ae41c435510d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 10:54:46 -0500 Subject: [PATCH 023/388] Work on coverage. --- test/CMakeLists.txt | 7 ++++++- test/instantiation.cpp | 8 +------- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index e54387093a..f144297156 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,3 +1,9 @@ +add_library(instantiation + instantiation.cpp + ) + +link_libraries(instantiation) + set(tests setIdentity inverse @@ -11,7 +17,6 @@ set(tests vector vector3 euler - instantiation ) foreach(test ${tests}) diff --git a/test/instantiation.cpp b/test/instantiation.cpp index c7edefe105..6246833526 100644 --- a/test/instantiation.cpp +++ b/test/instantiation.cpp @@ -7,17 +7,11 @@ #include #include -using namespace matrix; +namespace matrix { template class Vector; template class Euler; template class Scalar; template class Matrix; -int main() { - Vector v; - Euler e; - Scalar s; - Matrix m; - return 0; }; From edc356d0db69bd1dc7744257681adf7f1a6d4163 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 11:02:09 -0500 Subject: [PATCH 024/388] Added coverage flag. --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index ed11ace281..20df2934dd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -32,6 +32,7 @@ if (COVERALLS) -fno-inline -fno-inline-small-functions -fno-default-inline + --coverage ) endif() From 9e37b99d767a76071cd92a739552a45811c53111 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 11:38:55 -0500 Subject: [PATCH 025/388] Added local coverage tools. --- .travis.yml | 2 +- CMakeLists.txt | 15 +++++++++++---- matrix/Quaternion.hpp | 2 +- test/instantiation.cpp | 4 ++++ 4 files changed, 17 insertions(+), 6 deletions(-) diff --git a/.travis.yml b/.travis.yml index 33cccab7bd..a4b0894d68 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,6 +1,6 @@ language: c script: -- mkdir -p build && cd build && cmake -DCOVERALLS=ON -DCMAKE_BUILD_TYPE=Debug .. && + - mkdir -p build && cd build && cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. && make && ctest -V && make coveralls env: global: diff --git a/CMakeLists.txt b/CMakeLists.txt index 20df2934dd..bfbaef599d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,7 +7,7 @@ set(VERSION_PATCH "0") project(matrix CXX) option(COVERALLS "Turn on coveralls support" OFF) -option(COVERALLS_UPLOAD "Upload the generated coveralls json" ON) +option(COVERALLS_UPLOAD "Upload the generated coveralls json" OFF) if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) @@ -26,14 +26,21 @@ set(CMAKE_CXX_FLAGS ) if (COVERALLS) - include(Coveralls) - coveralls_turn_on_coverage() list(APPEND CMAKE_CXX_FLAGS -fno-inline -fno-inline-small-functions -fno-default-inline --coverage ) + include(Coveralls) + coveralls_turn_on_coverage() + add_custom_target(coverage + COMMAND lcov --capture --directory . --output-file coverage.info + COMMAND genhtml coverage.info --output-directory out + COMMAND firefox out/index.html + WORKING_DIRECTORY ${CMAKE_BUILD_DIR} + DEPENDS coveralls + ) endif() string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") @@ -42,7 +49,7 @@ enable_testing() include_directories(matrix) -file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) +file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp test/*.hpp test/*.cpp) # Setup the coveralls target and tell it to gather # coverage data for all the lib sources. diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index ca142a4696..677dd219a4 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -88,7 +88,7 @@ public: return r; } - Matrix derivative(const Matrix & w) const { + Matrix derivative(const Vector & w) const { const Quaternion &q = *this; Type dataQ[] = { q(0), -q(1), -q(2), -q(3), diff --git a/test/instantiation.cpp b/test/instantiation.cpp index 6246833526..9f425d0713 100644 --- a/test/instantiation.cpp +++ b/test/instantiation.cpp @@ -10,8 +10,12 @@ namespace matrix { template class Vector; +template class Vector; +template class Vector; template class Euler; template class Scalar; template class Matrix; +template class Matrix; +template class Quaternion; }; From bf6de4b710ac0d07ea84db2a12e8910b2f7fb18d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 11:39:49 -0500 Subject: [PATCH 026/388] Updated travis. --- .travis.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index a4b0894d68..5ad6695ec6 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,7 +1,6 @@ language: c script: - - mkdir -p build && cd build && cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. && - make && ctest -V && make coveralls + - mkdir -p build && cd build && cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. && make && ctest -V && make coveralls env: global: - export COVERALLS_SERVICE_NAME=travis-ci From 18f80462b7492fe331862a0933fadd58cf24ecff Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 12:11:32 -0500 Subject: [PATCH 027/388] Got coverage working for templates. --- CMakeLists.txt | 2 +- matrix/Matrix.hpp | 164 +----------------------------- matrix/SquareMatrix.hpp | 207 ++++++++++++++++++++++++++++++++++++++ test/CMakeLists.txt | 6 -- test/instantiation.cpp | 21 ---- test/inverse.cpp | 20 ++-- test/matrixAssignment.cpp | 2 + test/quaternion.cpp | 7 +- test/setIdentity.cpp | 2 + test/transpose.cpp | 7 +- test/vector.cpp | 2 + test/vector3.cpp | 2 + test/vectorAssignment.cpp | 2 + 13 files changed, 243 insertions(+), 201 deletions(-) create mode 100644 matrix/SquareMatrix.hpp delete mode 100644 test/instantiation.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index bfbaef599d..10040a237c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -49,7 +49,7 @@ enable_testing() include_directories(matrix) -file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp test/*.hpp test/*.cpp) +file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) # Setup the coveralls target and tell it to gather # coverage data for all the lib sources. diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 6c37e63bcd..dc72f85921 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -151,7 +151,8 @@ public: self = self - other; } - void operator*=(const Matrix &other) + template + void operator*=(const Matrix &other) { Matrix &self = *this; self = self * other; @@ -247,42 +248,6 @@ public: return transpose(); } - Matrix expm(float dt, size_t n) const - { - Matrix res; - res.setIdentity(); - Matrix A_pow = *this; - float k_fact = 1; - size_t k = 1; - - while (k < n) { - res += A_pow * (float(pow(dt, k)) / k_fact); - - if (k == n) { - break; - } - - A_pow *= A_pow; - k_fact *= k; - k++; - } - - return res; - } - - Vector diagonal() const - { - Vector res; - // force square for now - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - res(i) = self(i, i); - } - - return res; - } - void setZero() { memset(_data, 0, sizeof(_data)); @@ -328,133 +293,8 @@ public: } } - /** - * inverse based on LU factorization with partial pivotting - */ - Matrix inverse() const - { - Matrix L; - L.setIdentity(); - const Matrix &A = (*this); - Matrix U = A; - Matrix P; - P.setIdentity(); - - //printf("A:\n"); A.print(); - - // for all diagonal elements - for (size_t n = 0; n < N; n++) { - - // if diagonal is zero, swap with row below - if (fabsf(U(n, n)) < 1e-8f) { - //printf("trying pivot for row %d\n",n); - for (size_t i = 0; i < N; i++) { - if (i == n) { - continue; - } - - //printf("\ttrying row %d\n",i); - if (fabsf(U(i, n)) > 1e-8f) { - //printf("swapped %d\n",i); - U.swapRows(i, n); - P.swapRows(i, n); - } - } - } - -#ifdef MATRIX_ASSERT - //printf("A:\n"); A.print(); - //printf("U:\n"); U.print(); - //printf("P:\n"); P.print(); - //fflush(stdout); - ASSERT(fabsf(U(n, n)) > 1e-8f); -#endif - - // failsafe, return zero matrix - if (fabsf(U(n, n)) < 1e-8f) { - Matrix zero; - zero.setZero(); - return zero; - } - - // for all rows below diagonal - for (size_t i = (n + 1); i < N; i++) { - L(i, n) = U(i, n) / U(n, n); - - // add i-th row and n-th row - // multiplied by: -a(i,n)/a(n,n) - for (size_t k = n; k < N; k++) { - U(i, k) -= L(i, n) * U(n, k); - } - } - } - - //printf("L:\n"); L.print(); - //printf("U:\n"); U.print(); - - // solve LY=P*I for Y by forward subst - Matrix Y = P; - - // for all columns of Y - for (size_t c = 0; c < N; c++) { - // for all rows of L - for (size_t i = 0; i < N; i++) { - // for all columns of L - for (size_t j = 0; j < i; j++) { - // for all existing y - // subtract the component they - // contribute to the solution - Y(i, c) -= L(i, j) * Y(j, c); - } - - // divide by the factor - // on current - // term to be solved - // Y(i,c) /= L(i,i); - // but L(i,i) = 1.0 - } - } - - //printf("Y:\n"); Y.print(); - - // solve Ux=y for x by back subst - Matrix X = Y; - - // for all columns of X - for (size_t c = 0; c < N; c++) { - // for all rows of U - for (size_t k = 0; k < N; k++) { - // have to go in reverse order - size_t i = N - 1 - k; - - // for all columns of U - for (size_t j = i + 1; j < N; j++) { - // for all existing x - // subtract the component they - // contribute to the solution - X(i, c) -= U(i, j) * X(j, c); - } - - // divide by the factor - // on current - // term to be solved - X(i, c) /= U(i, i); - } - } - - //printf("X:\n"); X.print(); - return X; - } - - // inverse alias - inline Matrix I() const - { - return inverse(); - } - }; - typedef Matrix Matrix3f; }; // namespace matrix diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp new file mode 100644 index 0000000000..059a2d5cc5 --- /dev/null +++ b/matrix/SquareMatrix.hpp @@ -0,0 +1,207 @@ +/** + * @file SquareMatrix.hpp + * + * A square matrix + * + * @author James Goppert + */ + +#pragma once + +#include +#include +#include +#include +#include + +#include "Matrix.hpp" + +namespace matrix +{ + +template +class Matrix; + +template +class SquareMatrix : public Matrix +{ +public: + SquareMatrix() : + Matrix() + { + } + + SquareMatrix(const Type *data) : + Matrix(data) + { + } + + SquareMatrix(const Matrix &other) : + Matrix(other) + { + } + + /** + * inverse based on LU factorization with partial pivotting + */ + SquareMatrix inverse() const + { + SquareMatrix L; + L.setIdentity(); + const SquareMatrix &A = (*this); + SquareMatrix U = A; + SquareMatrix P; + P.setIdentity(); + + //printf("A:\n"); A.print(); + + // for all diagonal elements + for (size_t n = 0; n < M; n++) { + + // if diagonal is zero, swap with row below + if (fabsf(U(n, n)) < 1e-8f) { + //printf("trying pivot for row %d\n",n); + for (size_t i = 0; i < M; i++) { + if (i == n) { + continue; + } + + //printf("\ttrying row %d\n",i); + if (fabsf(U(i, n)) > 1e-8f) { + //printf("swapped %d\n",i); + U.swapRows(i, n); + P.swapRows(i, n); + } + } + } + +#ifdef MATRIX_ASSERT + //printf("A:\n"); A.print(); + //printf("U:\n"); U.print(); + //printf("P:\n"); P.print(); + //fflush(stdout); + ASSERT(fabsf(U(n, n)) > 1e-8f); +#endif + + // failsafe, return zero matrix + if (fabsf(U(n, n)) < 1e-8f) { + SquareMatrix zero; + zero.setZero(); + return zero; + } + + // for all rows below diagonal + for (size_t i = (n + 1); i < M; i++) { + L(i, n) = U(i, n) / U(n, n); + + // add i-th row and n-th row + // multiplied by: -a(i,n)/a(n,n) + for (size_t k = n; k < M; k++) { + U(i, k) -= L(i, n) * U(n, k); + } + } + } + + //printf("L:\n"); L.print(); + //printf("U:\n"); U.print(); + + // solve LY=P*I for Y by forward subst + SquareMatrix Y = P; + + // for all columns of Y + for (size_t c = 0; c < M; c++) { + // for all rows of L + for (size_t i = 0; i < M; i++) { + // for all columns of L + for (size_t j = 0; j < i; j++) { + // for all existing y + // subtract the component they + // contribute to the solution + Y(i, c) -= L(i, j) * Y(j, c); + } + + // divide by the factor + // on current + // term to be solved + // Y(i,c) /= L(i,i); + // but L(i,i) = 1.0 + } + } + + //printf("Y:\n"); Y.print(); + + // solve Ux=y for x by back subst + SquareMatrix X = Y; + + // for all columns of X + for (size_t c = 0; c < M; c++) { + // for all rows of U + for (size_t k = 0; k < M; k++) { + // have to go in reverse order + size_t i = M - 1 - k; + + // for all columns of U + for (size_t j = i + 1; j < M; j++) { + // for all existing x + // subtract the component they + // contribute to the solution + X(i, c) -= U(i, j) * X(j, c); + } + + // divide by the factor + // on current + // term to be solved + X(i, c) /= U(i, i); + } + } + + //printf("X:\n"); X.print(); + return X; + } + + // inverse alias + inline SquareMatrix I() const + { + return inverse(); + } + + Vector diagonal() const + { + Vector res; + const SquareMatrix &self = *this; + + for (size_t i = 0; i < M; i++) { + res(i) = self(i, i); + } + return res; + } + + SquareMatrix expm(float dt, size_t n) const + { + SquareMatrix res; + res.setIdentity(); + SquareMatrix A_pow = *this; + float k_fact = 1; + size_t k = 1; + + while (k < n) { + res += A_pow * (float(pow(dt, k)) / k_fact); + + if (k == n) { + break; + } + + A_pow *= A_pow; + k_fact *= k; + k++; + } + + return res; + } +}; + +typedef SquareMatrix SquareMatrix3f; + +}; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index f144297156..4c37fe51c9 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,9 +1,3 @@ -add_library(instantiation - instantiation.cpp - ) - -link_libraries(instantiation) - set(tests setIdentity inverse diff --git a/test/instantiation.cpp b/test/instantiation.cpp deleted file mode 100644 index 9f425d0713..0000000000 --- a/test/instantiation.cpp +++ /dev/null @@ -1,21 +0,0 @@ -// dummy code to instantiate all templates for coverage - -#include -#include -#include -#include -#include -#include - -namespace matrix { - -template class Vector; -template class Vector; -template class Vector; -template class Euler; -template class Scalar; -template class Matrix; -template class Matrix; -template class Quaternion; - -}; diff --git a/test/inverse.cpp b/test/inverse.cpp index 9fb23fdefa..21a2309659 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -1,27 +1,31 @@ -#include "Matrix.hpp" +#include "SquareMatrix.hpp" #include #include using namespace matrix; +static const size_t n_large = 50; + +template class SquareMatrix; +template class SquareMatrix; + int main() { float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; - Matrix3f A(data); - Matrix3f A_I = A.inverse(); + SquareMatrix A(data); + SquareMatrix A_I = A.inverse(); float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; - Matrix3f A_I_check(data_check); + SquareMatrix A_I_check(data_check); (void)A_I; assert(A_I == A_I_check); // stess test - static const size_t n = 50; - Matrix A_large; + SquareMatrix A_large; A_large.setIdentity(); - Matrix A_large_I; + SquareMatrix A_large_I; A_large_I.setZero(); - for (size_t i = 0; i < 50; i++) { + for (size_t i = 0; i < n_large; i++) { A_large_I = A_large.inverse(); assert(A_large == A_large_I); } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index dfd98e0ae3..44e0e3a055 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -3,6 +3,8 @@ using namespace matrix; +template class Matrix; + int main() { Matrix3f m; diff --git a/test/quaternion.cpp b/test/quaternion.cpp index 92a727d126..1e0ffd3424 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -4,6 +4,11 @@ using namespace matrix; +// instantiate so coverage works +template class Quaternion; +template class Euler; +template class Dcm; + int main() { // test default ctor @@ -12,7 +17,7 @@ int main() assert(q(1) == 0); assert(q(2) == 0); assert(q(3) == 0); - + q = Quatf(0.1825742f, 0.3651484f, 0.5477226f, 0.7302967f); assert(q(0) == 0.1825742f); assert(q(1) == 0.3651484f); diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index 0ece759bee..e3b4a2e7dc 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -3,6 +3,8 @@ using namespace matrix; +template class Matrix; + int main() { Matrix3f A; diff --git a/test/transpose.cpp b/test/transpose.cpp index 7dd7f2339d..fd466a48c0 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -4,12 +4,15 @@ using namespace matrix; +template class Matrix; +template class Matrix; + int main() { - float data[9] = {1, 2, 3, 4, 5, 6}; + float data[6] = {1, 2, 3, 4, 5, 6}; Matrix A(data); Matrix A_T = A.transpose(); - float data_check[9] = {1, 4, 2, 5, 3, 6}; + float data_check[6] = {1, 4, 2, 5, 3, 6}; Matrix A_T_check(data_check); A_T.print(); A_T_check.print(); diff --git a/test/vector.cpp b/test/vector.cpp index a1aabc6a26..c7ee34ec75 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -4,6 +4,8 @@ using namespace matrix; +template class Vector; + int main() { Vector v; diff --git a/test/vector3.cpp b/test/vector3.cpp index fe93629e3b..1535efd549 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -4,6 +4,8 @@ using namespace matrix; +template class Vector; + int main() { Vector3f a(1, 0, 0); diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index e5074583dd..9295fc1936 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -3,6 +3,8 @@ using namespace matrix; +template class Vector; + int main() { Vector3f v; From 7ec13f62828c311bdca08230ae41e3b180a0d833 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 12:22:07 -0500 Subject: [PATCH 028/388] Updated pdf. --- doc/nasa_rotation_def.pdf | Bin 122344 -> 709235 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/nasa_rotation_def.pdf b/doc/nasa_rotation_def.pdf index c97a741d0d006e856444a6e49eb0783444fd4506..eb67a4bfcf58a32d13a26ff2140e23aa015505ea 100644 GIT binary patch literal 709235 zcmbTdc|6o>-#C7s5+frssce-&v}f#OYfzH4B1Mdmk;yV8Tf`^(v{`bBl+dvhF)B+D zlTlGxFfo>xER|`Dk&I!+e6H_Hb?)cB@ALeg=Q+RY53kR>=Y3u8eY@sE)5T`bcAXu% zvYI2K?-;Vnbxm|JSPa?sgshnvMpoN_6hb6~lA?)z7#)nPwlhZ8L?0uoy%*z&(ZL$& zVRTK5FkXvz7$dBSuATu#R(m%_7prT$h~+o-iS@%YT84b#(p{rlV(s{R_;<;IDYbhQ@!vGcnQo zPnfO_*61%VU0svE!v1=muAcE|B9z?{1@@aq@$<*FFc2Z5=cSBP+2oGS?zlxqA7lSbO|L!{O~NpMX$57@if!dBkCHM z=o57G^bC$+jgA=;O#F5Id<~8Def5b%U44uH9m7l3!b0|R7$G$5hp%B}H8poT@A=`a zvOh`xGc;V!oFrnjtqEa-Ao6jHthNi`IPo+_*97~EKj-kUAX3O8$k_N#mI=p+4umu0 z@Gy+_K~l)^AmSqA*Iq}m9}%PNcADr!4q1d9A`v5rp)R3Be_|*x@<(y_e)i zbS0C6dvz=uhY`n5_05QrN#i79&*K zkr+nsBZLt!x+Xe5Isccy)zeutz%MOmAH?YD7+@Cjf{`Icdk-lnj2Md1-V;O!Biay; z{gB9k7;-!;0Hdd)|KqI1qfUo~5(&Yw%lDr5_3`mJ?&G85=R@#unS1s0-MN2Y47Z|A zul0GlWMRlJH^_}}^C-1b>s9d8o5#QN?!2iyURLte)Z?IL?SL1fBIn)RZ#gu($+6{y zOI~Wg=IbvQC`9B=+*r8R7e-IvZ0;%_Qo$m=n)Y~%QIrOy3m%+uv0eU;``A@_Sc>k{ z{T)8XGJGk-oAf)F;f!a!PYZHhWW4Haev0YKXfaL<9#W>@l~yZ0GW`9V;;wtkP(J_I z^vU9qllBi|OOXvlT`UYxwI~ z7o)eB3K!uA4`B4LKhM-YxQPGDwAu$3H!LRoMWn?IeZ#4wB}M%%?^ z59TL|6-L{Y7!`)``gw#kIV6l261Eske+IvGDEZ`nudoB;FhUp+gZ;Pi@{{rZh}9pu zlhr;L?i==&$bfKTGWR?*dzs!$V2L z(7!=((FOjdxK{rk;#!e|{Qd^zMYmX_?1_=p!~RSxde~oS*6W{f`NQA;9)tg`5?4|% z@$~isD=E-qhVe+6ACtDO6J-7}TR9M;@T zPmH4bX^EC9llvN#N1EOgE_>ZMoHn0a z{&PFrk7X?_Kil)pXyqD|rK$rm_QY+AGuvx5HLqV<#cf(WaAD_(WtZkefwin_4GU-7 zbv%PcbUhv3R6VKG+*z`)aI-8_=|pYA@qj`JttY-F>iK+IlUAyLIVNX=3oHMfWeSE2_6S1Kv z?6)gEm$Ml*$t8~!Jhp^YKPtkFomh6Zj86R{`NFL`XUji%7(|v$?`9Vq-BBQevOE_( z&Dm3swu*mMe~H0Pg`?jyjhE}OSDjSz{H*c(x8DkFI}n<+;bw=FHf~Yfe)ydml0hqb z-OeYoXX?H7aOCb@&nx;Cn&~jQ`a}4wBA9sh?a&}>IU$EVQA+$d>{`BUmwu^Ug3U_TK`;q|jF2wtyQJKu1ZPJAe%y)GB-M79i4}#Zk zR!ES4s4=+zi0F9H_4gtr_H0DKg!-+6o*Pp#TbK=*VQItLgmoXgHSA0}t_bEIg|A_A|F=uL7TXlWr;05HD9S!9tjidl-}JDVwgA^ciQYor^P=Q*+FspBX`x)^)Bfl z=O{{_j+ni2Vg#))&0mH4ElX|F?!2Q%aEzt8hW*#{M=da*{v9viZM4(In)&0&O}Fl> z_&O@RL;>iWM-TnReRVlKe)FreP31MWp7=$2DxdT|B5=hj^5cns}Yn~{6N>Z+y zk2~JYB6oZ?D%U1OnkrEKSQ7uiY?X?Q$mE5`F2gx9fw*LY^z>a#x?zmnJ*SP{r9Y2R>fG+YU+dVA)%_lfLwGF>)QM60q&N& z*ZVw%;;~lp!9tx_{jMRu?Q;ufDrVp1oYEgz;p%!}H=B3QcdOF971iQ|4s^BS#fn0) zw+p$*2^DI+WZs(8wnf&X@A%8gUEXyB{uMQwPtSHKSG)U2YfTQF%z<3#%~YbY<0b?bc6>fP5_pHD>WH)|bpKgw|77n+^mw&(5R}|6fbizce%dOUYW?{+}gl%h)GfJsmgfKdfYy>S6P4wzn7auHVSHb>hy)EAQG@ zx3w>h4_BT^(f>OG{MpU?xN`YFRqlg}7c2iwulhq1f46n~+4BD_JNyUz|7sonZrAc- zJo#Is9sgbQe|3SsFZjRoOurQW=lJqpW5SOi2J>r5_%+e|(?hJS?Oa{=5TbrfyRzEu zB)_l#jE<3s?&1hRIvx;)(bd(*VzjMDVW(Y)q1NQ!ljM-a5l;uBZA}g$haNmhI7Y;1 z+Ylp2$B4F}gfolxX+MW%9epDc!^N)_M`;&AXzLqzEr&_6w)yX#IFGM4hn|0Jw>^umu1>0{{ZzK!6wb_tc448~`f2gn-NEfJz#~ z#JuQvUEKskr2rfbugk1C95I%vpGu3h^fpr!&gB4z$9b<9SZPW<1o++)DRRS+#ei`LjkKn3=3;ODC2vp@q!3;>=An1KHSI79;i0Qieso9Y}_0QDkOz+r-gK){8>0B}mF z0Dvb-MfL#Dc;Z+{=q?1!5G;lO55SFpF9du6Sk#wLc+C`0&-z~kQwvSD+o|HA=ORJN zq$L1&5o-}4sg4I%0)a3U2=Rc=5@TQqZI(SzGOagi*QJsmjC*a zHt+4X@NeMTGid%c0GB&BLh)ytu71Ws7pC*NHRm37a(CM4+TXsz|)^sH))Aj1PGu&n6O)cxiDMyMg)=#zInMi}r^5Gr9)PcL% zZo$Q@;IqN7L)hT%=PB8d6FR(5im19 za6<&QH?oR5(3l!U7^wC5$4FWqQBThrp>L~R+pgYo(pm>$hM~)1^B6UrH8!ac>o3-x z|5kQ8r1O-`Fg*qmFu08JlS5erc?Y_}ZZ(R4cy#uZI8E)Vg_Z9auVb71|4>uEwX?9X z{?s+g)am++)Fl$u&6FgisY@5yq%-v@k~7nIZ!OsRj0fRoElZ4@zpZfjY`eQNDIW^>E2iskY$)?&7ullzSC3fju zZKUBx$|yG!{jF8GVbreb`U6^Kn)@QfrTtZ1)mA>E$EcyLmAAL++}}Udf1*0Gu-)SG znS_w!dj?L*NQ{5RMwr8$>_#?Pp^Gn{8d+y!W6P|W51Ip+@M2AiH~(&KHjWJ>6VecyR>C* z=&|c>jn&W;3WbusP?eq0DQjcfE_p;&<;?)sSKX{+=G|t(_DeZcrpq+|01K4|icj5Z zX2?2Z6(RRJZT_HsOY@Q0GjAP*_7{C;)BN?4Z1vE{3mO4w{u%*Kys~$9#_yf@V0-z} zwBDP~O6xU}G_J2xpnS9N-f{8ax3lRguR9ZUa!`*-ByBIDFAaI!Xnz*rb>rgm=Q>J% zbe?U{R$MjSJ{GF+fNz%LN~`T^MvJTu&Y;(wkQ1iYPFRaqIGl9wwhWfC-v>LKZK*w2 znkUx8zjt8U&xar4Z|C1HPEyt=T#T6i%c7XSVxugh(gFD5+tzP(`FUUG!TtB>BkJlF z5!y<(zdd?qT$wSVgZ|<>zjV(yWxn^$!FgsidF=>=^16Dz>7B6R@G#xN(bpPZ-7A(I zeNyWp8Y(5;beLI*`{K*NUcPO4AfJO?UAos${rBBWb;H61l-gJGd%pWoC)_u>2kkMd z)c%n6?siWL<@|~33HB~W5l$!zgwnPAZIiF#a|viaqb#D8-a7)y+ZHpeiA=jxphHJv z{_rmfJv5{J#rO3Kr%Pj<5*aTFr9g_Ut4oCeb3|R;G8%#zpwteCoC7(PO5c=x#q5zU z{^-?6sA$)-p$$*fmaRY}qR+C8v05%&;<`kFj_fr}Kw`QU)S_@xGiwif zUGzXFtlV3I3M?cEO9f&eK+^-vFm#2J^fh;sNk*I`5yJ_W4mu+0IWa;=*l4-1@qkPd zom~pp0#+TsH*oNL-i)=aiEN@E@51iRuwa&;xWCtl4dc>-)s;S!4t&6bpr_tu?MFYB zoU=j*q3DG~C0mf9cYVY4sO{#Yr2<_l`Vtj()Y&>XIf5TCRj*R%;YlSq%S zwhq4m^FaZb3?}Q9!O*UjaQlW%GYuehZQvZP{?M2njOft!7_5Oe3_l!knWU9hBx;m{;x>f?GyTrI)00qh zOmPJVO0%3%NwDuP-B-Em1;2mH$Dj+%j0Dh7{Xi+TQq>tp27oN2x`mh5uTAs@b9fdQ zV2PMwNKPcf0#aPg92+l~T>)hHpc3#!RCrpBiU%Jl?Ad9F6}Yvt3IaSBkV6>o0Z^6d z@OwcUhv3^7n;0D~h2fGRFh zVRp*?J}vV*sGp+j`kW2`hZo2PaMO+3>mIAZd65hZ9hsO^OIrp+vFv(?#bb@zm@}DR zmIi~2z_pa&*x9B7=UT`R_xEAmY?sIlv}x<6&^W`O%ac*rAR_>?t@xUO%`d{1hcA&! zCe)Dno}^c{c=CLk6!8F5F*6dYaawHSaMCd<6&!Wv^XkLQOPvM}4=2>F$L(G!T`U@6 z@}_U@sG|+#hp)xf$&vw(^vV!%3lOUfmG3!W?P(7| za5*G}+|j!uYiQx%`hmt8D5a6w+Ao55T;L|g<6|#Giv<-aFNQ&jdur?yO9+*+IO3AL z1QET0+%ln6HK0~)lCPFch;fu$E{{u4lYp7DCVs=J6#{tjanPNKcDIxD6 z6mbOv#FgQjHoLbpG4UxY8+w#ab|gwDdiA%sH8>)(h9#|iI&3hhQSBut3e`{FmJob! zr}a)v{xd~Po6ob|U3ph+LL?6$j-QJ!Ni9Y`5N#etW$BKAM2I zXq6XLv6z8PJFO8UO?1lg#tZvo$`3wx(w+V0(==am85)iDQ%<#$O?Km??vq*V(&2Ma z-+8Bh8h!1H1dRgQb+`mHy6~EB!44hJuHLq9MLrb()5C4aZ(r@dePFFws^CADbmm=?QAzqa}7drAzxN9a6r(YF$ZHq7`zx)c5;-_ziw${D?-UGtUcb zV#60}UeYkN=N9dYZ@`OV8#ERY<@=x6?76Y9!`jvlk97g>0C^&B7qBJVXKXHcoAUDbSQ0qUm>iDB;E^)M@}_V$F{ zNnB13Ebdz-N05=w^65S0^n4Ui-qL97r$=9}g`%TTbj6DZ>}`|YYHxM-8p^4(i2d}; z(Z1&jg_JKRPQek|UK<=RbGES|thH7--k{8*@?hDWNchy5FRkCkpTl16+|%n;SZKt(eYKu4 zc3gGA>FLN}g{mtp%PJ!>P#01{C1phiBzCx~Vr(;gCDs+34KzLCo)Lemt@l8D5)y^Y z8{2!tV+De8myRr5@~N{x3xQ2^l+qeam?`yF&(3u5(#2X8=w1B{hdR2YP%^n>m6kk0 zU!b&dIm+*8vGJ}%^`+b75&CpFdgS_C(llc84n>V;)omHr(IVwTpq!*H=rTOGWL1 z9ocX$)e~2eD9sj>av-WOa#UiZBLWpV_)K5q#Fe#VRO8a~Uqd#lGAB_(yDCy{&N$Qaf) zZ;349teUtETALEp(;yCZcRy;l#~AMwHm1CTvLnKJ**tQlE#M1=C+@NK&kbjw1!{Q< z@#`vSl{ZQ~Gfqu$I3*1k*r5CU5&=jLgrWDXHs9M4``Z*uByH&s&fJ`nf?~-WTAA#p zEc^STEoYW3?SB?_YgNiw={gWCxMu~d*Q#cOD39p@xsH%kT8UM(ee5CT=B0Ynk79Rc zF?2W?06u3f4&|5XJ&q+_Dw?`my5T8}F-f~JTr3!n`nI|>#jV&oX`kW*pT=S_kFhv7{kZ2ma%f{mR z(HtMl!}iXl3gbqArIx3{8)NZgsKG%Pg3(pJBQ%AlEe@7UHgA^JV!d%$F!{Dp=QKvy z6yKxZ{UlHb2%etaXzSW%?}Q6?kPScxa|Qv8TvOApxZ7jhaBK#)vo;?7T31^`9mbCo zt=dUQu6+dN;>Hx$#WfuhlQ~rnWWNliZ5i029wvs&)>_`-&+Ttakr&VL*d;XYdLcxD zY9Gk5(*cjgr4W7}*KDK?9+XsQ{Ma5J6|;=T`^s?it`~S$L{aCa0lv5=roXZ0teMXHU_!Hg!v_yUDu;vz3P>75a=s$4C|WW5@c8E+(sj zH?QP9#gQwvSjY}*U%RuZF>Ez|o;04ux4pzxy5O=R3f-u=EbLmP8geFg1^7Okj{j65 z@4DTsAufXmq>VmQU%ABI$PYa>3StVvO#H7Q>1rb&D7eqpwqNXFcyE~_ME|E|sNUj-Zq;HC3W-G{Si?&;FMdrkjmrIlq zOK9a!qWxm#Dq_IiY40Qd_}=I+F?Rfx|G9ICj#3dyrb)K4D`T`(UzkqqjrqEV-|_J2 zSVEFjeAfHIm*a0%$}Vj@RCEjop(em#TK7D1U?3E&6md!Ph+I;ed$qEZ-#4LjJ%k6d zWmn+4CAD`eVji$+Aoy!nAebI%hXP^7)n;8UyZcu(cHKJWG{*gq)lbSw)-o{?&B(lm ztk>3^trOkCha^^ASYMc=OhEM}A)GE^i+YdJN!MG~kzVf3UX{Psk_r}L0TT#gY+|Ac zNd*D=>gryI_He^9H}rH7sRa><%aw#pBk&v#z*8RGXYPlY9LtHhRn31fH0JKqL1DOg zL92Oy2Uy}>DxbH=ZqlB*{_5ACS^=LCoY7?7|2#Q8QcFZ5(pqv=h3iUCDbBxZlx^f>vYeU8w#9Q;vFwm9;;%FiubR>;^|dT zwj9GzMmh;cv34S4rFRYpXLF-v_1AO|5QL?Oz{V7&*NOKF z1x?8*^#Rx<8|VwOw5~?cs%=7(>B_JcWFs)q8&|C>erTRZ=}u}JltfX$K#iBd!;*|A z343Y}Npuiot5r%@n5M{IWFghe)OL;A*orG`M|zZHmr69v)wkfTgsH2W_$lL0qkj|cmKIC5sghet18Yb73<-7H`AS})CM&)iIrFWswsX%*RgEIt!hJqDJV!pohkn(@JPnqy(~qE{R^TN=R(T_~Vh*0J-Fk z0k=%4QkDoi`sp$A>aO^udZdCZXO~#PH2{LCy`Rzt@43TDW7nMHP`OeTy61khAX80i z24aWuz2_0Tgksx9!THQhp{H?!tk$;Hn6{xtNNBGj2ZX%&kTvI(a(6x)UV=jv2Ag|b zY0wBmu9R*eOP7-e2JU=n%!vtI8^`=$%AXH8Y?lzAdLl2%FLg6Kka8tN06}Zx7R*}U z!!V5{B$XiaIa#S2BRY+?4>%Og*y6!^#oH{^nba>7ECrtY?vj;S<`C$hHOw>& zFRZ6c&e6aQi(b!|+Ua8j3@v4I7YJPN-7JXPo~j@no^^R3A5U5Wf|HaAcB1Gjtke97 z&NG9=g#)Z>rVtJSXYT`n5Qn=}(zg@Q?W%kMm?oD1P|X%IJTF_+=APKMO%2(Sur4U#)OgPK z0w8`z=E0u_waxHAaHP(+<`|9sFJhQ|4)>;$m z;8^)ccEuz@MNO(Dis_VtXajlg-(cG$3OTIg1-j21nJC~7?;%L!c9i%T*{ z>BT+YO>Z$LAb3;rtq}?r!WhnuJDcyWW*pMU6%8f2;wFgAgGKt?8EH=xtrV>coM7d` zNiKP~Fu+>Ez)}B$&c5pR7`orYIKpQ4ZSwUyS~~<~rHL!lx2-JAOlwS1Mo-w(ZN7ZU zq{Q2a;fU~|j0bKz*SQBRy@#f$NTGCY@*70lyFP~^ER`;er3aPE1=v-UAlB?%tv}fv zZ9lo8w;0uTc0TFd(tHW&Zec3971xfv`a3}~d5{{&+W^3|Qi3a8oyzN+`!ow`zSKt7wEcZ3zuy ztyO}Nt|rHLm&^^ji|CT^{X-9QCa$stk#?dMcOZLgmN^MKUeL8j+=vL%+jY`rbG*;3 z>dBk{6;c%)!1JilslwC)tj1!gx!dO^9@6t@*o$`y(t6pl33J{?_ZyGBl;*`oo^-D@w4CnP{5P( zTDptloL01-erm1#u4|{>KF{W>PFMheXkZl|rVk~$PT^QFZLQTEq;1u|QS;6R=w50H zR`w6O|K0QjO%`nbP!}@`I01PRm|n){MYrT?3>}UBws^Zt190F*AX-p`n2y-QsQv{5 z%0i&kJh{p9wy3g!+r#}9Kv*$>VVu}~cJu1aoL#T|hNZo>GDO#x?kx8@FEH}S;wU{&y25v-9M-5tnUnYQN_RVEJubQFXHcClurIjZ2$Y4_Fl#H2uY*Tlt zFs-6%1*0I}F&c#JF*7Qut>eJV4#zx+BJ7J)yUoWM0NY{IXl&z5Hk4v}CQm%wuBX1f zWhP;{Wpc0cMeF9$IyO{xDnV`fLCE-5U3*0vM3&4|VytFx$xVV(Fi!tfhI%w_CVTbD zO>FD;H&)}M{EivER&;bT>ood;P1qMuoqYwji@Z1yCVwo}-9IvNNEj zNilZ>_0;IPc|WITdpH1mgN^yniiCM`!_n%yu=aqx5Nzu{jPlbH&qcp8bHDe{Wpe=r zL%_y=8WQor!b2H$Np2v^D~y&^+j{L}%5Db~sceI3wUg?+4qVP=4eM&ST~TFj5JG*Q zGlDNo?L3r-P$pFm>(c|YWpzH=uUjo#lCErZ)oUae$?D;&$ei_An+U3DYe zNI;{DP~nxz>|yl}FHsjXyq0;32MX0j?^)S}8u|TxM@5outy)>~zKB6|q(diYsFIBlx(Mnx|5oy3L=NGL4XZ;x}ePYfN- zQhWKJL+xasp;GeGDTd+kr(?@bCfV4;S1BFs*)w)?G;?j~R_Vu*lQ^g4(FU;ac9TrI)$H5KY8v zq*auP<5=XHLCbqz6`tFI##AtL%@h&<2+rq?6{6Ml#eYfG^vyVz&*8b+975J3%rM6f z=M^xxoU6CDXm60zE5O*SO^9Bq7Jn}OnWEDModPH;?gXm*3{wIpiMq|S(N{;2#?A50 zlQ&39B(0@7h>`)zI{f8$h_#6^1XG-VUN54U~M{E$}#+`nf4Vat_zGr7AJl zV$g6Zkq2CFWRw;&Zp#}nL~&QU84Lh;b{y%GmFQg#8?vIk*yiR{cYAL1;^7asfE-BW*R#4nEaLlN9ll8I9GFlQa7F=-4n)vovmjXvfcoh4No_Ek;R{W{ zVr?Gyqre#t$YSfbS-=A=LQD&Q43!ONeS`AJXwv2B4n&sQq>!9-+SPq^K&qnm`jbPHJ5FL~cZGoF!}Ph2=IH@vq`d6eoI`QOB$ld*nC2#xzSN z4jd+xpiZD7EDx$%zI~aw4dIH!5IdacazohsJL;*?F)YrY=p|yp9+A3c9=SF>WAt3= z9v^I&-xwlsHL4{`c})^FG$*3D$?4U>)?T6>X8P=0zlmyDg;(Uj<0H|z{RJ4Rs5%Eg_4{xK|2zjWZ%lDScW9S~d zk3%dfYjyyLmjTfNC4J$7$qEahfCY`*d?(fx7Z0Z>LZFQTz=;IVVWlDzy!`y#aQzh) zuAW5$EvZ1P4bwPavL4Qgje^(!47k5MndIXn;Nc(v5I0ew36d}}yNe?ThXvj|AclY# ziiIFNH<|^g{J^PRayXs`i3acjZ#bI=Cuus@Hpps&dGT9k5uh^RdT}LyK;=pf+y$OT zOOa^d0M8NyQirnVoFlph4p+>}1p4NyMMjEwTxbRex#U@9bZkULR3O}1BLG5iJpiEh z!^T;KhF+|5Z^ebA$y>K>VKm-F&gDX3cSCS~fU_~?`HPr@#+(nRhI3wzTg!#C+ z>0w>PhL7|BtV3$=9W}H9mGPH%UylmOp~74JIEm99NmC~$VtbMs+CXF5K05fa*@p} z$EAs1qvJACUOu=YC}qgzUH4n9gi3piQG22==Tb^cP;S|#rnWiMx_{Z*;xFIqY}3H>VshpbO3wgw)Fj2ZfpY8_K+ZP(&@DaKwU{ zY?hcx3h#z1v+M1PXpj&<10tDXj+hy4&jx%}F#s_hbK0V~7c{_URl4uJqHZZF4$E!@ zO}qt^HC+Bcrs)bd9}LXaEEs5mMk0o@phgoNb+_-hWlK~L6|*4*plJe;7og>~GasZ1 z0Gy3Ku`c=>z8J&|2)NKiQ@X@XCbNfjUxeqnKlZY6LOb{4oBF+Chc0rt$*`jRTs<=C z4%TaStC%1$;n4${CCm++L~h=9BE=Q+ULGrVW{^T-G!eRrF$`P+S`ZYUUaedfktkEU zeW{iDW`yYe93feha@_8e)DY*@$dLOTbj*TPaet-z@|Cx?pQ>1_gW}l#tdb(YiR070 ztCe@P(x^bx^Pk^?#qjtqsQ6z${8$>4qs}Pk`(tBwwDPabVh#XX-zXn<^&L^STzuz} z#bos?Q0FDnh#;+)x!A}4TGuk%TmO6pfX4wq1U&x>@S}GBTHmWSkU9Bn+6#C}I?Yt& zvPRp*qZ7HWLu|jFQPpAnc<+h2FmcOE(f0e`GaFkb5Q_uxcqoPi1110hFn@LB>wEsy z-&O;_fdKsD@4qYon6AgSUVWb^1xvFetaVrpQ5a}g>TOS$T;A`#^89bkG+L}>Y=Q?lqUFe3S;EWWLGM% zwV|ueaUQf8YisJ&r_By@>5~CIbC!b%LT}2rCYYmgI_4z{VapqEcHE4`lY~Ef>H?d? zXoo71DaQ!M1FzDXtYp)`@S$xPsxP zFzL9Un}xu-P8cz|tsuG_0()y9Ha3D&AhHjNttggr@u6vRzZs` zOXoYitj`4>Qlhd>Z7{c_IzLdB8c&I8^B?}YN!mON6?el%<$7?O>f9Exm=g}DrNz}0 zOCUC2vD|BF$bxP_1L9#h9(*4IvFsW{0GI@4w?-ba6!JjKL_+380I$Ojv{SM|mn{RP z%kZr&th{(Df66U zwoI`n7hmH@=F;wWMI>mii}$~M@Qm8hbWk218j@Vp*C%GqpphnAYU_?Xg$?6UV_f{SPT_3_Bk)N!B|34aIE5)M%H_C-?=3a3xjaJS}@+!!| zu?5VLy3&_#GF`04b^~BH(Fd~+w74o#(qX~p6kA?cg{EKMvFiAXB0f_pMI6>MhZTs! zy;8P{Dm*`zize$X$Ca(NP~de(i;4-PlI*gNcPpq_zhyhbd-++1-MKDrGrwbF@6ntw z^jnjgH*OvGQz^Td#g#gd{eN44h+-jp%DmVCEc%0 zj*68{j-xvRqu^%QSn|LOLrdFv@Qj`qyt2%c=j0W6n`*)DSi(`-`tJp=pBqRRBM@$l zMr^?6HRPNbDvH);7!?c)zUK31#AjOL_93Snw{AjBl_r@X5ayj&3Y1FD-4Z z7-G(*tGF}{-OAmu_VP4WT=Zc}NIea_pn2Zs)jWhgR+_VR^Jh>Y2*ZTv($eDSR@VC< zNHBUsd1uU+^ptgv?g_d=UGM{XO`gQ~~4Gj)X;coWMaRIm`%>uX2fPz7& z;^4y@zlqK~6+=l*yd7tv!z-3`P4<;=KnDeMssQmaHog&$r6x2(RyfXUmlE;%Hy@ z^_4m5i){h8+KpbTQjyXvNl2mxYK=t7oakvhHIC=AA{|zrZTSW^9j#n0YeW&>J_Wei zG2Cb<769HP=sLw38Wym~U}lBb5XiZ!<3YuEO8>{V1ue%B;eUL4LnoIj-D*w;9N@sU zD;=_lVzsNvMZiumFsMbO_E}ox2Dd&URPIsj!mW)}6>t|OR|cj}lLZ$+FBjq!+}Qnw zHAYg|%BmVt0kRF;=z9lC@taA%Kaj6|w5jHRYB8n|a;G^oOPWpC7(XQ+oaz4P}r^kk4DSchJdwM2N4&zx`#dxVVD z!=^s7KnJOZ=xR{xu*p_(0y_U+lk|b*x zl3pfPs_f+eV8XYJu~zEp>b)h2P9oXZC+IkZi=Y)gYJPYl1fD~6u&Al2Ze9%naQEWf zQ#A`}n7uDfU@uf|LAFG~wAk%@u=V$Z_EY2-FS@M#I`e}K&Mkc^MK@20ysEp6M*$)E z47ogpYwB#$*96xADmZJ(pYJ>Sm2%65OjyR#bcWfM$4cL}?c4uZ<2HTSq|JsV4uBek zBkJnv8r4a~7aN2#6~OkPG+;-9esRoKjsBB3Xz1I~;1G=kOye9VJT)_}E$nqf@SB$j zX{O=z`zJj6`2=S9H7sN7a_#CYs%B+V$lHNn*k( z;QWTiE{&^|<@ENf9?kV1p<1G!8Rc_KRP=BXXz6Fhq~@ho3|vXy69s1OH4P0OyMI-o zR6VJr{JlY#DTlr``t10_WjFMOy%n8$_se2)BQ_80O?zp6X7c%`^h}?3;CV|IcZw8JW-29 zIBuuUa9d_I!^N$F9XV5MPO0bq8qVdCx{qzg`+nEDRrOs{ObyDhfvQ35{=;K4WU5tSL+kbNIEIb1W1`}ln0J&N?< z?Z{+G)$4b>OyR@NuWYL@`QnA7wdOnO@9gBMJ%uT(m-#rq z&kB?B&)B0wECINZKU6sjx_KoJXDiq9Di#Cld0xy{S|3}_?Mm4pz z``$~Xgr3lQ2~AOY6+{F=la3%r6)Do22nd7-1PGv16#-E|1VsTs5Ts?%K@fpRZ_*SD z5b2PR+-I=Xv-f_^v-dvlIb)pn%lpoeFKJ`WF~=P9n)iKQzuzBcjWfg1B~Tb89j1EL ztpdggbq%gYjf~la?To@FEgOWT@TDrEyD+)*O&RiO&_|0kG#oxe8g;5lXtpWML!LLW zVnQoK=BzAu5&&VZc5HK0shu;A)vua}rr?@HPe%9flTB2IU)aK8t~c!?S`MvPSq9@- z2xdnkteEx)=qy62Q=Fg{<;LAl9#3T{rc3I2-fXIyIN(CsW`C%)k9gwMx1$sxj1V>9 z+P3vz#8C-iOiGi}5ewk*xx*2JnBqW(&aP9FHAIyTl&vKVdhdMbpO7C|V?XIPihjJ*-CT6pxJuRIm;)0%3>fJ6H zXgpn!*DW|)6i~vh4TTAbI8SJjLG?0MJu?~q@I%|PKku-3*>B{~@(=1H;fp^k_MpuuTL33KFL87(-)h&T`eeO7O#Mlb_$ z=b-2U#7pihg+DnBgboYdEZ)H!_u8(!bLjlwugW3XHB8SU?VjZxhA0{AuY7!Oic#2; zXTj{H=*>ih%lEieO0Sjaz}aA|_k+*~#|L>Q{N9mlVVwxalZTv}r~mlNvhhC)h)z^K|H9Dz zH=-dGwf_%`h7^SVoy`6})C~OvbTj>{Waytx)_*M-`VR@s-wK+){Yd{Lp!vrSU z51RzW4L{DBedp7*Mso8hOO%WJSnf2Ws5q7-@_KT&V#jakQ&o3nP3$pQDpo5UxxeJA z*(ts+@cL>)vaEgBM8qRDYUD?sdxQ7+ys1CBCbTzeGua4!Aw)CW>ni{4T!Dt&D|t9$ zNdK(w&Jvy^mg_vm86k2oF}t{*V$J?UHnFyZ)KjCGe||{y!gytRL2^fD_C04IwhYe? znVjFv*6I!PR zHZIYy^jKJ>KU;pBkfy_OoF?JMjym^IN%j`N>wdu-!YBJ;Qc|BO4-d3zLk5MO~{udnIV zevJG?ZTXWao8vd6(B3B+XLTl(uj2!;n%bJ?>}Q%(wZeU4u_gzxCce?FwPe47+I{$# zdkfaDf1K0nqdS7{ck3-da%5=C@rx^FR5jx@`8`jcX?dg-72UcwQbQalYD*7k7lq`&#ANdOQY&v!T zbD1s+k{H>job-SHy576mo{ecz=2J&{d8PbNe1qIE4aecF2L(f13-&MUgGRZeJ_*0k zPA?w)e2J&E+3&;ndMq0|2QD*%08@^LRV%8vCi_`Dvaz6)@98{ufBkaJvf)+fH!9*) zRQ{)Sx_kP+{zy$N=e#1mFmst{m_sk|@tz~Iqvo!PJ8q`($L~|EYJ5%t;! zoWeDKn56w=wqtz#^;K6#^3>s@FKXOeYdu?Jpi3Sof4+v-h6X!%%QN_S zi0$k3M!&NCrOMLOt!md3SY|SQ=JT`G%nq@`Qxj!WCc`D7bjT6?X1ng0L16@ zqIqHRChF5e1$00o*Q6VB*@mkF%~NUWFE(*Myq?_1+aZOT`hD7~lXI7;Vcz+j?I_-Z z$<#SqVh#(u8E(&h@p>nYmOZ&X+cow^dRg-+&m2_5Lfd&BUUFW2!;cU4FP}EpOgM6~ zHD)@w@!4+%O-K!!_9y1E`^8xwvNS%=x2SV4_k2+GP&xW{&t^%u=Z$7!!-jgz@1vyr z7wjbsJYpSn+9?931QKt$7t2goBy6@A8YyF(U&X&yB1!XEZ0ZmB!R_ci&oiTYp+=;fPZpM;Lxr~R zs&nf7Z)nVHXE+T5C+CHDeD#%hyHY~F2%VYIq0_s;yYT2s*(IEGy%1}i%_!?3g|tzz z)|KE&+g@}$T>I*S*E#x*)}@P<^EDL_6XD9v%_fZnfSUV{!o&@^|1A4B@#&qE>VHy? zoK%f}RPX;~LHJw6_doj+|I&_pu=vl~k&=JXj%0_@_WtK1`8Ns5iB<&5i?)Vj0U>FS6O_D5qm^tpHGrHnj*gyNv1eV2Q{n^y1BNpFc8TQ?&zkI9t&2 z)0GTdAo{W zyk2@;g9F)HUpiA4R(6u(R5MpShXq+L-+Uk%Ef<%yG*IUmhmlIKEU*-SE&lKqLNqFR z@_d4?{z_rohYJ@l`$JB^Q49uC``6GD4u^|F|M3atCCl1rHSm{n0D3aO#b8oTCXfEw zhTbPg4q?a)5QHx9a%q7~!KCACV7(Bw0V#mj4skogxVRk4VkxcLZT3rm9330&GESVc zyI_FaI^3~ZyyoWngaPV&?rQX}mRpaIzWvn5;7XHBDMg}VY-P(L{9MSN;i5WMq>jDW`< zDb>e`4FHIbb7Y9F?LXIa_Y~AbQA`}i7!t5hiqWgo&w3QCj9bwcN}kI`_U-s$4)TTt zA8Bzymm3!k;?5m{gKhYaqU-JFUpty4EJW@RKO>D@tv@radU_mxq;|(SEInx`EJG_n z*&s^1+B9V3-K(bHye7ImP)1>)@D28@RbY;Qbm&_b*95wepzy|k$5_VBh9{bwwrMyVA{t+`)czAMIkj4+d z$dbJYM$K*`5MNs@U_cAjVx+PtLmIsgW7fp-n3T@B?758Nq3uj^d6XfHm$ARr7EA~L z)WPv6o??--v{TlMN+1Lt#~Wm~;$oy(=FTsFLcMPQfIxL^Y0T%cA;WyS9g09k6~u^; zPas7+LGo(?=u8qAZZ_DivS+F5LQyE#c|b-UKXANm*ciwtqt$|pen4-aCFC9~-JvK_ zZI*oNqCC$_v;}6y5Mps#KhM)|@Lqu2wZxloPvPHJ?M&dz&*JP{X*@Xv^N<>;W29Lv zbKPXob9D|e{QLS~w2mu-n@&3oRAmX1!~}7rT`VdyCX=inV66Rjd#OX|Rdxw9;w4N> zXP-mqLW2$*{@FhhgTYkoyng;4U!JdAi0em~^S=)A)+^cq!pbm7m-flW2aJJJ4}%M}_@2&Wu1ZBN4`(C0`C# zDyA#8v-Te4^NJXpZAgYBd82oy>s(9^Y@V!qde-3ShS=oMC=S2z?VLNuz|sKjtRiC@ zp8@(34k3P~c5D-lYr=(^g!LyKV~9CSvyJ$c37e+zA-xvHB{@CDwtR?*zTZObgNf4n zNnKQo!Z;HVFJ0}@JTIl)vE=~MZD`0$y|2GfOU^g8s7CtXpqU+`jfy}p@*CUXaW`YF zG(OeznyGRv4n+!lb)-fzy?ltAl|&%}02z#fgQ4?Zt{eyM1rX@!e3H|qd{#a^@15&! zNled^<@QsG!!fn)=ueXXRq*ZsF_2gv$lo!~=fXY7u7^}2NV0^L%<;M}CU;39krQU5 zJwPS{C(1aAPiSZlG;Fy{MPp2wU4OTGtjvdN(@rs6Ye#N2kvE6|$Ef+9VYkhq2R^f2 z)f4jvcx24Cdu#z5lZ^%>c!d%^WoE(00 z7fXdoCkDE4FZd$~?mBgMnCA~)eR69RI*IX^fgD z*^~AgG8flXE}^Pk0U{O0k<-4G6u4lU^QRvvo7&(35 zkR^mAc|D7gZ&lr2`Z6_p9?3-B=eBVY2M7I;7ot(mw88=52QsFqh2S!)WdsO4b1ynt z+rt@!gS$Gc*pr88vk-baUL|@uQa3t-`So{-WzsP1b`1jr%Dw=h@E)G62vj8tPR|F< zbmi7Mql~Ao;!vh3+FgZ1p6zkM@ej{rY?`$dy3#=9;uE2lF6heWZLg;1A%be$o`pF= z8+yO5EV)9CBGTBq17x}33pmjP(UjaEbeQ8co;xz$d)11)uoG-OvXTMhtvXES! ze{4Z{NAJ6Z+yyFH6iO=rJF9F_FgrV27* z{MkW@`+}E<7ee7RB<;@Ugv7$a%E!DsNI+tCstL~PsP-Gvn^X^|UETUy1m-Ar3x0l& zh3;5VXd@g}^*bj?LA(y!-P?IxOh`Jsz-4#I1U&@uYJPo6pJ^d?uO?|~Z< zTplc7YEFaVUQ?IhH6?^0qk8q8Ad=T!A7HWk`E+pi_?b#4SaVrl_bs*C*JCbyP4R!G z7$-;%onMAhz&D&b5u zk=L-`@K?UXMp}N!q^e(bhv~pd3p(|FM{R18c441IlUGw~p5E-V`>fK!utrm@K$-2G z?N(B&P$bFRlwgsJA2P>A=rM!FC_FfzU;&l_Gpn18!D2!6!3HG<$v|`~N>i$e=BD7` zbpxR4brsodB@IycW16=2qHPB>#?IpjpOOOFjxBD^9ROSGcqJfU+fkr)Z$9r_l2y+Z z>ezKMe5DMfdz2Ku9wAwe1rCn{km`de8l#_*!iiB4KVN|zwyNdix_J^|bK2zv#R+?N z9*jryG1oRtAIt|jpQG?j15(KWVZIfRQQ8FCsW~?7Dayo9P`jU8Y~emHnwe1qEpoDQ z;%61e5f)pS|4j2jM8xS3nXC~CGw^eO-tGb# zjx$vnx{21+@IL?7g|bX_=1SUS@tsqm7ov5KuFt&)f7!Sw;;T+?pi1hLYiQ;?sCw*M zHucj^7oQF&7f+r3tYChwI@G`bhWXQL)g2lB$+Tnu(y5;DyEq{pQx7qWSKbe<6f~fV z6B3>u`Qq6dM^0qxi+0wk2vm@|Y_wmaO%Lp5%J7H#pCr)IstbfpS;`HoaV|=$N#N0C zv6)-KiCYp~UN7P9vBwXfl{F$~>7hyj6_u<(dj|_|-Dm3|N&<&90aIb)?_!r%f8Dm3 zJphWLMbNIMDmNk?@P;$1HI&sJ7Fj3U zDAq;`6yl=Z<4V`hzj`|!P8n}DyG*!+r>$E+SgYDK4bVY?0m zvg}&Muiih`TyeZn^s+HAe8HCS!z1sqX!tXD@A-l!JZ#B!eX(rjOIKc<^<*ut%x^Xh zZdhNEgulCz2aQ}?Eogf(LiYrJW>Y9;HJf;cqN{LcrJ*~zP1!C`gw}ONkS%K~o(kh> z;l3!Y-}&`4m5|xSzDdNTp}b$mUy5>gK3F`}t}2^~S<4O!!z4~IEkm$s?y4eczl}@e z^H^4)O41sp%3VmVkindAqf!vP+Kw_p3lx>+-E~8iCbwL6Iyy^q!roEwOhc%cxlC3w zD?a%BNi9~sQy5n}BT-Oup|4p%{)_iZbzfYcmQk}3MQdQ=eI93!I^`fbiF}+tW_t88 zhbP!)ZN|B-yaiD5ep)J1v9x=?)&^)(d|7dz-cN0n)Os_X@DZPu#AaDXrNl0G)ZP|( zjXc}egk7t@7mTO0V!^1~)&@nn8>S1k<-;Gcg|9aG6?Dj~N>a|v?Q^YPPcjX}KDfts zkv}GXK@}qM!!Ki>1W|r~7BWR@kid2iAPF4;fOx(;*0b$8zxka+7{FJ8`33;M^-aA5 zK$PUNMQhsp9FbK?4Qe-3g2xfj2`w6;ML7F_eaFrm?`GScaloBOSXqgCKwLZr%tSVNp`Fg4#V*pH{u znOK*A1_zgg`*kD|1zIO@v}RA!wfWCl@CN>!9UR{hjJzwn2r9R_3L}nw8M^PfZoh{+f&z75J+$ zBI9s__Rv*9q)ox>>SwWJp~X-j6#Qg!!ehL=oyB62Wnf zF&FsaAKvqu;%@D0UPWnKIHFBgcB9DRmq}e@6osP8K;hX4=AsxCt201!7apC4r5`6@ z7h5k%Wf?}ww zG6udVc)e2yM=T^s`SI6g?F>&?-ZfPsxwy|Zy#hHqHE-X)f1N>Kp1JVcgJZt&PD1`| zp7_gJFc{<@)u`RaOG)+aI@f*+jhTJ0_hB%Oo8B~s;w@Y}tN|Tuhb|b@7NUvwnHPWw1BTly1Yh+(xx2+z6F zV^o@G8JPdIfikyvS%KQVK$O^Z+GU6FW42|cWqv$-61S0Pt|xQmiI&4uf+dMWL=y33 z^LIm&4v@jvy>+d-Y3GsQt@wAU4`0+1a$HC;+zWp-@s3|Wf!^B-b}{2v@M-jDX|Qs% zZeNJTk#r-#DKMAVvIM}v=-S8n$*(sL+s;t2ls%vJ4|Ud2^-S8R+VibQuomo+H?e0y zm>Vk1N1`ZL6bR~H_g;-e+BOCfQtMKwbUGkvu1b6~P&u?KP44|rks*XMukCb`1I|GX zU+4SIF?{>%F9Pbo=cy@8UTM5C)2cyjr*OOXgoD|TtJ0`kZ1%-xBAkCuo9uJYuqmQ@ zdrX9fybuVzI2i2SkoI3i3b+P4faBLPhT;wu4XH;=70RgqkHRkr3l~L>ANepp7eSIw z-k@9@j_4{I0O{z|nTRW`vO;6puTqI)2bJvZR1CHiWE2>DX(v2~TL^ZEYCn31ozPya zqfo3bvoZK$P~B7QAI>)lNEdT%&f%kBWSW>TM5He0Cj=Iwhao1UE4}5Ma{XNbakc{Hk?v;W3cD^Ab z)uH7#aJIiECsmR{ z*#bt@9ULW-qE$%bk?_sSJk^O#lj@R4n%bo_9@^I_D}P??fLpk^)^nRO@FltIuf-JO zYi><4{={SmXLyG*)s7Lku%us)4~;sQwckQr(FGaVB6#6!SWfE=#+Tz&?IE zs))J6PC1O3iMjXYNUvG|rU&d-zN=A>5R<%Od#yKrgOf|L;`ace4}t4X1Vu70jh?yn zX6~svYwi0*I9bh-ekzQuw)eJQ1v$#W^zsc;?XPMNY8bLcr28#xMB5k=@0`lu+H@Fw zDu+hIbgq}5>(IV`iI*XPGde1-hwC=CH zTr$I+T2qn7tn*melr1E%JK@)JqS=vLV}nNr3iO@D&vyIX3q-!YCN2%4$j;IMd|*_6_jg#C7}Iu7fqJOQHjJkF(V=w`il zSz$XYBi7#nL!`-brO9KGi+!R5(W{2RI!a5pg)qzXo*8&*jKaIptwc`IuA5l(#CQ<~ z!Aoem;3HEe*_jXDP!daqPk#D%I=Lv^uoLc+E26RCWsSma&xnONn?}t%OQRzMpqc6C5^&-<#x~S&vNi4cmpCX;ks#$rYqGy9oIf_sDr_vyPB&FfgsieeQB7 z8_s$|W4DT7qu0~IrBew<_fBaK<6T;iPPpc)`iLh_?&0zejAJR*7GF~Bw7n#=Rbft_ z(1qp}fwn1qlXyOHL$awjtV8X0&E|xHE;_ZrV?`FV5ar}O$`;Qtxj1I2MSdj4uB(Sd;#Tz(kHwOCpxdM%unGc4v&40xWV$$ zejNoFnXsW@x1qjNY=#XM8oo!ml;Iq^KgD62|m3V)C34=ws15VQ7RG0%5SBG^#Y@sxXI>geWqj5oW)G{~miItbl8TUZqc^ z=<#bL?bH$hFhtFiCO$%eg3IwshezK$rMQ@&&;+S*k!oIdDz58^-`uI#&u*WlXZMis zTbu3ZjLzYF-!3eiAgCqs;=u=oiuOlI<_TuaTuhXbD)+ODt5WE6uBu?)K+$4x+Tx8i zi`R#Y#IpAGIE;iJt#isg9Wjy#OMB)@m30+J*v-k&CmAqm$a;vSOVK;fBmtC0WNc zOlLyuzh^jS88J%M!2Eq0t$N=<8|3tidadkB-ndff(p`n#Ey?-@7YQ1nmW6t<*%*n% z=~aBrP+_&PF|MpGzNL+Z!Y^Eq@{+bPqO$*HXO?ALlAONg>+CDfs1$qpos=n678+_q z#buKJZjjY@FJ){r%19-SivAruAnxiLDh|7jt8;OijV0xc$ph(VHZPs)+(u$_(qdWK z+7NYrv6t56kHxR{3y7_X(=Zs9#9d{tt95!+%Vi|?_7#0YifLhcqJgQ7c1f0@c-B$+ zG9t(qxR3+_K0rqRI*xwRH-py(qsR zt!#-gqIx6BV$!57LS@$`s*ywbc zf&TTw{a!&DUNnz3>t=s3t4iOFO7II|2iA*dh7s*xXom2c)6|B-2o`FIysvMzq?M_7 z86}=dO_7l!BDClXV=LNN2P^k>o+K~JZUeCk!X)jteo8H3k6#%V8qp*8UJ3Sc)PC#P zV8Hq~UVrL+mu!p9kjm)BWk`BIdE2L(*+gS@T5p<3Dch^LiHUkm?0tEK7=6ii(V9Z* z(YnO^qB5}m)ECs2u+Y4(JM;`;sBw!a*OSI@8nNelL&<@16E_AE3v?1pY1j;OX|8udZar3j1$}OR z_5^B_s1im@kWhkR`r4S{YcA_6LWqY3D7H(9d~|=q0~rxl_3jH+2dbJ4`+V zBhSmq>A^*594|gCHqifLfXDFrIL@SxRe$onGQB@nf2KfY`}6+X)#hvX_4Rjr%%=+d zB;kn`w;dDFx+gltSshj$;fll%Rd|}=9g`24PcM4 zp-s6+%b%FS&Lc87LESsk`{OD@jd<>7e)M}?Np~)pc^x=h;il^u;Smi5+vgtEPtLi1 z$E-q?Ma75^%(qTP5olswbN(A~sy$k9ok$5Sv`&h+k%BOSSEe7O(_}*#nQQIs3Ehi_ zC@dlrCzBTrnW|Qdr z7TA11K^$)&NO!Uc9DA|DqD#RNmyA@o99|u&Zm3ke069+Evjliro@lDe+wq>Nl`*fn zOu@O9BK*&nAY^ZYtzbS*Z7Y!;3o1~%fHKW6H5uBqd~d0KufL~wM$3BrJY$>tJ(#6k z2@cZ;aRIvxn>d`#OP#TgRr9MVd>k`3?iN^pfvc$dESRCk(t>jUcQ7SKaAL693$ zC`TLT&l0`8Ojrv@i=yi9g2A%!d^2bZeQ78- za%Ce5IwN}Ol(^JTAb)Ib@29xju5QmuIqcu>EGS(N-fedcrI0?7w)> z1}<5U-=WeLI6hNLH|%~%(l%ie*J#EZH+N*=U7n3$wYrZ%s3~Z)`$iUePl;XrXtupn z`%U=AL)7JtTF<4mgLO7yMfsNkDgn2sV4fY882k>jQxY4J7T>HCeuLwj;CNpK2F>6r&z-sZK> z^}*ElkD7q&2FN~AySt6UO~45xW(ij9p};{EnYj5tD+?7BP6qq$-`yQO=H$W-$lh8m z0L42@9zS=!Ua1v1%?uR|@_{j&t`q`gXN- zPcp;(?8Ad5KDf@Eh57{<)xMKPk8O(s6+IHblNvOZE#e4KIxW7xxOO*apsqo&L3`GE z0_21iB}6qd&Q#(1llb`E=}8fs`8u0&;caUT!}AZXHN3SzNT-2ZJp>GZal=hq`Vkjjwe;6m`6adP|60Dt`{A`^lkap$Uy;IZ-fd776!tujd=$jAH=*A^dZ~YKb zrY#sy!gy60(!t68;9hA+2B%4RH=7*?TMb^IcDAiBX$Mip2+D)-@B-qhGzX8k-5AipGR&!!&6gqm4J}3 zEdmdCwCWz8ajEsQU>FygN9qYK)cIPQc{d~bGi#k`(aZ&CqMt>)9NiW>uEne^&@t}b zmC`P2>1)^2&HPc?M(QuY@Cf7-;3tHV}xlI%NjUl_m2>APtPdL{I!#mW^a$Mabm zM#}6J2fHUpTq3z|dX0D~bV%wYCK=Tus|t8V*%_wFU6rIYoUY;OlKSfz<^x*ZP916) zwFAmdTrubOcolwGMO-RG3FmYpsW>=aVX<$Pt%*_5ff$O@HD-$JFxUO1QT6SE-gxM^ z8NrDSB|$Nz^f4z@;bY#D7Q~khz^0ziuPhYBbsnd->$Du0M|Ps6F>|Gvj40A*(#3Vj zgKX-ph*1D6W0L1V4^d|Q`SS@EU^I?R06ho4Pa=aH6J>V^pm)ZtMq_Sv1o<&XS0@Xk zll^2`jlZrwlCgu`3p`kvu%a9#d83CJZcdae;I165$$~Tj0AxU-aOJ+8$6AlIhxgEQ zwTvDlG@~e-ujZUwcFnYiT1w6_1cwS0Zqp3J1}$$4Bu*_1s&d|RcZ#xC1^Rl70TE2Q zP&Diomk0r(6hQQ8NLwwyqJ~^PPUblnk9@?{Z1;*WixlEqyKI_l>Oy*OLmn49On%4a zwKIy)K-1lH)Hb><%7rAw$l_n-8EO0>^r8pA_GpPG_HuzAB$ynOql4;5Tr2ya=&uV9*;c&Ix{buF$ z2SKk9Jg$Xp3=oBN;l2zg1~WhJorNBMpLa6X$Fb}PJs~L&s3lj%5Q$X{`imT)gry9q z#Y=egDVlP9^hTr|6v7!ll+id?n^(x?V%oA(^01e#Vm0Hu+n*;qZ+!})S&M+lI9=31ig zH+oQe-WH~b{?*k^m1FjWE@M?-Z;Xrr#v5*_=~D+tfGwMv{q_8vO_`V41TKl!LA!9s zHDJhn5DV(xk6Vv4G?^+1yt2hvw9`an}Ax-ZkD=cmfZX{%Q89;v(eZ80lc4-i$r|4_6hGGgL493Z_qX zkS%>HvEbEb^eFQ@uPa2^JUissC)s&2<59MO_biR0R&Q3OUA_)I*FiH|TBS<59bxsa6(0WvVoGoZU1q`7zp}u*r97%KM#vl>0{R$4to0^7IOG zY9%hZQZ{RHWUXW9asW9Zd`J0aycX3!=hMits`9A%*6cehIZS0qrEj;j1yeKs{Fwkr zdI^z3D?6C73N>B3or8R-BKS~XsYHNWma%wc`<;2amwiQ5g=3mr{?zd>scMe{jH@VK ziB*it#z0Y}1j+mCR{3=sg2NJD_&Q4X)2Z_`!cj^(q5zOwYBw~REVRqR z)(9k1e?@CF0--PZ8@Db6w;Kv-XM|D3hQ076hHlV!K@hrfyfA@MXz+q?zU@4~wf5=I zpb^@}cBa>Ar&6xJ_0p9&f#i5lFm~wN$LD#B!d?i}NiWBPyQQgiHukVgWI3bX+2i}M z0ap_ZxINA~d`~0p)phCxE?dAqBl5c&{xZQ(uF9wPLe4rH!vZdQXq$+mKQGsG9m3Ti za`EO%%k6X0G}%(;3hVPdmXhWPmC`jzTFYw#-MPZ)-SaKy;?;!Bj}~5Jo9W!qeP`Qp zSuYpW&ZKN=5!8cNILS4Wtbjxo2kx3(YUrKEwb+_Z%D1OM1D-!q6wsg}zVDP;eBs;# zaHyg>zAc`6q{SS{?{PO!1&DP38?-)U-lT<74saT70$}eDS==+eZ5c2%3nz}v-evhP zWm?g(hQB*~fLetrX6J)uxaIMSJO2da!a4^B$pi zh|qi$c5mC}#sKkyq8zIHFw%Q%9&|u@eP7vAlycG!YNr-_E1Iqga&G2;x3hR2YN3N! z*Qa-1iC=j^5>(&k3}XYn_Kq23Utqkb9JN0L=NhqgFqTsJSab&GvL5WJK7xNdJih0$ zzMjYUlotj&OgUyHZrjWTQAyzCCdiUND?2dBl4=V@y*IDZ9}FGMsb%I(tAvS>Zx| zCMoNYMI7V4dCp)kBMkCqsW{0Mf=M(Q&R@O;)uV;Qz(o&1R@S+?SEMbFF7Af@Y;DlT z&g&yUO@HYzOn{5${;(q3 z3Ui~{_h$wX$(EQ0?o{luc7673kETY(VJ8!haY6`wsykxpm}M$7etvh6yO9;6+6yXC6I z1!9Db@0~?Nw2RIpmx%Oq4zhH*0J6Ko(%cmtgAT`!`omcrP(5e+E_)w$l~#NAnn>?d z!qibfCPm23e3oMULF`b%A-3XM3{>_*C-zu>qX@+OPU}R164%92eHYSbx_~r=M}Bx= zc~aU|N3(o3uyPKz&+49o%61dF)#bbK2>VzhmwF%~+Q3&qk@sOp!YG@Y^4b#YdXj>1 zjx+zYRbN7>g#O)M9SY@#q~lFr@-@|OsN=ve_ne%8C&=U5cN{#qtdU&3M~Mb5KkTB6a6}1)Ms$MV*cJwa0-1_t-Yfj_D3i_&w6dz&IF);bQcRW}b8P2tkr7c?Sg-(5X7E&uyXWT2s}rk$h@RkO{96S~_w8KBmmkBJ zMa2O`sKLoAdL~NJV^T;pbLn#LZ+OAGd=WpGVAsvTpX^)uH{FA3onReQp$0sMiD|DX zt{jlBVxoG5L9^#y_uTx&M2{Tff(bX@`bRhXzigs^Ku`T=80MeCf0_P4!~Fk|pj8x> z|C?kzVQMTw0^P28gbF(d%UU4xh5wGe)e)Ap_J|1mN4%`8ZeT#DM?mNu;gbkstN(L^ z_TQ3^9fXbLmj9c3{SSy%Uhdy0T6wjL|4z~Vb8hhelA8MK@Bf7mzv&iSjSOLYK0}qhQ@9K@%kG8*j ziut*CPm>=bJc9j!BCGR9mw&#}TS!shehk*O5v(mRh&5s=Zs@1 zz0A*ui&8Pnzp!yeKYkaezPT4)Uyfvm)NjI7V76lBXIN+##IkOd7{*)hh}*1~cvmLK z@uD>8l7|n6zkD_vF8o9-ji0%E*C2#r~NQ-7Tsmzsnx^hC0>tzK9DguZ2<|P7kw!!(PP@p zD<5;Ae{|zVH_hiWRZk>%q)OGP)c^3wyF^>0@@e6DNS=HbwPS9fPpyub;Txma&TCJ~ zR;!!%`_9X47vX(*qa2e|>#6l@4}04J&iY)FSJR(LDK_bp$oMq;l=27GzxvB`C@#~e zq^8+VN?+{b1*V_}kqpr__g`ijtd{<8fNgCkc}Pg$K6oCk%I`Vd7y9l+@dqYfH5F)k z*i~M>?nuq#I{Ur8!ksXa`FvV%?%XCrSBw0JGfy!4esz>+g9O{ycJ}1tBi3zKQt*tX zrMSuWIi|O4PxOa8U+yr5=<)PSTt8MB^|>)_(odugJ-ev)Rxo!r@AHN}y=F$Q_ z;Hz3Edj0;6Z1ql6Q8MPs+ZKVEcy zLaQGb$o_2Lb)W38i%gpeaFNdaTo)&!zOU`^;TQ>~7!K>#xOh5tP^Qhns?7=y6K=4S zKIz~Iu?sY_Qs@k?bZTQh|H;fo(B7@oMqV7(IWw{m6s{TU(dwR|%3ph$MylJr?fa}$ z3fUyESYd;PnCD5a|7KR+6Mwh0S^9GRdqeD#T{*PF>gmIe16&{Mt3Hn+t5u%dmN%Uf zuxXVt-6)(PUJm5Q&M)91#TZ#$)LU6tzhhaKgNy#qYdmvt_CiL3dLD)vt{d;!KhJfq zOw*$KP{wNdX~O+A8^&J-`-De*e|#AEX_7uA_g;MG;h&w{?Wyj?Zc^?3_c%8*KLjtb zh_M~?%-_$MJPK$nC62ee3q96f{4$N+{GGp5kWA``>~J3*>h~^J*>R@wWS3i$C04ul zxj!m4*?v^QM6Ap~Zrq|U=QKT@t4ie3WauL3wSTPmwB*Qo4_UJlJPGM}yYnJPVZ`)S zUZ_r2^vy-FkJFF%Oc{J4y&7^b`)}k5?%x_-eYgn0wrK>y&OsJO)s8}wqw&OurqY|IDoyi`I@?@2y*54rInn0?mT zCYy*a-eYmn7$H}YTu>=w7XXaO1qOiN(zi?kAR!WfyR9Px0ARZW0(l(#rqsC{%M!=1 z2QkfHzNHF?57cy{RAl#Oa zSvAw%vIv)psoOnQ8@B<{V~)9zwnHu}H@yLIuT4dlDu81@u8F#qQ463V;*qF56aXtM zNw$=|s`~%I-MfcF)%O42*L@|8B8E`HFhm<6sg(UDD!XtDy1W1Yu3 z*XJ|m`~CX7f#`0!)i&tbc8%D%dYCb@K0H6q9 z5C#A}7(#qu@ubnHZ{+~2IN|_WO&0+!3{OLDPDxz;&=$_-zD=%Q?8pxKgsxmMFHC*LbXz##kLt}Mp?W*{%Pp?zj&u3{PM?TF(X8y1ysg(Ne^6G3SB%E;hrJ>2K8uB) zabd~eZlt+tIRBkQ zB4gFjlP#9btJto-=?k*Bm7R|2Er-whU>B#jn8OPn6Kmql!NauLn$kWe0^qeY zl|uEz`aQAj*Bs@|el3{S$sL#%;iF=k3%ik@#)bvI_D_ZySU(5xMazSc$b2>fAW(cx zZsei?#}9yc50E0{Qw7}dw*a7QQP}X9SLMQJ4w!F1=dK#O<1Ir>*)D4U1RNxqxtA~m z08O;1tC@NeRuqa{28~6|F|MxGRcEl*^z-9bqvPh7WQ{hZ{D41_N=X54kI#tbeUf1C z@ucUvVZ3Dr1QGsBjfFh7$Cm$<6c=kZPckz&V&?MCmhlT8#~t%DH&Az~>-IZ?ufLCfH~Hf>C- zuK@#EQb}C#Fc=a>pR&zLH89imdggFp_)L-L&yS%J(%Ide4jWu23ITVqnks~>-QzJw z54>tXi|BsZ%YJg-1|6+UU3M=Jm z(QY?d=BfYv-l}hB)j+>VEg(Sc8xyXp?hQWLD3H9AtQ^J#%*;l$q;3tX??eKMH{n5G zacEun$FExfuxa1{l;3X%BE1|%pQ?c0)sRO6A%6wTY4CT|@ZTz=kt=+U?%#2bG0M!m z;Z^5FXqCWAYxEIIlM>BrF}4`Hn`H1ROZG{Ze=K?NbaLWN5&`mJ0_~bVRW;YIv?1e z_YC_e+7NTa*4lMlo1dgyt;$B+V#qQ7VCU;J*Jjf?c*c;_q!;mipR4fY6)^3rdgqsK z91-w)fn6a@f&ym3LxFWY zz=;5-9*7_U6VZkN8v;=mRxL+(;(3bi-`oJekiBXEM63^<>nGM_?A6&~XuYlynIp%Z z;Q;XN;trDP%UJ+KLOKA8p}XWvZf!9X6Q-5|rU*9(0nz97V zl;+cjWwV{L&+jj7w(+^6uEjp(yiWdyUPidqc$wh^GX-nEoDCB8S08P%?692lMTJaf z8jMv+JY0hH!&E1Fs`zb?&=bQC2OisOw6t!F5joq)7&GggR1$c& zWQT%{W%1v$P_fu)cf-pe+ZgBZ{JgGLb`Y|0!;~I~SD$US*IjSbRBp^`oNNmSrHV zi2WpdmFoZPyr~{0aJyC8y3z!UVZMyFvW*= zo0f`1=x!KoNveiX)<`|2$I$H7YYD1C+EhiLI|!>9;bfck91JO}WMUoRcG-pYb6`>r zmNU6!B;nthNb~ZN6+@3UYJ$Jb zv0GW783pt1#`o*k7M-SG)uFg~)$(SD1t@$zwNWE{4Y9Pa6s~ilNil+fNCZR=qt=jA z^ND4|pYZ%V&7}?NVST-Bc4v3{G?FQa%65sco{%*nHFazyk zJwxd(G^d?G`NYzEKMc9~xpS#ppdl%|LNcHsN7RJbtck_`*=ypw24i>l{BBw8+Z#}s zP2Y4o&Y;I2uF2g816+?3@Nt4TvGCe)X^bQ3|1G)Cd_VCc*uP5$HQxH9V&$K#{ZHmnKH-?iR&XaDftTdPfTUMK1{C?$QQ#%0iu zXhOD)eZ*#3tqP?wlTXs$S)-Tw)o4Rbm53l@9MURDRIz&far2$5;=_b2^)oTjcvr*7 z0*&NrCSUGi722hqdCfdN?9NH3edw9l&&}EhTxibMX-8~3QVLYUtV9`Stj`|Q)=iGz zAF$>(l8an~Tp*#eF+#ydqDFd0__~}sKh)z?&uadNqW0dMY710}1|#9jt=}IRyU25o z!U{dw()=iPiDaOHgnGWTu2Md+b9Cs@{i*Hzz}I_d0ata2x}Ey&y9qz0zIZZFm<5$V zGmlP&dLXY%sAEkC9XA1_hMi+vrMQvW^WGX?A4OdW4C$ACTv#udEDxGFKWv=95Yi{m zqrC2P{$cfAWGGkr@nMJy6HplVk0^%w9=Ss4H@UitKU?d9tXX(_=sV$U5fD&#Gw})1 zRoWy~t0~+-L!&UF5p9NUEJHK`g&+dx5Bq!~raHkGA)nIUz_2Bda<|0^zS zma@9UB?*V|>e zWs&OE%lqwJjMA)p#v!zKyg7rf{XFyK=!3WQG40dOWC>tZ{hg;#U+tv;l?dx@0XXcb zy2Cm@KsL!~j>kmePob9*d$soV8PlBfUMA`#NFKfWU`=U0Qa5q^<8`c5qQcfcZ#|aQ zElo(fS^5$LqX7Yl#Ki6nS3yg?YjmKwvT9@S*G3ESxlE1jPGjZj{6NphK=V^gKb^ln zh_9=4tXg!@ViXuAl_s24fyyG9o`l_-+Ro=6%R%q7=UhEQ)jNK(XxBkitq`t+;gRCw ziMT`+Vj_E=6e`p<&rE;z_ru^J7$N(t z_dACqhP5P+5!80UPquuHWP` z^d}RE)<;1qomb=$@pT%i>14{QuU{C_XU7oBp65yXY~wA50kE}6?j0J~w|`N0s8l;|QfF2nuGa2h+%pOw z(XxJQD!zxM8@A%DzF6fit{b~xSxO=hA3Zd6IW%WvQ|4@9+_q6=qh|RPL2?%pxFWtg z%=rWQBdYhtYh6?y7=3=gdPt@Rko*DlDQjKXVqcX;lnTW|GkSpiJ=v> zhJ-Cma6SosoR6sDfEKG~G-r!>4rge6%_KT>7VeTcEKDv9!EJ86XC3D}>Yb z&uDdEe*R}#^e1ShP>6ufJw}pL1&lGxIg}$P%@6d@I7dQ7;65EekG1@~X% zU=lfc2t6tlu~_@q9IEu=cmfUr-M2sW8?-Ch?*Pe9V(ZVLZLgF*Mp<}%D7ATsCZI4PPUF>$@CnNM`vBomx8Q2JN1Q`RUh z=h369n*G*!o!#E}Z93;AXfCF;eZ(}}X~A*fw-XX7mwpYFCcuLt8XYW-_r%s59CTF6 zQpmzo>~(6_m2&ZUd`mK+31bo+F2kFzJra9waZ-C>uBqpb!k{JQ56YJ#Mz#h&^NE1P zP_GbbqfRl}hoZy6f(m5o(}c5&cG2CPCT+44n>BA*7f-aI)og{dt1hDlw-0+bzu4#3 z`CzHAs*5?E><7Adbd>H3_?HH~Q!V3NfZ}`#naKpw#0ym|k8Ddpj?$&8u6C20^MCf_ zM@D~A^SPdqM34THg(Mgas@?1PY9NeWbeWp0I6uDx{_32h0Eh=fVB~X`Y@WvViG; zC)$9-FTr#mTmtA;(4O_^-cbr`IAbnX0pj*`BC(!zK*%Gsw9M7=AgC35HBPW*5X{YzU5IDAI-93vLGH2LQr;PPyrvfg~%MjP487 z%voO;9jH@Sa?{zg&Kc8eASf9GzJMKX;K5^DsEt)isX!O>=(Gn1(srVO<_C z5=7rF8+sU}M+YUPN)sKhTbHfVtUhU+WSj5;FN`_w-G9FOS6-zW zskgtEhF@-2ta*9m4x==x^xB>RyOsR?B<|ftGcul=+SC2=(;Dr7yfg#ldrS3OY}<2c zZXc9VkJz2n80f2UYyJ6*G@Cp!Ls{B5L25!*Qw7@*Zml9#)#IdU@tQRg;sS7!l0|q) zGH0JR0I2g?1HH6>T0+{*+w1ur)0SzZKo4&_cQCah94zMj9$RX=Jk{zsF~-dWtYQ1<>DbNr(1S1i7G?}RJj452zf*= z$w<~Y#u*Z6FSRJ2>}sP--}V2txG!VBRo?G@# zAPlM~O^o5ygZP!dE@vb=874@T=10^+gZr#Yuz(F4EY`* zEDj8x9^5y0oUC1wOn0l!mpM)>O|WW}yllMzV`!t*7Btj%H#6a_RKz1g>*7|7u(MWk6P*-HWEakvC0a%QLL zQ~kU6ubW8>>%6Wltw*UZBn-dUPpL>Y%Iw-HM|!e1qrv6{lgKR1kF~RNbb7ZXQS%?t z4pz?^4w6Y~63`-t*5pds#A*Ht*fQlby@%N1K z7S7KWR%kQFt&$0Vj)l{WxzC=8af47}Gav(i(y!{Gc0%tL_lm8rc3mCsZfwpUK393- z!i;)K-sC{bkSU>|g;@d7=hSitbE=l}78pDITl^U)w1_<-5-TA*FgcK-l*0yKlLs#> zo)Sn751TY)~!>cv?*3RXlDZzBNrL-G*DP_rAFd{yJ3ww@-U@$VaA1qCir4<=D3cv+FLGpBZQ8w%1UpQI)t?_q8nqt6ktV5Wi7Z3`UnnBsmf-Z3oU71}M z9n33xhr7c|6&Zd5RR-`v=&^w|8Bh(t2v>OdlSSRHBIsuYnUhwZ?Lcp?Pm0tN>ppcu zbg8m$pHir?${gFIll>5FlxI;u=*f$TO(B;NnYcvt4~1b(^a(v3am1G0VG)x9)yFUN zdX`lv0>pR-IdytMOH^gsbytJ#IIlk|3M!-oOYhv5OCpg{0pK(XCWBeSK88spI6}lo z>u&SwG^Z4u1S|1xTY0LRUY3YA)K*%rjKyNr|HJ%rwnX~A24YbJ{v3}$lq{nHl>B4! zp6pS}jDLNk7jLTfD}1FSU(4*zl)F=Md&gZjfa^wmdI9HitzDDW>h9$(D;RIgk2OE# zB3LduoauD;7uP`T_pI^XWiUavUg#toPjJ!*%9pKOC?s^b^!8Yn7DY45z?sFcmzoUF zRBS!Q(BTN|M(ZPWOpX+y&R^KaUG);_ta*A>p`fxQQ@0QFp@?N(8hB|ETaD*F`;p!~ zOw?btt}5WO2XLFKtx*6#9&lX-2o$}Vlz5ojtP3~ z)qFTV0|79`-)M7b1xtO3YF78`xM+~eQ5OONKs}JR$TEk&D>k~w$l*J0wLKdWIE`Vb7DS!gwku%tOZU6ws@5QfGI-8zEjt0Tn(x~n4sgl0QJCz0t9Iv<$=fV zD@dwVdA}RC5e59geYN;q1o6;G6h=@|u(RpBh(nou4vHY=OueDlC5_Vh;uu5<&&yd- z&JVK^H3FE9o$$c-946g+bhcb0yN$(+GmWv)`k28-==>4D2Ucy=n~I8Zg7XDretv0! z4c?LvGo|lhPzR(K92IDp$cm^SmhhNe;W|bmiqB_je5xNAs|cj^_KBlTxMiapNWdAL zWf1vNiPAbRAQ3xsvkThiXCbX~{GNE?tdQxSQa5Of$F~LA9d6M7*Q2(Z488Jg!F}{; zTcC%f3IU!qjm2ptX(bxGhtMu#iOrfDuvo~mor-aj!oNIkWp(KF5$c5H$8*H%a@h=D zOzL<0?WvTHkGwYbwij)&-tv^oE$aO>@p#jtK+FE%p~Dgc^U{P`8qIlMav^+m@THo4 zfRUW)*rlx-NxpL9r6o2*hU`*bgltD`kC7&p^l8(woy95kWpju_;9TsQE)7b>J~1y` zt1CAZFJT=cd8N-!Zh50hpfQaP{558b@3gO&ENwnHe}}=0BFd4qCT>gS2i_SMvSv%` z!+84N-}`=^@f;BbGsf}>(~l~25(D?{kIIn~nf0zo)GY3c3^eiECu*roywjc&^(dD$ zom-dIqi#xLcp&UaQIFMYt-xEPd`Na^5E9K&?yKSVEMD@R=mUUBVT$4!S07%?c=2iN z-c5a)R1_;^q?>$MT&y`uc~>~o?K#(7ww^7J-ZgVB|CMD7Kp>y57QnAFcoWUp)P>XJ z3P7k2h!}f}!d>jY-|=At3bQ?>?8$|eftGOcdde}w8J{8HCgeFly0g-?pJgJQUggG9DAy7+?r+4<}zl)fj%uZn^ zE9LZYB0;?X%!Yx5DZRLxQ&tJEkaq%S~u z{OPU{&KTYjAObYU9THX}sRJTDNZx#739NTY#fcgYBrM6y553lZ2q2`iwgR9%l{$bd zKoFRf>Ckh79?#*dz6KOBG}emcK=Pf)SxI>LErNnV|cWD|+}kj`dvA6e|0M!Gh%^#1AeG1IR*H zOM!rod$Iyn(!lnhB1JASZr6tSmemF#7@{vycaMXpFmY*w#D)VHWw|bMRNcFHm z0>Cx5O()E!|N0SSO-G&B@wU)ON(4xVzWdO=p z2ve}A#2^3>OsE@Aq)C(HS& z-S6U>=a4E@7XSWio4(iujBn7lw!@8k>TN*7|E3nRRUdEY1h8;V-9Oi5XE?o(C|7BLEvF7?{$_8C(bLzGP$usz zlGx-f`hYQ*CN6Fwa)Zf)ozU{*v7?rxyK*P8Tr_SkYA2g$z(5G5>cTlY&USWrkR_BW zr=2eLlNKzsDNPev8^{}`PJ~0?L46x0y)kVVZ?R{~SrP_UJY>UvjBhz?VF{>juWw3^ zjhT@v%<0CYA`eV#w5U3GE^8Y>S-=A;%;%Z0U&%8#?6{c&%6;g2L7zI4o^h$)`8gM> zl#&MU1cfI8CTZ%vgp$Znorj`FEi6%+H#6iU$NmA4c=F_ zG>f?4Rr%=hrGF^XarBR0x=-q!H2#*2moZ;{mE?at#={!(J}T2>V2O?;?274xVBm$? z(ADL1S>!$|I5TAMG2YBa+0K|A>35uz(|I1R1rYHGq_Q_Obu@EAvkGIqck|5@#p;Hn zhj$yNc1mF4m$~x)d{K6O?d!Mu$m19H8-M`SMg> zi^tjrXly7A{IH|``e79$b>56aH@$t+H?k-5nHdB!>J~Q#5;VKG7aJ0}I56#O7B!q# zFyxH?VIR40EJe9ZNuHrdK9EZqxtZqeM8^r4EBh&U>~Qbgkf~m`eMAuXQq=t)fq4OY z>x`r1-cRf}E2EZU|IGE*n=UND!Xb@U}4v zyr+dtGu#-Llm713qb-lG2ON}}-smHvAaNr9@Wh15#$(C1cNLs!{UULEDzw*rFSc#Z z)}E(%t>0=~?SDCq5pzFbdnfkfd_Fv3a+=D0|NXMc;a~ElA$NP*^e_GD4A8JHxNBr_ zP3r@mTm1w3T5C3UodMp|{K3ad>1q#VoOJS?AN;_XX>K5IzuwkvJNZ|^(Yo5N-%l0O zj(z@lh2!^7%BS4#a!5tU3#YQWy=7&GO3ZTIW|WohmzLgOp%rXn{8olDi`f4p#OIa$ zb2a1f^$|a+?V?)~x1?B}^(?*@nerbqW&Y3C;eT6@{_9KWbd5L_tivwmBY}IzIZyAP z5n)m^=Dd$g(D740_K^FWuDF0YeF`)>G^Z)*%538zP~Q4jYEjM*-hB0ze@H{oQDk|b z>!CLHhrP0nr{skLm6ENP=9&fT^FRbRIwx>mxZ7H*4gi>vlNK6&HCXZ$x?as2u@W`; z4KUjBOFL(WpNg-6U-(}Ej$})Iml<-TuwENj@!eOWcMD{9J>pR`M<4G6}4Vu+)#`;J{R! zS(Fjp#I|{h4G131y^?s7#HEhE*0{ZB5;(cMVq`iacS8NlSL?N=vFQe=L1!EQE6jir z*&mB5y$l^A^+;b>)W%wrNJ_-xZ)257&|LQ|Q|yKk>0zUtQK<*F$B)HjR%_*1&n z;q#>%t85;&xaNdxeMar-kxLI+OJhtcyfDUiOJyA9Aa0vD3Gs&WM3$}o4z z2iqS@R=dmOLR>5s2UgjO0M!Df^=-jN=Vt3Dn-{DdG|y5blvmc+$T?y;05y{%bUzC- zc!05N!Rz{3e*81lUFkzvHfrI2POj;|<4xn46NmQXl4cF9UAi1zFBL4QW6H1_C%(>e z6YWjK2V8i~H&TYyM|Mg|mGc`&_b{Nk;nmBM??(blhgR0M$)*W!qQ}!Oc5c4&^Pr?j zrc-)aId1vPqnTa^W{X`tvrIx^t?LbbG_+$t}CH zkGZ|jc%r9oiP~qX7_1(*)gs<5-9JtZob9lyHcoGy?$da3#8%azbuA#9zQq`HExrM% zqR-!{fAzJ9|0DRkg6)q@Cv|=v)ePUZuKI|Psa`*+_V$}Mrvt;IRfrvjZ?7ehNNCHi zdbv)lbgCiCq0PvZuJoG3lL^)dIsu}1&CU^l*n4^&KD#2RLZ@(;7Cj5t0TAJwd zICfH@O+_-&@xA7RCbYP|S#a}LlS9xxW(UMtP2cjY*th##myU^7hn{x4%6 zY(JSq%2PF58bYvP9nk8_DWbAmhr`}~4mn)x&{vzkes7bVhbA`G&Q^2XTAxy>tg9MR zP8v@(i}$kJ$+r#U+Z%=ezz3!Vbb$$tw$0SX_PHAHj6;lY^^YW+sB7^^10~b=6bB}O zm2WX+-RG7V9~gC)jQzDwmP8`&d^zPT z3rpW~Oib9l_pc+fFwxvXi&zGD4H}N|E%L9Tlh%$K=8I4o)0C^4%*;Biu&%W%jlhKg zMF8j`V2T4|fJXK(Gn^%91O`@pqG`e>+^_+xxDj@IQ=gD)S#{9RGyvT@56O3~nbTc` zR`J$+I&o%g)@knUJzI!tEAEF^Pkr01Xpj{c zNWF^PoL!w?QCRkhdVhc79M!+r$~xwR^@E4fbLKrq?yrBeN1-O9OC(xOM}{9pvS|8g z1D`5JXO@$Zq)q<8)Yp2?i$J^9Ou4$=t#d*Uu#$xq`-?thTcm?KZsS7rpg~@i+jizk-SKs=K1bNPbd7)}&xoqP+qJ z!eU!YuOu-$OVD9&yTPB!%ia4>%azdjjy>zUpql5x)vFM{W@=p7_%(y%8`J>ZqgQ0JuuOdU( z+o>~+`f1ZVsX}tjvFk<_5h@bl{qk#jwT^;Bhwm!v4GkTqHV3K8z4);CndJ~(>A>fo z7|-ab&x|Z{1>n6_Gj=#Q zy^v>JzLzvZ&awX$l78j=|VZPZs_BMNrLns?(3x>UoX z9zK}-Bulb-Q;Q#~Ykze@y*K?&YR3fwtoDU{fBo{*ut`@YS|(0=mM9d{XqRPL3){nS5O|LL8&b`Q4QPu-9-^TF@;B&}-e z+Zwkr(rwKjOi}d`zODV<=dbqJge+60xM}WiAXe>n{Afnx{}>$qUtgPl`vdb|a0dSl z%rZ0k@5nskeg8kswlvl-5~qCrO>q3bBlGtBM=It2HQn+*E!TgUZu$4;#Au0_%@gyH zCpC=3DBj8c%;x<&L~PG~!vp`5&HGO@<^MCA_doJFW&R`3bp4S#uiU#sCr#v<*DYAi z^8<6-j$cmN-f_LIIQ2ruF^}*eW4xyaE^A;j`2s-uS{is=D6sJ$D^o@ zL;G%SN-n)(T5P?V=}=gOWnQdQKWbMr`0ajHNP&OM;@6~dG@VV|RzC)D5b-7SVB-|ar$^ZE4*BCV=8`7X%w z$Bwc}tAy9Oowwh{{Zr_?C2g_$!P=#RItR;sm;KI<#D7a)d)Kz&w_9UYp$|9NT`cu) z8mzM!8=3frL3wYaQfB2(O~;<}(<}0G5;!YK=P@p`zA_Vc4=c$>=x*LK`XG`o_u`M#`LVy+IGevU8(!||_KZ?6&LtOaYL*$YOHd=lgwCekG+b9n zq6c-Xqbt>gtlNK7hG9G&SRNZv5SMMgZ5F;5nS~r;y{7N*JN+eK!=)IVHNWy?$X#FNzx7-ONcCg zmTs%c5JRNF(2an#eD56!pv?I_AT^zkO` zfk#N;tMV$Ub6sq&G;Q)!#14Kab*q%kqs+pI0{NXvXU-mbnPva$A8pZFPg}i- z*F66^RnflX%h8xT^`X=UCBFTB-40{nr=Iv`I&c53x}IKMFuZUf(1J1&n;@_F{GCd0 zWRzt~`;?aQ+bbhkAr^&(U^ixHQdy9{&q*%`vM((1?zvFX=p?J%8(c#Djq(?5b~r%W zXg~7l{G8ObYRuU3)BCvJrGE>rr2SWo#J^GV|3pvzUC;iv=*fTK?f*sg<{r2IHGA{P zf1)R|nCm+K*RJO8TK?}Z{@=2D0O$a+J1ZXv-W#C6EUS?%K;j?~@Pe2CaNGbB1_%Tof$(`8!~>Li z006t0Lg!EbpvPU?$>X852I4zI5%CQ&K@|XJhX?86;17bJjN=P~iBg+g6u<)lE(L)_ zC_tDlE13`w^Z|;MSoRikmiEUE06G(ZE>tL9sj>>Rf(hcr0pJKgGXT)6h|>atm9ZL{ zF<5$K`Q*?624Jn)*+GLoFyO_q@p$}-{H0aYHHW(M;8wfPx@E%WR?%PBL)2M7O^P)t z`rL5RPr18)EBsTOH5e|IoUvF;%54vyM12S9+!5~EAe-xHPmlC(UUyJMdSp)ycrH7W z{$|^me~E>7Jl+CuaS#Cp6nF?s(C0bfSU(I|MFdzB0T3`zG0;f?1n|QF?g9V>!cjm0 zBGx=C5-VK)afJc283Moy5CDwU1HgjNzyCH09jZDogx13pu=?{em7s13I4tpcvN+-? zQl@J`;R9}0;lrs@9PU=}I`LM^_67qi0LV%?r%MPpE5Q|a`ZxJkuLKR<)0)e*e_v#o z#eJ+`7jXt#k|n)-9k+Y;`FgDF-Y;Eui+79{DN5#FYHhWEsz0lI4 zxF7s#%enmEP@{SkN!xfyU&febMYm2=8*3I7bL_gHtAFnI>rQ_@!pVsW)Qy(qA4zyN zias@%H+%1EiY@_ym#Bpk$}} z2A0Kxz|a*XAFyr{1sv(h7G7Pl60h0NX=k|R#BNN&!D?M)MU4#or6rVI1tWk(1V1Y%?Na5$e<=kb z!kNL$5!iXZN>EXypty}8sX+VNSU?inP6Qm6R#5cCiTO^Ckiji zN(-5Qf!6b^N2?wuz*8Fh%q#3?KC6b$C+#?p3op3;Ku?N3{Y@M3Im{dt2DRL2&j~AT zYbju=?Wrk;J~Y1N3g|5`9qz#)OaO#oLMD*{c+gug4hV4u12_bQ!$26A?Tjn~K9;?v z!zPH1>@9ovw2s zbSsLngoGUQMLcK**(SPNoPhKADwD+)6|{jgXeBJ$6!3v?nMeVkY(#*-IbS%#C9e$nZBOTy*d_n}1D)Mg>dKq#FxF)SRN;@c4YwlWb{6B9Z6 z!g`1uHvXiMNw{plWO78Hct}qt*G+K#Egwi{u!vQ;)+K+NTFF86V+q?$Yw`Gx0b9=h z%PwvPHOC3c|9*eNB5^64KB(+dGMr6(Y*Tf%y#ElM!PJ|2y6twcpJXAjPF7rGr`zwV zF;~2J&1+cw`aQ3$%Dz3ix>v)xs8?MO!I@i`O|n{|)fx<4+Y7I1OnlY#Gp50_0Db(j zvs{P0a^#L~a22-`e`TuVNqA0_;v)N0x9!9s*VQB(4R+-rHL>c!67#(fIKGPaGk?o&b-RFf&iH%xO#-D#0uLL}tI+0a#bk8Y_W%eI|)FUT_@$~|| z{HddALx!a8tZy%a@wn({{mp(cdoz^-BiF^hZx{g1ehYp6neqK=gEk#pd-|`Ge6384 z6-M1`(+0J?Pq+!}nbf;nxetNo5*R*)`RhK=F1D{*7f}B|vrF^G<|98pt!tJ0kf3j` zLM(2Rk<2Jwt}gmnBy2Jm9m$^gTe}yxRlf!0WDS1jn+9g=nIH8Mz7p z)cri4&g-HqSuY$|q>DYW4;NF>l=34R_x>w^(SME>82 z;*?j0FU$A|&ZjVj`I`0q7uwe+U=07}lKr3{1;X5J2Jt>rtI>v4YWRCx1BrBJ+6I5X zIe3e^PTJa|X_DPs z@7=w(?`J-Wp3XBe?U#FW?^DOAtm1%Z8ROlT<8)5iMPXyV_tnZs-YQGPC304Mi=qK1 z0>)%;TAq*CjrY{gzS-zJr|qIHVo4iV^niM1&)ePmXh5&SSRrniuk&KLV9(I^z?dr}XJPH%P0j)e zbXrv7VXjPN<4^kUAzA0d7i-9KFEXhIM{_haHzg@$3PH^WcoZIO2H-@OMuiK4KtKk3 z`vE}W|9ir~a)`eB{$=u-r*Fv#6c5m%y z#Em_4%1T%Bf1R8*qEq>hlAs)r^EUo&SgBNAhdXbxe1aV<_`N!{(0$E7S7<@WY zIGtyIh+?7oV7Ft5pk#hTAEVXbcDM*S3a`&STp9F7hto^Om$YvDhj&IY#;7wq+f}1ltP`UsQg@2z})ul>%&B z6NJKmA5ceFwu0tj!@y5>4w#8uivMv4O37XY2LBgE0S`taVw)hoEV!_uwh&r5h!*&n z6E-gse}-jfEIA+`MzRcpFySH-y1X@{Dd}SR_;|_Fi}&1!E~q~PiTEIu|09mD4EQ<& zK48tWhEK;fHj9vmA+UH>=)h}cQwn{9hC*nGGW%A8D-l)kGJVkWGBm1s?Yx*qlWTMSR)okM>o(jv6{A~qhQi$Bv%9>)CF z25W!d%dAG=sEWq<-vtwgBPE!cI<3Ucqi7Fz6I14N&=0y=^Zu_bw_QGEZ^Io3sMs5} ztPv0)(*z5Bz6S$e%+XF1?%ee$X>z-V;1Fe@>p#XhZSIlR4 zKH7u9^YB5(Qf%8leOkG9=`4*jWUFJF`6kg;&$0LqrQOQb-6S_(B_|I}_0LSwS-dx% z9gxOCEap#ERqJ4LwtHC-o!0_Sp_h06oSo-BPTvr2V%iRMJN50#{l`J$vz%LsqysnJ zwBN`JCu*#?x2n0W*NmewSzD~X+&-pZOtMZ?a!jG+4{=MbF8bEtc;=3zynP3p9^G&% z5t=qedhWRGWR^!J-~2s`6F&?S`?G z=jo>ac@LgB?N7OW>WVp!hD|&7Pv*}!=ftJC26P)70+2+2bg){Jwf~kuLQqo&zy!+U z$1>&_vS*{M!dSUy9*6;|8wD1n1OzO0hgKK$Tk%06y4M@gf=VVvTL-Qa`8&d4(NqR3 zSq|4mRT&^mj&+d>^XdY?Lr1**a>27k&e_)MaV`@8brGR1WAcGN2?_uo-`qL_Mr)0b zlVFE(6sKA}`Dd6^G72vOwkS-zPu|r7bRJs=Kr44)If?*)KnQrP{t##$iCX}&SQv2u zpp$dm;giu*VPE)F-Uk=}!Bej;ts8sBUaGv6d`ND!mJzA&ph8O()v6i*utT}fM}oq0 zKO!I?>qARH0T3-BiVfXpT&o`3ze?w84*@FWbjnstiRt z5_hJji+3)SujwvJs0`YawaDoo%Q9?S^X?u(ScV;8U)dr|2(@sD7)+5wmovx}ZEY*w zFh4-XCS>kpLcxXPA}0C4rhY+O#r>p;ekWx?ZbSruwQ-}#FGKe$KBB5NXZNf9Bg8>n zWKdUJ$s}3lrD*KM9sGaVw-#?=X=#ZI&43Ut#0%j^*B%yCdRRn1cI`Kfay9jMR4i_c ziRXgsJp-nG1fw(MNuQ|aN=&q)YP=?!5g>($KSgbYZiU<&ZJe1n^k|jdPpO4`rud+ zcazJ18;OnB>61t9|LMFMxG|l+&Nq7y_%gzS>Z8jF zpA(N^AE-F4}U*sP$)jVhR z;MeXg3KmD76n(5xH#^p%(d<5c@j)dCqp!hESK7yn&M`+E-|p(j%wFm@CYB(94|M>1^cDg5~&$bIQXVouTnreDL@mv`D z`I1P?;t)g`27$*Xs%9%5SRYL4K2OE8Cj&57#Bj;H9WnH4TLnFi*Sr+{ zmECo&=v_9uUgw)?GhJ{{T>?>nqa`!Gj0Yv;#0*!7(=q^#Maq4<^|jk%3MmicxsMrr z-?8buD3T`=-Qu8tFA_=tCzVte*FCmcDR1=_y@>l6%hA2+mLsbb{l0B}psr*;XFwiv zc1b_~DLnUnbCU&9(VVAq-Q{YENE8NqSRw6C``(2IacZUblTVuFrD13;0pSq7q%-_o zfY9jnkJetm0fZh0k%UhFxJpVH(np3`8C)rg;1{(N;9!KpgdRshrG&p6jz}R2fKNRt zLl6$K0{!Fwu-FU(z>g=uh&e10(UI6Y6d*GNC{7u*$^-;N>oy7lFYCgi!$knF7yE}0 z=-Eeg4g-|{SY{*vz`N5(2y!4mfC2oiUvv~Lh=|$A1MWQjPadip-^n=9ZsjH1!CHhj z!N}@d!Z$$J3m+9#R~sP-EGpvbwJ-unmVT!d0(p*um)ER>&XuYU5yY0x$xVPIlFS3p z0=NED#z&K+&vFdAq^@plQ$Sx4|zm#_ofX zh6ZRB;xwKDz64OinY|Ma^+kVzbno#vstrJ~MbzMzOfKD5$>PL!{wV|euhYFkQz!F8A!!<0{{@paV zCyWmH`f`wC(RDM?8;C`p#0U1;2oyD}J^Q?t`QnIzj&8i@*~DjKQ3jrOLdj;Sx?xpz|3MFz8eW3jBKZWDjn=wt%a z=jhQD2!Kw^7COiAsNl^6X(hF5gxDxeF;KO zVV|oB?&yadmSLN5cSgxOqlDR8n+5w0I590$(^5LzvV}sN;I$hytu-sgG~yjf)l1`9+-v2|7?nMMRov`3(9Cb>AIjSkSJ?j=I@J_bMI zP5H)x>$Q5sXIjapWh3SOpyZ<9Wndvz8fpPjB=W5qKpma{K=|v{)spRVq}N`!aXpgd zbmKLPAKlp61M`%~CWWOr*=j&2nH%NLK>ZuNxk6b$Jy^RKsXR^Lhe-m!t3>T4&_scj zDNwI$c^_e6qRw(V0v*bO00=0mo`IeNp{owKo5-Ejg#d_!>t##b_KyhHt~NGOKeycK zO@SMJh9?k;M4e_c5GQ`!Z^o4XER!;nE+ZsCNHEQK8B<=y z3t>o5mn*GEO=e{QjEY~3160hJ7}}dzZV#(kZlTR7_`-l;xmxO;U~tjRB(F|p;| z|L3{4F3V{v>VO+4s4M`;WIJL+sj26wZrGw0jIKx4sBnxcF8$fxvF}BQBL08mF)OC~ z4!F=~xPiqsVKl8oC0sQ1!0$x4b-(jF_CMcbn!>MXT{9u4(dDI6KAZtMkDdD5a%lF9 zsbuG#o;8=cFbfsU_?y?>4X(}j;l9nL%Q3kDtp8d*BY7!ZsnfSLp}J3Yq&az+UR!wo zofroH-4@B-wgmu*)NHV9W^lluIojll7JCn!Xi?bzu?wd}ePgiX{zNDB*v)ytlEXXmvVXEBya>v*=j9#8!KhCKM!)_MB^;0lzqU7pS zv#)6K;!NWtm6XbQs8`_k*?mIuiQZF1%{3b7v!+^`ui5GcDH$&^Rm?R=Zc2`cX z1(q-GlO50m!k-8PNh|CZU0}In9k3R>av=Q6>tt;HaZWRekHnNoL*qrVUooKfx4tv# z&j6qmT7rJ1gE+1XG=tkidk{tgUy$20Tg86X*#>}pAy|p_fe5_1kVRgzR{!TSvG~2l z0>>bOqz~_IohA9u$?aRxQ={|zC<9nfoFShd27uEA0&ciSrGs-jdAsK_eoTxRV)G7m=5}Z71WRO5~6)o|h8d&hng0?j~8^d|-tC z1DoV&4F|{8IG6K~?{E{C84x?)T|)OYxY2*)kCv8~1*Wil2?0zpRX@BtS3o z<@D%n+r?G`AR*ZM?*d< zuE}@Z{4+KEcOUVB7%~3?0hvn(a<#8P3V@l*>VNA&yO&(MT@KE+t+cxI?8vQ{PKR@f z?&EY?%;9}Ls}>g+g0P;ehx2cKI8bg|b(G!jM;TM3Ukva7V1Be%F=kIcyN|K3x~JFT z0BQ81L!t4_Tew>$&EEPje}3gox9v2l5tRDv*bxmfb)1dIu=i@c;&8dY8fL$y^{gy7 z=xeHc`lWbkO@iftTMDjY%GOL(MGX?hgsN+*d~*Q5HaUknwqPwXh}7`=+PYJ zwewAzvdNCSz%hcnE0_}|MTkW;X9qoR0S^orGnM{o} ziL*{UO2p`^I^mUqHAomiEN}W6}CN- zOjX4{iI9_x9v1r1rBVqQ&^Mx8Y6k>bu_wIfYBpQv#o`=#MOi+rY-UbV{nA^*6m1Rp ztT8i!Ov{Ognf0w}XPwb>AmySYA~pTa?Kw}&^bZ~HDZSyHdm?kkE-Ns!{da=F%5))$ z3S2UqdK_YQc4P)cvrRMOjY)w|y|63M=jPCVf#<2U{t!9`hf44XFqlcdd?)K$b+6@+ znbFS9^zFu-eZ~bxoIEY{?r9rl@DEqR`^^77*(X~fFe+56T$|fp^c_PRz|W4n+j}YV zf!`?*3uyqWBzz$06|qnR0+}ETM*SdExK;sB_$&Vwf+Z`r8iLVMfF;c6apZt@mQRWB zY?u_W;PKJ15O`h={KWvEd>{qjmJv_~fDfb^jju5f5-S0?QCNh&Yoq{LgWS$C1_MSH z1BDTQrojl*E9ESQ!@U*q%x)p*VgM1RDN;swz91YR0sgdAUm{wn5dV0M`bU49C{<8o*EBkDP*sbsYGzW+1%-UsUo-MyUB#AEvAQ1v+7)U9X zJ#*JG{^re`c=F4(*~-_&kYF7z%-EG~eDO{ceWC zMF1oq2BI)%&n|MgfL5#XhT>-j?q=Q|3#+O+O|~~=s2R=`igSK;G!5H~*`2jj{!g*C zrkTcnHNMRBakS++!ylGgTjEC#IN#4CGsLAdjnvdic@q%p3vGa9HFzgP5kE#J(-N^s z_2*NEe$$kinnv&LK%XTcyueXTK>r-u)zmRHbHGIL|L~0Rk2_Uo+>AhsOVFP{03DKR z;RGN732^Vu)lBlt3{SuqCYT@BUvH{KGrjhwBE?x@hpA3WL6FkGvB!9& zc&dJcn(UOo8Is=L`@-zmG0Q`NiOM-aQ(kz?+#4hhW)r{ zZv|tQ?oEvQ#QeLzRasjvGgo0}=sY@?GQ)UvC#s_{3u1;d>Guy_*^&Q}BlN04`d#W% ziPqR6CYej-zH(DWrXSDkEZBONYoR?g^hhoC+OZzT#5;LJ#cr?hR}JQ4XZU!)J*Q~; z{nph=vAU#9+L0j$$%-+BruW{SzuFK_AwhI82dn}V0LGI1YbJ=2skdR5Ydh4QtdFU4 zU5I%Uekm{Sm{-({eK(1EgbncHr<8pNr)5h4s-)Opn19FWP+s)enUqRUKlUO2;lAxs z2!QEhC@csA^?;KplY+@{Brc{7IGQh7_H18Q)0}_R&$97nA=qekoB{ZYa^@94mg}uR zQJ5m&bNEOC%MJ8F{A(BGFa2^H3_x2XJZz*62!eiWPN2Gn7ZjgmH6nAOg4v01|2d=x&xjpt-XP{wIZ=o9YVv6LMz0#XwU$#!CbW`hz>7P5|envV^d* zF@}Wbq%3QCUR@wk(Yl!6@R#G3VgN*&A%GwNgfs#!f9Ohd?W-%$tT(8N5%wApz-KG` zYR=F%!1ungFl)s+*7f~)=DjLbZMUb}I{DbYEqN~w3e!z2tESLIIp)&4ns zm3!hsP3@GTAY)^>Q3XfB9R#ykT%gAGS0vW>D!D0ir)HR%aWpkGRlfa~4|MtyQ^_2E zcwNe1yS;~ij4MNH0BC0+nKeT6>60z8QnJ3LpNEh8(^KAxx1F{(1U$LFi^?`X5vYYN zLR}N`XBMt5hqceHvpLxp_BA=-RtPO8Ms|ub_O$Ti>oA@TtMczt$?aUsfg9>B1zk#A zy4I<#^SCWa-3P865CI@|&ACyspLxl|{K;FzL}gkMJ)Dhq5d^A#?bA9y)(N_i^5nw} zC6gA935Dy&uqB%w>V3OOWvYohO{jB2jUE;&p51Ai-R>Hv9?mkp5uIq8p*KbyA4lx^ z*#uNLa>GG%C3h+lH(@UP`=3uUyU%nehGeRk>L`77|1}tCnrO1O-z&9RMT3;`O@nwg zStD8tzgkVkxro>LUtXyBk-)JM;a3mm`%MbN`IVQRtyXfv&h&=S60kW+T1vM4rRBxt zGqik3$S`^3p0JmYb@xg^p?ZVYh%+RM|F-}mvwQ5hV=I>SQtg$6+GI*ZMU3a?L$8Uw2K!WWo?hK!yXgD3BVg>nYL7$MxvG&ol z=G^Lvg7R0kn-&F;qEkFXDultz8E|&uk&Z<4V(IVh$>PoiE5p_E(MR3AyxcrHT&YXX zL^Jk}y!@SaD_MZZnr@a1f#O+9VSwW!BSWx1)GuesL_Q3T2yl1=!fAq+kHyAiKP4~v zQQ)Xq?i-aT)vZ0aFfL@F$>T{Cpn=bkJ?D-#;pyn@ zW8EtsR(uqK0iLsu5iXs!zKU&{Nluy&TVk!R`08x9a(X(#S7$v-fZ;SYGLy~*rg)AO zF;z^8h<_-^n`g7s)J&KskwT!H9?#_l7VZdtUT>Kwr_>*vGMhmpfftK9n#xqHRQ{wK z`ec1GOJPU1%M zGOK*frN<+26^en=vtKWhH?vO*7uK)XvAq^yAlal5j4N?#Y#b$yP$pZI(t2l63dSbl z?+Z`9KW*J=lx0+*-*vh1XnxZ3H3xs`VW}#^$1)2p7ZNe!0*v9z2m`wsQVTwPt_*`~ zSf%ie`pNbT$>y5H`biBEb$r`RH50178e7TP4m&e|r7~m4WCVcCHW#1uD20Do__pTB zKFa70RO=Kw-FFc=iMV8V#66xPg*C05GA3%IJXE2siQW5Ut!avKo{9p_=h3}r4U(HO zEs=o7=whkN(X@;~ixa!J7AiJ>J+AgNin1Jg%euW9*VQRA4ZadSvX2>~ z?kTK1XgC5yudhyI#npFwI6M$Iouh^s6*9b}-W)>zsaWAa_~)1qdIZU-XV+-@?RQ7s zHIf=T+;HPT1N~!8X7P&CvtH080cB$RwS2anHrel zB9UM!wNw3D9YGMr$>j~fN{@wMa+^CacM*dX2o0c=!{S-4>@SEQ4FTo*NcGVGWUr2I zLQ@w0au)$%OwYxdFhTsPF6 z3+W*e(jI(h>|wx0zeE?t_j6;vZQ)b^5Jjhp8>F<_y6F57DjVa^RdrosH<7W=(&Wmi zSfhFW@MAggQc5k6$tBaHHHg+ZBrLT%Yy7|KUsAyckMg4qpqEd{USHLEhFq-HS5z)m zF_vT3P5KbIEcomgF=?%eRV!X8MDJRKsj2B+>!t_sXP7K*9s`XOmWYE(g7@b&ZBkv{!z* zd(q_mcDu6ZfMKKTiKnLG=+(65w1(!X7Pq3m-l#77F)eY%Eq^%W<-|Q+c-8+vzwG_B z%h<`(lt`0OTZZs3pBxug)Y0=n`N`9))l^+<;W-6==NfnBnbI=NV~3ItkcPIJzPfIz zv-vN~CbtY{MJ>D{74tLEBf*GAnuAGmG`H8bTLULky~wmut_ik2xuA|t=Sr`ic)#p= z=t%!F>N=DAi+^pinNJSipXy=R@oTe6cUqf5i=t9W>tFVUiisW;8f;}cSDo)ZbTMba zp(Liq@!G_t3a{lCX}6S$zq{Ff`PP#Jg4=}kA-(qc7nsciRhtP{6RN5zW=@!XN?*{jC7S0}1*F)DZwc)p%?|pP)0y84chnCbf4C#dO>gq3Ljury6kSzpg19TMOgW$nWfJ>`rlNp9OonBKo zB8`8rX-QUXB$Xgs@?c{l!9T-fI3~Jrqt0vu>7+Jw8#3U#b^x2?VMTtzRLQeY*``TO zN)1xk3`4nbaS1tMSi%9KIbL%+OXlS@Tg-OtCSf0rDOH=AnnLd(<9nEaYJOdxGC5A%Y`yv`IboAr^`9jw zFXVgo?~4w;8-Q`U;GuEs@u@FlDpN71e1--C%4iyVZr6&>n=12?LxI!uJ$r0DjBk8B zQFM&{%zZ&SFd@Vu(5f}G-SN@Jv*-|Y3& z!$mehz=LrNIUDw=bjj2&jWjwx0WoZG(`@Z&$MJK ztfj;v7OxUD(IHtwOgP|V8S*pQVttAMRTTk5H^z!9H>!5Wo`v6NLYkGvuQ|U*&Sth;`>4iaMU%A4fP` z+gv*hWv-Y^N7~IKXsgOO6EOed{tYm-pa=-@5Ce?-9;p%uI)AICZz#VwRsNUk;i|kM-2oSY0eKv02I$$WHWg0 zoCyGhVQB~jh0y{S_(2;Y$nTv3HTz{8>C|JlS5QcZV6@=LZT6eLpSR-wiYg=sp8J;0 zY;8<$yf7}_KEP;5$O*1%k7i?Gz(d0jh|hV6Pp@w7XF~HUeleg1fM%Ic(irf$-~y`m z;X_xn^L29c6%LVFYngv{e4u^+aN~ap6iaD2t!s;zBwhR!E&FF9O6RG1ZI~9!y9?;& z~mKdTa|$DkkCFsivFXmza4&7u7b|j||{X&hDghjsG&A z{=BPNcV`(*+a#ytfB!EEFFx&q=F`h1Wn`{cdnw(uJ2hD&^{#hF^y7nP^dc_(v!AJP z$;vS`wR$gR=X#u4v5t01@VKeHStcP&8j|`k`igT4#^`E&=CauYkjlXFplOFegbV<9 zIaoRF$avjO5_zH5;>r291DY#u)*pGA9XpwTcauvdlz5fBcVi(k=3P z19z%^w3g?J%`DT5*P$w9Y(DV9m|{X%pO@ufQB04u+?x8Qh84+0l5pw!<*7HXF}g zqm(%w9B^?#zdeE$wt0N7Ti`hH4a3J{OEJ!5fAQMDElSUOFTd*EpQo>V-4X9f%OTUnT8sGMJJD(X#BO#x;o0MqxMMO* z=fQ0iy-56Php%;GE766o1|Dc_2#xjF#{JRM5Rbg7D+vqATyW@UdSJN6TbZHgTQuQM z0JR4LMCcVS-r9;fe7JPLhYj3Y(+h^PdSZGUJFBf+9c{jId({lEGiWZ0k&riVpukFM z#FovV*&g9lyf^y}EIVA=`UB6kP{VN&}RAm4y1j0oZg@g6A{rAF2 zJdH5it0xUW1>mc|L91IK?S@dQM$+HN#RE!0PS%UO?>>eYE(X>s^G#~3T`FH z0RTegK%f^!0Aq2<#~)e_hci;ZGkaC7bk%jxQV0W}Z+G$gm$3ja&B}lXI7s7uJOWGa zpk)UFIugnO5Db8lKi~-&Ur&t#fH+&HImR7#lmHGWDnzHc6jiq?@?kbWIbEHj#4`H# zeF7_4EmOU^JZ2)3Ap#=V%5A=oH?PhHU=RjSAK)P_z2IVIMxhwcXCTn|A7JG!;?5b> zNuy-DL%4(})@+KBbLIqXAIc8_+|fcH%9B@$$Xz?U#5BP_PFYB*wc zz}T2#{va!8gjO3m924;_g(=kgw<^r2s<|!JH$Z^t*jLG}EXX0*jLF$j5)P;9s%xUD z9|MONo_-a~Fk1XEd|D{-4-jY1@5OtyA_Fo6gS4}yU9@|zF2y9YDfswpT^Jc;S^T@;#^p-}{dD)x%AS-U*74IPFw@sILCR$hH+^*C$jr*; z;LW%{dsMnKmp*-di(Rkl`N^rXy6+F%77Z_YK+nMY^j+^Yy~x^oUm8C*Sx5S6d3jUj zT2oCWJ*7{&=1NIFyU#zy7Oc@YpXg~)ry;{TVFllemVT+Pvrp~1vOb^kgr$3x?ZRMC zC^2Nq9EL;&-k*!imu~B_RnoxOd)~gb`9s-v=B728T8RqQIhQw0J9(JrkVgx{f2KL5 z<5;Sf8ZS(JI56j_uR57uIhns?)2*G(l5Pt+_G_>pN1vpBsSCq2X<1wpSW02M-SX3w zd1(wi>Z&`Xw(ogK#AT;cy`lBn4uiis0 z3^&F*m{B}c8qE3S=B2NkW24aiM>2SB2KAjBsqwX3+&Fi{pfRzk!pSE925=uFgPWhq zHL$S?9irB4ORnYUvsoL;@#~Xg&kW65vb_ZTw7+xG10TPC|i6Rnl0B}PHFa>a?jMmcW^j}Pf14#%h(4eiIyfgCA z&omZTUW;iGEnB6aa5g`ffLIYkKx_m64Nf`rH~Pj%Xq&) z|4Zq&6&}9upf+5pvHz7?w^fB{yDS@+ zhq`dU7|3=3VDMrC0Bm+OyV0}dDlKolahei*zrsJ=Kv`)zaG>}c9LHsZ}CVKIZc;wQQ@46B0r$6&ue2^nBnos?`Ya)95LkG3j#mtS9Rw7j(cl-}dCVRx#2d~t2AzWLY! z??BEC^S?tK5XQRK?>={R&~k=-Xa!A8-V0k7n-jfGA1 z#p`)0nHQYa<}k@Jch}AK22s%v!pq{?X&NB~m-LP~O7F`M~H$A+&5HXb1 zyvSyA&_|14<3~oFKv8@1((c6rzTcCSQvP9MCBgaV*qiA7Ry}ZL4XoXja%(KIVCr#u7QoV54-)k zsJgCt^QRrFmrR{Yt{U8lOlyqvG|4hp|L_>LL5+D;dYcgwpcN$mEAjIiJev;Jf8F1I z!e--UT+X^XpLbtg7j*qtX{pmmv4Q;ndl#! zRMApO^|L*2{-}~Orn@qSr@rX9QA_=0%hj!zR0eR3L6zo5~pNKO34o zGG{Vcn_o7=Dj)4@Sa1l9@fzm=NVsAR%gK1Cqak~e1vWd!FZ=a3W;-<=){3=W4j+9s zGP);Mj0@#4sApdcGl&3Juc+}=jE^&$qb9X z>&L=YK8Y|h3L61ZJj4+HXaM63ewtVU{8RE$KnWf z!DIC395O8tuc)(GH9np=YXI>9p{_>M_*{lY#PSg!gFqubR(OgDh)N+r)oCt0jVO&yegXiG zG|fkAO^CPvP@;46i@Ixi;g=)t472X8)PcIUFj#4Q!}BFZ)i>`XmvcjC4@mN;T#fFG z29b325CN3}Ht?FbVigz5#$&)7lg!dIN~nJDo&TwSksB}^dnE!5+OWE@Dn7c;k*KI- zog?Q){(LVL1~1kW^~wm10PrfZ@bG}E-U%DA)tQ|E`&=$G)goLdDWIFUw#F>d)YNWH z*58oOG-x97xF;^R zp@YwM`753gzU=>(YBw*cJ#qex)9%ohXk+XuCrYFL!#x`>IK~Md!61a!{AkswfYxcK z;^|byiH{HdB&B{k5J6ti2vk?Q!xNkh(p1K(4p{X5cl}!3`y5&i_u6gRYWDTPJDyl(zMcus738jvn zg1CFO)8+?X4eic7{{nM)4O?{DbEi`ykh-BKm(`pvDO@f{#Xk8qSmbW8-c+akrjmy$ zMi=|uhg?jij{m%ESk`GMh2pX*(^`X4^eu-g_ALJLvCR5Y-8Rcv6D+dvjy3EWFOXi> zY=#?|8`+yXS=up5OHkO-E{}nj6=5A3AqdoS-aM-AfgRG1D z>%f8K7@z1Pw`W$uDKkJQA#By*ON8Qf-6KH0n#kPg%(E0yZo`|kxUta}@2+hYv9H`6 zAM){jHb995V(t&&buT<23CO^|%n6<9LveK_o&t;39W%Y*m(U+D1D=uiKp+6#Yf-^r zASx8VSq)mHKNBwun?IYtC+=8VhwpE|vnhBUICV4$EnEdwtPItCL}(gI(v%2VNqOF) zvfuUqC@z;VQ7l7U_`ml!15gizB+EDz;pQ%QBtjZu^xSaGQK^L?M35{NK1yeRDLO~G zyc=CIE$(OU7(9A60f2!_o&+!$lPLrMGUX=6ex8(uKs^q9~WoFdJeS zjN{^K8NC_yJMX6dsCD5r@F{$TtU-JYeb*-bD}IJU?sqItACRb5&0a<9<^-|L9nML~ zg{o(MVGk+j*=SaXZ`d;+nT~*N7+u&lx7f#NZ1i}H+|MM>NJHZ3s%!CzFWg+^3TA2q zYt}n}70`CFx!)-8;!5%iO-sqoX6*ll2c)LTVxbriPir8Tn#g?d&ew^5U|$^+C?1Mk zJ8+hGTJbTSSWJ?y64ul-z#aV2hhd++r1oF)P`f%oKFNLO4CmDitetOVi<+9Qbl^8u zGFy=|a}2N)SEFkCdVb`nQgupN7Di9CbU0XR=6-M41E9hCtNlT6D|F~9XF#4=}f$WIPDI=`jYE!{T&_u!J^{yRkv?*)KIarbo& z5}yWlggtz+sAa}Vw=hoi-22Hdy=|;AZK}o6biRJT?bkj7W2UOc(k58e{rV!d)Xm~t zOV%IwlWzVPL0F@}safFcU42K0)$E_d`F&y8{AHoHTko5S>ALX!A1jNMcPQqR7#I^Z zrbfyo6@{&LwPGqB-kr|F;031POUu~8yHhGXn|>x=E<}HeF-f$Xh4DIy6z(Hf>da-y zyqcUH1HUJDpD~#)%w&C_*bBZKE++ors>eUY>5d>_*o%YtC1L5fe_gU_(^{KaE$Akd zLGCAvaI?EN&cG^7cAUE>|mENn8)D@e#Khd{a2OKH@Y3`t_Fm-CeL zApi(cRSqFR3P7j@7zMfm5ojv`a8M4oE0;F?TOovUSX~4%Wy_B0NXj#rV%i6}$rw=g zr~5--1q;w}&;~@JCOZ)j5;%My0*$~6aL_Oy1PmC6npUdR&OY1-AO<7hSNaOiOUe#e zP6-)=tA~zC+oDjB#aiG6hQvTd;DBz3d*e)PKfj^hS-j)dzyyf3j(PM2DV}39SCi4X z@27Kl12r`@P1W_?=mdF9hSSBnpxU`S-eo4?<)Ww~vyAhG&Yj5%Xl&q<-RFQ85-I8z z*!eg7Sm{E_?)MH({X`3x$Ng@dom@9eRNG-!3`Xyzrpj5%R51#dQ6wWE*teXjAHr3|IJtI@+dpk{=1NA- zX{wkM2PeAycI1xlJp)uR7_(W8)QrFvy&yF;Gb1JWt-l4@&z$z|CMtm#)o3kOvm)ju zThr$(z!$E#fKdRD5FhECT7`w`YhTZPD)4x;MvF@c*||z{tGP)t=(zu2?QV@5*Ub}^l0Im8uutFVl`SrgnTFbP zd}Kk|akIU9Z~oQ(_ZrB>V7;kUd-H!43RitiB4*Z@jX#;J0Z*HHjxYN?-zs^TZ`*&& zw&%kO3|ncFmY1g>)CrFfg3P8T!*>_L&>88a2$Or8BQO8bs~>nNrL}I8k7oGc#ttdwoLMKi52`-i8kfk`Mi||6sMI_l6c&Ga1p4b;opfqbs}5r3RdB z6uV5Z1`ACyo=x=S?2+&cOE*g8$MrBx3tN0;-<$w*CLqG%uG8IIEtHMF|$M>RGS z@Mcm24I)@#tYRK43m8)=U;^v5O=RkOV9#J@0l1?Kz+5tMC6=J94#*&u8PgNjx~0Rk zH~e_31<3w6g#J>a zbG3xHfX6!WWNIyV&~}ha+IYL?twWvW3ll0t!eca(TE4b6;n0UEdb$9p6LqmOpbmsv ztTEMB^=wCzPt85dvz`=59-O+&IzL|@;5s$WWQNn0YdmLH@;a>aCxxvze2mql5@0_6 zyk}>)2o0mrE_M_a(_uC4kyVI|Uoj8Y(Hr+!*YYtRG>*|L?8?rs3HQd0sfpw}86wuS zjv6%iIaz*nuaeL4L_^5N8AlmEMP!8|5q=1=U3peBAgAKSABg9^)iZyLzof6_-l%U+Ii~ zG5OKrIx7`1;jrDcwVK}ZaBDL-H^N>X8r7|*oowrfH@!um=QFlzOFy`rNq!{c-i!hVhgfDT z*acfXV4KLKZ(CuB4DiSWfU0F}7amO2ZN0gqaV(2C8;qu7cUg~F!PudwIYRgKJFeFx zt;joH$S&5T@Bk2Az$}Uo66)uS5@bTorZMVPHJLigL%?kiykHGdzq%eZno6rntBa>; zzEtLd$J8{dm|2U;$?~n{w^FfECo9{=C-~w>-rUW9C*fX;LKIGweiq(o2XXD(az#$+ zWJ5B?-98Td9v=U@GbcZw5bEQjcIWOt4G{!F3+%#Rk~><{5ukoW%70$NKMTCmzZj_J z-zdEmUWzrcwEvVhi9Fao(6QTHpo^&RkH%!imtNGs4>`uQ0RR@VZ@WKzz4MIzPVkX* zsNXdfLL2--{zmO#Og+8!^Mxc2Mza3d0?h?`n|TZSr*6i7do0lWv~^<`yt~&$ABb!7 zyH9L=BH0-tx+IPXZU9l#=z|IDx$fP1ro46GXo2wci%9wD zg?(=4@)(Vf(hczG<4r7lTKIvRM|*OiO6u2^qf*If-byWZn?6FZb9 zIpq*u?eX!RwuXW$j%0JqIP0a;@cVbREuvoLZ}1>{(}}R)A)P*hPqTSXnxJiOJe5}V zD;AsrSf+o2crKRlyQ#JWx0bfScFZFKqt}p0VV%NBMO@h*k zu8w79X7cMFmQ}ObyKj+1#;j*1_Uv2AVFm@8;9V-)L@P@7so!o8OpLJ)Y0dTqn6d`Ex-j8*_z6 z^)N5{ub21jxjN=@1@4AFVdosedA)_os4rZANRwa@5|6)nE2~sU-iC#`9@AP=X?wwr zi7K4H7E@}My)VaJ>s@V%{~*ho*JMIQ)nWeBDSqc3KcsnFK>6}mN2(D%GhTc{^a&+c zNGP~&UtAK|+NU0||M%p=e-^R-r$gmG{($~B++bC>%Kzd9^ZX|`*cNl!3(li#<>l#% zF${`?yTFeq{TDB4{aMf6z&37wly||D_aC$ZhINRm9Kk6 zhQeL{fi^1}1qFtB1&00wS5^DB!r=dFL-;R$*MDn6_-EXI+7MKaoD^5#s{ghZ@VFk` zr=yQl)&KMEXkJqPe`N^&oczB~&!)b2LcK!Z%BFWPp6RgUcA5p)0d#{5pmz=!a&1?k&9^+teAJ*D{~Tw z&zzs73EW#z+bv^gtLd6B%iftzJl>OBJ?NR6fB2a<{UTEWtFgL!^VIhmdzHqr>Wt5U z{~|WA?`$nG4ue&&A1Wkk1doqat!fWVpM3k>Ns0eAP5Fy;zPCD>k;u`Y>=<46uB&6+AbpKt}^3zH>{~pIIDLe!lu}rsQOohNRjF{i}Jt zC0tz1EB#HGaqC6TMo7~m4n%*a|LB-%`LZrzCwfV?>-CAWFScJLoW8)O?p`1$lEuBo zM^!!?k1iSscl%>fwmdJU=3hngp4|nsw8hG(uWA=(Q8B)jeY?b$Cx*bumhD6aLZX)N2{5%kPu#UH*B(Z)vaL8d!UB zJnfAK%*;JeYjesywu)WM)^6k;X5B|G=z0Yghcc;g9p5oq4T>&$AK#K7Bh`>8Y!Edz@T(aJ#8l zv6|ztizKxrx$Dvc6<*pM1zs5|qASN4 zry11`*8`dYyVM`Lp#ri@qzI5+ZPM7;lr77xcMuML9cO-a{fq1GJ!c)q0s=45Wfono zX*a(4gzQF94V((us&1!`2ftCdv1TlO_GK-Vq4=*qkUx^Y{Wp)sBhAUtJo~SF_oEs5 zzcu&%?MV4=`0g)l|NngVy8ps=&&xXg=D+zd|J8uRIEBGf$pNL(U02J0^I_t#(tA{{)1E#rD8-kbw%0A`Lo<^KQvS`f2svkyvtd84~ zfEiaWet%1YGUdOEWu64ly{{e$dETw+my7^g^GbCYNrDernV-cy%U;LeFG*2q7gz&Y z((@)a90rWde(_bsq=?@!^Fjl8H2R5vW4;t&k6Ni~+QsV3qV@!-3SfcrNU~*4SXevj zOW(^{4{#WkuJ!BW;eA&TzJ{#{26p+-gy`BxT7D?+==K8a1sqV_x^lkHVbLRQ!Z|j~ zz;4f0h%gek?LE-4BG4n;N(n^5yaJNhnc_fa5t9M)+$t4K-gM$B6ghpKhs9J@g;vJY zXQxNE0v3WS#5}m`W(GO43Mv%9W0}WBoUcz|!QuHXG&nSNW&$^#TL-%|EMOs-VIiE@U1k8& zmqrBCVf0?~E+BS-6e8H&CPw=mQTq>N#<0K=yUTjA446dPdM==b5gF)x2pX)CFBKby z&)k%+`Xwz0z&nT}wS5nX1q1c?A2+Fh1;t~*wo;{RQYjt{Hu5A$Oh7CRh7AMy1K*r& zK%Ym@z`_wmoa~C-0C5yxmpiU62~^L&jX*rJj2C0+*d6zGdm&5$Z>~(35UC(-gvbJi zw|Z4wfVkDX^N+NvvKyHT18w;sLI)!15FgKdu{Tc-;D&b;Rdo^2bKa+mma4~(_D*$nq2Ta&swdH5hhSv>4-IfHGtu7nRSp<{L21UTn<*gk18s#1+}j z0lJX!onv>Z1vY4lO_wA$HZf|Md;=yybIiqs`DXiWELv?=54-75gwB;&w)=IyxuSUJgbDgcdk~d?Ugu3`p8q< zHT`4+!o@p4HDA2ohZ*r1P33I-dQi6$jr*r6FFN11k0 z1TwqIU|Ujp5wQy!De%6Jo7gyY1tQKSqF5if*e;#V)m$QA6g;wT-7%0akh(nha57m{ za~NKdA91QXM6NqTufj=-l4&V$kMA%m_30tz)RR&PXRjMBw?Es}NH70t=NlgiPl=eh z2EG(vp5->pAzQB*VBiQwxte*{yq{f^YhWfUt;Fz#9uGdBW$aONzE%bFcyq ze5b6(d~1X_)RkSwL-MB-rz3ppgle8!yt0FjMRc9HTYKemS=2?Tzb>9J)*}T6f9Xxt z<4;jiKUkj^i7HXej2bPi@qH07)A)AHVltLYrprd!>ZNIQAT8H5p%MrgmvfD@eO7a0F+599btUc zNZx^bKu(WRS^Mk;*LqxOTu(ctm14U4b+^m_5SIbi!xGx*Kn{RmrpD?;h0Qr-R-gZu zdL~z`<%<3RtBgorb!wkq<+a3u%vmIuwPMY-g8dI@7ILcBWDF-bn!|$9fem?2A291N znjU36ojZop4FqQz0VrH;os`6~w3t{T)lW{HxZ{=v7_*djefm0#&S~sSk`+70Q*CYD zcCh$+r>mq_iEOmJiro$7o;=!v@F*buBvZO1g<{E*WEX4kq<_e#ITHf3?G<@C0F)Mb ztF*XQaz*Y*PoW@ zc$_di+&x?68BVmj==-Z%c_|OXxGIakG!nOzpd)()_MMZjm3`R_K5Og28K~;E;sZHW zJE5Oz$)5pOvUv}=ny;@i4#_H>i}5&79(Jg@sBiVqGm`O>u?NWA-7o;aavf-N2o*l( z_c#iS^0Hj}*#Ow;i35Nl_nJX``qUrZ8~R>k<8dB`N{JC?O|Z|S@BKc)wuvK+A7jR= zpM4g_f}SieyZt%vuSI2~;OHRxV+I{3Qh9IWfnV|R;iLUqTcz^cW%05U0yxPc)&amY zt>ls79=(&m!``@NcvdLh`xZw^!rlwsy}~eFVzsP-QX1%S9%BYgFhRdF8W6U5Km(A(T2q2`E~AxT4t*rkYFjCGbt#;v#gvsw zyZ=faPNJ_bueuq@2%}S3{jP-lsKx&M^crj$p}H7dZ60l<@i|4|Zg)&dj;QAW<{G_s z_It1CmN~W~k=*m#h`9m4mt64>ooyDN=VYT9)M>vK{#GjuS-hF(m8^%46W9Z-)D;7F zwsNGtZLadP-hDh1O8Ei^L9TP7|1y}-v^8qn30Qwqa?{Aj$a)3IDMsKC&g$>B4gCB>w_cu2+ zWuYvZQ9l=m=sC0v0$c5r{^_qSlC!g9RD$ocnrA3NE+h*^r+n{k?WcTeeZq80bY=n& z#Ok53-VJMH5vjg29YC=Ch|xX9EIQtzcho-)R$s5@XYi z0;YMQT~Gxw9Kuqy_EKnhfk&RtuwMXyLW$d1W&yy+a?|SFrOiB#3A&muYzZ48q+2uz+klw`^0Fvhk(wZ`69|P;qk9}C z)Dc>K(iDkDfI71rMi|qVWb$e;0%&#B{4#pDc?3fG$SL!<0mS~c$)XOO|Yr~0w?e(gr18TK2)8;5Z-L9MPT_v<9WJ$r(wdl)qH z%MPpKN?vs_cl(tt0}>2o~#t zdgg!>Ow@OOz75JWsY-{0<8+Nfj-B|F#W!F^!FQV)pd4jB3f~e~HM**MA%{6!@Y%0m zq*G@M!)}%Ppfj1sH>C{oF1w-&Mauvn;?H>y7xA>|qm<}e&K8|DvL^%e&J9+SX$fb$ zp@42m^+OhmhSGu^p7XJoy99GQ$@Tb) zz|{WF^V~h5+sy(~-0eL4A@8h*#+N;L@;OMl2^j8qD|LzDxXIL$aVC;BcrWd@sxP4Mxx~!7uzVhH)+&bD}cQK|p!E(3AIL>MFOokW4 z40Y04hq&GA@=CrUn5lfQum-RJN1_b$nrDpE3)^I< zk4oa&n$=e7kV&w8vdUkstF0NxC)=(j6yMIp+AOo;MNZC8$C}&AiMmC<$x>#$xbp zB&vlNa3g5vz0C?bj{L*$#$_{%-?{LZLbK=dY%LREYoK8F2y&8S%}6*zMyW+h0t(pl zrGlZJBtW;)ct0^(9ey?M!e94L#nSA?7LNqk%Zh!BPW+Pms8wxSfKV z>J5AQdV)63AJLyKU0Q*;k`Ciu@E~KWi@EuYy5?2CRwKST`?&sk_KWDPw-`vQY3u>6 zT-yvZ>oHgZnyj*7e@W^#!%9`tiW33DNuPhutSkcKBXlfI&+E7;= zA?p39`mV8z()j4$_;?g}9=N>#KqHaB0Ccdm@>2rrlui?{px!7d@Upsa9Jvg}NL;|~ zWknI0uq?o0Qr5IO+E#U@r+up*mgJRV)On7=Vwn~sI`%-2bvhPH11wh1?j`5W4Z0QG zg|edTTTV6@%P@P6-DV~;-z2%nXtMyO{t!JlXc9yZT($Kqn|pf2=!mL;Z0xP1GC&sN z@C9|F_pyI_G>vxU91jORiwaN?k(x3`k(8j_IPIJpW!y%*vjx=yqSn3Se9p2!Uf;Bx? z>_0I)2n6FgiB>wvIOA=6#;y4t;sJ;&eFDogv+syKvX~rQXSK^kJnpZV0C7o~9Vq^& zcPPD*zB$Z>O2XsQjU-{1fKzoJPFwWfr$0Lr%@JXBYO*^kFRz0zScSiDzF+(1D)g7| zKnT~P(^&~@LZ{BDBKb~!JU-xQVZL-Pp#Ig_ksmJdW>GS)m*YfKy5YWu#&=5>_$I&m zlhyGuhE>xtBHZ6=ALQ%2tjh~?&%M3)z1D&E@xDQI#$%07@*=t+mkPb!&OvzC6Vq#0 zt}fLNBjunzI#wKHE61FVzKZ%^eBvV?7{ovF=J^xvqt0_&=)O@Y;qO^n?Hj=9Kr=}2lI&-BJcPNkYEODGbxil(s1% zyG*|HDJ)>U#U6xodwM@ake4K7d_U`)5iwUAL*?N)PCKEhn4L2Ein-yusr`Aqdd{Nu zOyvW4$@Zl6cp?E*?qQU(@0dT^y}KV6OkS>#TCOf}W`Z{{8DZ8FI%ELoOsxIp-DlW{ zRsX$(1%`A_%`-^=(@-eSdiw6vZ})h;KV3-Oc`eq;`{n&cHnNhj#6%YHfJJ;)C!`rJ z^w#nPb%%k5&z^W`2<&nw5VONGjH z6TW&??`hYR(+{ZO<|UDI7Jn<eOlka^}sMS$@ZfbWm zN0C=i%kx%4`RITA!{xb{(XqLy{niY0^%%`O9A6JN|jm$cA0RR^AAP&f>(ODjcJN*`!THt^% z?av|6fVYeTqT&JSmE?(PIqm5VZ) zy*s_r&ZA=Rt_fv`xM0*mrV)0Ep&z6gpVi^WR$6#``U%#jb`Eufu1Ya17>3`}3w|b! z#g8I#UrJYsb98v$wR3;E$eWS*RMzmvHoL~u9>);PiPtSw zPuOfsNEMJ9?DtJicng#uc-2>9`P&O4bswlF8oc3cWNMtY47s6sXk=PtP^*^fTeD6k zA9-GBhxa7U=T2iE>z3dCmI#TD=Fn&&_~f;jsoEW24;X0TX1W8hxY=h!B=49UR9{hp zxv$wOE86x9PyvDN)+^JddM5vO^SuGrDDG0pcO3Ay3y?$(bz#FT(Zi1J`%CiNuWGNa z?oz*EXJ;97`6YQ-57yZ34;dcz;_%M9_~qz4?ADk*K#PGxESLs{Z4DbTA``_gNqHG# zMkvHKCvG*}ia)aA?xMQ>Wl_!+w>aT#Ks%sNTnNKapFi}4*02{{*(xh;sNM}3UdkJf zx;ug*?NV9HI3}P|8DJu@WncURw~T-4koQ?R1V&wSxw^=ukXPN!WHG3GCN|lvaGtWm zD*-6zo|tSf#au}AVCJuo^|LH+qT#(ng_xrKpuCv8i8fQ#$OZo+NW+>?98vDlFq*jy zmUmJ+XXQ|aLOv=*SLBMUG_GjNZCUGQkNFyvmz9;3@sI+~U=7kFd+Z(Odca@)OJ>9l zX6#O4%e-g|dU+?c_ezvJ=aMfNB7mE>XnR=<&WmX zAH#cOLX?Ns-Z^{K<@4WPXEAoEEpL@$M*Eg(72_Jo~(oBqM8Iyv$~4=5EBQw7%r$MFbTv- z=5y?6XR$3(coC|6G_$Qp3g*)&TaaiPF0dLg2%@a$%|_GV{Dufc&v#+c3ysw9V4W_j zf7chvpSG^rb8%Kf@gs~q&u?;2JbnY_V{`(cisZZQM#@BOjO_D4?wiX??kl=vnm)L9 z0_oHA>x^1+CFZNCsy>Q%LRzt^^>h-lg3NC`Es({LnSLTo?@~Z~z0QeBBk5!5W?mKz zPWZu`7snqAc*gwl`uk$IV3Z>s|2^eubzTCyv%gQfe&3X#uH)<_wpty#k*hUl;5k!+ z(oddzW>1#h)XrGJnO;3}-)Gk2LV{=H4>R5Jk;5#GD` z+D*L$=?aHn#0bo&Bb`lB`pa1XQ?pUiTbUR3&)X@$_7y~YcU1L@HZiIxb|fPSeKVI- z(VL|sLcRkiLHCMFl84zX7job0n}mScjF-i;kE>+mZd@(h=Zz3RWw5S#r!i03`S%R9 zN`EiEBJ8JmRljIcdBcWsiXiQZzHi>rd;vbIaaC90e$(RxZ*8Fzo8K+@xaRBl<@%hx z7dEj=ky~K11(6-U7=(Om()XsGa{y+YaVztMsJ~NMObgrV(ab8hGLoNJ*HDGFdm)MU zS130?$I*XH>`r5HTC-8eXOcpdJ=+p|qv+&QH+BDN^-daL?AHI1xq+4RJn#HivEf=I z069B*hm}-Cl!^2cmQ3rHj0ZS|LUcpTUKR*qFm}JDrmiP0hSdy`PVR0Qw-*!BkB!07eY`(B30IrLONS6$qF3~+nc70bj>Ie z{CD^VmFuyYfVSF-_5Y4&^6YoCkxVT&^WR&4-MXnSy%9v0KJ|jR3z#6=>6PZFtxAO9 zz68V#Vs@=r)I6e2y4oAJjfl@w?0=_wh4Pi7W>?4pAtGf@5~9coiIJO zF@uB_x~&x!SWIBmn}|0~nVsxBR2OxfSx#{DpFbOMKwQR7fSkWBQ+lcnMwSySs7`sp zwCO>42W`jAfa*s2)y{Ublq591>Yk?TmGjlT{9(Bnnb|(_W0<6|L^LT2W4@x@{V3s> z=EV4Vw?(Ug$wfi}gSw86@V%$W_vh&(ed>D8pVi`(vsRz}bo8ByisPHNY7q;Jzo%&} zT9TC&9cg*r_nszP?3C%gHkLC)UnbP`-ixc0o6qR zstk>%S}i-gyTL(k=`BM*k;Z|A%k^j?U}R^CcrRC%d3ZqA{Q4`AW_;(QJ>)sVneAwrZi-2WKT= zt?MY>o~;Tbj%${$YVH^-U!HWrQfc|DDCxKx^vrlJsN!!57PsBu+78UcGjWD$(Ob_h z&aoZB>uXW|p*?fQN}uq10Ga^rV@_Kvt|@j&py0=Q-p8Eg6%eukY43(OmzDXM!dPg= zrv#241C?qrevcsn0YR7ha>n;iLF@TM5}T|B6IW>g8*jH-7B9p1uoA459QJGs;vpw% zW^-pWy5Sb9j^l66Xz;Mjk~sM~)`_^fH54jpJ;CyoIM!TfS|B$@riapH`O5r0tj+z7 zem7q>L07p2zLvYi$t^EUQjim0t%WUI$G2*G-?SniDY>-DRenHa?D0ftb4;9-nidsIJ4NEw)FbSEjT3gg!sDl_nusm~Q zJZCd7`&@WGu$(-za(7q&^%t34a?hY$n+KQZ`m3KpvMirw{^FKwn>&^#-f<u z>w=!{H=ypxMplz5MqZAv>SnIhamGIPuzJngCh1sSpW~(>`|$Mi4j5l+s1v!!C1fs) z-0ZLo8@nP>XoP`Nf-JTK<4Q2Cn3Qa3I)`k%i|#HtmQ^?yb3c5GTLW;&bjq17Q>%-x z?NwAPzg5Ad;dE4rVCJL}gN5&!c|jT>8MHwa~&?I>*$wr`QA{ zQ5su<&cEmfM!l`Caf?%DFh;?923-?wGPpB$kmK9qkzX%nz5ABHS~}g#3cuP`292#^ zM1P(tUaV2k7sp8^ZF}h{7-MuoPY0O`)zswY&m>5%B6N7NGYK3*0*aLu$El~Bn7!Sy z6q75;uv2C|P?ccU^8E65y!bOpd=uhqxY@$YCx#@H+-YTw^iDWw9i{w*V2P`PDkVS? zc?ghz8oVVUzM_p_Lm+V|8TurOX`r(4j^*q5u%?gBEsvNQo9-7i#ANTB!LU4igk(`; z#zlAh!v#Bg*!B>j$BkqaNzg0W(-1-V;=T?he8%4u!*<-O4#F*FgX40q&E^>)<5yhg zAWcoVMO&ilmcG`1hREKki9P2J;aUvsV{aT&@GwY-kCu%+zExoG>UNU*qZq!AJjbe} z#j5F-g`QWwudU= zR*F+S*`X={weZUczyHX`lY=OnJ}z>m_Uwu5lI7R0CK}CSj^_^62UR|SB5JCQLPwSp za$J+eJK(i-$^RNM&lAIwo0x1kPI5w#>}C;m-+RS78~hr;~?d?H43;K9oTAa~RvOVnj#1+H-!?Vzp7S&E#r=_dtYZIY=I#7);|MK+-47=)P4 zVVHQb@0jY}h}P`V^AVLj8{B+}u{c;x?U}DD5q4igu&uatNJ3J-z26z%>U6SBHdLc%9m5Mh{%iGZ*5*!{A|I#dew4#F(%*R?ttdEcz7F$0!#T7 zu9ki8#KJtcScgF-jYmA32{-6mRFs&CNZ?pe`OxwJK9|gdaK!V;GOH8W_Y5+}xG@P# z@n4U&;uTanGVT{(W}#-cp1Su*4!>o5l6l7az*snN=}b0_9KM#2XYgUYe+8lR&RnI( zIhkq>f3|{zz$|%$PFV7!EJFmj(`DWm*1C{58rUD@L%4~# z+713Mv))+|tlCf+NiqmAtUJ3=x9k zRn}23TZ~U0vImaGyxN5KC$i5$O#4#qYgQU08V;zeKuzGVFFtV8xolmPEtnkFK@W

9v`_KxT#Pl(E2NpVTmhDT@ z*<+mK+y{OJWAK}5{);gd5Mk552hEs1vVDh6@PPzP)!bnHn`$M0z9ZRrYKX4{I|ZbWv7B%<+nD%|J9nhl4ULdft{_+fle;3e^#F-CLWH7n0k z1E=Fd1%4!4<>-a6XGj%^G4wo&G+EFx>M z0deK~C&NVxE(>#mn}(dQmR(UQ1O~hsV_~D%-c!wKh4TqEE>C@f>p$mt7y{R5HkJ*f7A; zmQUP#nV(XK zgEF!tyBD^>X0aTTCGKM%_bd_*&%GykE+FnKgp+YyD9tJad1$F;4lme1b0{u`RSgM^ zH#(sHPC!@fpO}N^zTzKnoafu;GHYqA&XMGlkr+!u3kZhxCb)nTJutKDo39&WkP21f zRhySplA-nti%69Op16wzTjTY4HWv4s-eg`0X}}d`WfG<5lQ{(AX!FmM&r9U%%HsHD zTZ}Fh=4@CTcUx4jTMND_b>_RLy6Ztx-oAsNupj<;P8q&kEZuDc_gLk4WZ2 zkGoloGfrf?&bCne%uq?VcHvgi-kj`Wn6IM*-{!S(wDi2~H0QP0o^$gEC|bJCP1Z)? zZ|B2Qc;Yx=qOx6dyiv-Kt>@|i3Q~Bz_sT8;UU*y}UcKY0`8i8VX59g&bo}2r4Z^&6 zpN$eyxxYY}eRfMOueA}Q)aTM?eaVy=V5L!$J{Zt?)-0QAt`l&8!%DAgz~wE$q99=gogPsS&LxjeaXv0 z!Ipatg`duSw^b3u5x>H8;sA>yI3p}M-JGqd}!HMhYh2?!3fehuQ8P7PGrkio}WDd1~Yuz z;~EkeeyuYsMx#!eP;q*TGqY!l`ns-_t#x4;eRqpszs8aIIA(g}K|EJgSmikJ^T88b zLoC5ZsS9IzCfzDqbMyGH#oV9DhnHg(l!ds*ufM$`d+u8!PLv3yU0jlGI-i2x56|Ph zEF<~V%&DfHkh9n*AKsUt#E~oqVYhH!QW{%I zl(F^W6Dl)bJIa22_noMlsR>8QBp60;;B^98KkalsD3AE~=byU^4cd|TG&m|LU_@nu z6fs^CP(N;2ULRVR z;^}omkM7_?$8V;~2i#{NR!_#VrZCrLD!XpQjnf%x)Gux`(X-R&eHk%-Qoycn=Nut2 znL-`ur3SYy#&+(XvN|+Q(ds^(|eN1M;@HzZxh( zX>YD*n+T4({%(FS#7D+AO->iY+fH%n8I`}tN0rtXj2UZz=%hUrTr(#JM}qS_ZI|N# zBtGQ&Gouq7KRqymNik;*bdIs@-_WppCT?z31No{|T`0U|T zH&E$>;2D2mUVJR8YNakdy^?DwAvtKIs5aT**HR*z*^hG1#RuNUo=7!?i0oWkaz%xk zgz;HByxzNx59lx&@D%k#!ac4n3ajb=T8yTfuMYIc7d({uB-T#pt|}7}xv}b)uPgWQ zcjecXQIVpy`>L#(fFjx{V|NI4%>?8+Y^!AS#$Gdok+I+{;N$FMnOhqTlUD542 z0U_FRR*o;%Pw)EL9gXaW>kln&yZf2ZHs7(K2R*+sb*~zctfiNHkrMf}s8y^*&;hOy z>0EJUmm%=3tg=wLLRBQTaZbPvQO)&TmviIcy};#d6c!GqT$}hwta<)WJ)(%c1Z?Xp6jw;*sz2xf~j!u|UcHPWD9oOA+)i?b7w}cCwYkZp5-*V9eloy{+C^<^3 zj$ef7#>e3OI}=YBizIU6O@bPfBC*!?n9ztQUJdQcX^nP`ntmmEOyN9NDu<8G6Y*;j z_4ualy4zx`3h@Ppk?ngo+Iun_F53@=oS}17mNeiTb399fedShT?7#c(kzMPJ{E&G{ z@w1<@GX8=ec+-PL1nlxNk-y=e9=_!ED|LRqxj^VwQ#OQz3+irMc5u#@#VfwC z)vbMt(JzK#TxcmfKW|mYmDHd0sRO&f2yl}jC@rC?ZbYQ4-OicA#crOT+Vp(PN~ScEcYo#zN$2bIw@G3 z2CPS(PCH{MDNsB%N@i2g(G+jFbYqi4ZPT~9^o{s*h&=02jS*N#oaxc*6;$Jf`V~ji z)W{*@EOrn4uRpS6QOl!z#@?}elQZO@ZrQk=TCVo)XTF+E$vD4>S|7{*m>8Gor8a zD&hhwRS(Nz5T_U_-u;9{onGawGGaq)wal=r&`3PV|?UrH*FJR5zb`&^sON!bzl9QpjQQ z@qcz){GrT@)9R!jh8Oz+kb$OBh;fBuDK!jg)-1EmvuqoWe{EaccMdFL^@)t#?Z2WQ zTU{!9F(Q3P?wKv^=NvG$K}C$x0Ifj}?1I*o5k23N*j<{Z-AeWWdlD~M>DXDnc98e4 z+SsP{-HG7Ap%k(;OCgWOJuYSkql2XoasSn-7c4-Wh&G&8jG(jLhd&PRM*wjtO*FLm#Ks#%mDLvNs_R@@k@jWYc;xHI#)=-iL zhYy>zG{2=`2d8eD{eJ0E9iHTnG><&%0VCzf8V-@NHnsa(uH;Pl!4vr&syQUv2P;VE zm=g!gUI*}Qj9yK(Da3ET2>N8Uf7V!DKt#aUR;VRWZRBV0P;rZ>@!WvXUs)5Xk72Oy zRcd)gD!d$eRQJ@6$*Gz1(l!>rKg*ePy;d1fTV%?^Hu8?k>5<_l#Y2#8EsRPA$%N5>NwALpc3-EJh@p}LqPLDt)= zz6gKt|8V#2;ZS}3|Ns52-cnH{DW!2JIyvMJ5tBm)WhlpTnnW^9NNmM%mT6^!= zYtLG**IJL~vw6$%=Is{3xZIuH1*)oQmb_Vfc)@~6+kRH{#4B)?Oi8#F3^+|V`6ly5 zIT~&g;acIdHeSH`ri zmH%z00#}RK>ml*77ZVO0xUBi&fn>_+>D5-j9&#Z&ALnlNmHmvE^eEj(?!Os$VgIr9 zA4=bXPMPekf>31je0GwUpZQs?{cYcp|3K00`QP~7|3EwI8~p#6cHXV5_lr3Gf2N)F z#3;DE@_(b9|Lx=YkF@j8dSYxtoJ`+uXI^>+R9>FmZ;w9-Oz2LPK3l37UU?y5)Q3Ozx$xnLS6IO~+>0tdzCL|m z+@(15 zX!uqXr*h4v#{1pfF)opoZiH6$=F52j3a7emS5}xjdmAL2Sg3j&bMb=Jr>FL(-AvyY zZS9ctS?TCb-(~jK8k zb(*VpV7QoMjYc3(^6uKMSfpW;cmwA}>n`r;P5tfKwm6LBMq~&t?8vv8BP`Z5;#G(4 z-~DOP=#SjRI#sFH%Z6?l!xL#EznIJAABny8A_+?J+IKwama61qYGyg=m2DBu$fk?G z?~d58^ZD;d$M%hx6Yne=o)&~IE_xXAXJu#WZ@K5*X|G&sJh4UX`Z0?=ODFwzMBIHz z`Uh?4CQFGen>vgBQ4=XQ%c=75 zont4Cr{osz>K}GjCC{YtRQ@vU*yZXMj;ue|zVyMs^Iq-YOQoWnC(<&Pv~3>^5%n(B zK5kkXQ5&x*Bei9`ghH_eqa*7Y>S=`)$yYy}eByluv>V?Yl06oTGQ0N$o^C$+_g8E8 zIGPs-h_v=4FH_SvBWM0W+;Zwm+mnjFDWn{`a{Vovc<;+;CXX|kPxHBY;eqyN-?I+4 zDmk?aj@&K3_f`eJ;k38r1YE9G+t$C8WWG`F@0wPuuYXt!@f^uRzK2eE=hkS%p0BZd z-rpct=yt9iE>Ac-?W0d#ly!HbAkltb*2b6_N#W|n-Vcb9e>?Oe?Ud(KR?N9aZ(_;^ zGNaDiA&tr`Gw#?r;q7UXW54xn?6JJx`saxw_2u;~wcOXU5{a@dw|CWk z40E>*Rdt=r|NT_^nH1$zx!z%;%Rh2k+_ePD``A0yt6GHD*~hv3V~@Xfq*h*zf&Sw- z$HW%-;!8z^k?;L0)d zAC|YWk8RG;-hA|RTLe)tUgF`_)QFKqPK#$R9Ef>)pmy!6-&T>%1n0{e47e+QUS?0q z&CHW6Dcx%yg%)*?3+twJ9K76fZIUm2>5B^wvkq&7Z`&O$r(2K4$z@G$Nlx8((8UsO zJsHp3@Ga){4*H4gSB~0nAY&)-zPnjpU+5_*J>S25d;iT*L@gL}N(uSUq42D^Bt$wq z`9R1>2H|zG(Sv<+=i(;O{mq&|lZpj?+lm%~&KG3eeA&zXz0z=Fp=INu?Y<8dM;0Ew zD*t-AdGWDP-{&1vC8N_10wbTSlV3>~H3|xQunCKLrtA)Ns_Nd~KS?qoNw$inSumAXg<=IP@XC_?rI+T<}J#3k4b%4-6 z9N1*}UGJXvq8tgWzyq04iASp?%qidL`^J-04i}i8J2$13urGbu@9gbnt^W)a{l-YOsS7gO!crz@2)3kB2 zSTs#}YsNd7do{~?!^waL8#)#%oiN?g`|T;yrNn=42+iEzO|`Bx{sya4CEciUi;C^J zN0Ra8%Bu%_6_<`Xsy)i+vCTa#xbU!L%UgL_TJKKMi8%Qs$-$bbX1gAr&WS(Pe9PoG zGm7xl$l)@Y+yCPOago&D9vsH*{P%%bPb{MGf3WsH$A|x`FaBQ&9RGo}-{th*S^J`Y zW9`$Xm$vX#M}Y=NC|-u4G;*n!`>x=UX?V@TfD4Z~3Vna5!9~HaLpiMK zlW6!%ofa8#QK2;A{6y7`1J%Zem*99N^{ER7*kmclq8Ux!B!-*Bdx6Lll8jS*Z;Rai5YA!aZ79v7`q9{d760WRICD#j&bzbGN zdE=S#eGDFu7t(PoNGx9uD2@VX&Mq+=*6)1!wo^})x!~|=a0$(=qaMP)))47l$tC9g`w zx15OF|6}FhScjL>sWx4)7U3$df}X}6&^tH1L`wPjA*$>Zwic0BV>>pf?5DTz>YSHO z7Nt10JGuLe?AJ`=87=e0onO&ou-U|XI_zu=NndeojJtBsd3yCal1^q@=pFN0UcX8B zy^%Phpk_{5v`EGG&>g+$NxFe<(C363*K}{cPn9tdb|k4O?X7D!xsB~6p6wS3Io`aQ zrwtxDG0k2QXVmj`VkC`D&rHW1`Fh?aKd;;OxrQM4uC&zk4>QGwOjX0aytw~PO1I_y zbo&8P*ZTYKBl`TFJ~YQ-`{^A0jjn!*D^*qLM`M;qDf{VlDt8+L-iw@SH=a5GZ7pPv zi<9-TOCv9Bzu5lD*5q|tdm}{-Aqeog;$nCzIN#K=QlDe?>;(}M4cuLRZOFb&9q(ne z#Lx>iWZdYuU)i4DwbFV}OZ4=D#8Ur9_YBUu)#}?4X&;>%0La$B<1-ocLP0nbjU1S3 zoTdis-aHUkx9|CXf*O|1)+fkAqS1-t z(ZGVAUQ)%-_M+i47enwSCJ1m^3k~-gq%nc_mD3A6_OfqLqfEc3Z9ZX;#f!)52WY%9 z`0xg2ywet|HV8$`nKlH$Q8r#Pio(JU_{7Anr+ClqIE7B`AW)&Tb&x7;YO^W*#~UlB z@u^e@sJCt$n%KQD2fIE{yDe#$C>bFg5>82qbLSWhFP&a{C3{&hC9j_$x)xzeM<>&Z zqeg0LbB{oI1#zAR$;6bO0bP>CPn$+rS=m8xUws@9BN<*4qi&klT#A)a5em~QmiEZ}Md1x?Uv4UAPgOPPwt!qDR$a-Rq5q+s%3>h;%zgdWF-tfP~Wi^0FuINL$YU z9+@|v_im}=mG+C>3HP@g{44S8&E{k;0|%NE3>sP(5Qbdr1wN!u|)7#dGb(#Xj-& zyI98R^T22fY_Ow)@Kw+E+lI%V(&5$cmK58K_UDY~^x%(IP0V^O>0dbdAz#p?v@IaZ zD&GH#7LCv7J@j@+M+?RrU^c{st$mYG^c-8GT=HC9&wlZc&RT za8YcR#GtX+3Bvt&tdu>(T9tw~&d1QkE9>zK{t-36gWY#AMs@Sx_dfp+J4V3}Jq)L> zX`2r6*u@x}xcgYT>_EuqUOq;aT`PaCr_sKiQjR zpf0QG=USU(PcF)&vx;KOW9gI1&EGo+XgJf8&pEMMuH@>)goJ_Q_^SyCH@z+wOB_|4 z2p>*EY%v3DmT@&$ev25!H%dsTvE8odXW-bklrS8A>s6m*qTIBstXx&1OLcd(e%uw6 z!okqe(uRbD>OKojz~23r$N98h(k;4jRAl%mY}mQ;0K(z0}kquV}5@6}1LetWHJL&MI94uV$%$?SVf!g-#pqLgwoWl&n; zj(V(_roZ8q^}9GbpH`HGg*9bSk-;zqp?9T$rPe3zeNOuU4^%39nWfd}{qtX#A4VVB zX3K?b=FT}T$D$w_8tABP6NH4Yd8%=w9^Fj$-U z3~>Um+D51lZ3wK*g}2(TUf}?p?}iPd+tQ0`MzFqeVg-ZT1wcOz-9-kr<|-f0#ywwu zwW~9n9m^-%;y8|xX-%zFk>}1u6@t{}Ov8Dfwg#Iz+wQYjmrurca+XF^>==2FkdSm- z$1<2>*55x%H|0~2==*9G-3f`$tgPs=Ee3gS)ng=G19&OPs;Y`>nod7hv1!LQHalre zb6aJMht)vo^)1g3;=0zEmi(l8q^|5S^IJ+@B0~ z-v)-=JRjAt1gJBEPF}|B=UkkYm0iuqeN||XF%NI38Fmc90x680vW@1j`C{9)N9ZvW zgp8a09#cdBQQabsr8D&3ukOc)#mGB(QS;#qGanaJtaL*i?uVmA*|B2e@=qG#)@U%y zy}O{{B^R$4yef(@Qu}$h0-8!Z4{udxV>})g#m%19ufysAfpI|-igxhq+sF$VxPc|G z`6!oM*)^O)=JS%qxVW&130NPkLUV=r z*%)}6c-zdHEvRENugVUTtN6FFo`s#d<5Ae7Nqna05x!yxrkOubB>2`Nu`<7iwPOX| z-+$u>53ix&j!OXiP3#Kq2bA&6IlI$VEUflu)pUTqNQAy|o9dhGy)YS~Qj{i$DtaAB zL2#Pi-c;=#!+@l)Fp5@_U}xCL#Fg}5#T8rYUCPT27jjUJQ=_nOmfJ}8?@)QEe;-Ra zEC}RCkP9#~8pelu=5tq(Ye40!qHpCx-M}!ZJKyfspPyxM$$t8&61S|J@@1u^4d_ka z?k4Nl7bLs(rA6v$Yu#97#y3;{t?z@<_t!1YcVJi_nD(R8W?h-6b0Zz2D;CO+X-3mO zT8Vo*@23zIm&;_h0>%y(aVwgD9ZeJ7G#=YqXXckkd`QxJtk9^N5&QPzo2Qpw-nw;J zcMY%vS*ZP5{ns0Pay6F-qZtB(^1&+WjL+Ee>uS|E00ADuWKlw|9my;sNB4p;jT-;O zzXM?vXQ#SeI!;OVvJ;sQm#kOSxvXM*)*H&4`rOD=wn)9oYlZo1vQ%uc-seNQL=~gG z&vMt_b8mmC{3G;`@#-ZBHe{8P9%SXE({h z=c|mK#l9}t;G^|~c>yVE;x6na`WYS_o}4WSXTV?(A!p zp%XW)m+V}B=Y@>upoKz0^%lK7`f|<|!Osu5+}Luw721kFDz4w!&*gOxHuJc`>M@~5 zgySrudUmXt(i*$+iR&&62|2aDdR|?;DhoK1Wy*Md{nO~`=QnkHb!=5<2Q@;~2?C8k ztI^jFK6CD$?=c)rJD=MVFxI@vu39N?YMoto5=qiapH3o*h$t2%fML8IVf$n|Fg!e# zuH0zOb6zlfY*|bx+4b>SWSsy(6vAM@48@HJgYWY+&nywJv7JVRHJpO^c)aAphHl%9 zC!AZfT_sHo&12W=rG;y(luTZG=z{m>w%2XTM*334Qv|Wr19e=4M4%j;Y3Dhz13a}! zWkRRQ%AnMPCo!9p7x92|0t>}_ozRi^9T5c+Z!QtwgxR6?Rag?M{2CGu>>dpd#3Ql+ z7~&YP5dp5d*#i$?(5UkW%v-u(pWb;zMT00;+YTQ<25AC_ZdnL0pmD;KXcPp!=gGwT z)z|>t0C5=ZxgC>BfjTkfKJa#_-EpsT8Vg?-?7L-vGVrGQrMy#BK!X=38%l!MI2zt6 z^7v>VB-4e!MN$0v2!KF{bnK$im{8qJ_1nci&-0!$u{CfuGc#`v8TYp(6PVOHs9~5V zVK*8Cv{~UY+H3zSj{RI-^-u%1scrfYQsb+Hm$4z|#Fb)zg(OBoLb8T?4( zH3HXDG4v@Z!n1YKVS~)rlnF^nc?^s5Dh`_nkLU=SmR(yG8nZ$ShzEVp;P^-P@n;z| zcv^H7h@x-3zqY@gk?`=JD>Vr*d%V1ha&qcgND>E(y^eZ0n3s7)^hFQ3mPP6Jnz-H! zl9i?8OY3Xu)2pZYg=CyJ%O7}H`paD?NLJrMQ!>t7*~`I+Pi+x5nIh}u`n_+h3AONeL?{oWGcdjSMH`<5T%H@I@wy|hqNdItffx-k6c9H- z5GBBIrB(j+O=mI<&fV}?mVRy4KmCT4#?6u$If2aiq3p|bNEDu(N4L?4eIbz@OE)jN zV4B#cjuU`mQ-%gwwEoK#EQCf?OWX{SNDcgL{Kc#q9CSJu? zQ9_cav1ZP0!}=Vrn|hM5dhWiL))Qj$lZjF2hjGmr?}ih*hT4fI#Osl=f?*5Z8~`x<+UPIg{6-(z^e zySDezI*wczWh$nBthvRaJDd``&b;`gj+Lc139sM2WD0c_IkC@9Lous9Jg{Xai?v{g zs1p~~;XDy)LXNm9X{pA|=`sAlK*6)95 zsI~W6XpUHq#x#aKALT+rxHN1Wg+j)09*n+VRpgMEG}NjM>Z8nI(kz~xA`GY>59baw zz>Jigk^12Az7$t;9?SyQ6NCtt2XJ{CxR6005HJx2ikHAx;Z+?k%;_e96}S@-$}>_h z?R;RnV!GSb5y!=b>7znhK8ONg;bH?H*b6FnA~AUm1kodCfl&Atqkkk2U=D2~4-J$v zyR}Cn_KmEILV$mqI*Zljl3DzbK%nhLnUE${9*=K3bl>p-H0k4yAG=EcSrhXEt*uTZu;^}^jY}!%N=`093<2)@ zFeUuM9~^OTt6}wXu~kYYX4g&qDJjkJ7LS0>dSM^d;iaW$lE6aMd9T&}A~}u&V`kSN zPsqcu#^pa>ts=Q)MStf1ab5Xj>^k#Uj{Z82imPKuva+)8t*rLn8=02rmAH8{TcPY@ zux8C5_0--et;VPj2u#UNDog^N*f#X5c?A(}kCQdO>Cc-N`E1F~`dqo~fyp9Bdp+5w zo^{bYt#gvlS7`Gm$}zDi*Q2VgrqP**} zqHc6;Wp`8s1G}h7P?VO4Sz^8-YuUnf85{Kr3JKju-YseGl8t#A>r{T+gUED2o%-}w z(i?1NyJz1lvB5*$>@6@f_-y^VF~a3yNme5aN?y9hQklM`qb4>(T6)c+OI2+WU;Q|L zGDdR!(LJkUL+(oMi`5|61Y(LNd6QY@_XAI_q+tNnIL~o*>ixTFt`>d!kBL~-;3&oQ zD`PF+y*O8I?4;T9Y-7-+jebTQ6;h3U+0VB6-1XtA$Xbm?$gQ#(o*5pn8m_zV-RLza zt$*uOv$TG zM5lIc8gDuz8+;e1^6*;5Uo^VeX;@jrcmhd)hSi{NT}Y zH#H3=J0*(?Y+wW6$FsEoV+(N@5pV%&&K3|mO=~*I_uQx;j2HzP-P>0_+tmeN=Hpat zs!`Lr=vHK!X8tG&%8CI5-_W1N$Sz~s&pH*?0mct7JziuqJ`QM#+qu731J3M59;5t^ zoS^6!0?8aoFZlx6V8`cD28*(%=W?l=(vNm6+(W5lg2CvCJK%y)>3F}C%*k3g+vdTd zlEJevbFc2XzPe}WsHL?n*=PW_j3IqXZ0J%b{>nW!Go~p?uWmP;%SFDQ*(7YB(}$xF z!E{JCRq0?&6x4NL7^B-NVYt zRZ2Z3z3Wh0jgZ0Zb8wpNun4{X&nBe$OD1$;Ok#t)%JZ71EmT$4sjTU{(tXA--p^ZB zwz|(@ZNo9bS97Om@rd@b%)DNw(m6GDJo4^u`gF(6+=azWlap(0CZ`8(hg#$CwuM$b zIVtnD4VO9N)p&n7yt%nACyO#OEOF?d17i?q9Nnw)=69u*ylZ=KDQ1afh8FWqyX+#L z?^zk+)L8-8jm;35MRK+W^-PR?*B zxj6uZ!YZpfk6fKt)y6#xi|Y4h>0@Kgaq@C+O0Ki%QI$~09_7uS?$RHPZC}NTZ4I2=l-t5>HBfLz6y)VMY(%79+z*&-cClhb zPS8XznIbDISHJzS{ft?-F&tsn#Hh1lOfxnO`bGFkFBQxMOifleP0MZ+zbQe+7rk_1 z)aRD9xW$oXn?tj{vv#xGMDC7}en`r+tW0-8rG-|H6roL*Mcop$tEtiR@pp2~7SV%L92ns??Lc97Jo-wYj> zBwJ7lMpTq`PD=Tn;GUKIJe(SR@7f>dDd{QgGkbEZVlQ^-Wtv}6KBl-up71JP<|(eJ zPjB{%m9d!qj!M1TO>bXvCZ|g;=w87!#z)_*y@yZ(7TV`#EOlOqEE~*O(VaI;z$U=%{=FaE_NoK#uT;w%bcHyYl)&89O zoi7c(q3tWH-S=qVjm$tc7f0JfCsg__7}B5CZal2$LF6Z~c~B2tdq%01LDuyMG?W1i zxKJiM;(^0oOQJNy!pb2+zJwM-r^U0vT?!EG=d$p9AooIDRx-@5pifVyPy+`Cc>@FGSLfyvl5A8$ z>uE~mX%U=2GPi~&-ZXts{B*rcEL3uDoUDClDYCNKAFKNOvBVmC9_OK}^eXX0OmXY&9RVl04iIuGUE4CD&;;pn6c1tVJ`!OvCW z$z@Ti#ND6@7Cvmj5dJr2NOXxdmrD~0fkp-#$4{3IATWki7=xhC;cb5}TSVs0xuq3D z@5(wZ1%-S8@I{mSLN@v)3qd{~(vJWJui$VX7FFbyf!&C?ZQL1CD~wf)R^2jEaF-h% zg+X|M?fTSqT`%NoOj7|xF^pc+y9zUiK2|DC{83%LmXj9)=E~esOnzV4Up^nqW0j1G zQ@-Jtrm6Z1i9hrDo;`c?uw;jimC-yt zto0cQmDy|dR1nV6jvxo(AC-lxghKL>QIt^p-ms|!4}kuRC;;if^eNy%xQDqm2U)rB z!fG8ddnQ8Om3)Oc2hjw~A_C7CS^LPrcev!)IAEr(vnVoMWqlLvZ3S4`#f{l;XL14CRYjJSU=+Uq~j57Dru$Aq#?F;ym4r6rBNsG+9}~>ntHf ziw3NIuE-yq7uf?A%^Zd~g+c&oG(a*B;N_)!@k|a2ZDzteOPsm}z_fvlV@ORa4Zls~ zA^?0nB8C88ffEQAxdO!yP9Opp!YdR2OZ>*;DDP)I#4{|hi80SxSS_84H#Jr4Kg6*P zgIW6E>8ILwR#d_rDm=f#fVrePa|xd<2vc3^c@sxH7lO6w-?qP2D^ast#$fRKx=+UN zGnx2gVvR^WbHV=H)g~=>o_=JQi1Ozf z$py1Bg>k35gYV`KmFLKj15hqniZj{>EalvyRad$`MsK7t#Cq^JVerUoMqgZ0 z_PryM8=1w2n=&w%xZN8CQ15Ft^!6W2?xEeH4L`21w8z*C9Qb`v;Ug8TO0mdP`iZvD zhBA-eftCUq^i_}8u}THNTYKfn}!0r zg2vzr$st27vc;Z!8vjZZhOk{o1?-U~K{x=bcZ^;xBIDb3qf@YAswu94EDJN4u4aT3 zQIRu~0Q~2^ho2eV(SEU1P<=}C_XDR4FPwXPt-EByAuHoNdiNPGo7d6^&!op^XX+;Q zwm%58VlREE0&|Jbi<8#!1(Z+_(v?F?l0%6dh?+jq+v0ZUsr@M2+WKdIN!r6Kvn(%N zSpsaN%)yk9zMV|3?xv*vcKpFKTV3*vNm_-ftg_RRmO9^IzUI>0plwneRZCi-=loz(kIF~=jYfV3)mkd|WDPFZIP9Ih z=wR++XLwuZ%Gm1I>v4j)$GcHr(!Nszi!tXG&86Zk4cZ)2B3DQX=1$SC&T7j1J+Y<_ zKdIgvxyykRKy0;$bXQz`N&WMb{lGVTnI(kz+_99jTvk-q zLNcsoRHq;53lUEKiqP~`o7cv;InI0Ol+dCila^RmOFT3=NXl8{Tu(g}Cr+tsk(H&l zhR^j~==!Wuq4uEdndPh+Ksba$WRZP_r?C(hRWG>wMUjD&opB24Z`7)GOD3J5N;vH9 zv+eyI`d_cMPr9T?X*%p#GU#g&KRdXT2HRBSOFmp{7v7%RFZ;Z6Qnk$=sh_QtGbxC% zE4rwpxA)qg66q;IG8!E!QIST8Rm?g4qT5(HEkP8OeQw)5k0lntuWZ|6j6cxZ9Nl-& zg?bCSm?$&0Ye{n{<)yx&Z=z0Nuf*BT9|_rMzwf1Tp|#debI=?=ETh{_bEeN~SH@Ip zO6p`zsJrXPcpde<9Ba9tcv<1<_$AF1dvs-TC=zQKf^RsA71(Z4QcysfW;q5N2a-OW zs2;OCM*rZ0_18XLynI?J&Nn@u(;g8udHXp8Q${R-F8FN8^)=%{_w`K3`V zE)l(L60GEUeyrO|Mx^Lvlw^LN5F@E?k)gULbbtPexW|zPEvJiYh8=(gDKuVWIA9v7 zjpX8D{Zpg2S#n96zwPl}2&}2*R`-uharEi90^m&lkfw5AmI)v75BGxN`LWl-N$o?2 z3=U;K{oJN*cII5tVGZdtrH@ri0u5;RGgO2yr=f*)FC6Bz0g|?mUO)KOSV`}rcU)%L zIrEFZz5|RlNG`UyYDea^C5w>Db8@2+$;&t~^lE%;c4a!Z-$+mS`q%TpSt!QD5P1d% z#5sz#v6>bfeY*^pUoq-9@bMaMuKWT;kVg2i94}(b&bO;T!-&^a7A?xkCc+_$ru0s*d%wvef&Tw7Uob7}#~JW|3n6PeQreUUi(o z2Z(Gya^@6s00eu)Mk){w0AxIu_RuG{UlE~H-U_LTSQ{@t8LuH+-m(k%P}|176Lu%M z>5>Gufk(q@1cHbLa*fRmyyQ9pfE%HGDOmDbJ78gjWad2&m@XEinf=UBsKhdkdl~t( z*(f*j*Mk%)Yi6P_c-L%E%%N4?CtKc5;rS+zEcRXSXRemfLBY#Ip6>9#8J zOq*aXah1*8M1s6|!9Pr@Xw7rV!Wz-@4D?2+MM;IR#qvYEWt}MA)&jPqtCT9yYZ90QdJX0NGdmo zjymx@LSKhI)5ew3sfE?VQ41K2=R<4_2pRe=1eVx3Rsd6<2W|zyouoguUa9CWtU7x? z&71b2x;&E_a)ivOX?w-m?J9{c>}))Jqm*2ZF{i`1%pT~8<+%#QQY7bP9oFj`7kJf%kR6^CXDg zL0!<?uP8%Aj<$SeVi2N+(<5kB9*AHoBKBn-huu64AC^AvZR zx*F}&dA7aMctdzp!EJ$eaJn1)y)m452eSe@#Wk&}=Lhar*3I=UA>@U{u<$IwtRk={ z?%+A9^Ij4$%S!#P5IBVzt9rv2V^T7diY(e#NdvTaSXnt*E`M&|R&Mw?zHeS%(}3JZ z48v4pWkm<(@v;T?X7zt`kYm&OUZJz;v!)@En=5EQ6EMw{(VeANTrq97NADr+AOInr zAp{i#oqAMcY)bsW#!aIQ#=~aoV5)Hysts%|!({*%6@Ws22aSN2D_vnuW2m6qdt?}4 z3wM{4MouAX`2GBG1O>+f&nLITQg0YNwn%z0e!|IxD+(!zwI_q`h4ZVCzR@vN6vJHJ z?0W~rn`2MkpPhJIitub?i0-fH1U&0ZIO?Mo7ubE;k|_wtP28KyB!3xhUd8=kjix?- z+t6DX0)0#QD7FyFz%NS+*p7~ukpl6=oKL3-q1S3;gmH`yqCXErA$I)wH!WnWf{q>o zG=&VjSw8K^c5@TJw0Q_B-m&8qHSK}1g=f{ekBD`x$q*S`$7PRVY=96U&O(6si2qSTCWflPta)q z^&r4&Fd=YVF)A1E20EZ9nMZcxA$Mjr`}{$!e){FOUp}DO<%lTpfbL#zn2~>~CcCE3 z_)QI$yS*gX;+YOIJ3+J{q!UB@yCa^ z?(1x|?rkEp(Qfn8ui{x@xKm>9w_XqB9?KzGkA~k&ZN0F7Rtb3sPN=<+!a2)o3>zJ3xNwQ*d9eDqd86=M zeR+Azm5N*8Y$og*gg{pB+`(a)QX#M)BDA=Jw7q+H$|gE%u)J_VW!^5_gYO()Q+xBC z&R}Jy$+C_7sTv>)+uVbKTBcGBsfCoDZQ5XjqVRlz!hqJf3O$ z(rUl?y>1!5b>^kL0ew-SaNslDqi1>6 zrn+%3p0edYf1Xh`^6Y35CJ$pbzQw*{_>yb}_Do(+4n?|bHlv7!XE z)j7M?G+f!%bF{8pu>VzKUjSXrv$6BG^kUOR(s~)xyu@3{x@;@?7``AnYt|-g$Ab$NhXE}@YGVAs=OMR9(nR)Mm`B!h^rmipJYlGFS z&ULMNeZ{evA-b}=(bV)Il#i5ryJJDG%#sZ+Dp@GVTy!A0U79?@2E2dWgNiq^Ux;b1 z+D+0o)^%)JZ)g)Ryj|Ud9{98xb4>VCLPp0*TS9h4XSYMoh3!jKkEV3}HKtm1>Eiuu zi!NzA+#K8(;ka!uv&OENrVx~RFosPJ>OgcB)=dG|vCq_uUdA*pa+XeSAeoTPDKqGHl`$|8Jm>^p zUy_Guv~hscgZ=F*?~vk7tPlH2(40$L2^G-baUSK2pcuoy{0gU=*uILnS3{(6Xt$zl zJM9+wDec6F@$W&Xc0i0{Fa(>{-KPGQ)#d z`D5{epJjmbz@Tb5G%7?l(fJ~ZW)zoj)Cr%F(x5YV)B;ssmAva0dHC^ZaoUba6D}BH zg$!WQ_%O{X^ALK)R^J_je%kjK0kCG}daInGlThBoy)Y~oBsVuVy%3}TFn?TNl@6DF z82hQA4;3f?dmyUCby*Xe%P}S2<_v2iTpk~2;`J&_y^z@w#l}n+^8*+;`DcoR0UQT6 zIAOL-`Rx^9xGZ&**J3(*q$!swK!tYfnod*qmLcH!BRVtO*=EbZOC{5?XGwkfz{M~O zCK2wj!B=xAmF6lO!SN)eg#eN)Q>jiiU#270pt^7IvSQX1$0;6T&7{XUmo|BM`He1B z_cyvz3^O|_8&7FUR;%@^a#p#g^ZCVsIToMCWnMd2Fz{;!#j~j_DP_8rjMq`h9BG#B zZ@{gsD-?yuu8noyUvwqAnUWr5P|Z+Na^Mb9q<+OXR_3w#-Ej)C`Lap|EpCL8Vc8Ey ztL{X$8*eh>x)TEtV7V7LIbZeBo=;))*p#Havrp!}IejRy;>_)KRaUwcaXUrAW&3^= zwjD_~cgLYL#Qn`?j;`}%%8kvTsv0P;z9}@qY2}GOiNYFn)fGy`>pvvC?w{HGPWSSK zZ2Lf9VCD1}l7!riClZcQou@ziP_zHTZOc{}^5o`K)ON`+hiCnvUd6yMu;@PXW1&l@ z;F7a9j3>QtbO7;ngWggXNa###A#z$PJ-4 z2L+UV8Cuxtb=$7qyeD)a&}yvRI5qjpKcXh~YRGym-Yc(TepzLHony1ad52M(S8^Kb z?_Dsw(|Pb!UaCr#+Utk=jkQk`$-@W;5E`sR8{=4GYu!j>@L}}wIgPK z)`rbNfg!O6J>b4~0SQN;a1bVm+hB1M8 zs-7K)qrf4qcvY>j$cgL;cjZP+$Q({UYZO(y7%&s@c{+N7II;mODxPa8Cb%Mg2fhblI1(dJGFggyxriE(u2JIs^MYAh(@F$r5wy7sONM2)P-y51Aegtq#I%tJ zp=FGe%>iT(_R4PQPGy9a z6xCC`bS?30K2ULdTa>R7gFoX_|NFIHuk(qmF_Jpwv6JboMYXwe)|?$AGogPt2~{f1 z>rS|?ue#2H(SX|Gpqh-9F z5QsbMaK;;sh{S7byg43O{PXL6U-Iws7q7MeoBK15jMtO{;6C<86c}H0i|;0IgXyla z1a_c!fuRmZ1p@pQ@X9sA#nCYBN!6|1PgfC37P;1J1b?9G<_PLR&;Rkd-w%^KO{69y zB#Zq>X;D!JJ8$<9xfqelhn;mH}jV_F=!v_}e!O z5-P;XK1YuYZTosS^Yn2Sp{>e6^>&ZU-=Q(u$G09$Vf0S6+b^W1VK%o2FuZu4KS2;g zufT90gG?pacYsSG09@hZ1K^KO7u0peL{6q)Ken&v_Qx*Wx*P%X%47sr))4LUfz}M{cJwWA`W#6&HLjU9-J3gSm zpHn1EzJ4RiG3+y+7FJundGPvx&yna1HerZ>F`=^tK=it6{d#RaprhJJ+mDdj#$o2% zZS)%vtD?<@79`z2=Y|O7s`NFy<>2K_l|#sIjtj`{$Z+<#S+g+sC^upRrq5Yq50F48oBgbKgiQziB>3A~pV$MNCf9hus| z!WPoj9JqE}&SSRA3Ze61`Gecg3lyzLa%ViBnb4c_A@&FimS~>cBON_NwhcGGp4yZsMvcx1XNq zx?M1!xixu=C%bxB)6?qlx#ic()e_E{5n*R{Pwtqis=rGR;Z~P?$=Ss;HQ}`4rYNP@ zgXFdm-$w1nRkET(Ur*%qXj*wFUA{ljGD9@xT5qt?eML@Jlg5 z+d*96Uk5pe&+yMy9UQEcb@%+USqBFTW!*hu!)$T8;yOBF-H%_=5ZcG>PMtmN{p%vF z{k_hdHdNOC)%^dv7{;&r`)^_x|MqeHXEBU_xrmF!Fn(Q{{y%Tm1cNrP} zZ!wI26EM*}KsgtD`hv3dfpcELr>#zV2l|{=*0wnva3i5wDs zi8PjquColel{IH(wY_}F!r!*quldIfN0mPZwzU%wjuF?1711N6R>`iQJzb@oP7uyAl~wbU*w6lPYpU`c!N`~HSunV;Vh zzUN-h>6rYUpN+(?$yCEfiErPiAcq$(Z^^%cc#enu{s(vV?coD)38#5?{rs=Sq|57% z_14`Zc7}~NuP2pdOZDacXp!kDXf^xxD6S&Y^Rl(;pZF7YODrcH`gr(VW!)G0jS;t1 zh+3F^_6Fke;3Xve(tX%9)2~z$neQDv_;eU;rr;~j-t;ajA ziqdu^ib*%mT{_50x7!>e{i0^U;G3J*yn&&dIvU;a*Wxvc_+8 z`W@RpGy6>vXz>hood_E>Ub*K#yZx${3mETQWiK{;1aUR9~v5EITFaN>PYU}p{mwbj6X#roL^ov6EsuESHz+D%nocGAOh5no+~xtA zDdhwtB$O~`b5kacb^YRLJb!v`%S3phjFf`x%GMFTOG-rfcd<=Xvhu4@?XUN5rF-&`vz?`XxQB#~ZcKd1dZ-Ua0o2N3F9eW#qM1p+`nqg@%K7v>_$_G2emy z3R@|)rAOKZD6Hb#m(>)de~SKc#>sr|dFlJ3k!tdasTVwN>Ir0f6kL91y0s5Oa~#4zaPb#&lj0*k0;49`K0PzxSp~N`z$6R_Pbve zqq8TVGyF#w)um@Fu6R{#wpui0^7n=DFH#qOjbr)5FW9(i=C+(Uc5_V!@ghWVkCy_|P44!aj+kUY#f*Qwo_hq^DSjKh@xVEp)ZDtS4@XNi6#UO>sZ76_ z_C8bopl_tO&VYUOG23=-#wFLl$q`JCUo@QT0U^# zyh(T{!Ts{@)l+Z&)|#^`miwnP>QnjDpM+k%qemV)$@LtUza=hiQGMm+z*p5Ty|w+( z|7sl&Xu1+;+>mm|UNjYm@|fJFNKpxTX8F8MNB;WycVMDoe@o$pz9jF^U)+ONeGEDW zf7#c#KT*yxh{k#G)Jkxoai+Z5v$}UM5h>Dn7nr#R3f`#};AF#~m`&-w|4PLhe_pbE zePbcjH?z9CzI9BARZ-dWCZ(mg!co4kYcw%Uaaq7dB@^Xv_ny1zuN!Zt`M$$p4{vGe zWbQA$dY`fHg_De7w{(a^^GPE6HhWUrLN1R?+1X-!5x@0D8dhi_1M%ftV!Rkfci z#CbAmU2naiNaPlx(NfUJ|3MNwfPA=koAg!I*S@(2et7syGOG^K02mU3e`b$osn z)Y0@U`#1lSR+h+Ptp< z#EVq9zYS?@c`NIqU!#0~?+usex!(QUkVj#RM-Z*{AoJYD@xK&mH;+rN`38r)c^>yv z>+12B=BESOUuc|bDzr1x8o6c@OZ;MG-FY%&e(l7AHQd^_<9{W+_xSqr1XG?T*ZJo) z4sWrJrD#F6zy8HH#R0}ny&u z(Wvs^v{ko2nYCK&+~*&b61DF+V&`X5^(`MJo6jINcMr<{A(rEDLn^51-Ur=CPo z#s0rT_nG^D4vHN#H*YUPsmebk$vOPtq1NGkvYN~F9_4-*F8C_O<@-nn5qbnfqVGWUnwrYH; z!&BgIj4fysyJ;WgSGpbW{ri`3i9;H5N9@0d_1NS@V-)1ul+WK*BVkT5Z2xQBBYRB~ zMx(VfF7Qi#C5DaM4!t7KX)2K>Dm?XE_5A&w-A99f=E+jso}h-m+S&hn-Rl5kd;VFc z3Jq!HxXRD>W#hS5Bf`!f`|1*Rcfe3!F6&R5`*>*7^jRal)W9p1e>K^P1;Ub7zonhX zJ2qeA#w^|v?Nu9u2b=jsj?Yx0qokhlYE*w-R;rSsm>TI;3Y~oH+WlDdTijF3uiuS+ zMX#@VShb&jGb1};9U_!pH+qp{=BP82Wm?tPyKJO^FNsAfAz5ZKf%ubxcUDK zJ1VntTBqJz{J#od>i!P`n5>e$U;b}iW`_s=*9ZT97r^NK??`50VeRO6&g;(qLS+K# z&RCyte_2g^9o_#w1Teaqn*Z+tn4M?+zX)J5G;LBpp&K$3wA|7@Uz$91G)`;JjSHHY zqjFErJMb7jAWRasv(@8Q!Df0|BtbpnDVG9_)a-MvSX#q`#lA1R_(oO9jsXlnRRhlE z3=H}o0M6S41s3*1dTL(B@sBr z5gkaP{W879ChWl}#Bd=lWA7w#=A89#4gLEgPoMJ5uH*@BOAZNYhgLptx;sfB+#tncq48IAR>ly^WM*K5d^&M*q zQu-Kx@;GQ2_L2K`lmvxfBRGJ&A82onJ^-jfgD5kUwr zu@G|~%A#$zCE%>0xd)u29j=%Mv7wJ1JGZE`1PI# z_b}uPLuJ5h`v}1mKOhPLv~||>j01T5eF%~h2I|@W z>P5YxBjv(^A%r04p>FWZ@$Fc+fsB&YX%VpPDxOZL4Ft^XGQkh9FtKj>gba|y$k4VV z0!Qas{tM(!`OD(e&JGpY{HU8A(O#yoK2C%Y1fTk1Jl`Z`(HTzUdFfS9h%aKz^8 zpX5^+qt?yst{>6o8euS8#;hyiG_~s?wXs>z3<8Ca8a_#bV{J2+NpKA`6h$Y&RT3tg z4m1zM<}?pQ(DOe_g@BKivlpYo7XY&ObI3V+A%x*gmt`SakFVrMx5sF6NEv^1S6!L= z5Tdg5Izz|zz0*FIRD6a87AIG&%Rpcm@64QWMNHIM{lZ`{7-jQ^ zQ0A>xqdWPRZ0?)wwTF%H8s_p!mq8FGvIvmVG4o|;-PFkTT9^?69O8Jz4?K54tYTsT z2iVAxuM8bHXfIREX2AxSZosrf94*yD(32^j+*R#Z`+5eq?y{LMpc{E=vMFG`84kjP zzr;>)AquSc;q~W;4I{wKDI_tC#{ppQf~7Mb3u&8XpB9>?O-LKGX13!Zdp78Z_U#JN zy8))LWkjMU<8t7~;JiS<<$x~hc0e=(zB z6L6qD4VPK|Rhf$uC*nut&y1IPH_P04uo-`MR2i_fD$~=50|AlyhkSF@p=r{|F8?*| zZzyD0-h|=GW_M{MgBFctEkG1NxZm_uep|6&-Ul_-i=MRc@*5`P&nuk7%^d zd(2FA2jFaKkW@$d+T9*S#Wn-`1(!wcmiV{HrzC}I&(UvWD^i>21lGMWeoi$6hPg=Z z>Am*NBSa3%ruWA;Hx_J?IpWDSD@@_v>=aN21Uv+WFLPl4kO0|?&9`3!w8_qETGNDT zK(7>jm%9~~y$Apn`hBCRD4c$#`60x(Tp03L(GT~uzMuiD>u>>^U`C)Xi0{q3CyrH@ zpSs)8Jl+bx%yu*zuvoqS=GUx$dsh#!r%0!wz<4EERF^R_V#H!jHB+pkR%?{>ou*Hp z=WE^``x<+2YOm<*{*A@mGLU@;?OVH%ZC`bee{6$9BZ-H@=G7k^U|f=82tsc4@1j-7 zUTju#?E@^;Z9{OQK{7cq4`=3ztq^Q79!f_{CW0#RA^;=ia@*lAVW`8+(rn;3um}h` zQzfV&u!v7wgzud1-cp80n}pEdMebzeRfPIVvS*RRS}p|Lo3&fJ&VFNpxI=P8V;sYk z)tiQMU8USZW2jn`3t$GUbdnGq3Jn6>^Dso{sR)5)nA(=LNiSJ6ss*o^P$}wnOAjZZaM>dyXFt} zv{hnzYi3|Yu1nWDbc|Jw1qy(tgl_q(<}=cDyMeeo_OWcmDCzU=s<2(!#9FSWlPQoeCF@`h3l^Us?u{+HSU=KdJT^`po0 z1AkwxRycJ^S=KDU+$_?aC(qyDs*KN_hj$(JwNb1j5&R=`9#;9+e)StP)0xKUnW$e-23q?@u%lzV~h}f(Pi0sZsgsv!1=qF>nL0e7N*b9#<%}_Zh)a}^q;ZTFzr1U?J>iPa|<#s``~f$ zTKsN({3EM*GiZZ^v?3j=QsIaRlU+@(_D4tIF&6*}0hR0DCsW#@o3YiALR$v>N_pBJ zEoA`MDc3RAr@4TzkoXF1SvpCf!7NrK{U}F?;Sd^mMBmFG{>=LsN77EybsWRtY$TST z4r@Na_b<{o9L6oix?9Hy5Lpl={sR>O0H>>a0YK%izfn`Yv6VL?^VrQ;>WAi-+8>sp z-Gnw!|GcW=ew;rV9n&~Pt?nAr=hetVp-@ap3%*g_@X@vY;6VHzV&HascY3gC2maO1 zY6=Q5HLcFtpT5nw3MC1CGBvHvTPqBcTiK*Yo5;#K-I?V(cP>X({yV<^x~7=S>XU(h z(^e-9eU+0gWAENe4->)9?*7~N`)h$+fB#c9rHN7?P&N63ubwy+oa$4fQTO&{>ap3N zi0hi9*7662>2>G~UBz$cYnEokKbkHaqt>|2v>UZb*E&YZ?I-r8`!`*<) zD)&pM&4IKRv)!h>v7f^=r6bE;eC;>5^dycPf0ppd{7T()Wp|W4z4?4mAB9~$=Ie;* zJEmfHRXDjP;lgpNYZFS-854h{tuK*|PT%wq8>#CQ$1P?frzv8)M+b}hrzhI2CDBES z_%DIv4M8`z zTfL#L9O}3iSj<*JzzfLkll*9%UZ#w#hpXU6W$cy^)s(Wpr(IGha1cni(0k@Dj~q3d zOvMcbBkRpxZmMC=wm)laV>v(2zNS@1+6rt`{B8w>lJqA7N9;&bZr^Vm&!63I_Rz&S z&4r-rcjIoO7f!*AhC-owUKAI<{m*n@_Qw?ieUyBIOKQZw*QW<;PDYl6_qbaQItpHw zdoFqUqI?wSbKK62y<+1NZgMF`VV*8 z5k>3;9BQrRJ?YaNmbe+&=||#g?^abhdAMDv&nGxTjj)<|S4KSY#t;c5n&x0+*;5!` z(zAW*O!{nu%v#U6D}`E)**5#!;{0yog?fJ$l>y}Q-3vq(_4u&|(TphG$6pRbiWIt- zeiKA1ANllJXcw=j`7HLp1-rAwxX9;)>|{BOcdGg~#+n6q@@gmiTW%KU(?Foz@J+#R z60LM*ZAMM-)L#D9(1DoNwdsi<=nep2e58A03IGgyLxw?PgYA@9x&^2B!%l=b8kztA z92qSRSr*iT@1~PTOjbw8Ju0PxS;K{^+NVe4sND_w>1DH|riK!3H*@2RMOxEyp(Npf zhw0_8j$0c#e5!P0PWYupypnOe`Lr1Ib3$NQzKfSe0@^YoQYq71b+dK&mJ#uz1z#en zr!C{>S^YZ}AAQcRW$nH^mHcw+rc|j@38|IY2|N(T z3V-gZlX?=%_W;`8y5s6!`PU5#Vk7l0&^yi_vK;&sm~KtlPC<%r5Zrab?W&$FT*oGO zK@^GhA@Q3z--4Rgl*_<{ilV@e`Kk(oyb*_K_Smos_QyN714$uMwPf2XT?YGzTzahd z`7W)0xt?V2tlQ@>T5o1JF#EHVRra8u42ErmKBvCHiXEwv zecF2nyoYFWrm^nY?x*#Gdk@fCX|3Dp6y%%!P+45jtV*eh6UJ*u|-%28p8v^c2rc@610;%>T+|jQuhhL*y#anh%{-dX`{?2MpC8+nI^0q^%*aYEDSsY*mU$s87<#XsFhYr3k zg*KOe{r!7z>EXA}pogrVkk6m4W2;RG@l2!+BfX^7sdCuO$|1y)QceM@B=6vyc4&my z?)*9Q$r4ttoNHgbF@am)Y*MP(b(Gzf@jh)FkHyJAJ|<>`69py9#3D~0CiF~4B!!+i ziJMoSdBi4+eR*VDJ0E9{LP&GQ+yEp8X^)$B$J|7pJ+WWl9@-6d_ukHtzv)s@pYr3j zrvk`sX*h%$>~jfhczcNKfcr??GhI^?)o1U1|5L{CVMB51L@k%wXC+WM0SmhSiheKH zGM6VA$p&LGrwiWO{MmYit%mwEKJ2E{R-f4-sOP8c6Kw3{DXd7O!Iwd=p={@kxR0I< z8zgR@Y5$Wq{Z;Mv=FP162QE5<#qr!v=&WdK|K6+$;&rp8t$sWwsSf`-RJEn!v_3qR z9CU5T8PFnAS{$z=IWkNF5{iud)~0t`{FhW%;&s_`xiJ3hmIyNb=UvVY0Yu6rodp3mz`qGsk z=15VW6d*`zzs`{CYwQ%zv12~UlnP&y1%fa%Ljz2}Vn6_NaK(X8yzW84FWusm^vTqu zo^F0U<%7X~qv8N^r!5JFF(ulXI&leP zyQ%DX4Rd36-&XdHnn?!GNCX6qF{!U2gny!umLAiqE5lGIsWOCx_$$LW7Ug6Faod># zVPm_vBK95RBtb78ce$Melg!TG3j&)nG!3LbHYE))S!A=RS<$w2Iw7x7VhXODlR|MhO7~7bJa8{qxa5OoIuLOmX zj%EXjCQ`IBpku@Y@uu5z!TS2>@`;WUxKWSb0be33226M8!yIbVM2RFi?BWoTOAV?e z6pzTu>v>}Uy>=quOl@VhnO>5h@4^vY{G(#BxqcuDl~Et3fJe?^q%X|KfXpzNZkY@n z$#lWkmK47VbITh?Zf2JjlQWVk6B-9_*BU2GQj%N`3|(Q@+=9taDeWNd0N>8uJyzu?f;g_7d%1kq_AQ|2YT;898$suXuZg zdI@H0+%Lf@g3{ovu$(~Rz;Uw57u3x$;s|J`vsU9%lpbqX6@Q!ia_YS~zcMu%rwArw zV>+57^F{wy9MdqX#C8#&H^%4AgxeV`0xu|8>Ay~Fg1EqCyUB9~=*d)4ngFkn?l7y_ z9ja&3IJYdCYbuZx3;-DTH56Ss@wzttq+v_=6cu~4uKqcR<0hj@`8jGfI}=}%&IPNW z4j{ytt&d1PM<_1JBW9A+mkwGnzjFeFq7`;5ngnnGaM=uFeE=?S!P<(@1}Pr^I6bIR z2B?`3z$36x1OW`O9kc>a+vediGfD{0tbKJ#R^ypf;9!)G>wW1WAfn#dAh0R6jSX2c93T??j=bqRtn^R`toipzZf)2(S+w z0%TiZR-?xtt^@?GgbZ8*lkrOqg!%kIy=Z0!Tc!{iU+77FE|7PGo`qnXN*F~B3TS?}jLlg9_zKcZ9 zW{2;Wc8eXgTeuTKu^Y(>$<7@LQvCY;(S#yWI8wA0yo`STcK=`m4xDPV0nn2z@8IH0SctdogWuCLR)m_m6Vx|u&OTY$;FinONdpg*_rpEL>{ZK`! zq?U@t{Wt+7O6%N5X*e8Efzf;r^AJ_C(@t*N*y<%pSb_K>;A<;|`1hB@z zi?h_^cgoCdA+xDdM7{s0twtEidolPURIWvS! znyn8>Ion!VtRNs?jZ{@21MI_1IDkM}IBS7CHl0^~di}Y$oThHxgsa-Iw(0hj__CF5 zLVSkhOE1=PSbPZl4}T63zRZLl4mOH=>A0(Y;8PD=$SBpjfP=|>kRqUMBFR$|+*@l5 zKu<>2XWD2a@JgeqqWzvm+rCp5Ju`xP>N^E^!#P-5nNsjOl)Y8JPvALv+i!)IRkD{b zWD_5VnoPyzdWO8tXbtV_UB;$pp>0#K&$aXObT1^IlqfX{SWt@ z(qE3Mg4ZW%keeh@k@0X{7AA;jtBQ+yz^+_Gp_~ZkNyTLPQ1qh=`?{MM{%(tZl1yow z1c@88b5vUN&9F;dyBf*18ugw2=Ljnf&1Hkt3d4cggy6C(p+znTHoxaaaFJXtnl-?Bb#%ahj? z9v=gN_Z@Nk5+ow8;mdun>$wmt{lP2k&SQDoXv+)MTl+2p4v7XY5|*4Xlq6oXMqD{G z!tTk0+YF2JpR;8@j4U~}U8l6UXe6LTE%4=}C`(@oYyumQojpmoh4$4WPHeh1hoOyh zeM&5eZ)Dadqfk<+32Fk{R}9fmZ7o5#-A!gziG>;GmmTop5tf%fG_?0}BRg^c6nF9n zE|!5O9cyU$ zm5k(iX_IVKi#w&agL@m}G54TO8OAM@=m*@*8TQ-2m)79`QZ-GTb&)3P*uHwfvfGm4 zz433;e9tKe{}!9evY*L*;;%cOc?joW@|{`GFpjJV29=#%=S}OW|MpOp-hS8TMo z$(3_%XpCz`9;sKV;@Oo4b5H-_e_~c<6FoaCcvHJjn=|=h;o0NK_&~lQvGt(g38lP^ z*WQh`AW%MKIm^I7yVJ+zzWq5xJ2~xvWc!zPa~+N6j~i>kM#RspYs5b3ye=Y+3!*Xh z?I57H;qIbY!cxsC^W6eUd7~;kFknF&sEH%+tZ^WP1e3^EI|!L?|@4 z?`y_TTG?~K$Pxvc$<(_dr!?dC+MDqd1Xm>5?FHPehDvcEQY;!s4d z$>1?-!>mLZDqx031+KtKG6ZrGiCSsLYS$+7RS)}Ih?0B1bFPtj{#gATFp3j8N2Yel zG{70y<(oyIt)I537i+%9t$_%h$5vad5g<0uk)+j}1{Eaj@Q0g~161bn4BhRx$(_+QS0% zN!i`ynEIGM;S%6mZu6A1bhi1Pw#o9Yv=Zq@Wx8s_qkr*=yWeN&V{Nctb3P5aZj zRqeo)x=bdgUl9)z7Cvz&dOmnk0Nk+!t#;y(Pl79gTO(CoY2@1S96CR(P+r{nxJIQz z0_Lh1kVaf)s41bPS65N0;QA@wU_6{ z>z^kk;_-Wl?*d&!bT#Jz9dokwn)*ej3^vMNp3H300Y0Y9s76Z`UEo)9!R_9(;IP_oce=7UBpRXeC z)|sQ?cQvK@eQjB&UasSI?uDbL{r7(t)FZaOw!ILFUi2*vY_&rQU%O`wgq=)1gRNF# zP;)N5TJaH@7Rt!26q9u96eMSx-xaZjFHZ=r*^iFy6!L_<3cplK-;c}V4N=2vG;e1$+R64E zv?bSxnoXN575Hb%qXW|p1-y(7oX_3xVzSD(puGhIc0QZy7t}zX6bToPe7b7;^g!Z6 zF$n4Qn50uUo_XR>Ew-l{+8~htSi7maRxT-vx6u~4U-YPL(?6FX0{N!%xZKsRe_k}I z!}K5^gj;9-h?N}vNw2OX$dExJaNbC1+t>;244)Rk{~Y|N5#KhwG4y^c%$l@Ga^{%r z-4Is;EP!OuxPUe*3s?jSK(S^%@#t> zETR60N_Z);@lzL(NKZOsE-$YDz&b1>Ltq2ak{Zd+gyG$OEHJX>wZ)iTlI?&OuNUuV zd2|bD2H_)Cnh;3XJwdIZH-SId|%gY-E zn7=+FCSv7&4Zq-UT~nt(na`|X_m$H!=?X7loiqK_Z2LoJz8awLgemwHULt#6S#fe*v^`OuP-Kiu_J;)+^`=)0`tDW&Q zCQ{VaXq286Ta~T-AI;JvUA^|g@)qx+hT&O7P&7CaE3cG?d(%wX15WTOY7th=~}>B_MZ8N(PhVG}Uvu^=^y=AX+zM#n-R zHu6*x49Bc}0F_%kGaQDO$?~v);+blm$c+1>O>j3P8wOyM>v;UpggWHY?dE1KujNYG z3UwnaO2)R$ut(dA!>S|QcNSPnh5{f1SY!LM!N$7?lwd0W8eBVz_q$)lr>Pn^GWi?U zMa>fUg|!c*BOAf#b?_p!QpW$Rb8~rQftx2eDcWu zI|5u=+{v$$_YsZ0-guu)SRcSIJpF+~@gyeDqe}z>Uo<%NUb%*!2~RE)#fZc9?nKj9P41UOLBgZ`1$)Uw0PsL9`-tTKS3r!gw`pb z&2dtxh)&f$WyDjc%Ye%~=sS>A%($48_-M{cefqgmcP6$juM+IDWmq48M>^rlS1!Lc6wCiOI3|3c zp!sU}ntJA1vfrzf>O5?9#cS`zLA{#~Bl}l+zvzmk39;9O=C4uH$WwZ5R#vagmsGsN zXtyR)+Onc6%a*d}+nTRsVUu)#$m`oN6y7+Z6$}{$J?E~y-^G_e?u;ZoGSc_$Z}Ts} zE_&AI3C2KdRf2Np4DJ#2HYsB-J=y^vg38`vS9 z+KS@W;u!`E9eR_yTvIY=*q{IwuwFQCGSkr-oA;414&f~C=JPp($3Dlb5DN|*JN{D77G@9_oUYf0TUg#(-c79)d4TCj zhZcbd*lvLl2|&>dl(@lsBQOI1HSmXJIV*fgw1l<_U@(ku;uk^{lN%bs+%etFcAZoK z?E!3FeS)Pm)Ez|tfCM`u!HujoH(U%{9gye6i%;i+mWl8cw(R-~zFeuj`5(lB4Cb!K05F1N$6=6&&>Tay+1v>Rpp~Cy1Q)WRcQEBLD_b;;e zXu(eGZm!*+p3i8}$+>4k!yQd!M>TFd3exd}5nGyF!Bd~mYp=7&w(2icUZ+X4n)S^?Bq7hYu#2f+P##;h2mnkNXaQZETOW3R7q4cdN$QX2QvY33AW_90KUS! zqO$PFL#FR-d6ESEwZ%8>vU2uWMJXRp=WkWM4o2r4y>XR|ra2u&ka^_rEXJwDXDCofrYSeV`p+oY}m$QI?Ht-5RX zpIhtn?dD#KtSF}zBMj_8K}g#j9tWhPg!tS`GUGo!Je($~JABzzzp?#;lDDl!>wyoV z#x!%_1w4n;z$Sw+Tw8t&TO4W04>4QkEFv06EkOV@_XDs^V-zfWnR}vhG@PPh^D*#? zprT*#fCkdBC?2B7{Iio_S_J0PnOftd&?3opLFug&-PE-f_Yiqe2(jA(3F&*2n9{?b!yhsIWOyeVbdWRFvF}$e$ z8hO}6+g-e9bl`T-2?`9rnl~XQ0syBw@T3I^sVYICBu?IIX`N69r6Dlj2!rjerkn|f zsP96&8uzRHBn6Y)&KCxC-OF7haUcqqiRe(90dx-4Ut3=O>U;f1_uBSNnJ@v^$l-6B zxxN@kyOOIEzt8h=r=Shvcu1fG1^`VQSNapef`@tW({d#Y&PiM)s1sJzU#9-h>TXlq z5Q^VD(6YIncRSAmaJxyEwx!&itP`cXtLA1PXzDB;A@dbqOGcrBYud<>05)hO zZ~gZKLy|AWbN3l$|9$x2S?yzYMQ5Ge(dXQF!ik?>@2e~7bx?IEt9&yiw)=BvlkKOp z+zb;Z58V$xh-a-)=Z9+v>8g%%nQH{D(wRHOod>TiuuI0XGlJ;7w1|$kCwZ?XJvMvB ze=#Gp_2$>}$LXXPH+|GUy{zdJI0H**0 zYMO4>z(1QE8d$eZP?#%@j8)`+vYY9jU^<(B%xC^rm@Dd*5WYZsFLvqivb%9(3mXfn zs<0JFLhD?Tk9Qdng0d~1_S_k`bzxAT_*%vFQXzb0!h0T}VGnH^+*E>qfC;;tjCfQ! zEPbhxN+7%0Mla6NVhmf{_AJT}*Mjwad+#e>SUq#H_}eD|uLN=7LTXT7=&;beT!v7( zztU`SZ_A<UT zL|Xh9#d?{dE12a_{AP82Wgwnc9Q(saNUG=Ax<`{$c&~B(Aya!A#cMmCg4lHmWYxV& z3)-OFOMY&fc&q4?;>k}~fL+K!&GyIvhKR9DoZE6(gHXMy3!8f@*@-sFh1;l~ZrGigsJ zt6rhc?s@j(fpI<~0*u4UQs8|I1+$fw4>kk6^t?$p0yWGFvp1jy_8uPqqc_hW?z<`P z>X8b3du3&pj!k&dC$1;C&8!3^^74G1ZAdx*L8NU6tgERRjlgvb4Aoz|cICMyS?cCx z%+Jwa7ED~4SaLF0XP6}2e=67)E-x>yV6nJ$ck6A$)CU+RcQRT8j8J;I89Y&?3TLTv z_kAY3H(Of^uD;#eFvsJ#L|(1nc=H`IhYZNaFx+F4WiTC-MlvrNVpc9`F-LtT&K|YB zA~mKttg*8QwMs?R_{(5O*LE~uXvLe$8>T9nNn{^Pt))`$*xQ?*EE&LmD#Fzw72%yc zyy$akOS0EmQK*mStZZ`O1bHJ(l(fmiTy)xr3l0gI;Pclcx3e!bj8mAIj%qG9E_!`Hdi(|VxXJ7Sb2Nh}H?Ysor%}THzW7q6+1S)iE zKVAJNV-#)W41U`v6&5p$^tSk$moi`9UO*^&l@>1AEH_+szC=wBYF?>itW8x_=S55)j-jzs;AS z@SZv-^`-;lEtW4$rm{7(ld$i`LydS_0}RQ7PH#GAvdZMTL#{jOZRD$GUhyCH$NY0q zHqX&^=i&`zcQ&RmLc+)7XzouOLg)iiC4i@OyM=%>mtZUMa{q|5mMyvGuj|f^UQ!m= zWmbuuY~KDlCP!Z904T=LB>Jr;0D$?UnL_VgWtT^I?2otAab(PT590ET_5CeMadkB% z>D5R0&u|2apBK@8(7>YP<-^?@>r7jHFC8*-?nCAs1AFjuN0arg1Cs={yX)G^R{@Fg zdcvSleAcbePSj`K(JWia^9ZS~eJVDeOUNR!l-J@3xrL}-`p@Euq(=v8_DK|cWByt06@#B=@6LU23t7$etS8Q z|IS+BbXs3JfP1L`HgSfKW-K9~uteY>s0Lu7Lf62h^*ZT%o`AXkPJCDSqa{FsLbz}O zEv*o4-Y8FNIG|MveyK?dMkazKx3-|0DuIU+!cauUtEg^UXnFhbMpFWm-W5iyCslh1 z{t7f5z^7s%>_jD&78$<>pUPCID6HVi;nmpjo5off@g$%f(bwe>6FJLv%bvE?QGaCDWFZS-a7i3fBV{Oxa*CVuRh(de)zI+qBo|rLQr;~rJ~Iv zSW3^<*zwcVB-BaX_I**x{svjZ|B1W%ifU@>`$zvgiWC7!1f&y45Nz})AR8h@5v8bz zpp=Lpf`ACpTegN0LA(>~e_xnHZbMcP< z`Jan(bJj)1$QWy`k&CRXnctkh&lmZ@78ivGje3VOH$c*PvCJhSdt>LzYMW5622lYFiM%Wc!u+_#tY^)s-Jm48&WVJ@D2Wi>q^>OflF_TSoklbx^@l=)Fq1eklf9I)|LFO|8bhLC zR)3uRgm-rt=!dDCPK$6cJi)7R!vHd|fAO81r2B0@cCh24{Qj&L+~7J{JHw~B(frt_ zMn=(Ip+wLK8uX`fB+%0aM?98VkP=FFKLeFX>G2U$qt|OHOFo_uBy)VE)_HnV1ebChKCcnb?Hv=%@sZ0-Zv0CRZbU>&U_Hq{hvteSHQIS zVJJ)(7oh9y>#g_4w*{fdCw%NxPkZmbmEC!jWJ9t(%b)F~g*6^61iV|DoMkSNvYZxd z4_qF=I`vw5HYDIl*VxmYs;9lo&CRbsq0qGA0C}DBMLbP3Jz_IUnPe($YNQp{r%}e5 zuFn3ZN5bh8-yo>2>~AAre7wxh6~Wc{v(m_+g%*+3O7nnOVpu z>ngrOj)K(^;fHnycVRLndTgvT^cJG40^}=h5C56pq;&N}n(u)5`D4jvnszc4?&l|6 z20z`S;<8}JhPiv|Uta9M;gT+&_)ssyr??O#i`!Y1IPthF(b&S%trXWYG^Fn!Qn;!b zf6@$5D4klZbN*oNVYRkEXVSgkhg7u z_zQ8X?@kW(JSKlQX;)Jh`JIXDKd%DUIr4swS%z2am1ltiqp>8z>(0nAomw2O_ej|7 z14W0m%Ab{9p+}hqx*rD5K2;c=ybQHk%}gDZ$i0P7I{)MeLP90h>}XN_A;%x`Dszb5 z<=4rM$C5`6jUg7&b+5`EP!D@HY>&Q+>Xqu%c`U$pNb=d9y|Beg#o{*VcTtNDh$56y z^9Ahy{PSlP2KEOm9HciSyGk?2Pin3!q(v{@%$9W*Ir41Cez5N<9=Em7m^eG}e1Fkl zWSK%*lzWD-J%30=oz83RSoxC&vxV>6Z68B`qtJ0#{K63*QD+RMT&sz*o|hr=+4uHE zM4W~~QAc+7a){*zt=LG(6VF=higt0qw0`xQ<{`4s?eR53WCV7- zd3Ebczp|@$-s5=hb*po@;qmmotiy!GR8@-sS$OB+aCvpI7?ea!{VmuPb;Z{%FZHbQ zK|!V108==E8g#ol`W9T${`#<)hQyP>PtcOsOJFrwAD4LE6!HAckE63A5+@ zW;i?_Z+tt(sbnrhf-A; zc+|xcaNpwB7RR5z#x>}iN;>k^;A<$X>vqv&10S!aub=$u4B!9I@UQ#d4gaG5)$xDH z?apl_QBCXH9^P)I{$WZ^O1nhCf7(v}|D&+jlIA7zb4veU zS*A*wS8s;}DY@*@0-~B`{`Z1z-wS%6ghc)=Z2iBcu>KymOD#Ali6Z~;yO96LUH?sC zA$O6l-E*`Jv`_uF4)Gs++5cXL_{Rv_{k;DLpzS}OnCn2hmvdf%3p+~xbK_3A#Ff8p zD%savXh^JV0ZW5&jT zA}w4C9zH)AZ#*-@bJwqi67YC-Xg(gVdd@kRxTi6i?HkqVc8L3mgv#y{K=25W!QHMd zj=z#~xP>`+p#+gTr)ghw&8cP4>8HZ4e{D;IJ=}+OUa@%77xQ)8mm#jlE_#FhdhYxo zdp3Nbc<}w@__NJ4R(`}Q_!%3tvIfiZql)yV!K8A|on{xK6v(%VGdfx|nc7U|-BWUh z`#%fMZER*ahHKPMJjX=_w~t?uQrFyn^lIKvjo<}Qhc67p%Z^(*|pFTUn){pUbH*Milzit+Ys%4Ht0W~*wfaQD2{v3Y&-&YUQ{<6znO%!hZ z-uOP5{UBoG&wHhPA_ct*vZE(Q2G58+_xMb-jj^(lN~%7?YfhQ)SKeD2OZ*eTK%CTL%gdo38?w!g zstxHixEb7BB)!CyKUW_g8q2PceP~e57ukOB<(*%?H*Up6rS7z8Ni@Xzi>ba5hK7Zdo*jH81d~kUyF=bs>AouR`?sLN_wa&;Z8Rbu}hQ)}*1w<*HdmZO?eIwS; zY`!S+a^*at@%Z;T^nIStGVIK6#?$sThgU!Q>1)hiqmFS;Q#?!<_xOe*&t248xpG6( z*5CDa;MakO!)AhW@&>2gUCj@M%PIX1Jew9LBJZ(Zo`Hb+UB0-wBm7yb!10smM*kaD z|5K!%7VGZg1I3p7CTkr-?sK$1y zO2nQIg@?@~aw?aV%Vtk^YCk>k{TAiO%1I|$CNj_W52Y(rDlzd9d{z}EA9FIV7-I$g z^}76%#~b+!ZayW?q{HmRscU+r(Wd?j_#YAnw?eO+khElIlzb_;ddorN!Sm7nV`z`# z+rh5AUpY6=d2C5*^o}CKukBR4J(O6V{FZj8V-un6TVx}TpT4P;^~CEOWbn_|3Rj-U zen6e~epoTHmT59df7DNG&v^QE{C=NXbmyoJx=Eoz$Eo4dSopsq$O#kVK4WiA?3v?# z)^Y6*9qOFF3TbI$htKmgA_)B|2{vfB$@wqIb9A&1>@Q zj&OMFGgOK7a~STpMrg^E^730!mCNSeQMM1`&;NY3-^ljMncpL>%l!ZHy=f9pu|uGhoU-g74Z zuCkdh_5B%8^ix0;-t~xqusmM&O`ZGM{CDM!!Uu!5)LXev)@oJWeeC;ud#Wh$mXLhe z0s&GQpYg%B;v{Twnh;RvzxUT~zk;g*DoLj0QFk##_9F>3O}|f;_Mf|)o|ej*y5Ebt zIhvXshMTe2HvewKWJJ$jug+1sl6Us^HC5wR=EBWM%1N%zq_aGO(={5x+X~a*-&tK( z@r7(za>U|bLzAdEu^yr=kxL3{^tgj-st_eIIGYMut>#Gs)w7ci& zt^WH_gZPvcC+T@mzKTJM6cXLro#5{xA~0~x=^O+%~?TOUMl#>-nb=Y}K%Wu#La@1%$-|Il2Wmi(lA zhaIYG$seHhNH{%jzRC0OVW&Cp?}LzLdX3!83QFpY`gz7nOQh%s0?j; zMcI39>0KjxI{oLTecM89#+e^$!#48j?m?_sSUKnO3MXRThie6+h@V6;Lv}G0zOUar ze~PwU%-~eyZ<(R@J%Uv?`K5pMow^@7 zmC5wkc8T+$Hy$Yc`d3Kfjbp2NcLZq)E_B3^oz`cylQta*~(@m15}8Qwcp295I^zK%!b#D29k8ix}-hqiAGw z2}Z!%;fZ>3G&Nj@&H)?>rBO~h( zogfA-vS>swO@;ITmhe*w80!>30~Y`oWH9yf;D>#c`|f)V-Sw<30OeXo_nv7ZFu4}XV7WPUI4V!xQjAA_JqJet;2|0b zm<9P5u!;hlbpSX)`C#dBD37=v2>=x^TYD`PT`;_Nb#-tShFLFPZVNaA@ra7P8}Ck% z*<5~=pa{*_OTWF$eE@R^myBYu2N6fio;&9oN!nw`oVN|Q3eMD%{vzo0*h@t4tx5r^ zAZ`eiScgKPk|z=7#reQ3tWbcAOTq(}iXK3uiDEcAQN6WCW%AF$|47c-e^!v14UYj} zZVryX5kL%p!nVwJ7a7@TmDjYRk+ac^vv78rPN7ooh#|DJ*z#cb7y>RprLmz>P$;y^ z+rnCiuR2mH0~Xo} zGKYc?Jq$b3r1`WUE=m?~{6!KmCLHhf!*;AO2!XW=aIrVN`pM*t{RwD-Alg%a$rv=; z*xx0o^0Hle3$6De^C~%35Q6W)ZkoIa?ogT;T8G_9tuJ&D1KTOC^)ZbLW^(%Y=vv0b z*Je;OXa`@*jPup_zCT)AoI`DS;xn^5pkT|1(o5;0Y={QDQ<+c0xzZ8wHxsZ&7Tp}1 zl%a4-TU8l_)YTlHE`RkA6WvX_OR0lb?6XwM_EnV(*9yB74{6BdW!fsD@Pq z4ASu|M6GV>K(hv)%C{IImx~!i4kYyH;joZyT++Vk5shOYVc*b*-xrY#|J4X?WZ71FuG?`d;}G|eG= z&*w(AlY|Q9hP+F&-H@asy5=`Oi<*k$DLxxPf8etE1E)DE`c}UthP;cWOL2i~q&m{t zs?tzAwgzjZ8m6Rl=ar|)k8fG9q^wG$&Lib_MZJDOziZmwz|h15=>2|pVs~2fN$!*n zrEI1-BEq{O;LfjX@7OPH{7~W9f^b}Jif+Ik_uuO3-Zpo6rXy4EK?3w15k}&E$jA z=-{Gi?#>vUb~$b9@emW;b*Md0ZCn1-1$m{7(BZJfZmD}0PCN-pN>bgHW>`&t&^}SNix+ zd_pwGo2pH;?37aH^$wT4(UtJOG=O@SM|gR?fynAjTZeoQL?ZTAv{hAjv`9b! zg+1$jQ5Y%tlO}JXB0ZOIum8za!PPu0g~Yoyhzshjw4U6Ly((Lp?Ojzsw}E*tKTghQ zdSB`$<+yul-OycU^#WR?E!v(*cR?~+lVzH4^96B+G(TewefHv?FRb?pS5?I@$hNj* z<}b(itR6mf-DdCCS*X9q?;gp!MQ7MTRI97D)NKw13N7Pi?mG~M43q(PibU*-lgxcSm$#PeAjt=>PMGMB2+2u z`Ya%)6=sIJ+*IbbaI@;Ye#<<~1xd118iu1wv!-QIO&4yl20Pz+)cro-_8GePbg+YB z@(0aEDKLz!Dg}7NC$I#|qmB)M*h$K&(uz^M;wKsE!xzHgC+#%47&- zeLpXjguBx*yH`*rP%v)eh*>~u(&~=$la4*gVX^b;uPyn$!i2L<>nx322E0ZEYE^0D z#MF)H2{$Co&a^{xuNwTp>8^yrmp43Y*cy|*>uK?c_}%QgStBIFD)d@gcPYfnOwb4^ z>&73ZZ^Gb!aJgII9#A*DPt6$aJW%KI4kmaSLr zdj$|65ka{+gV^3zLnd{Qd*>K7(mF$7ZfR!?&wjMvZ*p!#7mUTKW4JWH4d#+)fSy#h zlkH%3-3yUquK@A}15U7;%&4#u2;7YjrmxGI?MgQ>nM& zLII*2v1>2@7^teq9Yq+xgPlgL<>txF-QiC^gzmrJyTs#_#44})XB%gToNQB~S6?bc{XfEaT5Mc)OP0Rz*el+>i z=)Km>@}=mC=>>O+$WWs<7fb_6^ju#3^Z^zQhrX0?~C`cZgt!8 z$mK@}0zaY$r28l9DCc@K*{M84vG4dC*~uE0%>xq-KX1-|=C8OqEG__->BZqk-sM<= zN>w9F&)68k36tco^4Xif=Ck0cRgJALP-1Eol9AOfpM_ok)))ncHXBOlNKm%@t*T%W zdelKulJTN!ve4_}g%ZcXa>2O6o=67XMew**S{GuFWNlcy^GJm25B;`|anZXb?ueU1 z*t+B~7+;#YETA&NTfc>4C3Jg}aqHJIJ7L;lQ0T!|r){aJ9|Y%cVB<~E+hTPb9)ox# zIHyM-&%se?PQ&<|1eK@zE!zt;9x z>F{r4)@t7{|I+hH&hrD!a9$JRYAO4^<5J{#~w>NG?EveB;it{LU zL6@S5To#4}N+WmD7w&)ZOU2*Hv3y*Yr@DUatIxiD^*knwd*Vvg9J#)jRAOasDwuTF zP?FNKU6k6XzW3B-!;1;;(liCF$_eU+Jun=e({gPD4M^KMjERQlj1eMr`tbU&d%N3o z^bIs~+UQ!dHDkJn^0juNFLRp8T}ik+!fivB-y@TjqtTV+Ep%Shgwpb87Ya>ui5!-7 zfI?*{)IttvRM^m_=zMZkRG!ps#8MJ&$KuWEsFCrEpym@yyJyqj{K9>WKXj&Yo-Jy= zFomB@&88@Z%0!VC-A!e}1tJ5g;hN{yeDJ@Cp|C7QZ>9f!TT<&Jv2-{nVJUD#8-jFRbn~z_V-V@341(L9F7xyB zs#1n{$qh%`lh6xuP2>?KiChb)*D})Bw)Q06i1p}5MP3t=eW49=H)k!q#OExYaFL2{ z&tLW#sVgB~WP=hO(eT}9ompmMk^IZLa_$6|S-yC5nRTFoDEArBp~AVQSWAB zxYytorusPCP`#6V*V%6q!O+eV=hM5~*8%TZ3@Yz~o*}^Ns9ZGss3|y~@G*@n{_boK z7@VKqo}Lj)>*ljS_u#-FEf~S=i6wsAbg$|8VZC4B!)@fsnB8%B0WILpkqZ72y3~wD zTZ73N>iPKKJE5r^zA20QLu%rcKK=Q&w?wPR;9}p~DtF(HS9|+B2GYmsqcJ)ohI}^; zE*owpkLU=LiW`zqsdZ=8P_&S?(tAeo7YBbuADzf3b1v#bo_P`<(Vl-d+dJ?1N7ESk z;Eb9s@@9uf?jz+RveHVQbw|sl?-4OmYZ+g^80C2429*}1O$tR+AzoV8tFj?4Y-`zm z>e096r*4Fl6JiJx_Nl(}x^9qXC;t4Bs!Ies`-6ng+M@dlvqks6&0>YbON857jOHeTk*`xh6Q@C3#$0rdNlRezPq#} z^8~ka1*c}wI;+qn!k@Dg8{Ir0W&3oVL>k&@?eHzW zA4f2sOYF39_IR1pK$2BEV56AWaw*Y}NaYdPfKbCis|YRYu{dZ>JEzaAjM=HKED;^t z`>HuSp!%Fq8tg=9Q}blC6Yru#%SKeY&x}Ih&SBuJHv&`Y!m=+`?HeZr&2)^mO$6n9 zd?}s)4Og)TW1`XfU5D7qejFB9H3W_^WEvN6$N=!p#Nkh1x}B1rhl1rI-fF&|5uX})$ z6n}HP#oB40qdJ2K;wjt{3Wtmx*=svm0I&9-|49&d4U zLy?k0sZgl);Uqp0rM?ak@p_U;nu1naDqcj*yR0;C!h3?ooqNH$l|xa4%N~kF!lkX$ zyi2o7D+wV|t|WW16M8D*?>IUr6bc!_X_*v4Zesa{UoR%^;fJ_|x$Qkk2*crUb8tBP zcdL%UDr9~~+U1da7!VD}`(d#~hIx_~y~Ve>e8A7>jn|LX1?IO;*h+3lri4mIZ%?`N ztZL`M+tZ_~cY=Cnb*8sWm#QzM8>&2c8kq5>v&zWu-P_#W9w>dV7blg zBkpGY_BVXpr>Q{wgj^S><}$E)bn;l>9S?J%0+Ka<`1<}IL)WAL?DSzHk zD&BBRqky)RytWl_8=9fexRuh7msVb^yjgsh{Z)NX?3hP|xwK*qa z5Nmo|mG8dFCG&e~3)f%Z+!VyQpE?k<%WY`}`n7!@t*4p&utUv&5>sB?kX>5dU78j4 z(hB04#VCI+gcMQ5nxB~E4|-Ksd|wN0EL&|MA?~GiR8GdMAT&K*q){kq+++H*MrT@7 zF3KZURb4!!rA&S51#Kw8%b3QW?Iz$|Fywa9WI{yg%RcX&6Ao0~W{Zq8qY)Yk3Ergs z3ZSOrivk=>j1ya`#9?eoG&_1F4~Y8!>3R5`lha0eDP8P{P4-YB5bzAU=BMImVG$1m#V2HqsVX_$WwP&_^ z36%#l=#4Ic`qFI5Xz6$uPYM8{G>82(fnLuW!93qnw@Gd{Q^1m~X*Y?yRDBKxjFEZu zqY=LVIca`*tSQoI)`!AF?YtFw;qrYtCW$yhq;e@7F%YY~e-O_mf7Js7z@*P(7>5Oz_HRF~vo*N<3J(25 zP)5gZc7)tx`hAw7<^Vkm*d_urhDY_`-jCsG0-hj*!a3C4T@nFvQzemwC(t5l>tgS6 zL^K*A-hEsALH|sh@lT5`S^7hd$;sih9il4_Q@N8fmC5=EhjOHRBz?-f3qvQyugXSD zOd0;><%510?>&(NK#NJ~ORP}oIpemf(!A0aP95&v<293Va);uyYd?||s{9DW(=W9u zLt@>K>V`t>8SHEW}M^b8r`P@6!E5sCwTmYY}tvb232=C!Wl|#r40d6{K5Vx^ugp zGdQ}EefR3HHY;OMQEDQ5+V`R1)h~5JccboIm_5E=raWH{07mR8OeLv@_tx5BS#`!i zK#7D0Z4~DD7aaP}pq;O}!+}T{13uGPL6e6f$%jR#5_(7yOc4_L)i6ESMo?peUmEJ*&&n2x?ZdX7)0DLp8nQ{po>;DPX;4*6 z?Bu`BAE}~mlh~OSpY&LjVI$vEpt-lR=0(e?vMw6}WBTS>q zV_Vx|g*5z`<GJ9B@Bc~n!u)>OEj z>u=CWAf)hf7;2N1e1GJGqjqPXeO#UBZp-=~$|}8Gf7=`2mN+#Y3?A zMIy@3gHM*Q`}1D@doQ0zCwg2x6(38owo`Db16Jry6{kJ_t%Te9=g!B`>Z*cB_4Q69 zR}#}kMisp26*_s{xVw6`Q`s!en_@G*Fb^@2f*2qR@!-p3JjN z!yJ<=G0EGHkC#Vhjd^G#9vSS&5HhmYt(g#cB6bs35wB$v_fV!?daA#ZLyall6yMes zh!j{P3PdT4N{^Y!gLx=;5+fv49b5>ahe^d?ax*W&|ZV_%-E(7;^KgLlcoA}>}3 zG+aiRX`y|1I-Q8-ac_}G`wNYbUr8p}f-g);F{tuYRU0>cEJM~!KY6J6K$_p=u%X{+ zwFB7mt!FmwGn|pmm-Vqa!UHWnl%jj%@3mRW6{3)fU52K+QxYrHxL8qsNLZ}A^BYaT z^(nJ#4Tx?-M_?2uQc=s!j}7mBQ>#vFyR1#+R!p-)OPi-6nRsf<^4c;bF05oT9eW~& zms2KHCEnd3S`->9=iwe}vry!<;BQXXSZejkFI0medNo0ae^#M(^t?NlLlSFPiS+#Q$$AzxkLIn|jb$Xb4GftgdUxjVVViZ-* z*z#nl6e7`uz^h#r4KXsh!-r!7z-{FE0UnCY+KDU#OiTdz*RUG!1Iz0XnJ&qWuwTA% zElvef`6uK6y~2DREc*lIssiYCxcmXQ(9>W{&KmgozJOtfVQ;Jl@0y%3Qy3x#!*w07 z0qqTiHTNo~%whrrFzh7^SbX85Q2}_O{mMXty!2v88nd%jeuJCa*mB`_U~UVsoxuSd zDir_u$s}dq@BNHD`5peC`HU+-YbwfnF#m>~r(B6rL9L2O#h@pT> zZ1rES4REU6iJRr?h_|qSuTIqNuECm{%l!F45SL_9P-k{a0uvLabB`B@43XO=~K7@4Ge5^fz=lG~%h;VJ-H-UO z*8JIrvNppDzU&i>n?E4(ePB+1p!>=rdkgLjFPZ}ND%=EO=SbG30iuHO*$0Nav-)D^ zq^;%!@q5nKEHWl@ z*>GIvM_!z{645n%Y(pQX=OU={!_~u~A8S60)x4p0z;eSqJrb$ams~`-CXxRB{&=0U zfqPS(Gb-Zp&=dx^od(kmZ5S4qoFoA1WNB?kT&e|jn*YWj0=&&7c0-97e&r*vQ-DTx z_F)diRjIC^Ziqh^t-;jG{@lmF2J`M;EE_MI$?=(lT+6OZ2FxD726Vu9Sn?IMov?)l z+z8h4{g#QU$gT1SxK`RE&+2|YWjK_BAq=&TV}|Giu0Pe0hEWi4bdo@E`fgF#FaX#Y zD4ugP0O_#Zv?%&meQ!2px^Ut%*v?{+8`p;bY1;$P1HbUS+Nm8Mp>qdl?WN!7v!EcvIc9ot=mimK`18R z06xPP6`epwvbzTy}oqhzlGfSm8ImIVws+D=CeSa z24L~pBE+m)tp89V2_omD)e45Zkg_6A5~t$kj`p^isvKSj`ojRqmnN=?Q`mZbaO;<6 zer8N@58$$?WmVj&SQ?UMck+Df{CZo;N2rjg`2(wYp_k`m688?syi%H5$8D?H;5~2e zbQjNfF(CKOf+AY{sjxts#fjk%S&bvPTDSkYGS4cV2tD*59&3_&7i*<7ppmi&F^!E4O&c9rv79+=!X#b)eNkeUj(f37oi(l2 zE9bp(e@Nef;+Kh?Y4R^N?*vOVqUj(h<22a!Mw7_}#IYu}8M!UEef8-ar>S__@X8TJ z9>L3}x>Ab&dhe^{u@Hluv#!&JpYFIGb=dJu>b!RDAaMfip_Sj*J}JS>h4P_F;$6h8 zjUs8Z`k(tIyoS3&cx^H5^&=sPe<$poJTW_Ke-K+t?7XckFbE~9b)eth$! zdol{xPrAhHFv&T@2h>xIY=0m`1}kpMv1Gq%vJ*bhRm5nHw;Exb;(m*FN-D!&E#Kt$=vbt-4raBG=DQ_mSu2 zXGKXz#~kd89j8yVmh^R^%0fab5I4Lxo0lh8U`I839oGB96Qv?!H!zZU=5efv)x(9P zyM3=zq_ZD%h3H4~c(ZpzNW01li#wQ)C30!=;3c8aiD%zjX8DX_Azw~`F1yv z<4x%J)uv35m7NG__CNFz5+Yu_uy*07fJkoNq^iPdOVPbyy(0g646BfjiJglrsmYM= z`?RcSn@NWMG&Xt(IyLe6#40YrAPNBa8;z)*R)vEr<<9?8k&CKqE3uAw75zY7gG0C0&b4KO+r00K7@ z!yIcrFGZeG-lzowCwb^N+ocv}RPB&I=oI4-0k4Bat?^ax@4?TaCY?1U0q6l>>9;7@ zm_`8#8T6q*r2lTV3ji@~fSf~VfrNl{en0>$o)nmkm&U|!HfWk-uXDqXyHM^N9{Zii zh7d8d zwSXIB@7X9hey)aFCEG=sy1O$9^l;?8d;@lzF(VDcp0Ztog~fZoO<<$B)mY(BQA`85 zPEp)Ca!i_#wDX6rVoz&m?mKcwzUNOrUp2*-)X-9*cR@$FG6%h(O$)YJBQss;pc_3} z9G}n~uztDKyJvkj%?ElY)?C_J*i>5S=41G&hmR`wA#NAt#f3Z7$JWgJkiaU~-pP9= zr!AWE&s1C9OwimM<6UY=C)qZl>qx;w&}9J?Q9dNmW-0>Fiq$EQ+{-tl!{ifbI`hGl zU)*}HhWLI{U?}&@qVS(9K%r24q2u6cFj{EKExNlR8Nphx4EPxpZA`630e$e1X&7t6 z7Tw#_?08WYU}i%52|@E`Q`XfY-`ii;JN`BA+wq0+1CXHn0JTs59+)#YEvkg|yLkUd zaqn?M$YYmECSZ`Pifl|E@m?oQPODFpZo9ZmPn5pwvY08ECIZ(Bmlp3ATJw7;FJO=e z&vx@z#7OF=oGE}qmm8LhDsTt}*tbwkQ}ml9_UAhY=$9yth|OHXG2+Df&pG*$~M zi0lx79;k|R(|1FD>D79e|43wOC_duUKsQpx0QUKXRZ5tOR|y`KbFQlUkYSpA|C1)K z+~9P@-kuG2I+@c_?>cHox=N}~Y47W@))lxGtNZH;R@Xx5teCMmb#AMe!70E77X_H` z4~M0OfX%SCvqiM_#Lf&_l2D&vlKB*}Bj7G}e=fQc=f)qaJ1cIIgW-VMm0^El$s5{Ja+l zV@EsGM8<46v=Pm$3-Plj6*|FWb@|99b<6hJfo{ws02~mFp_75)0n|JIfQ#Ym!}goe zGhp9J9}=UUybtB&9o1fH0b|k_uJ;a_rP$`@Bdo0myoqrpl$g=t2ovilY6LG-2Z z2K{lOyT?IwmdEVDn%5`YidS`ms~W;@Y=Up~F?kzdYt232x6e<|lJRc&vDQ=A~4~SpGg@nmNr#>-);2Ow`r%`n?GFZtnK z5zU|vC$3+)jJF{JVE80CDh7t<@!AZ5(z)n^&qiY{y5gT+4;Sb<4@^mc0zwLoJLVR@ z8_91l{YTMPd=W=)l%OhXq zg`x^K8``mGGa6cJH4p4GT_k}wSL0ABFc1M2z4=-@SXA3y%T$xhxLKjuAGcynXIua3 zG*T?K)es7h`uy>&RMysena5t5fI(cy(RwP%?|MY{4@Ojq&N(x!rj+j`GO;$EuT!2~ z_%vi;575@Z_SW|P_4f5i*1Nk$O-ZJtdK>98q?9~OK6&Y@2V}NXAt#lyUPh{&`~EQ2 zG*VFJz;h(ZD<^>-!_}OWZxmzI4Qq42gcchJ#VW)q#L9+1ypVIUUP$G#Ls-FtUnD^t zeGRO&R@V3080%@&Td%dgj&|o5X9I}{+u4kzygrMv7y#NR=`euVe95XRtD2amuq=rW zs?y|=ic@&gM(8GH(fS-hS$CZ}cck^a($q7gtNx2{Ly>oxPo=zc?(9~)M4F*4*#<`* zxTGeh>ib@o@BLx%U`j`~*x5MrA{CH<|1y;VSYQzk0Ptq*xW3E>>t5aqmzj=DUJ9<3 zQ?wC`Eey~~1bA~q@bN>x0w%rXi` zE)i_Zq5uF(xeorI*g2X=WrA%=b$bF6DER>j*s&D&zsP&jsHV2=-SeEIA_zz#O5cNE zLnplkL?DVN0TmIYixH#|rBQl>eGY^kX~YI;MIi_Z0i{v8ymSI$14IZ0F^5ip5F$tj zB<#IvQk*x`LOpGYbRNI&b8(diheU`*Dt`tDp94wNWVnZWUoM*n<3+|^#I1POC+(U=4eET)lay_ z?$9*j-CbVqy@I~Elq+>gwtaKcdU=vP)lW`;S5xPMgTh(MyR6{AIn{?cf77 zB1%7{*hRiy3TL=(ReZvzlYlnAFJVA>Kh%`{%eZniTH}k#JM9(ye)Ogp25f#X=uhAnPj+K!G+(E?$M3sh&SpiE zk6X-M7&_gAF*-9I%ufTHqSmUR*$# zG`}-7-s~AKp%>&|Uu-Kj1JOD?Bsh2;Sa$_n`fxO?+j=`e5}YQ((S26uxO^U>_UU)1 zVw9GJNOPY7g6?7<KW=7D799t{otcZlRn0kvYPQ*MH(`zj7eemGt2(=>k zZZY-z;xulR)v(ARY=^;D^P!TM^}iP*-U}s01^V3SoD8h?pMXbnPRp zK?32SQgW9Ssjcg5w;vWOIMYU>g;43|RSWkRsi)g(m6D{j6J!LNapE!>t*n&qDZK}y zdLw9$RDx&#w{!2 z?ooiJI&YRgt)qokPB{047gOfpXr6zzOV~V_NoKP1V$?bxmXN^%bH$n773u7#+T{54 z=_1B7(s*{KB}~5f`lwEfa2L}5Np;O??@OgyTHz;CSJVIkRw*m@qTLO1Q7J(O<82?O zxJwxAMoT13b#Jk7C(cQzK@Ol!FJ?=7)H7=Ff%dN*vn1_9B@|+-S59oO^K~$`u zNAq@eN;FXG<%omfdFRrMw>y6Iup>(M6+!upqE^6j-~gOhEou+>0&1LXHs~(+)sh^*c~9}cgr9$ z07w@f06v20WpnqeDbIyk_SW#1n*fi-Q;q>}8UYRiEC`0!bA>LK0pMYKhnb5z@%}ZR(7{uF{+({XKjJVHI((~fgkKORm+Oo@=TvC zK+hEqv|mGf4p83c$vT0OZb{h?>3v!e=s+WtH>U7qcg>ia)i(QuITIaRmm%^M^+bei1 z9`qa(|0>~5Ow?_xLNJAY!MJ@C(=f_9ZhoP+j`Mc0>v?RN_1Jvlk#sMww9H0b)!vsP z503Ct{DOKQ`4;=c0Y(51(4*mX27R@-jTr#IJQu)C{Dl_(4!7fkz6G? z{|YfpQgBtixDl-($!<|I&w23LBdy75uEr7n#7XiO)xY0Gv;60<*r{$;w3MWP+N7o? zhIZUFQ6VmBO%*nx;)FtzM)?i{>HMSwPijN`Ab|XL{PSk`Z$on6pHB){Y+U{cyK7HA zpA!$`986X9Z!Q`dBba?=qL3V?ja30Qm45&+Id%_GqMPOeAa64 z3tiuxced?~N=ykQdTdW@Yc-vTt%&Oj#wUT|J|M895 z5l>a3_%4H#&W=A&R_LJ-wB-?X(RXUf^FN$6#0%>`bqFPhG@`fuYtX1uT-0h(2u0Xp zRY(vDHdDErFr&9cqi3sFW_H41<*Xf1Ieln}Za<-DU4p3A?&qlYms8>tQm`sR(tVDq zTEdB)y9iHEU%X%o3nMs`zr;SjN@e4AvYgVL9rSQ64y)Aq5sX_AlM$`8(?nBQSKj{F z^^9PvA+wu@eld>sNQ+Ch&lMh)uXos2&^{C_r-{K%AgL{Fof?=XY_eY->!{l#Pvhv2 zD!uJJ>+(xU;GTB0A$Xuh4z;>Ez3#6?o@ah5o+)nI{>^Tj-`D%n!su&m$E3yfhjN6t zpT#F*k7&utEZ8k^2zXaqZEbMIp(nQXK}&pbAd$J zu-WOpAUO$~Q-TdHQ`V8!Q? z>_png^J^j%On>@DF-1&E0g{%6tLPPp4eaxZ6K!-b)+N7ZwRh3l?~v#^$&6$+)h034 z1UJ_3mqz<7*4lD1VUqprj2KVq$WbaTjzjU}<1jQDmA1J!XJhj0_~TA7RjC^&g0P?K zwZCHc3b6#Ler12h zqt~WRp3_X9wrgt}-g_H+^ADkY0CT`rVacyKUHf0gpQ*ZsizF{Ui+_~yOm<9l>$|VG zH1#^Ev3PY3cFbvth4GwHQ-?ORqfE415yEK@@UgGuXSfu^Si>NZ-`MEQ4Lw0hhrE|gC&(ypXqa=~szRC3d zaUyJzT{geHV(rA@v$7{*uX2;p-=^2==?tU^o9Yg0g?h$H2cFv3;#X+oZkLqaqH!~L z2y-uUPRTuNmBE1_z>l$$7zvAovcMn>w7IUX`?uP_G4j)-)lom^iNw;qofn!$7-g0; z8gFAz1Mfkl0S}2O=f@Ps8JQB^qOR#O6O`66K`B@tKjl_qLIYr!wNrUci43ONksMP# ztrh}+)<;QMv+V-b;7-B?iS-7;jhy*Qo+~NL3pEhDBS03h;t3s|08O7Sywpm!-LIFD))% zjRAwnL~!Bbg`0qB*4731K@jDe_^AAc8unmJY}l*t7}~26avgUfCIEaZ0U)P}YJul& zu=or|@Bq{~*M)>E;-y(PMZ!(Yroo*^gT;jS9;ENgb&a>Z3dtY4MEc^4yezgpL9B$t z4}RFo1q?oWluf48`2~U9d`7Qdv@-lWS`i+}$!fZA0;me?;0Ojb+^UL+3YZ?;pVh^; znr{wx%*LPTa60zh{ueG(_JFH&Ko`!4>cEN{rQ!^ND(IyAFIuz)hkglvGRcll{kIYo zEjj<6MfC3>*m!FR*41&MTIhKiTJ|DVGciOtNm}Y@(O~+^zuSegI+xUUsBd_vWjxxK zTat_IOaU9aO85BwzI9}&?j&jJ%iJ{of&KW^kMDk&=Xww9ON*@8rSbN{(-#+dFz4PA z^Gif;_SNN-Rkc<5IPZ0I#K=(%p3i%_XrWiBOPrrY)obU*oH1Ma6dIduzDzNezNZ5K zxr%*$Bw#9U5Q}x?t+l%!xaq@-IPH(awUARK_IYZS)Q5Y&)NEF`>7r*%b8fYJ^IYFH z2`!qTrj=7DgVpXEjhf6C7qaz<-)c<|T`at+^1j<5&+rgV2rX)WQnQpX)UR?ZNu81x ztl$)%+fiF`cK`jpPiEV?`IjMvltwvN~BRRK_gDH-I!k zE4=#cgvG9CEh!wE698^{ZFnIYB`aR5_Rxzu4wo#faPM63)ROLfYN%zsgh+itQc~g2 zAhm45T#Gb(-JtvB*@xjJxy@SFWuwbbfv4oH+E2-8iOGi5_A{+a_sWSs`Stp>_v(}I zFBndr8ik=D0>Ct2z{VW*5EZTNHsdF~n z)|$9Aoxz>rLhdS^BuT2sW2(nl@g&JMA^T7{ai=6y0FkP$xY{qlcuaMmQCLPl8zozk z#V0CipU>+E*Q=>@qJ{GPNsWy}cOz}hIzRo3^;Aze#oQP-=laopOMkk5Zj2k>Uenis z6*L0x{wTXF(6bEwM}hk9kvb$iWoF27*l#Uv+!L~4M9+F*iZri2QGF3|O-A*tI@s^- z(3+}?vL;AO*(M$KP|Nxe+BW^G*#bTCR%7DE{db==15(VjmSE<9_7eCJTXdiDGkVsh zC|gErtGU5-cc(*+y)Uvg(4l7x?0sSjQJW$82J!pUZrKPMT6KntR3UXcsqHNN1f0^}eyH#61-@hWnpOj}cm$$m&Rduysi&ZmahB1(=Yhl+y#ePd|A0Z8yel(Ox zNwdz5yT5g1xoqAe} zvK74}&{l{E0GALjcU>}2Az;xgnal=LCF>;d1Xwad0ippixItkC0XLv6JVL3AOBKsL z*N2=rXC_VIgH=#^1DuwSH}&_QuL$sA9^QH~c(sN*&WiDGY+}I?acd1F_;7Nud#3F4 zm8YZw`|l(bg}6ywKm4!7K^M-HNPl(ltiqzPnqOvy#`KjHqZf4LHS0g)S3(j-8Z!2MoR^l((OZw$Jq<8c z2~=5yfgiu`kldlBUH2mOgVRJR_^7pzf4a0%-I6X4L)_LLLZb!4L~9$9q({juk=_G8^Q@xUm7@dR8>pyi*-A zukvmiP_R`7y(=nOVXE6G1Gh52v&#WfSigbD<4H9Yz#IxPp#cDcK`F|S!PmA0fOix; z7!5yiG1kkF;(av&$(?&n2J5ZbVLXL!)|ne~mZw4934=SmYaAHhPlGA7qYwLHf3%!p zIX;CODb1%DZIIVg@=_xJj*J$o#{`qbvu2gIouhd?dU)z^iyg8l2)}iPnWy$0O*ASX z?ZVeL;CpH!>@y9_bSKIlmRWzeeh%l2wzL>fw4rB?=;t5-cwlpm{8W>z_pzC09r_DF1qSE!@zms62yY{R=JWRJ*3U)%N^gw<{W*dF;4# zPHWcHEP6`H?2X8KUv9Tmq|9s;{^1pMSvnbG)@`#~`&32kSuaK$ZV7_IK9eqR|R$>${)r$SH*DS5EXU z?q)4#VH#w=>}Gd%+&iice$_ovFsL9T)k$FouNL}WN*4B2Kr73nq zH80Z>UhO1o8`-s0!}<6YZP^ow@u<(X+2{*5t8TrSI`okvfidn7y6BX7*3VPDh@o7R zAsxQ^X5y|rZzCLH_mp?r7SXf7%J`+tTXhW>&3Lg)Dg9%wG9z}VsabA(kvLmK>)0-C zi$q*})r6f)NqU-VtQ1~qXKj{^+1FrOdv+%Hj9p}=t@ySZ*!vn&pP^rEyQ2=C{c&YC z+rxmeuNko{`h3Ese0uOCI_z@Fg4vy@2|rVNv}41b4QZRLw$rWm$eC?m<1X=p4=C~V z+H$zjHsko)m|bE1(^8RUvsPyk&LkFwrQ>ey{kNzx!y)Cb6>Va|$s_4!ti-N9FG9;! zrEYv{ZM-(fTOn9=cDz+ssx8#gRWNo$Lz@j(+>Lvy9azR_@NwX*gi+>Mr`Q)*+l>Qf z51?)L`c0uz`h%2zggr_lVl<9mE*h+!NHTo$42i(Io!w*|dCZCgm=XCOf$@H_mmg@H z-Pws+M)&6*S>DxA=KC-N{c&0H+2e5Otd-Zs%DE1EhjhGKuRj&eY*$lFREns|+GGu> z>p>~4zR^hI(}Iu5=)S+bF!z&hhNmp3si`>|zFJoD&dtT5RI|(Dw}qgioNOfP@YK7+ z5cA`dK&1$h?UtT%4LP593Kvyn`mZf-vaMpD%|@OrV)kMhWZi=>FD`wlGFCfM|L*c| z8jA0>FU&y#-Js~6_B18;LU|!YnV-Ubw2d4swy0P1`8cXvPC(x?++#hGGG=1SHY9eH%%=cjE5B`Sxk zXz8Bw{lUY{P=$MXaN9EmWj-d1uLuFZeq93t0BFFil)JoUiBJ%4pNtF|P+}lvFdTPk z1pG?Z?5@Of*TC2z4!)tN3QyjpdUotgvG+qr32Y9WkBzGK6fULB={s_pl_$PtroTmV zZg4toMBer%-Hs*mmX^`d*R!BSv@-Fb|F4%sI~2@HKP%tuvKfRlU5COma=L50DMcbN zIrY&-@6gKnzJ{W!cQaEl>Q8vScct?El&9`hslERPA%Iq_^2>d%u6{nSvi=hGp5^ke z8hVG1fzoqS{I0KPafUV4_xug?(Ed<0H4SU@o%;i%^ADsfQtqm4yq;2jGN*zKB}flE zo%^s0mBGU8{G@jBza>V!#%iJ*%(j7$GDs~pt?=^$AN1Jxl#R`$ZeHqz3_YSoMpcO7 z@o~&H*PNkHLinknt>;jW{;s&367F{&IrmcS$Qkd@r~=;x ziE8>IQ`U7tKK>_@WLmmNr~3}?xBhx0CFNgRe>?VnhAA2gkl6xqv$^^IuesWXRgC}5 zwiYlM|8H@%jSu}l<7)qN-+#E;#sa$eITho7bFlvhSKHX&zjL)sjs81V`=6`-^PBx& za<%`t{r^bbeBm-4IDP^ZYx*~&!rLXMzek6B<#)@AH~yUK@H_kbPkCW|ztoqP&fK#; zw=!$VqmW^Iv62uWniVSd5I0d;5a$D+^e96qUrbx4{EfYK%RKOBBDs zadF=-QD4?&Bwvu}`5@2yb*KLD=HVlo{tWkvR7mH$;?Y-&2a&$+X;CP&XL@`HPyRW5 z*@wJQaF!MaZOUYV+lDzg?rPJ48DDW@;#1pO%aZYbOzti4`1|i+*IxmjCY_mARTj1x z=Y7c)d3{rrBLY4yC+GMjcb!ll2)SyX5yQW_QlOvMF0PY&JjO76+aZlZ50vdoj;N+a zT+#|&t~#=H=55gd{k`R*k<~5Q;rU-m`(8MmS}YqZ`i#BIjOQABRyQPds7;uuW<0M} z>Piz13;DT_m4ez~E-BHL=FGg{_zW@G^To!_Ol$Gk0jd3D`|gx?yGa=yS+yTit!oIk zZSqcyZqB~`i^pj^C2dCKRrj* zC3zm~U4GSC+Ws$mio&n@nYHYz=ghx%|Gi=!TQy&RPhMeJYP82hRajc$a($y>1+bAK{=I0mwl=A6E8I* z^UO2I#J{fZb)@j+*Kgx5ddcYYmnsE68^5Rboibu}-B^5wLFI%l-?)Hy`Hx|grc?c& z9F*EuPHdWfSKop4_hoO_@2QA~tNp!Ncj;Zx;PEpNSMtt1(XcB@4|||v_Fwfb=@@wsi?N@EvMg4 zM#S%%lkxV|IyI%5v;Kb6;x+H=tMt?6nV%z+I7N$*U#%=02lLP7Z#`eujv77ZV(A-| z*>!*#C-aDw2mgNW@$dBCbYqNL+}mzx3)?Xgc*6V6^w%0z?p4hc{bSSw4*%OoV#!X| zyC{6SrIxKED?WR6fMam1WrXwdzS+ae3!%0u?x~gQ6BhfbJ~W@Q9OTGvouzl5%eE3j z&h`bnmu{6y)N2a$u_d(y9t1T5t_%+Y#)x~^!7SCov$xCtb%LQf_6xN@NZ;*AChgMF z$)JwDt2mnQM{cd!Ol%G0>|0=7KoKRcNlqnf-n^)+VybPUr|&N%^iJ`Rq`oidRUP@d z?Tp>n4atxDRM&%uTOWv9Xl4ACLcA95FJJCG7q5S4KSTV$pMHd}{X>U|nnE~956?cU zBPfbQ5BVEHt4%oCZSHVL+hf`GUx^nq>qEXyhQQko&ov{OXOgUD`GtF{TWs?`MHYD2 zb5QtS&hk9Rru6q}3S2^=Y z)A<1!g=nmeepNZ)sQ25O}%7$^+N@g7qE^e6x)+Uyw?)ZY$TT{V_oBo`1eA!GJ%-EZHHcH z>82bBEAQVF8OTiQiyyn!YkoX-A$S=5I~5EcSWg;zP;yJc+1B)4Q_CnXC>|W&CK0=^ zaPDf`?cTG}8E8=-jH_2krpbu*kMxGpyFwEh0ne+#HO%-o`KcYuifY#@fgi3-T;F#& zSYtN((!#drQlIeRE!mxGni6e0nw%oPS9}e+{nyVs_5PaOG|d^mYDL({*8cOE6`@-r zw|}$^Pka|GWZR@!vERI3IHFTV{B=ZrQc-66lhi+D0#|b@?y1N#!`*+2s`)m2`bFeh zGOzdHi8aN7^E2`%ElzSzoxNV2RS*MXpBQ`9x2=uuy-@UVowLhoZhu4suTrH=_@+<$ zQo~aQy>#V$pd#MgI$w!@Xz!e+v98=9-u-w}MUtjTT6PR`WWngv0pWW6Q+HCb<%oas zx6CH4#n1wZ4C-)Osqgn+Q8U{8yY6nh{2|M&XC7}o5Vof~!y%iBKCw{wd)RZ|KdeOz zQTBl|c9|CMXMT^;{w`TfXOcYK>)jt7v?f&wo8cKj%+S9?II*|SUwtl4TddAI(uc9e zoy-4dMpF&B*!DL2SAO}MH!tIUqnX;_aF=X4tE=)-!^<%i>-8^)843-LxWgs)hgB-O zxDl1onUTN$9!ZO;!Hh%qKBZdUEK3tE`vaCpY}IToR}OWr%dNfN*5_02wew%&p`cif!~u`S$<-_CvPd5N;&uIQ3!#`4z_S!3Tk7_ z)hz9)^1CBxvD@(CW@Ke*nn?DF2*=tC&i&bJa4q+d;wN1p{R;HHt+bn0j*^rlZG4kE zcYHHy`g%6ud|Y?XnWm-{b0p$1d;^+_crK+A^=A4v3xi5m%Mhd0A$9rAPuiK-nx-bn zDB)Z-J%R1PxRXpB4=~9{QV4Hu*{xFgeQThG!KQ(QB_IFi@4wA>j?ey2@-~5+had;| zFGTKt(ue=0yx`wfApd*6jRP~Y28OTB=>KLdy2VhxsBmDQoc*XEulQQ!ePJ3WZwe=w~Y9wdmng9%W50$t-Yo3 zgB-*whk<`wYjXfgkL!vDu02OfJplmu-eC}z|2YPL1^`|_;PiY1lLCGncY!!C;Mhfy z0h2wa3}9%SThkUn_Pp080t>F?FD0;A?|52{a{hu%^t|d?Ps) z3wT`|kJxH54J5nB&bEQyzk<{@FU~2CiwVP`_^%Y^79xOWDcew z;rs8lX3}UpZ|9Ij*RTD)Rp{;0jct0@mU;&T&ockyBU^5IrTm-&pxIPIr-Q{SHswdaBODvzEY!Y>5EFN&936jbE4bjV&WbP!wKq?ZC<_jvK0MN*M#II1> zg$?>G*4co~rkzFr&@Ow}Uwb0<{>ACNo!S2Of9a8$NRQ_3`ji9#&k>;nCzT@u`g^(X zBOcQe_le93BpQz_oK?(UqkC7f;bE{UWB+IX^eOY@?4!#PaNFPLT=O}RK*_2^?P}&d zu#mzywm*cH^;ah})Bb!oZ<6cR6thso*hmIU*y0HOUOG(SUmV7r4{e$-eQg!5>Ss?! zMF1YsVSiW#X#g~l!C*F6QPF&WafYw4Tk?(SUdcK==1N3jECQJ>p%ozUI$Vv1=S_y*8scv`*m-N zS4uauXiP3cpbvvB0oeFb1#1p%l__aimA_WB@V*3WI_!;Tn5V3^H+cfu`ssy&wf1qB z8-WWieiXd=f%LSrxKpL)f!ge3Vkw7FO$dALG{dKIVlnUeV}wDeNeBMUsK#t4wgEfVj6S0YpSKlXbv!cIzsc9k`4C5?c zH8Vclg z#W7yV7o4S#m{eq)PokcHX{X_1ARj$ zAN%Te=8*Tyqd6eqEN`3x9*l?_V-6aAz|6|RkXzW z^;=WzA<(IJ~4MAX^xbjA&g13MB>reh^^OAOd-E z^`&nj0FbR(9v^!+rKTq5U2-1Ok3>_3cfW0s50Ksro@YNt7>IKUb`gs$M!h!*ZfMn% z^yE99rLh$vLas*@*wsE=szaltn&X=3T!g~QJSsd*)D8DS3!zd7Lhe4njfMJ6!BmHl z?d|y&vjmDt`KxWE{v?$D-MA$ns25=cT%hJ`{e*4HXcX-%(6AtEU&kx60hfuiLErq^ zEx*}OD%KjZxBw4+Sw=Duw|x9Ly@+?|m{B~V=+2DKFBhotoVNtdpnO;VY4RP{Z%QX@ z70VUAo%&WJDsi5Sj4~x!o+B%cxmi$bRrJ+A6y94zc@aU~x*5DM^AxwKMH+5T(C%Ed zk0y5Rq*}}B?tXs;tKEOUJE?9vgD+7HL4XH+@zwZc>&PHiJnl1p`ko*Z2GiDq@H{zz zF$#&d+w+1)*OQQ(Ocq9jRA?h?*l|-Ky8msQ*}J5$4)FYDFP=@rt(!s5 z`3`U>%gN}Zp^a`kB0ddhYz~`G>nLj(FQ+vNo5&u1m}PP|Cv%CjIyLBLBW&|wo0jYu zL;GnXL4Gz50l;6MBm=;U^()$tM2Z;m75*ei=vv_7Y+MKgQFu)9Wb$w=;2}?G70>V9 z0lJHKew{dBAsLtNKTnif9}EbHE8)Rp09f26!PEd~y2!Z(Z$jVpXB?^n*YYls8#cdz zgw2Ay;DjI!h;G`mT)#3Am;6R|uesI`=E;ieg&CJ8;h+WZ?D1^+{C6-u(TxXW#1bfP zx`1zVlnZnHYPXEl<9>;Nwf$Y2PV$Ns8&Adp68ud8r=Q0x$Med;bdpN_Fau*SXQbAl zUtB`}atHy+^Dm+nd3-#e%gTU9d;swLfQ;KAf-YR6YsuI0tj3%-on}JLtQ`dIj2n;_ zezWbIE!t6)+k-OmWLH3nK7ByY;7HD?P{Q2s<6A<^jA>P?H|J+^(}$M6bR?D2d_ zOC z=e$5Tq9U3zWcDPm6CSgw5<~A4GhFT)yIuHB_`TYd)J~2&%Uqe_VXDbtvu+$+%5`|( zk7_*`|IxW{k3@en|2wpXDdXQ{)%o6$Onwr`!duNhrdkojg|A+$j8~2J-1iKchGA&M zbd`C=W8;j;uLoUCL|E4V}PfWY_OfO6|fO4mv-=GPbIi+|K;@mEz0*Kbhq) z1iMMVVP&6N29h10I1H)IgJq7;a=U{ihZ`r!6#*kIs|(;t^+R(r10T`SeZd7pgO$-M z=N;sb#?7a8aLq+nG7M-kd4LZh+sV!zAQ_Rp6@g#>=8X`(#nyn`i7Tcy;7 zyex9zyzMCEt%BEMuMy4~94E*X+2iCOG(Z#=At*YWrF(E@SDufYCWZ!p2?daWz{x1t z-9HE^rU0*sv}y?64j4f1VQUkf#sWx}u4??QP=0540_%Bf@8}|iv3Tf=;ue*s7 zmgg+Xfx0hbL@%GhQ2rtKv3Wek)i<`V!L1{VCtsBb#uzQjnD%$(ixmDv+%PHJJOMMT znT}^gxKxQPk)xLsj6tOR1N0ajamylFJH`tKAe$`nN7|g61G#2Yca%QXBHu^I?wA1) zGKw4tuY97e14Y0*Itj8=@iQ9q@l!*qemL4RPJ!<#USQ0VYJcWg5kJ`#%l`cCedbt> zN@7h59$&ArZcJx<#RF2&7tO0fzqHaz4S6rtx4Q39WJ!-&K9j7M7V`1XhM$TcW@yneOEfDy- zvGxOl5bD-42u-6yP*mJmIZMF1eW0v&nf^^0SgWbAjAYyz;CZ8J#=J=~L@(_rdYRxSEFj_lPk7dr-zj|Kb|l1Rtcck+eYZL@`FDb0w)ZZB zFd>SYeZzzEf!X2Z8WAt@-HmYpKYXe<=Q{&h%X7w}PM1syX_$;UOS^hY_ucb0oE1(* zQdA5Klg^8MkoV92qHj*{U+|tcJTT?IvyVw>sHYwq^!;@Qw{5HS#(}i0o@KW)t1*~A zs!#7TMk`;gAJx%Mu-DA@C*3}rcMQ8%ic=@8TZzKs22 zs?lw9KhME>+gM`+fZ5~ zJw8n$uzO=o)|4m}m4y^Fi9^2B@i%RPj1fP>-~pJN#RQHZ!Kytm0)5@a!Ak#iPsQ3B z3YjT&@!|Zhe#uNum4+pgsh&z|c7)@Eo97ubDxCGDrD!2jDQFtp!K5ckAKy zkdo!36~eyiNl#r0`c{ZFTIxSq1oOBP2#vcToAcp}5fO{EBC5$|91vHOPpW*}>8GD( z_3ijyZgg05tQ%{yt^as6squ{r@1Z5lJt0PO;!Mpyk_{tOQl9+*|BA_<{zuTLPBeN~ z;I@#rO8eKAVF}nE01t{n-xthfiRwM(>yF_D(2;>*g@5aHm5ov%%pl?H@b#eoU|fQSv9N$7V?AboIv29j_t!Mm?n%61`paayKccBE zU`-jkt@G&n)~=Bt_R=5%8`7TFhQS@Ir`C7+lPVwcB;vR{0m3s;{JK2OY348e(CQj@ zIqkKM2a#7Tc7>->uoG2;u!j068Jy|2WC-e;JVFMvNQ45`$?B1u^Ir>?p(i82JS={s zhO(}zxf6zt|LEFD5d|PmggU?7u6fT+*+ZXI=88DQfA_2FD%_bX^p6&$eAELVS1~$L z@Ct^>3Q}G#Jjk@IMnHxo48Ex z$%gPyZ3~w|6S$v|00^Z_1d+Kcr)FvYWmeZ`wLm3bD60J-Kyo6$7)0Yi%~oUPdnem` z(vddy)HFE@hD-%V$@>?Dj7Jy^fYy@b4U=<(e>a5~ zObYEt5TP@IJ0twpYjn+~#@6=#@_CSQbJvZ>G*Q*fGb!oT)DZ*6fQhQu2?ofbOtoA5 zquvvE{3VF`8GKtCG4}947T{9UAMJ3E7g`0#>BE~-(agzGw4%4jl#4U&X1qK0hS2LwCu>Ta>pQ4!W)}ZeM%QwG z>DAztxK_)hwrils$sK|`wtq31U6sASV}6KI+#jettbxm}KQ`DMaDKwjT1#)9?oSH8 z?5!j9>^MMH;bzewy8To8c(rgli7)QM#(JKA^@SHpQdd#FfB%)6cJEV27)H(%Hf&aR z!o28fV3{@0`ixE}w>2!}C*pBqcn=}}t(&p5K;NZzR`usyvV*7-?t=p+z%PJ`pwE5mnFiVw0ZOeQ$M&oQLKi5QgYeP*L*q z7OD*^lxi>eIw|kir>7r`WdAqz-aQ)1{*U|p-FFgENC^=}sN|4Cln_QLhDsu*NhsqO zw^L5no#R9iijZS9LQHBLa=LD(5D62*h{>taU?MY^!}Z;3?q@&ydDecOz1Fk$+WWu# z$Mx4--!$|A!fB*<5D*-%f`<2Wx4V0jS$xEIHUm&O%L*PlHl z-d}oP#9!yuTQQccKmlOEes4TqWI@~}8Vo?Qg#&SgjY&?aDb8$`nlJ6Ivne198=WgM z?O`?6wZ?LO!T@mn0G1cbERbBCZHbAU>ZVbc;|74j%}&C)HkJi30brMkkUAHp#*Lg? z?dYW5bg4Qew zMK&YU@5h93u&@KYY_N{MFD3|~(ZjEw>R3$Y=NOt1@(~oOgX*K7h7o)x7>+_I;}eeL zM6t|*wclNBl9*%Yg7j-6N}IfJemw}#5f@n^y$9)JQnnsT)lHxJ1rT1&;@XuqalOI5 zi|Zefa8u@YsCRTpsIfn}jqJr@#8G!dVbNZP#oNI|!W$N>zrA92h@!-mL=rWG@5v_N z{K#Y-6&)Sj)aFNmDI|(;*6QuQ6NC~!6Q?77H1YJvZ}R+;o3 zOf>C?s*H0Xvd+bpM=XNHqIDZ+rMmoJS+7G>HNl+kM>KRZK2hdsBsEj;;scJQyOjO2{VqU(&a8V5 z$ZR(@M8!=_sR}7{Vsvc01<$nXY1<=UpTeeqq#xm}^($G?m3QRKazes~jow%!cK6Ho zPS=a$2;x4b7$F~RypzF!_C)hJwSD5RQlC6<{I|6F6SP83!I?YKU`?Ii?3jk$9CtG4+Z+vO#q%UHm|AdY&uXYXJNnv;?`rw^5!|07+XL9%#x z@!BngBx#Ixi_sNM>6LD!OSeaOac0M&C}$bib(C^?MDxLEprEl)N*zYGWyxU>DMmk25Y&7MD19c0gi(@3&j3 z@m}rU#_qM40%(Bb7I*A^++=^qbah!UL4Tb*#&k(TE2bp&eInc)rIC^i!Rt;7J7uWV z*wBk`cI)>1mxkKD=2poFaq`m9U{S>nwR!I+zJA9KA54w!y8ltXa)+o&NbdzAv2$b* zjA{@aecv4zfyx(p0BKYoqem7n$D^7Jib?2vy|f}>dn|n%8e;eGj7?*WPb_NoS?!59 zv~D|-9p=-B>uxlo;>xA+X9N?{I=tfb4w*+CRwe=t=U?O|0MoDM)b^3X=3qcx)+1wd z$JKtn`Meluz~uBR@Sx?L3OyK$pAh@jZG|k z3O|U-gk3TWx!AAR&BoGroN))RR7>s;!|sTPy(d%?%>puwgWJ76i)j+LAcY=4gd)@pn#2RhzFgs5YjG= z(dpG-)FJEaz4?A}&aA&27%%`ltsy%KcCv@v%!}qt@u(4q23$873&6EH008p`KPI(E zGe?Q;6BO}n(eb2i+^9dHz(orZ4L8;N*WCkM^>gf*V5okp4 z1&y}aC6X*D5?~(rj505PZ zN&7d!2cJuE7PXX3vrq*Euprj?!AmtfEGcKUah0qiYq3VOTO@=>R-!R`_H$o+s34rp zML47m(a}Be3!!gLnL%Jw2RE2zvuUq=SNv(5LDo>Omi-?Gq997EVpkUV5%8n$Ip)Bv17-TM01&yT!jSulvgmE1XZJ##FT)pA3@3A;YruKvDY zvX)*h`Zg<7&Hr?EUF?;kl~JOclZx$vS8g3cN%sD*m_6kcYOzsAM23i+>&-|r*fF&y z(iBFD3HdmxZ$-QePw;%^$%lttKPzJZXO19v9Y-GxU33(lBHbO1VBLcJ%1b(S4~15g z^4-e4XCf{0#0H+;`YmwN6oLETNe~1ObtZsTS&@N6)t{ytb`-`HIcJE+8M1Q<;=$M^ z762pM%_os%DQ4y9nS^8ClKXZSxf-EULV`HUdStMHw1KZQEM+k^nu0X7I`z`*NTpr! znrGLG;2e{)#*}QRj&;fa`a0dF&;S;wL7)y$c6MNPICI06J7!Kigv7@Uvq=|@6)sko zkHgClplwWo_wXhFyp%dNfWh~!vEtPXPER+>|FlCz53}b9GzHaxvbnP0s9i%8Vij9q z6U&%cgd>1+T?S$bPqI1exVlNsD1-$7k@33bB0836_S8os(<*NCxO=@UCkd14a6vt^B4rbznt58WS6|fu-{iN+jMrYsxMW zhZT0v?NPyo(jPvqt})t=KkM#F-ZR#q$)b0b0ACbpD9v`ryUD9ik333g#@2FOgQ?xD zw!c6(|HPQ=>MZ(nJI2t%NVwdua*Cxjw{E(L$CH+|>tWg=uiWqF=IcZ>T3Si8^Uq!U z;<)_vKI6;`-+WdA-&Ny-+%c1}FK`{ zA58q<;}AsQ?MAjRJ2g+y*hfko;GA!-nHxlkjH;3Pi_AZN9CTFA7D}axOFKAwzwvtR z+v9Fl+yB?qd!4e7o%gwh7wvx{3KE+DaRPHHziAHl{`V>z;U8yO_64CfqtNLN0PBg^D@f`o{4u z6}2rT=%!qqfa32K0aVuw`?>K;qljV})eV>G>O@FiUda_;@u4c6Y0zLC~TZ6U5-s2DOuZjUe+8~ZLMWq}5Xozz7 zl{?{HDMjT03i8S_itgY?Pg^{iRYD@SLWFg=hK%*wAoePa(#v`luPP%2RY)6eY@Nnt zE2dQWKUpWu8rgAzs&AN1N=R6*WJL`JDgdm*QWdK@?ZkGMUM2gh@w=yP7}BwQdZQsLP>|qOjlQYtB0O@&WevQyx-^|~aIUv2Xhi+o4a56{NA#naPWRk{ku}xaN1H=< zJUs*CSUB;xOJ(yD9?peTem&d@Eb?I!?XF(^rsg~LqlEcdp@)v7{Tu7H%&_mKOJ6VvxHHL?O8dN{t#ETUuE1z&3aSux6US8)#&vTTR96MJ@c7Yk27NiFC@Au ziQB|)l-@j5x$BU8-j#u#IqR&5kf3$Om06CB>P2tCGi)CDMI30bz1J-;srJW-d+*C8 zJHjQ+5~a_yZxiTHI^}*?$I~DH63c>>YOw)Ibxh@RxhqIcy=o|JEW()OJA6f zV3ug{(&633BbyUNd!Ks?Se(i6xkusC*k(W{i!Sr|dsIY`ATuvyi zae{IeA!p0BdWDtt?sg8dijywq6>KtW)Zd{097Egq;-Q_t%er|P0(0C3HrxQBGDkYL({2ZGGDN&(*bcrwRB&a@2A@2D zBBu#Ys0G#8*>wkx^*9p>6J=Sk9x&5+>-rVj8Tdvc-Y>kt*M(4&A4_bYT`~BgcI$0F zAa3M-cntI1%w|Pr9#`U$D0OY!@cZu4*Bx%zU*YAs`4g=%Xv;++v`CEgoZ7h@ZD7D* z@S7j=I}fq;zfK@gM!Hu+4!*xbB(Lr-#g)gk{VZUun{x1YyvH`1&Uit|t0QmhsFT&f zvnZ6N^ievlVsA9hvKx)I5Rz8%5V2xTqfmwC4n(CFJNQ`ET)S(K>N)oz;Ihig$)Obd z0#;!m__Mcj;^0RK(%BzAR(Rx^q5Yd9TIF7?r=AdRTGDbA28TOEJRDRn&kuH7dJjJL zYM6<)Sn1B({_C-M)aS**5tDqZk>cfZ+Id&4oGS=Voka(fm5ofZD)T(BE9*;nleT)Y zeu5R5nQw(;ezxnbzBSP`*RwM1s4#LnADA~@c=Y2!r+>N#p@K)KFJ$H85C48l}oqlYkW4Eo<0WkqP}myC6Y9yTM0 zdkF3{-|70X?<@ZNvs3MRXT;TUM7xYt05jp%NKVxo+vi31-p?^t%dm9}NLj>- zqW1ia|M38I=)r|~Q+JpGUq}-9X-rUXGYlpylH4ZtMyamb9+1k9s;Ml>dvdR&L(2BZ zKQFGy{F9(2`EPp60s^2Fcgpt1Lk3tu7`DrXbs1o7)s%OY_A3_R8mpJrygS^nySJx5 zWESZ&-*w(%>SWL>wTL7Jm}A0y86%5;Qe#TxV1Eq(4&K=0Lrg(a{kc#O@pA-#*(Rxz zQSC6GvlY@)>H#*E8!GN2XZT3Zc2Z5s;oae~;Btspbe;}VV8DYAzA?e_c6L-xHM9>% zy&uQE%@`OvfFLW^wRl1Nggg;E{xdcLVy&2ZRFAtHt{H`DSXB#j{)1ovww$az1Citf zCYwz zm!)#@K6@Jt+6{QTI&HS~?d}d=aU7ijs8O9lmV|l?*#%&+OTj%f7VIZ6kW4j4p_Fpc zL};-!tzWeBZ#0`TJnN*>FaaUQIc^YOFl6~jM^UAmO%@`rystG0J zbCiU{&7HzsR(Sk}yXOGXA@xE~**|^dvz5l^OE90Lu(hYc<(`4;{b$tm!G2U_TSZpK zi$y}jGXfbXN1{y>gjW@cM9dUqMa{0C!FSoeSRd^CkgZdFcG*D$BVzNkT@Y8kyp45+ zX|s%~lX|MRq@zP2>HkU^r5%?L%}H@$2h zbSsD*z1qa~n~+`#ykMxW7HTW^Wcl6R@T~B{a#1Bw)WO>}*^1|qvsl%mL6qjXDV*L# zdajIN$n?GU2v6@*k1W9|HF3hEbgwDOTDcrSXHZYe00&*2d8BHJXTJPtwo~)F(hu*TFB-&XbQs<;^ z%mblM24`CZ5E|DMP#8pB>jM@EGkKY2$Ew(8;Saqr4q=gddnlV!biq_}emN^jO{A6#kZeD& zPHV6RmxHUp3m%~V?uZRTG#GG=siBngh0hCiO9Awv76oYQZ%VWn4NV&j>sh{t1#xV; z0=(K23vSA@U|PclJq48Wv*}=l$bH}uPdEpCRvg*48CkE9(HD($@Ni$5encA56s0B~ z!5lwD>{mh+9+xlwMZrL=ND4RhDI>>-M+eXXb%V}3%7X!)4c<2>TU~ZwmyX>oh$TDT zI1;2M5=(GHZukKy1V9^|5nxqRNn+e~*{E)%FJpSNHTr^Nx4=pT>3cp@Pejy^Yv1vw42Jqrbe7c4aqmJR};&!~5(9NmI$5nhH zW0`xsvMxzTC2Bk25_@~x^qVoJ@V>g*b63gl*AAWigbS9y5$cO?;tD$Eu9;*L}0{m(!>aF*t9ujL#7LrDrN(`mc zU$mP2=8*YZcvPh`$iYrHPh{0^;`ns2AFg}4IZNtX2#whso`Bc+aY0u2om!b^tKcR^ z-$L=dt@zwY1w}me;=u2lxwdRO$2_$N5EY;%=u+-g=+GQX!x2jI6z&(T2CZ2rH2?~h z9Qkn4+;%u3yZ-#U106VaY$@Tkoo@3{!8q*?+lg!EV73B-y`5?nMsws=OWyGCcLhQPTXy7bMO5u+X|hRFJl4; zS6Ny?0D&2x93V}pVZ14Q(9Ez9E{TdnA8D7D6-}QL>a{>z5Ey}pfv}+0; zgRavpeVq;2scN|FjQ)eYJSezq|zw_~6)fpOCM1Wk} zrq)$hMcuc8_h5EP_o7&-uC{BpLIexE%og>&;KwMZU3^kY-gRtzwp9u(b_HVNEt>mI`*zd8O3bWK00G z9JB#g@WjVY;cfZf80&NYTI;6mWC;h+)}N(5XlzW8^A9HbQN(d=6-E{fB`XYA0ipXuWy?oj>C2d|Zxekff^*rMh?Z6o_Z}5(eiJOJQ68CQ z=dO&$r^`xYzOp3HCFUHu;!fWaI@!~mqyP}h#(p)8rN<-c73NMAGZ%K;3M;#Yv-e-# z_8o1rXT}&4WTe%VSh6@jy-^v4JHNZIVTNEQf9z1JR$SZMc97g!?SGWkcfSO3`|KzG z`pisG#I01GM0H8Zd0i+ODao66~ zF?jy0Z0w3w{#B4pv97Bd1%q1a$Y!|G@tL&L8{k*bjk*~GGeYJ$0y(z=IMc0GqNGDq z^<12c0ol%d`8dS6*deNgE4?Xi0&uJpO{c zzjfki?P_VJYKU^x%-&P(a_C3^wkm&miJYrEmK0oA6Ru>b$9|LZFgC0^V%^q@{N~N4 zCiMq2j#)N(s*>h*NZLl+pjkPw|IQ?2*~Z{LuTzQX{phQXdFEo--0FO0u+v|UoYmNN zm#5Cge*IZ&)%&xi`}76K*$(qg8(Zd?oJZX;a{X>wvJ+smu8C_f?ILQ56*f&N<2bE4QgMte10yH%gEU_PHfb*iM2A+#F%gDl2Qzk(zD>oEw z)hg*>bh0YyC2MWRommK5m=_s@U%7Q~(q}MSom0nH4v7HD(Kqrvl-}kHKS9Gc>PMP4 zAvTkEal{X6caXmP4eAN3`VoM3)$Syl|WMg&5+Oa0o>aEeU#pZfa-cqk^?0ZGqT@1~d|$=!;*-kYz3_!i z_;-H5QRljbOQ^lI)48K!m(JH`nH?wTV=3>mV^SXfi8D4<+wi$ic79ldbjWGt2s5zl z_@XKkp!!OUy0Yxn*^y>K?}u`NP4rBXFAU336OUYnSZwXb`LoayO% z7q9sABJTI8fqPmN)_1n0w#klt*yCG%qeyDkJ{4h!a21o-B>kzg($%KUy~XiL9ed37 zD!swU4qtkdI_{iLT3WiB^>SHa%5j}>MO5|TsLt6thU_3hQ3US72ctc6Y+rE?-I+gj zNLdNkr0bqZ!4I68n5cXe|KfwoWfe7Vn=6}M(`$3`m2t^gzIcm{pf%dU=zMG_r7_|8 zu~cKp6wSj=Peosm4wbffx%c zUlvd>rspq`h3?-On8ILb?$3`vUl-|wtf1=9!fMG6W+dCC?B|#%YI$X%hLDHui4c<` ztB*w2JrYyQJlAHhJQ$WoOlpdnMmp1%KJh5)X3D-5-DUe#K4uOj37LC!*?Ny1YEt0r zFi#M{uJP%;yc3#CE$P$EWwyhHRCah_xm3cH*+G7j>Hdkgn*E6<&IZ5tk>sob1aN~E zJ;Jb#gsQA)tfm$eQ9V^&DjS{;P8Ib3l>z9^fX>Yo9>qEfMU)HLh7s=a9Z1G68@#ou zau9z1)XCa6kk$o(1sDQM2&x0b+SrlX?N?c%4L0eCLD?y50w)6*Kk515O;KRobd9UU zlj2xo%dL6tvM;~{-Z z83EX8z+)r42*AB@Bx*~R>fx_3mC9xr&3Sr0AW{RHnvE+XpoHkykU^5|emcVQ#7aHY zCyhc_7aEny-dLo86h05tdOx!|25s3XAZ?a}37o0PQ<^EqrKY{Ce()f*vegZ0p(4Ly z?K>1$=VF?Hgt!kHjZyN^(-5=?1#N&S^DY*Gk>3%l3MOAuD&Zk0?p3rLNXD+VI9`JM ze5BK`cREZPQ@o;F)8 zVvZtX9E@xMCfY5i?K3~u?qoib9qFOJ>_NvhM5dV!dF&DtCbDgGruaWbUbgc&i$dwB zs*${O9{e<&cWXDg)LX2O8IqE*)@u@8Sok311b#K#DqBd}ruqs>YjDvm=aP)Vo4sF} z&^>BKb1B zkm*>SC~ej$q>aaluKQ<-2FvxjXJi(SfDEPQfL=g9i96&pvTvJ%pgCH7x0 z=6qbcBvn=x20b(pDEGi z_oRHg5sw*#O8J*OHLxliK&z^=f_`ww6Ndy#s_@Kph=Z4BXDAv;{mk9s7M zwY_e{?JI4{j~GE)jWA>F2hlGwnpC28U()%~_-2lIX{s#fdWUaX_`Zu#1j&nTH<6}J z9@Gzm7i@PE&`x|9@8@p7i(V?I%3)Y%Kd5Y_*T8aWpn<{w7>9__SV#7yP3Nc?A}208 zO+{KID_yUvaJ>M%EGR75z)%wtp;7*Ipv~>)PV*($Vj#8&Y$q;sguD7xZv-fY7H7p~ zc>cbx^11^MpEUEh5$io5S7g`_Br5>k`ti12m}7Py0`RY5+K(7Vq!?nC=hZL=unY?( zXaIoC1Fxg7*qZ%Y0(H%{WQK!hMmp=L=EuTB25_B%v6}{1q&rNLo~*!uC_%374Jziz z!i4jqdL208Ga0F*99R4>Sl#Ed{ zOIrJ)CaO3Tu64273hd*tYyNVxw-0)o`;A`t!)-HJNIU7(HKirhJf-D;Fn}e>`vf;| z!rR#ZUgdkxUo)&rJ{OIF+>X1nIvl_BzUP34%h1hThPVw0aSstJ6F}rE%cmWJKgXca zmfxf^Ha!9Y^pAzjR7kTD98zv`gIg2H$9(qB5X5m*-(pVXUX(I_W*+KhSxVdV)Lon& z77F3-yOT_KXt$crRx0KN1435IR5_jOyc0K-Gffie6z1)ZJllB$po$g1!V|rBUb{7h zOs?&4{8cn)hz{fSW(LPR&MoPX$yd!BTLd0P?n7sOAFRx}dA4>sV?@j>FHf!L{%oR8 z6Vd3;Y@4Sa#4@DB^*XNOZFlL$7eB~b%@J#;`}Dk`(^ zK3rZ&_sz!nBVJ@V+au^9 zeP4H8+}B~$o$eu6nAdhevoIjDt)R_q-Bu?kk`Z9EEJPZ@Wj}uMyHc6g{1B?CSXY=b zSv1MQyfFwJ73|d5?egw$S@j&I>?c z@FF>7>eL8kh2fj+J^fI5Pj&6CD@<)huT2KG;fKO%A!T)_XJb@*D5|b@v@t;w_wGQZ zhv7_awPb{H1n!G-cs^XJ^fk?Vzu5bA3va=TI(Fy0Gfc9mv!;O6*xp07Ze@~*K@8V| z9M-MT4M6qtE!8`SFOSO;GblU-m>QJYOG~ERv6&J)?pM2Vzsl~{-em{Xc|qp#iPAQT z9oO$Nl>E)&1tSl83OvvS#GYKg+?_<`DClGZ@O}GykYGM>KBX^%#%NwyU$(DXd;+if z$sNSjyrA8tHM{&MpqvN4S}%t;EL$ha-u5mUJdJWhuiWcE&k>Ks+z-!BB9Z5-7;SLp z9DSVz)+qpK<6uFuJvZv-kMMa!oOXKbI@;9WdofjKQtEq~j3E$Yu_yFvyPoX09Tw@<=Nyp!ISQ4K=t8=>*>&?7Q(AE^$^*ifSi8EqOA;j= zxDv9E7+{4I0^V9HazK^cCZ<`7K zcy79NL~Gvh8EQL>9~e7^mGB5=>NqQ`=)WAu85P88ytT9FEzvaKR;lL8;DKY-eb23Z zr*;nnzAC^Swl~^Fu=Z2J30}QnogMXZasKU)j=z`8H*1TFg=!vx;U3und6@z1xMrJW zRiW~78P7h$Cf#l#npS!1Rz}%{UtYKG9C`MdII|<3r+>Am=*d0Zt3Mt<&uomF#Vc(Z z3H0|p**kb*pu<~`>~}|J(ro^p5xoP@K}&_JYsYCm1YQH$g3rdn^l`=gZ#UFPsRyB2co*kG219)u25e3%~ zrmhZg?AoUDx2ABL9Ya05u|^%9k<0q&2R{ls&$YBPXs}6UDL=ZRlmuhsepyN;OQRFsYpX2-N(rkQt=5Au1w^hU8Y#q4 zp+0N$a$RgS)kA#qU?N&O(L*p!+v@%8%PYBeE@kNoQPHdPK9~s*eIf$0qbj$8FabuJ z`lMMfn`l9RgFy{ei;bScBI=ZN^ydbR$-O7~EG0>w9~llCsOajSvCbL^;L&fdz=9b=9e|;pxLcdLPAO$R~~L_v)$EkMx64im}|);!aKMmrxi*IOa;Vy^9q6hNUwOX`mZmMKS0!z#_6 z(dV0-)BSYZehe$l9@DT=RIEPlJnx2;n47Qq9O4w$k&*Sb?&Uo3bDXu|{ELf5B0T`8 z*rYSNUjm?5TJm(UgmKkXAoSZq{Le!+RlcXw4s%oUf-&F!WFGvLaLIeO&<&FdW-X~z z_YVWaQlg~R_H)SLXMN`q|0-4bk7b>A2Y&1N=vC`orahqVx^wwNieve#X<_P7hT_Xe zwLZ`LN<`tkU^CF^Y>- zS5D-d4AD56rxN)k#52)wzV>`)=55%wV1Pbr3J`i~oeJh>2kCg0@9D=o;&*?BRLrj; zrt>eJ7@7|bOvruhe~pey!QT(L$c0b?OI}XLT*f*!xmUw)RX1>OkI1N`Rk)R9%iWL zqx@@W4g-&nnFdVc+$*;)Z>xD%`W&5F1$wqJi&ek*^bKd`Z(5H5U#+-VM-lh7WE3j= zb>f>nHx0qUyUH4r_~nm6$vQ!L0ah9}5(Duq1$&>}@uNbO%aa$Bap!AqNZkL=8G-)^ z&CTHdM*;_U-10uIt$5*t>A+wa{xih5kr1HSvyQW3{i44O4CLv0Sd3aat7QKMoWlM^r0Dy7swo0O>)?oR-tg)ZUAH9$ z)6R5-u{B7d(ma*Fp*XWQD3IK1&s*$U8=*&vZD;yQLY$U_E~Q3ZxK~Abx!=3) zLP5*1sQ34-%ej_g9)Eh<1nt_k%B~np;~;%v-S)rFEPrT}_=j2KYwNi6M>Oc8GUD zCE(brk5Wm=LETv+j~~^1wbLvRKq=MiPf728Ux<;HF&GSs_H4a==paEXxd5XuSoo;y zp`8Gz6xsR~yV)H@PLGz-U+k(OecHNxC6-kXJxU6LEzsIn1nAVd~ z+xbr-NlHQ_alx&N8o8ZE>}$W&k(5}XxK?$VSMzTrBKcEx$OPzSn5&khtP+u5Ooj8|C)p zM7r12T~^vzkm;c02tF;ocB`?5wpK|kkh zyW`uL&zO>%(wO2GG4TM7Y5R)1lD%_c$}Xk7L@s`E6+L>+==jI8u(PXEluOs4_45bA z9@|YyRo6PdnNZxy|BKjj(L1Mb>&%@8Nmn0ZE~te$f6;ooUjJoX$7Se-t$$yeeN@!G zM|;#QIp8F*IOK2nK=Dn~e6Wj8>ugYCqsR4LQL#(!KaseuYsD>2?4663bEdA*?_KhU zxbwKKApOFBBJ`bS0$=qszQ6dNnDCe&m#*T98YSwFrVIX?)-{5Uwt^D2PU;Gtd)$6- z*Zh~zW>L%MU60#DoDb%V7?xkzabEMy&-1UGO~Z$QznP8o(XS#3{StcXTHfR`?9;zP zui0Ny$p3Vu5AI@F*mVWbh+^R>JZ1azw zdo#A*k^j3O@(DZYnOJb4%Gsun&IwYDLDiCNeXe<62>IKN(6nn*!H1{DHyd3Jhxn*} z%-CvqwerALz1#9}RYn1qIfq_GK@jw35)~Kat9BWnnr04#tbXu*wYuL$L zK4&X4@v6bkP0lvr(L#*0{5du1Ldnw8-h!$rfxBK(EpX@FN4JlKe0ga0)qEuNUdz}a z7N~gj>(zzTS+~dg6mGW3704bO%-6&Ic~Dtfmt_7Us;z=fx$bjk?TJXjQc?4(52k*U z6xFG{mX9^GulA1>tm|Kdv1e=R@5j9T8+JZ3a3mn_uM1(wS+9>{Qrj|g60a;RMdB|x z-)J8;EIP&M@y~R)rX)^E+@^YtjrJbs0d0)g}z=stPv?> z-hT>5#^mY!8dlwZabi4J`E8G8shXRLWwA_DHanf(8mcQFm=dP!Yp4+N@KUguO%+a2hK8@hdep-tGzWU2f1 zY}fmxF{|nF6mP^aS)y95=ixsQ8uP?oLyJV^FPx$8)cf+oGW{IN5-)$P^6Xfn$8C=h zS-Wj+lR58*W1WST=Z%SLF2QHF>l_{eZC&)h{cgeIizSmkBIX1n!sPFt|M={r;^ApY!-Lni4V?WA%4!<5u9pv(e0kpZ>RB>~y_%pzNKue$ZA@?q2^F z-x|c;qoQkPoIT&99<3LB?S1W^t$hLy2kY&->m&YoOlB3I+dqy@@lQ^8Gk#=W!R+p^ zz2@3ESKs{ecwd7uVyn|~JA9zXn8<;^qc2rj{!o@yJhBi)BFVfs zmGbny#l#J>g1s_If3G>dengYCewQ?-VW67(b?N<=mDFm7SsB-R^gSlQ2LJr}symrm zk#QY;jx(7hYyH=gd{{K--G62W9n}sI??(Q!^%XKkzS^nYXQp7r+#^+tPp26=faYT0-P-U{_m{CDvGIU4xCBmw)B{C6ne zf`>ac{wK5HM@;`U4*6e40Uy`?Z}a^BmIbVH-0;N7|2J5`neT7QHJv!H`=dn)F!2q%ShtYkAOLL@VrU4_ z6;@VUGlG#lScyPh5PdUw5@xmr1CWw@=HAgL9v2mNLGa>+aW2Bt@Nd?}B^Cr>` z0^p8vgQ7RW008r$>R9GkrzS8JOE4?Dn415_<3{ZfV>;dF0NVcW6_nXUJWPvbCz#+9 zBJn|KZYiarmzHIA;GGSoFe+CJX2>MFe0j74CU&>qRnjALQ5xP7fbs}fz2Fq=%I z(P%X1@mJ{s-m|BacoFNrR)#VFU1A^1rwy|*Exx6I`=ODA3Cqx|IsyhvOBo#?^S5ZT z?Ec``MW_q?oO@^A=U!-9sC31!#&kY1UD3yR7Nx~a`E6_>B%a)up(J4&-!+T*e!oRk zm>4tHlU*v+m;q_tq@787>59H1{78A*HKV;szyG*qQG-(FE&R^ycx5vI@L=#}f3xtc zF*jW)v38GB`dOhb{`YT5kT<3!F&H2rQD|V}j@5b+t8TX66>Y`Ly!Ekc>!7lB{tPK8 zSV{sjy+saPJs2RJUc6l*X-~nvpsnppZe(0a^Bs# zGpw~XwiB=Jg4v--eb{tQ0MhnTUYK3NW66u*=kNn-Hv9C*vvSuk7P>O|MXX?CVgQMW zSBjL`R2(9a(;^>+<&@q3WJLg~40_MMNNt=yT7D=W}Nv5bA z9LC+e1%aZQd6AuV7(=j-zGc{QKm3CNHYWWD-uk44(Q(!1huRQ7Qz1PRg&f3n)d{sz zzON>)x=8a)Z~;F);|EYu-((>OFjgK@0FcmMc=VU5=;J>H2EV&kQl4tt+bDkg^Ochs zcWC}gLz~Qz+(28?J2Qr>fcK~Jx-71|I!={zCYMlA2^8v_OvX6;-eOj~hp}WBJYiRa zk{)<3lqyMh>iovwvh8sAuOP;hCXuT(3bkoPHr2kakp}EHykog!bDxDzuR2C;|YOifMw8=Mz#d zBWOz3%qm4k43EU>bqMAMLvch+ojFXL3E;Z60RSLG=p~?5t;*8-e&7G~N&9YMhf<7@ zkY%Tv(Y>BGHGL&Er{&eo*C}*@bx=0Pe~!ejADNs3GZ5P^n2;aKEALlGUq=8WMg&BD ztVV$eiA5?~sf1>MK$UJ`l{W@yVY8x5s?-e=Ei!Mc z)vw`uKN!?PD4e16vBrpq@X9AGR-?QKc!LQ*9goF>f!)$NHi0CuQeG_bsCSI1-&e!EDMwPoSGg%5?%@ZJ1<%3#p z`=bG?6#%M_Tdl-3IrCMb(4qR=P6#{)z!Q<&^f|%9&{+zLQ=MwKQV9u(FmPT=(-h)s zXL;Q4K;vVlEQq+u_Db;%iD}f4Lu~9LQy%X(1itt?Ht##j9$07k#HTDsijg{kGz>%C2Wk0re;BPdB@{9>TUqBvFFhZ&Ys4pu=MG`Uo~k-C*7cZiEO#IfZWMkIM{V`R-OBxE_Zj8x3sGzLpRp0MyUUB zo{nSPtMeIiF>S8a&hyZ$a!a{g_y0!HxyLiz|NsAYl{DqBQBLKsO>}Z>B4UjRX>?Y^ zl0(*#LqbmPPYgpjmSc{EBG$nvVxJtsMTK2VT+^g4`}*Vc{_FjE z-JXxfIGk&El!8}v3WoDJ-Jg%Feb=yZ=)V|&m4N@K~WjmUpi48;q{t& z2dS-s2!V$b6fa$0x~V^ZqDg;HKs#b?sVL+|r|a~zlLoiU6cgX4JqW58nF>86>5GrS zW*aY4TbKI7JKBFbN$2>O5|)nLRu4;_%6qQea_v0AwBqA3t~lg1kS)#`d$&tgSgG@&?8Y_h&(ax5Deh&zH)&3&A6Cmyl4PjiYZ z`G%qqu5B8e*lxq>Y}daQb6){^rPCprDimmN229>fILw{>R5XW?UPv;E!t|4hGLxNz zqSPTBc8eIW0Fg0u3PNYOnVo3V^14Z3qrRMO7= zI@Ovl=@M7AwSx5rWi$w6&SYgB_$Nu-&L#D3eZk)it6g2XJ*ipiFf0JumxyHX@4-D? z><$T(M4Qy)qf#l=h?IeVpUAe`J%7KrB!fxwOK+|Gx>3&A9x0FoU1B;B_-cds8>V7E zpN;jumakHuV)$cEo`R{~GB(%+0JE9~_yjQkED*z+lLfb{mbu20nTaJ-D%F~ruEw62&*#x00cZwm zSC)7m$E#>_Ja>>P7!~J{N@QROsdf5Fc6#spqv`hIB^u~68SreaSJv)Qi}M^=YH{)Z z$=#>;JBhJ>ZL*5EETVzA;WcI#y|%h(g|7C{sr9eS3ST@vDjM?}Qd3ndf*vI(X)xZq zI(B!(+eKU_kKK)xK%vy5i0gh33kV}4ojEPg!)9G>F!wU-Y^Tj_yyUflpFeOF6XorT z&fBi8L}4Acl8PkM-|gE zU!;cq$9STqto`h|jjeOlAyvv;@FkX0Y%8aN&@&Hf|L5jKp-fXt6ceUAU~eJ)786k& z{kv1QsI_L;Ff!u%Zcax^)}hx0fsZ0nUkp<&_QjjzZsI=UmGxI{Xz1toSn3_ThLSV7 zsNoJ@o&O@|i1`nvcc^vgiCbXAYr{SPP5-Z>}xx)%-Yy`vGn=ek`^ z@Ou>L$dcoU7soF?!Z28{{Divi8sb(t#y{z*!!n6#3J;8q=^A&NYzhczPZ5W0zqT!Y zKX>oNoi=%$_)d!zaUB{eFBlCZl^1n}JA8Zab6V%=oHxa4>qt%j$57q(v|hpdNyg1a zSFv01_K|;rg@nCeD_}Z3b%vz{a*XD`re%an%4;EHo>AZ)@J1v>v^#oG+w@)-5aZ2y+NK0KZBi|004~P?eFq(+S7T`+u;TWQ92f; z?-Elqw9L{|212Ictm~Hiap+&l5Qzi25|NsuVzS6L{}YnW-K|0602%~Rl_0^Ck37hT zPmY%!Z3_3(k^ZRcSUvFH0_*}{90k02!MMLm|f-50cfrJ zCHtd{1)P?EmA^S740Fli!Y^3uJMLxsOvxxqNd2^ErD-Uq%HEjn`y5mT0UdBX3| z6a;{PBlyaNc)Sk7`27&@83wF5{ad~CRN_<)?REjXveMU}F!rdMM__^s&G&Me~%^Fue8XRI7SmI!gxg zUjD7)*%XbCPiooS%Sm7gy@mK?^XzMK`Wj-&*3tj^Q;7?ksi^LcDTzORmqjY$FpO!| zUMFg5Md!s(-HWdX*rlfKt(2-xey#=)zT$DJR4@6+5!F4ur=$P$x~hH6N+BfA;UZGY zYOg^KK|vkYH6eeFG#akGYbyl5da`&CgrIsrR1xVnD)PZ8g093c^93$0XCC7c1HbX(g&w~cJYwBzWo~p$i38I+kv#%%H~BsLy6awB36d3^r+U)%YwucKbJ ze1h#T?)Vlsb2Z3JGhFWHx^863W5cQAOO2^$ai7h`q}C?&EyYRUXNRqEK8mLtwMRcu zLn2gak!FQDZM%^^HEp=!?W*v)*K}XV;xaud$_Jk8Od+&S+E#`Rs41&NKi3hx$I--E zTX*Eq)|ft30vTbE6{kun3FF9j>lQGdNo$g-7u0PKK`^5$hjHbFtB3g+H`LNsEp5BG zd(p3Cr8Nf(N1w|m1%xO%bWLPaP{_ZpTIOf(>vMwyM1;+l^grHX_A6%tgz9y{G431t z@>tGe8{$@5$$JV27n_Tx7@LMfU zPRP`(u`8m2%zmBV_zM9i`j%~*Ty6b)YPw`Ls6>v^#wR{4{2CN>30wR-?4wd{o;-PE z&ps2{y=$-X=oPPcpQp>~^Aw*sSOq)WNoT+;TyYd-t9~kVP?l8`mn$AXBZ%%&Y1F_H z#b_YqqN`aGz*nWawX8Ac|DZ zm9GF_vJ+u`7W#Sz4M*3wI3?$+trVLM=byA=tDMnO;joVveN-(VMg?L zW(JRiQ7&+?>-ICM7{NLUk5)ODhGE#G4EPV`4OmwYjHRN5PWXxH{^<82*UHW0J@>4o zCM8#5_eKT#-IbS1zqR30ma&7yYSV#wIg-$uJ?{{E$KP%ZE z72l72{!ScAG`Z;Cadv4;YP5JkxobN@^hGnVIpwIiVI5Sp%}6OI&#McM%6N#^nNkjK z$5Et@+TroGO3!XhEh3eV*4SD_9Df{?qW{nQf_`J%7bPo&HY-c}p5eL?6A3qsF1vcW zn+Fh!Vd+$R>3YXTdc36B;4 z=rF~8OiSl53Y|U>?0K?*6gQ=c+xKq?JShLf_1mYrlJxKrIxY$|rpWF8{Kq&g0Dj_m zcZk!j%-!zM?py&;5soX*)8=0A zI2DqlW>#S@kvxWe;*V!J>2aoA1p{|?631+2VqO(!&)eA_qhFT#tVOXlIp7wvQXy<= zZE|AoCapN2raYJLr`-as;dV$Rk=b}c1XzC~A2)-}>UL&`;=d|G%lr%&<~wSOW5E3r zCloZ}0GO*OC|RUthbh~Iv>7Z;njj+*$y1zK&Q_xs*o zL;o5s3cVY&M(1o_d_wC8_Var}Pc^J$zFHmtyA&!&eY zoQyyqIxgv2@9i_YcBk(&1{o8+ZAezTX%kSDmhzA{$S=w!IlO#5>9T~`4h&^hE`PnO zS^5?qjGa;Y@zv|njeCr4+iUa0tX{6TN&2lrpOJ*8`|$}f13HO!v+l6jddRn#)-m!s zCW#OEjBb*_S|e8fdq&Cn!wQw5iPjgcNJdDYJ0ATZX;H{QnWHyEt3I$|O|>wa)nI8< zzN>q0UMlt34k@jvGiPi%9{nLPpyvBYsej`iVej>MeZ+FBqsQvundwPWntb)a1L8nn zlG9=E*(No6*Qqm_8q}~mM~F+-EE z^g-XU!btC(hgL)G`I;syHXSbuJZE1K3)Z#beV^8TGbku8f~KTXdOrE&>N2i|0=+*~ z2de#L$i}1(wZY4lCcD{gi0ORvx_#^n#L28FSXst{Ujr;gQy*|Ed|hDY{I zm2h^`pO3G{y<>sUuh93ua-|=`3k*j|6|Cw-a;fLfB0W`Y-j@>c;OJnaKA^P^LE8;E zU3xv;L%A6;k}s@brnMT!LwaQ4!8cFoe5md*&yJEfptwG70^G-qCoU)qZ69-$H39CY zOpZ-4uoMQf)(+A>t>P=yPBm+2{zlu1{OsX#C^J6o(Y~nNu0WjNzjrN~&QsL}U}HALgDD`kf{JD_Jb1b_ z8`Ly?Zi@z~0IUJFKHzQJ0`U-p?|M`UQa2PiW$apZ%&UUMq)Z~Q)V~JgTL^l05XCK^ zVUE{_b&kT6jH+1<=bB({5+JDS3B>)~XC(lTxJ7V-4jf!Z*42)7GMJ!lMchh{G@%{$ z|IIFS<$@;nIdz3~l?NjuBXrM@QRh*P2K3#mjbAdN-Sye*jp**c*d))CJmP3Y1gSh$PqCj`<5~d$(XSxh z=tYhOc`=&FyTZi`w~gRpytqb{Rwz`P2JEaIBoz7N)zgt}*UL*sM`-?C?dLPgLt(1k z9R~mNgW@6L+MVpsk}kjyiWhD2KN343x?q(tamF5Q5 zKpn%qzgD{zgF>OLC#m;Rb4JHmGDeORm9ZzfgUf4aV154yEyCUdldz|`irT*q@rdql z(LGeK3i~(BD$@bW$&vUYoF`TZOivU@JZ^>O1$?$(S{?ci{pZ2(DTJC_)(+{2$pR=F zeh!<0#u9#<{yTlJQu!|=Amnm$G=KE#%or>7Ns=s7AH zeYf$x{@X_fFP+N!>hkrG?;-a*UVm~{PL@^1wu7m*v%W5;#H`Ev<@wU?OeZ4)(ZQ#) zg^B*eUmw2W`5J9-?`K)sY3FmD>Cs*a-3D+&WKO;W* zlfmu9h%n}j$sNn_Md`16yS)&5ze(m%7z8;6po@pV;N)fgO2xcEx@npnC+7KkC+R^6 zunH(?PG)-`fO+Np`C&#UJW+Jh}Xw9xUD5S%}j1asD z0E_E_i+-*};Jw=l&+z)LKwQWR@(&xlU$h}^YJmVPu7oKRUHib@xhX`?{!-3-aLxbH z%#{}}Fm7Beh1d@ls_fi3WTXU`zQv-6qF6TLWexVaH*rmn>TAboK%>#thD1d1{WpiI-m`-gbqP#Z6aRB0a_oF4{TBx+-Qt772Za8ALyF- z0Dt?W*F&+?3=3#%H~+SQ3+Wr7q3e(Qcp44<^~_qrKn-1AS$DmkxWE)+M*;0&y)~~! zf7Ih|dUUh2HumJXvO0x-9OrPYaEyOBNRy9^o)_Pkh~({ zlJuH)ooA)HcP}*;<`wzTuOQwa*6FX~nhb*B+zFVCABHe7i1#!08ZVvfeTs$qzCK#} z;`yt5`<7&TEJXxd!S%Az`PA&M&%!l2Y|;l7AtqXAeqL4{p5daVtMx8UGsa%8GUEp9 zE%y{9#(q~qnZ3_Nui~T^nS{YB=|=l4Rd8xY?W5tf&#yxKZ1Z>~`pM@*g|8Q<&8<9VTO>d$}$_8qwC7Aw_A{S{^41ts)S|Dby_K#l`8P#~|0En=KrCOvdA-%a*!fO9zM2nJ= zS3%F1)u!We#5x^sbE~T(g1N2U^a#26pbBL~Fc!TEHi|jg^=yxi0bb8;Ch|fKZqh;t zjz1CgfYZVP(@l*PU<8jS484M4Gy-`r9r|iwa^Bj?_aXKNN)muNoOx@49id;RiT?$>0Ju^aA^3H!G@ARLo?~1ln<9 zH`iKQL}2R{?$H|n1afsSiy=jxXIC(Wxq9EHg3%5@4M(^J{K58=pEESJCo@^-hgnj_ zm87r0S-o|wUB|ssCO8dPI&i!X+5#I#OS#F)WUq;2^~qunNebTnQ|Uh-6|9Nxk2Nzf zcR95B_sxeRJcP1(7J8*v8Sti=G@K|qUYoNyWBPdIV%LhFX(JnRo>g;14xL-Ku*JFB zY`Vl?x{Nok=Z%kN0f@+iKelhon<~lH)-!p%-qJ`JGRTw8{M#T0N9m7uFOJ`K-dpyr zHQ{{3k|?6Zqqxl%uZ-)!L*x2iQMg$_g^WRy$F=@`4;YpDG|YkDq;zRbiZa~abUl>_ zx>v$F`lnDRoig?182CN1u0(R>7p0rdR?n-qC#jpGPD(4IoUTT;+I)SlRo>6ADYeVr zyOCcIof3jNii^~~vsCPBTKbB*)l#xJ$}RHzVt@zcgf9Zd*g0i*r^C+C$P9s)Sl!>Z zV@CsO-_3~^HZ#F^c6Zn)M<$L&XMwI0kyOuVLlFr(}3Y6EH8N{KpWJ-Kft@;X;Ct|s>|0k!nw{ylrSk2rq{`;-aNZvJfYoMN6oKTqcJRY(4m zDENFx?xqG}1&BqS2(OyiF3mukLXy@^olc5cF=MGfLG6R}&&eKZJg+!5BKmA+y$qOk zfYPqVkK5uZ((<54-~5KG_47fouf|VenF3KYOGx|W+pMn;c(XVq|HcmGGi{Q_6b3;u znwXiSe*mpPh<6K^W(;51OJoO6e2MeA5etZ4Ve;zm5UG^BYEtR_0TUo(I%duoM(Hy_ zs>#yd`CP!-EYkel3!q&)U=lR(K{MtTu4&(2(bbXAUSV_*QxF;}BQYx>1Kxf(ZIE?7 z^mrI<{spPF$av>O_Q#Y#kU}Q{2e1((VgV>gXCK@TDV0tA@44V2mAz)LP>nv({FmtiXghLk zPPOewh@*Jqo-?!e0JzEnU@6v-uYMufOvxkt&4xq z+%`v=z(#7bjLt#G;~NjsF;Q>X_yx@^4GNt`*7YWivDwAq$zmUqx5fHA&<+WlZVZZl z)QHSouQIO>gX!p3p7nVd8g=K9GtlY-*0x6U4}BqyH4}K>bUI~viR-@pQyIuy2pAYJ zpx|vm!yqJR&42WR3{uPU@8+@7Q!BL0q%|2*aa1Zb^+V*-e{&z`sZ`vz91<en{iy~mQzAH5xl zqeyGsdW{cB;9?k8+7Q(=X*~X{`!E`;pGin9-W)SVvQ-cJDK@H3p-eRI=2HA5R?635 zD%LL~?p~00nv_cIUpd*^xsrWTtMmXu6ICWJ%YATZD+oNVqkigS;f&>@s^-EI$%nm<6r^<@EJ7Ez>t3|N z)iicE*g2S^w5kn?xR1R2tB7#)pc8^)D<4#Z6#EEkU zw9-u*ob(o-L2K=qJL=xeU-FlNfc$+-3QiIpFm#zbx?MDp;BCnL zh8oeqmSGu~!me?^cz7=qJ=&}&g1-4y5EnK4gERE7U`!yO4Rd*Oy3m*?M5Te;`D!Ae z^YXiQ!(4@+xbDT}HzGf*ssU8?B5>hFrf3wS*+Z4f`6{sKn*M z9nfb3!N}YWB8w%gK0s?Dzxy6#xEgO`}gNBJGGelKy}S%4OeZBbfcs6 zVrMFi?(~bbups8~n9ZBKT63wwaivJOAx$^=-1Rv$trR{zt@y9j`I5(FPa;XVALD@CkuI_ zk;+K8FMiQ@^nYarHj>Y*R8pT#?lkarnUwNX_;d22S|&OfcUsxn>Y62T1)8CNlBQd>-& zJk)M8uJlYHxNTB${w(S*{iV$bv0bzfqKjA538Q*{H)06NM*U|O)sk4{gM+Hz-8=8f z@>Vt^idZHB(B*077UBQzuK95BCLLOrwe3RzAXZv0VskdOu~g4(2y6m6Ffb_>fdLZ; zthNK8ccn|I)?H5Kf9VvaOVp@{78=%FXlpa0qEWkPEdVTVherHPN5?)R)%Mqlz=S_n zksDV2oe)zm4|!Sc;aN*Tz%2?|)Hw)kPa%}5Kl-nq#M&qDzxI9_f51<9Y;+p8qIUm9 zYVsbmX`g$k&hWJE^U8qUIn>!AKjak3%j0yaU&rP2fv}VmJZ6Qo+saKTg{$~jJ4EGX zYVsVJi`k@78#9B;LzLT)8$Z%=D5?R~pVSUe7gMFmZy0A1l>C&SpBmMVOvv07c$=!t z7|!BhJz?mjZ&@k-S`l~~NU?Qsf8QC1pb4rTsD!v*ylAhLjMVKcUK6koNc2Z-_bV|t zi5T53Z^wF&tKb4yKTy?52dt1*FwGd4W(xPlPGkR=oOmBcU|(N=m0YpYjFFN^A9j{{ z6=FO-re4QuW<+D`do&Z{>~Gj%3KWuV7&VAIT`Tw-&nS<#Q_f1*U)7RsK{_(dEzGBR zYx1Qv$L>!e=;s=_v+aG9hP5;O;ZTRoqdjS}UY1(|$5*vq5YjeB3A;-J@zbAEhg?FR zzpN0P`QFcnX5b5La7Wm{MSKkpr(Q|<`~u|xkLyW&_Z+o#A)u&iquVz-e9OR3yHT8& zO3(zNs3@R!wEVd|EZE9_mD@C^JBk}H70cI%n1Gt>9?PubIM)>D)3%?{MbncO3h{~K znnRSVq9DEfdM)|@60YfKCIuY{=Fb$L<2M2Dn=dw;NkI;ulUOcdL+9wN&$m8od|qiN zQvWpxJ-n#{IJ9Q4wv9bZtf-6{SX@kEx)OmviuE~ir6IF6Lv->lg=@y1wV%{rAfp+O zTj_vE3>or+TB5ZGN)BMLVQ<%E2Zzs_W0#Gh%=bpdy-do!Z>)sz*PGbPTunIqAU{Um zZAIy$85>J?JQHye)9>Cpf`^ zx^z{q`pc;%P))3$Z}~6GOwd1gZbM#O)355H9&W_3$PJFjL0OfTj;GrPN$)vb8g%D2 z7e?!IBDW*$r>F3MhHDoGh-qR_vZ~hCUF2!a6p_Qq$o%X&N^SjnzhBq?{D+w*1a9F` zzWTtLvB?$gFK4VcNJUq(Nzs{93VdjCTOVRNIM5un9}cgJiTW>|+ND&1bM-Bquj1bG z2a|;zXXAtq*~XsNlW-GypEHSt33{+pq5Bco$tK+JLhaxNG-c+bhB; zT{TrS0E7_wgXseoy_K%cV?+f`7KwoTX-q*o!BY6v%Q zR7s?z$;A+WXfj9TVR$L8oNtZGIi7P!lDMyH-^QLqtQ^phYr8A1-)5(ox1o;54qXms zR@j442xjYEOZ9!65raC6ln%&~bHz`4=(%H@w2IHIalQgDiMX

!*u@Pf4|Km=4uu zY%sbWY13(@a-zGt6-hFYY|mE`=WPI1@7$8MF8 zaSZ?_kJ?gMpHaFLBWtsB|0{4qNxsHPwguZy6uLX+^|4w>gRbylZyN)^tN=iSJ#?H5 zXu$updr>Hf_8zg|F_}}7)#OeGtPN1MmAh4v>S5|(C8IwrHcrU~D6`+zX%FVwL_TMm zEM}%X2%Jv;15>p9+z@PV0Oq!So|%K6RRHr{)+$#R+~$zZtSAG3wbka+Id`Xt!o7Tx z|97bB`(~P$`2v>v{tllWU1aL+6A@aD+QfbKHDyeXD}^>-?&Y%w$9$cO0q2*=zr8J3 zAiTO3&Wj$``2vKh+%TUb)tj0;r@9e_!;{m#FAN_Aj9(h_>PkMJv*r1{>wVLn=Vn_@ z>xK2h+{+_?`(>hGT=e$gtyjWm)ga(WI$+2t79iVAH`t zASG)_7m`=Hm~Q@V57}4gB9Xq8+0-;sxW*9I%MZ;*3~paqw>{fIqIEIXM53eBf#ciZ z>(cO)3Hdgn$Wq|scTLOmHeacuy9m(M`q$ZhspFhUZCjgRf&1{_l<6zYQ8<6-=ps^W zTqm%LU$|bh6@T+$hZPLhs>yFK*Y`%xSpL~O+jM9kZynGGM|tfCNk2XoySXt64eDThB$X6Muq4L0R%2FN%ok{Yt$G96wTxY_L9?NE?4+Lg+ zX-t^7sy!5hvu3nZ(k+6xsVm4G>BiAYYo+srx8ms1?YlIllwDSOF*k-)^k-j$@vLE3 zYl^BYGyUhs-Xp$m%9BH{$BXl-YOdcC&tn{oxC{tU>u63QmUWM~=hG^|8uNPft?n7y zcJ2FhD_sstC|0Ey7HF@PAuhS(Ah6excaX64*){a)b^6R0V%%<#`Q(VBg0E(Vy>@A? znsppvIO81H$g=vJ*sUdhWz-5?&R~=DXMaAPZKPLTbtOgZ_;cYZ%l>#m#Yl>k@Ygtg$*rnZd#c|O3QO|5vFqpz((w@rIMQNT1JAZ6Gf53b=&pq3~>w(B#0%nR? z;WINM3q(3^pGg4#tFU^gRyVm5uO}+?TpKVg4Mi2R&4`SQ$MS6tKgyneC?INR49Tl! zvadcI#{v?Vnr5!-CLKqGW(UK=Lmlja0K5`2g*tW9Wa64QdyNUL(V6198@nGENfb8? z2I(nq21PfYTlfRoX{!leKyXIMt#SB(PyeeVf+&szI6)L`7-srR=&S$xP13bELMu|+ z@Q~Eq2y^muvukKldkDaSXf+OO5J2_&G2&prw68Ak>e}`1o?i|QzuG3?5#&+I;Mkr; z3x(v;fX*S^-2fc!h!zylvD=Q$g|nni67p`UvX1T1T|kS`8zn!q+tBR zntm`66wIer(i+y^mkfsdm7hGjjXITmpfv`BzE@PZon>|{d)QLQuNt@M(BL=CBwSx~ zOhv$u4oZ?^)bK0m6RpR!nj}F4G_+3t`I3Y;1~t~aPEx3v?yq-bvJhmeM5e@X{!Az@ zLk~!dn!DUIDnyN*Z*+fNw!t-CflnBBX|$>^A9+c*az@DuaZ#CNY1Riwl?Y|)wB@md z0*a+=$WyyUWOA_Yhvo?gq4xyjWv{Zw*to3Aa{54rvq1HF5uvO-wjt_7w1Tv`82)c+mEBv0(Ux&p%lEJpq+eJ5p^lF7%JLHNLGR(jg zHyHsV(n=lq_TxKsC8lwM!Eir>yXF{Qdc%Qx(xW~PGllkw5;y<6XNGf0{s^q&x zHBH)E{#$|BN>v$8bjbXC8i~e+AOO&@V9P|Z_NF%cF5ClyT4G4O#*eRd-I_>j&wdn& z30A!TtkPl`;t``h(wh785>YfA0O=PH7~iO#&k;Hfm@w|8u`9?Ge7Y(`zs3TaoHilE zVQ%Me*7gF>5qoyGjFPPGb6G-fILt&KqzVe5TF6NNw^S_J|6O3C{~FL%z~`w zqR`>QuG#+*H%&HAUWfqV`(oh+qb+KDJ`}!wQbb#X|2}tZcp4-?vVbTAcbac*h~KYV ztt0GSuW#y48z>Sv&_VBqqSZCgxR`6fY2a|ny2cd0c7g+Y$?cA+l2_ZcmwVczk<#!K z9-s-gZRvo;)Nzl9+<1}wj;^uB;&c6??jfB=;r*FGKd1nJ`tdu39<)`d+atC8BaQw2 z)k*91RlY{n#mwf~-y&8@KXp4r2Y|Bmdc~ny5fB$e7m-J$k)(=>j=-owp)0|>Ie7+t z=C=taU~;rPS9v|hQTb>H{C_s@0uokxJb}DqNt`uY^2TPAJUL zpY85I9m2pG>lO(%+Yx&u!w(`3<}FsFQ0!nsL5Q&P#ckthEyK@TAaBmW2GBym)n5z3Q`R|Bc3{8 z+fHPh@6K}qta;71OHuHj(%<0Lh^S|jdM^VvV}K@gkFHoBvOaOhLLH9Mh=m!%3k{X+ z%uX1csR?mGiC6E}Ki+j~!S2Js+*9zrZxU%3tLdT3H-irU^WH-%Po~k>+$9=Tbww-h z3(6W}pC|tuj-yDUl>VULbYpy7Dk_>wtrO6XPVUEtWxOmj5Eroo(U(Zi;CP*WUzdlf zWN7vN%*5x0?k)*FFKRL@Wxkn^(V#c~NtI)H@lNTCFC3-*t@FR}u~NltvW!NO$V_{( z#~NqsxMYga9CW&IzzPL-wNnigt?u22T1@kr6-2s_Dn>yNYyO3o=UlvWgN>a3hCSdl z1s;4H8`xa+?oa7L^je`-&)4XaIK**l2~{~i#!Nw}KP|l(Kl#D%3npM0r35*|9EzHGjD=EE1wagc`Y5)a z)XrBWeNAjmZ}iQqb+q7XE{{1|=As3Iay6_%c@U{D6xCE!i3xE^M5j#k#MI{5mf3bT ztD*`lyg|wlr!#54Ge}}=W(t_5*b)`lW-t>yzP#PZ9)dYKp}{d`Us27*#!}UaXgN_1 z@Cg8D$NXAu;DPjkS=Kb$ggm*yZ>5W3ff%sFMSu;q8BqWbhq6&y)d#SdanWEOT}}F7 zWYi*71nTsj91_>I(g#JH{s=P2fdITMC=tUE)tW9~fB$#Dl6wF;eH|F{^uwT$iilUm2IqZ z6o5h(=t6S&==+-e;*BQa=2J%h$==T6GAF+gmAZhL3w@pLX7r1+!GepYZ!P)#Lq|g3!n#VKG^VdGjD9HuB8jeA@xGf4KM>#C}X2dHE$`e7ce}csnn|Mx#~vytX~}9&-OdJl-~CgUl*&-{RfVdDkX9 z7}fF+mxT=ttssw*M@gfK3h~(^&wSd5!@1Yib<<|K?;|7B8BYBk&eOp?W(N( zKj~z=LQH8Ef+!lPVl*_cTFd|8Ni5tt*lKcl>E(i`zr$hB3v1S;Ndo3 zyp1s#3GZx@l+yX#yrW#gqjFpnhcw$})WiijF6J^2N7eWmprLj@cXAaR&?X9d>;l&Y!$yjh>%=&wC~Naw)IU!#8me zAIdwjN;}+#ezIHwZ?qOBPYW}AE-K8)+Gwg)k}AWYvgKG9Mo*bwad~vWB*>7Zb65Ok zz36?j_PQN=dd?tbOR7vE;l!uILEO^N2TJHi`GGQ8W7?}jTCVq71)ZFwq9FjnB5iLV zC(>BFF&Y6<%)Xfjq_+Rk7t{MifQyh><(m9c$J5Z*dQizh7W5T_ZSa7G@X`u)#@2K; z;QZHlaA}I(hoP5rJ~(TRK!DmJ@eGUif>`cS%7JL0yrKn|xX66WF30vTZ>)jfQHWh$ znd7+Bd*!0ni4@O3TVG6lTbT2-Cp1!iB;`#P&^Vy9w#MgL4qN5Nk;)@F)& z%YukaE0IPb+`uxRGlFnYoW~bKB0UxjUNG7^9>%+46>@Fc_i#FkMBYzj6 z7GZ3OJrklxJ0}4BnhSP{PyEq_HVrQ?+dcWJ-ole9@HOWRnb(QxV|PvFC~2s%u1vlr zNPf+`N3NjO03rR_sX)G?I?IXVb>_r}Kfs6wL9Ho%oc*^E%V4dvTgEMo$O7t&VTQJ# z{pq14UE?Jsp+}aedyL(sAwnY5UUUJCs4_RLIuT+yH@EKHr=Of);mhFe`-aT{G1t5(;wdB}E8?X@yJ{~DH(aON>AwZ$2i z7nb&NRY61EYC0{j=hJ_2wq++_}3i{HX{o4twm zB-j4=ya0|{>8MM>v~fDwy@c~TSP5&b1ZC9coO`PL)k8wG8T|ax+sA@17SPWz3j6T* z&O>>R%YVn@{`B3@CLM1>P8wMt51;K(sXE9QrpF0GxX12xsrAGZq1Aqi z%e7$lcF2caW|D52KfJrOV}lu27>?N1!AOrKAUHaqopWivzs+m<@QKr3^5oCN?&-`= zwT(eaYv-{m^;ETmelwG$*6+MuJR`Ld$t>~pXFTT&746hB?@6T^NQ|z9F&*C(RWbhp zbJjwqTH*84fB3>R@d*`m4HMOWm|LjMOAilyT*;j{PA;$3qgE@kOLp z>gNtOmxkK>t@42I1sle=!fcSD_pcuMJNmDO-%2%xW@7tEtcq%(i3tnirO0@z(|yk$C%_C4CZfh7W&SQC5jM%bvVw z*v?gw763fA`(;;!y%Nl`D@BatvBb?p`ny6(G@TL$ z4t~I@q5NrpNMkL0ep;{>2zfcRCDnzt;%{|RCE0=NowNCszr&#dNKC9=`o_8Yz`eC8 zgvS$}y5ls|YA)4&9o!xT*@*yD(!k879v!F;K8&grx{J3r$W@YV+d)#E$xlaW4K^5c z{p3eM31DNbR|8nnKm$vuj0VWhgWC774n}jim$_Gi8IFs`tqr=sKU8kcIk9E)Qo)#v z<+qlF|Ksf4IptVp zikJ?Da@to^LpsouVZ`LnfiWgBh8cUW`!QYL&;9-V9{2Zt{2uqc|Jo0;*4o?Jd+qgp zulH*`-*>Wx2$^Grjh0YsaWJlj93Y+QuA`%~TMGay7_^JVo-T?*Glar3Fhr!>uf$-q zSd`oLlmxtV>0nbCFHAaMw#8n^CbB8bLFErqWg>bczDSOF34wi!_wcA4Ju@c<&eLjX zVCsp6D?=-SW3OpnnTQTKEMAN?q%;~QD5M>LvU^XF{&7t9Yg|3>);ym82>A0imT^1_ zM{*9E9g1|ODXodm^hD(|>bi12xh#_}g#PY6qsjI2I)zAd{80 zW*o_#+m)NvuQMH`C?5%ypK?E}i6i^=MD*P0xrW(_87#3GQZvpy^q_>9L*i-ncHhFIfWm1^Q%GLycV0S<8!%Tq)XpTvt0LOVQpz^>cJsqcX-y^ z>oPa}*j!_N?k0l}2OX28Gre97MFSd@(k1t`8x?YYMI61?-)j~doMRrD_Tfwyc5bIv z^->@T>#lb^_E`Ej-lRB`GE4lDat@+4+mjw_9@^}5PC5Q|q46p5p+A51;t$2%J~4;e zIKg;P@}PU9-HJt3<{*Sy%rXA%zn@FAHOm*8W9Ef?)g#Wb2_Ye$0 zbEJbCha2-2~a?nXQs^6 z?kBcq13Kie=SXgf!On$B4g6bH;TttS6kKrLq_;^5HR{ig7ED?SSxI3CMHvVe#^e(! z#CVA7bS=tsx=G)f*l8#gzLxQ90SAPj1Aq%pVK6Za`3a9-aOy41JBJ!>w9d`$i|n&H zf3oD(uYIa90hViOUW$_L!r;9u@Dn1DvtT|Yyx?_v?ayW5bP>Fs_072}l55mD40$6$$F<=BQ zpydKki$JvB+k3VEx){&}zE85O+kxZwScJjDkajy7K&m29P-ufdU`p{qLCgJX3nlB> zuU@?p_|z?1OtsoU0EoFfu zIW%M+V`}>7OJNM1C+5X8%=hx-z2Dd%)gdJ=bqoDAIjCq6Pj8TW9~4O0x5wl@rI_uC z!R+~f!Mwn!cuv{*@TcJMdRQ0>hX%)%l6o^`oFDb?*;n)jlDSxyBaY}mprEpj!<85f zC#M)n+qqAW*!Po*9UGz)V}fJ3VlwuqTC9sWb#|lexrPohmU!jh|+% zz+g1uH*%z0|IW}b9euuX14h;LhG+2DV_WBa)|)>h8s%t*thGMrL@OK7{VSBQy@sao zmw>KmU&rWiYclK)i8IvIKXBAD_e$A5he`KWGnda`;yX4Lc`@I;3ElDG0e4%ad;`xq zR{JOyEYIAP!L;7lJ$JZlUtjB+>}S!j*y}nM&M2*{aZm3Uyj?gN5&uE2ukp${>2n3T z_J94Mr+7}veiGMzr?te^Mb>Ls^Xj9@>FOW{^8k}nJI#DIEYpGMi$AKPv)@e{gI`t8 z5`Sx4&(_=bO6Ka5i!y2wy89T@o%ys+n}cCFF~$nu!j6#Qnqkq)<&yT3C#vQ-U*SsY z!dTrXw3Q$|F_%9#mzng|>SrXtDBn-st_4nMqk^I@$v>lQe-Ex8Qe zlRONGhC{nMxnn{E1_)T-P6XZ*ZNyl<;pOHuxNBkzppz{PUBk?<3k4{ImW!#$FqsST zvs`vD{GbK(gHN^BCC|^#&;4@mUV9&|e|YLX0JL5JV&P<%Dxd}Lqk&HF*%R~hSd+U3 z5fMyX5id4?HGrSP?NNX1NCPwx5F$_5mp1}fLY08NGSIddc##hS!2cCBxuA3+&A)=M zhzd9W)F1|62I$40;rVe?`55|>_2vplM*U8k93~{;z3{;fI}s3k%VYun`a9zBKoARr z%pXr#bC=-}n9CIlXdGZ)O%=;Mdo=TMRbXZ;XW>4jNM+e1b&UcG1Ve~jI}me(mH>n_ zL0T-ncT0;uQ({Oc@YyUyihC;1zsAj%VH1LH?ift=naN4_w#S7PpKGdk0{bVOl4XPEV7Gcw2dJFUi+6Gt7>6 zp<97{mSh#|T=`=E$bPn*KAwl$EPLnZZ+WhD@`=|+f=vn?baZq-$-LN)nFZVW2AXp$ zb9WLnI}VPS?N+%FVipiTZ@PPSNhTx4h-9Fg9e*U}Wfw~`K|Qt&%6<8UpVpwKhLUb9 zWm#Pf>A07Dp0B!nT=yIK%Hj2!uIi4DPq=Ih>DY7UdP<>qwOyBtl6Sr;Wj}+k?uQel z`$(Sx<}af}^NdFy!sdIyD)hTHR@XaV*$LW4&X!uwcFxJ`m)m?z^WYV&pWXT&AAvl2 z-+HN#cUFY0blYIkC3{(|vE}%(pM~9Bf0Cx6Gn`+f9>@!G-6)ftraN&$W4udErOUA8 za93V-v{$^waje5R=a#odcDb+C?S9~S)45NJTsf$<%TY?1N+#!k*EjUA0Es%Xu6-BujgFnICz~|t+UJUo>__Ku}ueRRF>--?;5EXj{o&`ef-J3 z_|G^TEDbE3;@WK=zic@gpi+u}N zsZX68bmQrlo6egCM~^t2eZcNrEI5oh*o}OvDyrl21?6vB6teSc+JIG;fP5O~LV9P#-^EuQnX-`|f=^c*rfVGy? zP96jCgU^#4=JuS_et77SD&gj?+XiHE&V)-O5VT&cvJF-J!&T-)wEs$zH>#~q_g_@{~-@@jGyg0l;$ChQdSQZI`k_0X(s>S%LoM(-ADG)j~?vXB<`e86cd9hf%ek zFC#%|9&(=Y=aS*dH-A97Rnj+_!s4&{Xl17Fpy#q;2DIgmt@Gl(hykGI+|eKdRBNvP zScPzsHOE}X5wWStllqGh*+FD2V8W;O7; zA6bBzeRG?d7GFx|5pFp;h0~iBVeT(oC)3XTrw){;(il(n9Gh#stPWI*!IV|#a{blq z{>BSIL5{yR-)yK|rS0~N2>*<>Gc#i(wdn6URI8-B8OdEFX9t}vns_K?-yb{NJP) z#Zuy`ll2`{wT!&HQy?fn=7*}{egBSSUBiomY8mExrcYVYy0ek!c|!+M$7aH+#D?at zGI%R>>w_kOeW86+h`2??vdI*n=ILO(KriMj|Q@45qRkKr6OHH;?uX~*+Ic% zwn-L+yl&gNt1^{et{k_=^xdc^c(LCd369Yk(di|Vi;iYt1+|*bEPLM;?bbbU_@*v- z#NT|+Nc6tox0^1izWJbrxoP*|=H%OoD+G%JiZR;9GZ?#$f#cp1t%M4t1^ z+~PU+dUe))ZJAr14MvItHy&|~Q>Dxgr}!#EsoFD4Ylm8sDjnT_DgOI^0L|k58#F8b zU!>VX0q4$O<&E)Yf`|bQ;g_(!SP4UaC(Z(ExeJH&!^#^U3Wz#$AsTD8>mRtjys_t* zi{UX*foCpaf1`54FGT-7!FyuOc1iLecw&w5E?9FDi~l-zz?z%v{I7E}thuQKzUzrK z_VUDt z1dP2Tbxi&n*>8N@<8;WGz<+M?pDYEYSj&If{QsP#VCO%Vmp68d3Xk}o`^z&tIw1NC z)&whWYm1dU1PR*rcRk68FIIl%Kb^GmpIemo`@hRb{u@adQwvLz|E~GJq?Rz=M?4>W zCJOsMbBX`y49P_=Mn|0q2$NrZAid!jK74$qV%w@NNHHpX#fxkKakBRhmzKT4Q|r~$ zZC1*x&&>YxI&Vj}ODo)d^T0uksGy!fza0-B7LGt>_6=edh2E zW_gxJzVoSC%s_|~)9B>HtF;3P9nYrd1;aUE34exJw0z$*_v_vJyp~CHH=A7jF5~81 z*_UOrhxC3;`8B;)IldEKbhiuAI@)F0>{sbq-R%8Y>5qnkJ^Bxdx;q^%=U+Y~vtB_j z2(epPMaic>sOGHex;cBI__&~b_R2sJ7F~5)S7d9a*&a7^>|l5 zCaP@hr{QJpqisIkk+-%@yXlhc?sEUGEx1V!ce;1#i_7D04Y=FCg)<%eb5B z1=%;p*R9!s*muze>sD@S8}0ZKq!6Dr5IEJ_gVFM*)o)_<-FP$ieCueH_Mwci6r5b) zUL>)rM!xglNofC>qRakK81pU9zHh!0`Y4R_c!iUronb7QCaBysIJ)8UUw`4~r;>Q* zxMBEJu5L$eRjl|SUcV*ibY!lqz1xnzBRX<0*Dk#ph&)mpnEJ=R!~EOdXpTcEpVgkH zjc0!hPk)-E+Hbk=m!dRn6QlhtU(nWNLp#2=>b$?p!PPzn*V!Wt9=B_%HtBhog!Rg2 z@J=}Ra37t^*wuUf3@Ksjm_n>>rGOita-s6$Tv}hpI=FP`mgg3}-91|}WOV6(lC8tJ z@2i%sY}s2Cp0MfG{8RS%fbnE!l8pU5%DoE*4&puC970^SFM8@KF=!@lCeBOhMS$tr)d0<@4}w&gZ4KRhE=P?&QBet z5AIF9qk+8W3bDR|3x1oND>wZ3Jh?gDAgJTk`R6l!e{d(_7PiJNC#?akMrO{}AI+qm z9Hqu-9j$JsQTHFc-WYu&O(o#!Y2wU{(o2Od%YF@KdBfO3Ppn$TC;N^`*4iuNyJxW$ z26~$JD;4qUJwr)7~@%R)#pM4d)Lc1QQj|% z2M+(e{gk%9;?avD-4ppKcejsRSovz>v{K|CL&+`v;JS2bxiK4CD$UzFEMDnVH}S9i zZNh+bghtvdj{0-6_}J5|{0sxO^S(ROKHWbo9k$=qQ1sR&e?YEb1^zdIvu#U=I+JjeBh*Y@EZ%(plHp8L7f+eSIq$6zmt^>ClRA{z>yoHkaqEmSn4cLPIsd>ZCS&?RsB~1t5I_2&SPgeisox#i zvb-z!ApbzQVgH+X(o9yUTbQeh-6;pV@bjgXUn&!COCOq=`j?FW)1o#JTt4qS@Xj>P zBGi4;uCD$5H}V#w=sfzedFq|zl2pCxuij7l_9mh)%+3{d#B>lW!XnImuCW4mid;{xs$6>rKNSQZj|?|*0GFa1C7=J!1P|AUQh`rmWq{~H_Ma+ev__`n(Bx!`E5 znVE?d*4Tj==GNJjyE~An=R?fFDZ?JhMM4ARa6KpKJi8 zJ56?({~y`-l50t9jsHp|AThE`v3~zsKNW2=*E!A`fB3XJ_|26QdC!afc;$LHZy+g9 zf~ylq;Ep0hfCwQVT8O10y8)O-;xAuhb*6wtv|t&Ufe9=KTm>Q^6i&wQ5r8(KFkp!} z2!ysJAP_(xn8g?Q2bqb{vL*sZTE#={;5o~sygac2hp-+&K+(GJPK6H)W@sZUTDJTN zyYdjowNv{&pVbZsP$x|+05C|?Vu^*YQ1lRR4vq|i`Q@D)^shud@K=H1nGJ0*=mRY< z>^B5z=>)(5Q(rpW+uQjB(a&K3#fi{nA%w!n@|>>#5eWInwqrt$0DyJ@!h--HNRmbZ zNm4rzkSvQXhyj!YApp<-;wkw-vP#KEBn40yps|(^2n8&W0MtJMFa-DjpfIWep^}vn z5YA#vCZqrk01y>`P=FXnTA;)}k+d!nI_`iZrKjzLNW|g{tnk`%`|25(MTYqth4wZ; z70{|51IIU^sH*gaO1uVv7JK%#*K5EKkp|Sc| zCyo`}eN8&RU!e9Gm+VvBRN&kfo22$gO?lTqao^F5wklj&(7gh>4W(^pd#EW!4O9CM z4HhIU4N`xbLB->SI62b5A@SHEa&g2Z=3()=0gMkw)lNJ_tPFN?+Bbk zd0r!#X|K{dr)bOpt~>`i8{@~&II4PBl)a8sU*PgV;Bs}#G_WNYE zA-T=uoLg^?G_JIuUcT~K@9fr}`$Wr+x7H*z%O@e5R6hZ+;O?)@p@cEt`vjV7vF=%S zoup{BjT`Ks1fRL?J9!yKhB06``Rk1_W_9YMVIo-chx^<7Ab&r=MKlz#j^=JE;Zbmg^>D!m_P!H?H2=m zn7?Hj+di&*=HBY2TUA$bS&v7a?C6WxEpNCR6N108!<_)5?RLLm^Zy)t0Qvzyk`M?6 zOT-OMYt8PLmi}ci&-b`>xbYaxt?J$1RV$&MOH#WwENx2?it6_8_N0m?i8O$U$MmkJ zl!aK?_Gmm}jo#6=!yZ;o$H+a$UP;+kRCYOoJP~ZK*t*~B3#=DqpjfFvDmC%)S@{eG(ph7Z^iMPhvn3PgCme#SU&>U6D>FDbx<~jSXN;xcP z6?c!yP6SIQ80|ZKSjcGE@*F2Izs<^v(iVWx3iX>#BGi3SZ^S-YGpkOkG7K z%^M~{el{8ShS3U-QJb9Q&Fslm?FHI#0u?Y>cs(wSySTj$0HFh%$c03pQ_yZ4I*-Bx zK4``dAdm;TA@Egu$)c^zkHAyowH^Fv3!bPFNr3yT_&|hy0c}YV{Vfc_Ac9y3(322o z=d*yi&QJR3?coHO8vyt}?4?ew3h&q$Qb93n7;O%=l;CEUw1{YRUs@@)xV!3U^ycikWwDCzF&DwCp#@oV!iT9%8am>e#eSwtX z`o_kZ`*l>s-Y3m+N){EYpYs|xrW>{=QO_n%Q!NydGfI`cbE0RRL8X04z#1uCa=;2H z?ebH>Y9zx|5+Rxv56ARqu*Tz<_S9gUTCgKtW=xU@9A|ai$#$z`uH&x8labia(i*e)Rq|$8L7zj- zyqF$tMVmj_77eJo74q!t#mh~rO3D7UqMPM{RzAib$HaQHPuAVtm$z7Z*aIzx5*XWb z@{P{O-EjIw_9)(eXAHd9FNLYqvzLmsJrE>w=m66uC`HO)R<*13oPI^-#EwzSzcXc2 z>`6>Kt^@kjrn)ky*m9k!qrtubCxa(e`WTF(d1ld3^F7!Od9Ma0-uie8oo5Ho&@=vF z#fm!0Ria~$6tWY9fX$ihNuXD`FO~nYEy=%Z5bNsE)8uZrijvA_wy>PrUD%heCpyiz zunl4(=iI*zL>+b>a{g>~EowVGOzCORd`I+tIp4etW1X2v=~?O2nLGkL^JsNj#oV~w z^xe32K~%)sO}@tdf*h{MXN*U*<%=h<9o@ZJn=Ucj6%g_cPep+KVbuDAOE0Ti)Y0HD9g zdyzm{HjIG6Bzy6E0g@=F3TJ(77Is36$;Da3SoCQ@Q)1Qt5Kcv#Jz(Bc3nUPNJ}cm# z{;CnJ1vJ2aX3F~DIU6dThbI%K6vUqFZIjSEO^op6C6*47q<|VrY@>EG5G*%Y*PzWJ z5wmlOhtdEf07>74mJnEI>Xh{etfwRw4I{Krozdg}J1 z(TWZR%0j|mzW0oH97X3G>)6CeYHS(FM*`9}Z%{6 z7z{?k$^Q1>cpW>oIAD#84@RPBHz01@F85oXo>l3gHQ&2XS(yU>Kz;tq9X|P_|J;#S z?b2IM9#L}pDqb@wg&zKMzES5_Zn|TwlD>gbbb_qeYUf{bWFFwX`r)t7eDyc6?2Ftsqt~Wh*0zRAowq#-M3`b)2OgnX=ilwX9K+OKFg>r zyfRB8EvDY?=7hnrPf6lq9_}AAL=StPo@!`rh9Cgbh7&htHmcejHxu0bc{@J#10;QX zovPK{c^$z?14Kv~FxT_f(oPq*#pd%92n4{$ZHq1Ufmb3h79x8kw<^moh7zaZ%0DAjtX(BxY2x#(E zk$eITEx#WJhQ7AL01&=5tOQlzKtk51fF-LnDE@T}5DCC!0*eLO!=PG`#AV{bJsT=u zww4G30jruPnOrfIxQX7texJh5t%5TNOlXq48eYhTFadJa$*vd#{Ep_H0h3QgkOS}kLDR1#y#Df zx>y+EpaU+Mr^goTPLCB1j31dXTx&#wgaHn0BAfj=K)SIwr1b`uqHJIHvJRoZzIY3F z7C>2oE=E7AC;F4cZ?LG5%F#l5N+Dia$-R3wNi9|};DU-hN!5TSV|FSSr=xmmFUdaT z_t+Sd#2pe}IPIsq-T2wTCRTK)Nf%kB6*{IV{UgKHrQH0F9$O-D(123c&@qM|K0*M@ zb>t*)ZWSJNRb;w1#+I8Yom^rE1v76EkHqf8-8dUCbSTw&n@i93??k!g%`sGNzR@RJ z{GUbI8;%C|20L!Gu=d#YX{J;s9HvgZ=Gh{C{Dg(t1S&F_AGgHhbYw9L|5=*r|`{RTV+0xP7X-){{yT z&m8ZN`@QAD$!HZxU2&c%OHqu|_;K^VkyHaS`%*|o#Ytb0)YS^vnvhTA{W^a3*D4~V zm{_&J`54~D#_mX)o%`2kgOt06X4frJqkE%I`X6B+4{HuJ$H4Tv`SVPW`yO(`AmQ6FcBv zkScS;D)nCK4#dx3A$5%lT3%yh-TkU`DdIy!ck`AQI^(En^ikUQ<0I}}!~OGu@uz35 zB+sr~K#YO6SY)u)f7hk2LoZ5GEtG@hUcW*k>hH zI1MkwfkYJi1T<(09zxscEC9kKLd1z_V*#Np0S}T@5&(-Y5i%Gd$G{g3pt0Rrq=(x%yf)0E9%ruS_lEvZXlbjDtdb zz_-#cGtF1*myZ@;7T^GWixvEfkG$p3B$#7>7Be)j0d=vaxGlP^?JX;G;r#SaM;tL} z;OK{(fqO%%8D}|SweKq)q4%AA{Sw1DEPr}i>vx~fv+7!Gh8D4gssZse8Gvv^$bu1E zw?a_hpaH#sMbF5{a2yzT$a&;G|H2@-7*cpB#^adc`Jp2$xb^MH%GpQ`IJ$kI2^y|p zFVxfyR&^`XP-^3ni-n;S7pAX!u|r=kyMif8A%!`R)ItMHQgJJLgH`NFqcv>o!+;f1 zIy==cdS|46hXw~SBod>mk_=Hx7m7-8D)y9g8RyDVB%CBw7C8qWNp_LwAG47J8mHrj zlMib1YFrBdFgLu_HOZP%-n=i+K!!u8t>xa@o$Ppt!>#54fhQIkLP3=W+7T`$%tC9;2K*qVe(_(1 z*0;Vy@f7*}ZAwjI|NE2oKeNGx4Pc5NRu}`ot+9=BvsSN3$uguO9o0%5rHu6kW^|oi znvHC4-2q4G-YHac&}>pP@4m5j!Po;I&2(EvNtY4XmlL4mUy17}6NFP8Dc*+z(1OkC`glEh5@bzUj@D8te$8<2n z32Y1|Mtj3MEnHX0H4v2{d~SB1^>LBu}Mh&yN?zQOW~WO@8(XxgEEV znkis?0_^eW7Cxcq3-Evex%*X_%jcHiRYaxMr?9>#``ldk;@4~hN+?i9XbBgZ6Bf`# z5C0Y)(V7D`yYY_?U6cFhCu5GyZ%|4#A{`!^JM_c8&-#2;k4BT>*q0ur!PNbF3u^s=CmY2D}sW z?LLG9P;v~_L?9rNKD?g`ZtY$QtTUX1f$IXGN!Ft#Ip4mAw}^k1g#)ce--O(paj>HW z^}Xfcoh;7*)!-92|CPq#Iup2POHFcPk`F-)0R&!LXs)XnrlPf>F{qIhx6x+By?b?O zH_tDJDd+J4n>8~aCC#kzuQR_gQrS&I*5J|q1Fdhfzz{1l=CNC`P zP$)Fn*g~VR0Xw!l6b!gsPxL*~!R7{7dpArQZ56`pMmvqHkZfDyvC<6gz*wU-?J1E` zEDR;)X}%k^vT!qMEJrw;*m4>I3q|~?r@wbb7Uuoq)~)k-;aqjEQ;M0kQPsxFo}~5z z*WbOi)q+lV>|V@Xz9gXyYLis3%#|ngOG$>fex|sA7nWRNeR#|7cK&m)$0|vaPW~!e zB!h77{AR@`)~*?|Me=9o)Uc5TD(Qze6$?DvrVF(vich856-|~)wNK|)KdYt`4c;v# zF4|L4@wT7L_E8+{>S2TmL|4a0^;t{Kb&=V8<>cSoq zCxZ>I=Js3Ntkl{^N;Dx4VIxVh>wdiHKEF3>g3qZobnuvPMk zg$}3A>Qs1{-k7s5`u4VDl@nhAS3e z+WfS>Vyu#zL9nANeD9e>9F$r(eKN-f*mW(jQFqigTwwfhsONtiHIf}c3>9P$a zbyMY2%@>*zIzF`J_+2K7nBQB54-_NbO1se?8(%6Hta+OYQlu z?DM`GQ@IPQIHI-$o(0P4Z}C987^9`UBxw2( zfSL4v2CyV0h?7$!W}~8sgN`<-mrSI}VOH`+;|@AjCP#Wr9`-!I z_Q*}A+&`_Oqhm-W_mY3x*}6OKT>Z>DbJhApX#IG`CkyY;0lbsbe#z6=(cAjhr)L*@ zvir?ib+;TOo^dr>p?ep>5g5urK8>_VvxS zJoY4aq#TZe07#&@e9cJ^u=&83cWT}mq|)gg+VOARFt_&VHe;`I$+|V`*B{OG8PZyI zxt1bReCW#8LHl)Mlw#>b*~+u=OVToCH@sdDi*@%o2CMdV$W`W7T#@*p($O(X+p%P~ z+(G-I??1^77bzD_rYpLolw?TXV$P;WsaBZ?H%iuWD5Y$Q#PM)bJhy^!Rs-9iZCVz9 zQwxxeu$ysx!NZNI*i(v6QP{zb9Rbp*vV(=uOb69h@nXQ_3;6z@yzS=s6A3MX29ysx znEfEth%{OiF<8-OaH_|uFuo+3+L)PPAUk~6D#~>5Xo8WN!P>@4QKr4|mf=5>!;*qa z(7Yvs;^|U&r>xDB1V%efe7^byewo4TpbN_fVj`}&G_nK>7+_319m07eN0?QSd zg(Iz6!4ch)d0Ey{^8hitJWy);a^2~1k0xdeZ)bi?`AM3j>0032WRl>|W`S&m3>Y?9Uw11`Fq*1xfdz*1lItE)Z*K4d_Pz#Ezr%NcOM zB%p!GL_lZ;peMV{MIl^*$2GPKp~uM9UsecS9`=e(E^@C zCp0RBtr{RCt@cUofI>q_ypuaD7MNK%3;j$XcnQL}jP)o(G#joFDHMbVmLZMEM+_|n zG<`k^p+UnnlS7?5Akfa^(H{}!VHV!nqdKu&_?RR1Z;A^kvSj%_b}!cABsT>y9-GdY z3g`=b0ev3jC3>3jynKCmn_v7^3_Cg5r@X8t3om%IZ9b&tDZ`>B4?4wS>$_}l9XK8+9cid!^@AeJA8XHPRFLLb7)Pf zW{B9sl$ImBXqFnL;<*AwOA;&;1FmHE1prGsEzbDIMdn?ee%P%#96a6bSrqH?q~gus zo`9mw-%k&&XfGyK$%a|~%Dr7wsIyk!j^wxA9~>+>vdo)6a6FUpoA-)?j9a!8pm1_I zQhy&UPN)+h3#nEU3<4y2c()Wm`&j|;IiW8r+0EjwIp?CjDT$Ee$DjXxGoCvqL+WxH z(tV}dVPBLhpD%r`!0e*I{yQ(Kf2L>`nIwmHG1nPvUL$xAP3zuSZA&b!HOf*O{H)#Q z;B0w#q?q{fgFbYxDdS-WwPF=~r{w76xkLvAY8Qa^0;hIt0DCwg?NTGctaW(+=-lV9K zq9jWxCRWNB01m21Br)Bvy}>5MYsXZuy=h8#oLX$5{Zb%65W8&73}OxV9`mRL5WqQp zp&kuk_`jctZXoJ{b9L{}cbG1^2LA-TU#NhfkoXMG7r_rvF%!au`eOAFOOV=WU z^I_tk0kL6j13=`ShP%%VSGi9r<>>L&ZF(HhXVsI4x2w7!VzHopEoyCjS+Q~_la(_M z7B4tyd3j0B&)abk2w~IswF>h)6~KnDV_e6CUeM{k{b$mSaOQa}-p6Dm$=gM%iWHz) zVhF&JST>gjKqCMLVc}BiW+0+o1vBbCgJtRhE|Ppd8KBi84>^d)&2FsL1yENMObQ&1!=*(C*lXoZrm$GmUFCR{$9|Tn*M52WDoPEEqScHgBcx zGFEOiSB7bz{tf_i5VqE8!HUjwxAt`x^7-Sm%<&Agu<5ZW%0ijPiT6Aj`7;2raI|Kx2a#wX&#ZGQxt6j`PzX4;c>h_rVr26*Aayktooa@vX?^;3`FdQI*~rs!TW zxoN1yukQ4_FV#5xfpdIf%>TWZCg1Ip} z@D5+YWa3Ry8<OKHi)&O^n@bKwJiahnspr&#m-;?|}W zW^Ms1aH`AWkH4LDO4+?P_Ya+dbx&Mc52g~ZZdaxZuHRaB6C+=$V^H)=`Sq{m6mw4> zxp}BTO_Dh^QI=A?Dj6gDGQO=$HI3|6a7J3uyl|}@ZJ@eVdQ(p2WWCH0uY4Zy= zYzL9_@tuv-o1bnK2khCz9~O9PcO#~KnieHhN(H~heTQPOg_MeYrJO!S>Q$k;ks6Vt z7D*&AWvQ{L4k|v&k3@PlS$SGj7ZBV)GMvD9DTI`1!yE=%^!59TopK*#ETbo8$_}b- z4=(MqPE#1pQoexiiS1%|y7yT{e_ogfpLbs|!O-7hR^PkZKs`T-k>=f45_d2-$}$v) zCN97PQFG^_8N<_(@11sS>Un{~mf5MkxR9nAhFn?MM0ic)^IK8d-#>lH%}<7{lorYw z?l&VJI-zU37OxWLaJj7c_HCmC4lt6e5fz}I4(e|EohY6K5QtLH!xDfV z4XVE)K_Z9n7zh^$oxj1Xr8w>pcggDjFTa~zSO1GtP(%YDKjnG?0s}&lWal2>u)guR zaBsYG@q|`Iht!B-G8>#Vu6&{Zw%7r|J7XdEl{{*Ylex7U`N@j zsWMKE4ssiCIyx#2a*7RV%F-bn7$QY6TeZlEs4%6Yee~>vAm)!#Z z82;(4|Mwm3Ck;jH8$DRl(ySg|>ps8yGY6-quOyeEAa|0;OjC5Qde-}7_#I!+uqpc%GK$HON7aq6$TchmOet_WK4 z*lHGJY~Y%!AG44A`B41&{asskyDTW-afXRUnD#Gl@{+XN=N{;+3m`cx24Mccy|Xue zplEh+3+}DCoFcI-S2l0@cJ8_WN~-LHz8^LC>Z`=nM9mXbCbJdu`>fl-aQ)Bs=quTC zNgc!rVqp$WQ!&_l^iY6Fs(qy#c3MgHC8;B2t)Y!fTB zYvrT2>O`g3^jGJ)7{RxL?1wx}*?Kd6cilB^p5RRvPB7lbDuxXk2@nWvi8dB@jpT>0 z7H8D7sHpQMde=yIGi7RWa)JH)merA;4e)Gxt-4&%7x35v3A6jwk>DbvGg%9Ei}SrF5wd@kNCysC00YS%(2b>bNHn|v^Farw z3ulR0fZ%!xWT#o#E!x3IrR*_=3cf}S}eXKNJ)c6 z;QN-9^n~0FogIJ0UH@q z5lz+*g>0n0conCKdjV~1t6+Ng*$I4FTo)Q^irGXCk<#8oWm9fnX$p@yM&uCd%Y%Q2 zU|MW@8|^;}KV)+Ln3^<3K@Quoq#_>flrc$_QmwN{yLuHbT~}Ap-Q4PAeniQE`LO85 z1}7({gY>lX4r&2w_VRv1z|+h3zI)^AKyq?&mP;bm;+-T$?p*K6{3m+cr3*%P*@Fl7 zpLYAmeE0W&ThSBkCvIid8}=`8u>3zwKk3ER}*b;RZNf3MVujYu38-}yS@|hpT8_>1m zPi>+V)~_|&&Y(ecC_LYBO>-iG8y=4KvNq%l7}3!+h;e7-L7@nUKx5;RfOQIdsK2q` zN61|$xh(Hz@lGngfa0D29K1FmQ}jlcr5M}#VO z+Fd1mzyf`yEP+S&TFDEC0s`P8l9c2Cz3;i$3ZaeH`t7Qs0qBnA2$nKXHhl)3LVis) zFAoDTp@}pYTU&4{=fMac&!0LPFdyJEVNt;_XH@#HPTs67=cB zwS?rxvhrEc(#)rv`RT8yV8JFU*Wh&Fy-BjKx>m!h%C%NV&f;P-hu&bgN?mb`nKXtP z*u1X5X5TYu3cAL>HcU}|SdPLY zsbRQHl;Q=qME}v@iVg)->?kjD?t@x@bfE*!>MUsnG2`HIEWvcXh{j=0l;T*&nH~*q z77irpFEkBP%KtN}b31+yPjV*NBx^wj``$zXqo|ZtB-b9%**R^B+2YVkK1I5ebyr76 zuXezZDYgH_{sW%taXP!9wBmY0lc(e*nncvl_xesE=`bBJ2 z%0V6XnwlieWKEwbdZak$X7}26e^={!Qi`Dj;29vLMWq5xfxV!Uc zHrM`t^v|=~Dn(JPsm5sOVA?IERaL}PQwORwrG~cDRB9^a-Zc+3ccau;rL+V^)O2rS z=!lePlx#$|hzKe|hWq+0`+2_K^F8Z4>-^4H>-=@@Ka<=mS@+6)T~~5_-mj0i4PSwc zmr2ua$u~<%=8Z^`c7zTaKJhd-L{?jg6d9JY=Dt^Wzm)YcSM6RQMZ&%VM)AGEg0@md z3HGvvAD-aUXKPd|?r&<`9l~>qTF(Y<*sK5rZ1osxbFg?g0|CtwjJ)}4M}==-h1#8~ z`MktBU8@V1kCd1O<4@~Nrk88Bft&v)BIja|_Dl8tUdeGJ&c8D0;79nUA6wH2q~`--*u8rBMI-W z3nxhY2I|+k&e=@tC&U!80U~bxOQ6Vg60}>B#s2yDybjUTF!E6?DAxtUi^s~t4X*($4F;pSOFhg9HUPAd zWsNqtd<#Q6YH=OC_eQI*cl10K%K}X13K`;d0B0lxW&<)7&~np|DI(wiu`dBpv_8=RlN4519qBV2LV!C6-M|(+aq>2;5^ZzWX>n*FaIBw1>)SFI^Z+u?|60e9 zbJIEUE8~VMgmLS%%l~yl|LZ8d_yw(|CY*F2 zMr=Yz@uPOU2TJ*06&R@fD3r35To9!26SK2QUU>J|LhAFxptZS2t6a6O&8f>7HQL;w zQC;Ix^KNk=`T=1cU}6kh(5ie~`dNCdB<)#QRRTr&fY58S`%`T(*_+brdl>t1j}iBC z4#PFoq=OWSDYvu2FJGk*@lT+EmwlV_+`c5pHL9#t zQY1jSV0c#b4pzfApSFF=-5nMl&cwj;^I(>1AVTOk-*HxR8@$o|b7s2;Dd}^C zTi%AV?=auyL`Ju2rc(~+OAJ)VKL2?Bs_>0gP0kA3LUy@M3%^%fMr>xRtS|=RM{c#V zeK#$lwTJiD{=G52b13axvk$+(nc0td2|JtKVBz_JQ`(gz_+7y6gNk>3P=ca2Hmy)W zHCLC1UZ7SA+0#pRju{od?0TRS>2(8VzcGF)HOrkZEJW1*naq!t+nBo^!9isZAgUVd zveUn28NWeuX|Y?OoN3Y6B~USU$k~XBB)^83OoZ8c+&lAY0psYUX1K}q=;yf889Jvw z&XuTs5!;&oau;7LY5q~tI*Zp6pH+y;_%&W`xzOVUgwQhXW%<^y z`HN7W>n{G&+evPsVXnJH3}lCX_|%wa4>8s&G=6?VUpD2d8Z$d>W^z!epsBp@PLoB6 zs^#wFrE@`>#jlJ8mg16p7qyjU3WfQ7XZiSV7*z?32@CF)5ykuey9(N2VdfPo3!YDbEz3RyBfRV2&$d>=CH zO=OI*Pd42Cp-a^(aKzcVEpYJt;D_Lu=r*ru)Y`E5gzJWD=cxdS=cwLrpI}!-AbKvP zZzfyS-L3bC!GUP+wvd$lbF);k6AM!t(6%;3RKPkaAVk`?!&I8%#=9_fz-vmNw^)+> zx}8wLlG%l#YF11UEBDFM5N~k>EK>M-hNdSDXxLQCx9d138-|??u|ql1F5SR0UDtMm zP)Q9>K6WamID7Dt;-U)Tb@PLWGeC4i$V5Pd>aHumM3XLnAu(wa#i8TZ1u;xuCnp}o zwl>EY#qo|uV_2IL?95Cl@I;p<;eydw=J`?HX^&K%FvBC=X_udn?WiSbX406EKW^sKh72Y>>3&8%m;Lvu` z@g8jinJ&*f#m_1F32GQ7Qo@O+*mdYZNdDX9ylarsn+HpLtit&l=?2M&($OtJ3 zoe&Lhc#h6q8Rek9DG2JdxC}7?zjfi zujZ5~m)g@PzOa)L)TQWJCd&71Q`@q|Cz)vA2Cj!WaaWr8tF1OWmumZOC2xhjY?FE~ zsPQHB?z6v=M`iCMWyM>Ishod)=i!D!Hh0G4U_1(Y`s4J$?Bw|OVahGda~lL3tyfMy zg~Fki3mo{hYDiU=jYM;m3lg7&iEDpx-*wbPMNXS;I44t8D7?4YU3+d^r}^(f&VFr~ zTX9COE-rt`L!3JtDfqVrjtd=W9h`B4z#AM}^~$eLe+}=URKx}axK`SJGa-fF?R%JPXHe}iF zyp}d%2xy21037017z2nHi0qi@49c1yK2QU7Ne`SE}F6F(%mH+^^baC0A z025n8crWkUc{i4GkT~h-sU$Nnu=X{)ae$z-tYxdw>sp7Eq_zedRl_WHR5}8{+}74S zhadJ?HzKn3 z_kYIyXelMpk!0^38b(;qDDR?Tuh5BH`Jrj;-u-kwaXXbcr=98jR=n9xwZ25Bc9Ot8 z=EfW22$e%`%#@L9=oW~G+`Po9W#A}gZx^0g^V4W~SNo_TlHCM6((NR8GfP>0m!w(+ zTy<&XrdqCHU2UKpW|;1MVa(r%&-Ntb)=r2?8EA2I)!*P`YAB7+HJ!gj6@s0jD+oD9ThkW}d6;k=jZuo#=A zPidB8A*C$vDmkzps;)+k!|x>c$-nyo9)uM5rz-ZG<0AeL6<9&U4NZ`n$KrgXzM3a(t5gXs3E*fV_CRWH=mee%YA*i=c_Z zj^*;I%G^rgs<#xkNxi>`rb0e$`e^yUWoz2INv~@a@1VP08`M)l>e@pF=Vsd5YazGd z0}6qFcJ5sDUIZ;TTbX0DAFR)OT%P-i?iomqJNOFRF-% zq>JfYpuTT3;)^u6^VsW>*rDu*?=ebxllR0%vWGrf-Q+(Noar0RqLS;25!_DMx=+=? z=cwvJ+1zpQRMkT_%UeDq9ocxdPflDe-jd`)6GE9JiiY7N#BH>DtBSGj!Y@&Gx&@qM zu`1+8}FlPwO1kem15JskyMpAis zG7Kx~IH$Vy!2>Kk^5bq-JEy$jxQ_}6i2#tXKZpPjB54=^%}#--)6vl_?gc?K-}t35 z5K=oqLO_QpjNLC!c3C9g*9O-b@r?lA+Q@8eZ4L1IUPsz|s7Zo1dDAm9q|NCqQu=(V z#~dwn^6g{Wy;)ohwRw96qZ?qD-5dnRA_SIix>kFesJfhXIkm*E6=x$DB4x=Z>V7J) zY&f%QBr?L;p)K6!FHeh|Vh=H~eytm~5~{^~iV6DhJ=*Kc#6oxd(^ZxmYs**v9y4}w z320MJeSTOAFVvmCZSVyEd08JA58Q6Pw%N7l5~%Uji*#G37O(cy`DBf`$GNa-?@+?K zGyCp-v(IdAYLWg{exTC(O%pYTTuWZc@u}J@)@iY9CX9sD7XudCp`#+4`{c{(F~&{3 z?j?bz!Yrf%vgd_XPe*aHlx~XF@n271u0^*rPjSPk)jkUst%z_nEE7~&dq`IR@A&f7 zIn@B5Me*FQUCgD-r3`K-tpYZ#0)ONJrVeQ{8jFlEHO-8}%vvhODBD_6(OosK&3*OI9M z5$8Zqz~gy_C%zD1G4fAC8VC6Ql~`)#@w(<&HH98DRaWXn)%QvQz=3|vnLxh=v^%JV zkzf-aCe_la6*mbsw8=JWfWus;!&87B2|#V1`j1Q@oMn{C_I*-AO_aZZ<5FHB*>@BB zJu-}v#Ea^NiDF`Y(F4A|@`paVWVCi@DcWw`9C4E!8AlFD*Kxl-+b}VgG@$$8CwqVhTts z1E5SRtye5UcPnf)l-HZ&WVTEPtrAJT$;m^KMw7=VJ`#@u3TDoy$8q!%#IpZU__pmh z*23fLJ?U2q+7>kvJ3mSQcvGMeM-KulCIAmr*wOWdS%o9f35X`hDm}29=+*`^k&FHM zr*Ds@k-3=-@n#jeSioVe0p#Mxj`ICqAO3QMB9f{2=yuiB%W+x7{WIpHdOX$Saqino z+rQ|ScehywE!>0>52yxc^C%|BT^@cufi(I03V4t9t}t9cWn9cwC=b?MI;*+$bSCDk z)X`mP(qXSn6e#=S`7`kuVKsmi6=O(wQ5|>%4BKLeV#BuPr!U?CVqQnYpT&sXK0LJi zR<;xGRp*uSIw{5#nHzp;qU=>7lMB08n0`!5gZ|FuP= z`!6Hu|6&pSkL&dxEuz2A`?p1;yF)@de7u#y=kJZIKc^)Oa=fsoF`SGhe+^`MiI9b0#%fO6%!U zTkT_4)rNge-^y%cEh=XmczE3PYVfIp$B%5Uug5%(iqONz%ZuVA0R?>M=!+w!+3hd? z9Q+_+BqlN{;*aOIA4Z7ki;39<$|Y%yA#pXxkA%l{FN=I8({A$YrzUW%cQtki+j|w= zy`BH<`nTV{5w+p$+3oky!+Woj1al*gIZSEb>S`a$?tMOu3o^}iZT;u`rI__!&Rr{8 z^T5CO=n|=tTU_I%xgbBX(f)ndW7i+wfA2V+rXRm+Egk*ZvFZ4q-q8-{SI1wc?2Bu< zoFJBR?9RE=%Vt4MdAEvs2NfJwD)J8&3`g_a_I%YW9Y>B_-~V~xB$fLxO<@1jwY0=d z#a|nBZ@&AQbkt3>|AcaH!O(HEC5%Xg#4t zbGE;h#u9I{>v#wM*j@d5h-7+3Lll!=&f@}QUhG8Kfg8v4fA8rX%at7K5Sfa0 zssH}|RpZJBze>$B!H)F?!q*uWMBeo2GxMiz{R2XKx_?yKk1mh9w?b0TJqopHb*@I_cVbcXtUlHLvjLdhnJS^X8_Z z@%zT@u1Yai;me168T3lWmB5qvcTb$KQ5UDoL?1k3|84PE;h!}e=SeLBU!sI;vFE6g zN@&JIUU2MLf3t-sE!l#ZD<5PY?CpHC5b##{`)}&eDF%Mu#8!sRWZ4#Ef3?QBz@6QH>ercn-U*hp z5N@7`A->H1Ae+1IjBS13%d=j+r(^IxoqpM$BY#%rFn6yU5?yOIcOlVHYQ0|1km+vO z&{y(Ct?A83@MYpzy9XK1r0qJ-bWSnGhKAWtopr~&@a{>3f)@U(7*su<3w6bV+?R@GX`|EZxeSCw9 zSATu;_0CG2`hn4uT4Gc|Y3s8>&$`x)k7H8J*&=(gYUYYF{n#$^*Z#;NqC5vMYTt8T zq*|FUrKXbq_;%yZ^6LOi+dqDE(U|@AfX=x@8spHHRVo?%zF|Uduu@g+hxF%{KF9bx z=ViE0?w%jJX5v&+x$B(M?-#{_zAAf6D9^p}tyOe9dtWiY&i)3wa_P^*Wp{E)di?AM zZ2Yw&Wf<+}^6i9omlQna$hRN*@e_z=D&^pOMcxv_qW!EVW{@|SId^hwqTs<;ujz%g z{E{l)N1vg~6KHbNZdSj+R!&Vxt%4ir;r_46*Ty$2MDZ^Sv3XxAMe~ zyZBEj?Dqdh=bWhPuN}M>Tfcd;PCp-7G50GqSjZ}rFL9vqt_V+v#tn$thnaT#dgpZX z{WGRsTYt)0P>1tQ``uc-boxg>%Dh7jz9sziZvEY`?B&<_kKfJz`thc@aha@TxmfKl zSOW)7%!BNMnoglrha@yvrVcM1*KJAEzV<(^J7gP39l;&H^yHq^LxUsVG90%)?&3)n zr8S=j41E4BboRT$rCyzPzBR8Bo^(9@aj@KkIG$?5k1s-LuCzsXFFZXR#~+aE7w7(* zqWdg6nr&(^)olClsNFRG5~u!HdU1fmu+A>b@+mhN^EaZU=iwjX#Y!QL-_>RQuv{Ei z8p{53byf#;-VEoexx1BF^~a~_^$Ur1hg>-$iyQH!e^Lgz*7W)Mj=DTi{ENI+khbT3 z%2zj}!McCZu1sBNyiDdG&9m&-!CFD3bVcpN zfdj`EC8vM4zK}E~lJa7x`k(31f$t(r3W9g-B@V2w{%QD6zJCnKhhqQ3%43J{+nL1v z2XOTF{P+K8V*8i>_aA_xx0n9|a8&s}fTQQ8d%=JBH2;(LvwwL1w&H(#g__qwJwpC| z%)5w(ft)MVH-!{r|;2S}CgkOGgUz4|t&X z_j~CcjIvL$`1c+&S#KMFh0YaO@0%UN^)7j2I4q zG1(Y^n2meMB;L(&1GI+<7rACh2yu>`E`_J>fw_So{bA0uaBUYQ#0*-k@47!=2%OKi zt#pOX57EdR0L28-W>j8cmURN_{i^{00y#&=TtX3k(l46TfCbL0YoSA34awc{Xb4cl zSq#By3Z4bH&idNjOgvH?$YDr94`l$4!$R5&F^`6F5i=IRVyKBS%uMWN0VK$z&LwMP zBC(7H0N|X5d5_6F=tet$F?@i)1_%i4+fUrwL}qA!*8wUe-=v-)gIcas0ARMy?vaGp z4ADNoiKPSHBLfJK0f!FpZe~YQE(P)+w*q(IhI7#-a~QBB&(P%v48Xz>^UE;wC{iND zBA-WQ#R9V52TYFxAkq|oO?Syf1g4&JGXy);WCX^P%bQ+-sO6w}zTXz~UoQZ#0zf^M;E}|VJS7U0$|eJDqN=b=#c!VJd*(dMWHpV?Lzr{>SUQ7#U{FZZTc+=A zrhD*tl=5s4gPZyy<+hVRymUGx!Xz=_KAfD!-j+B_phwPiWD&JsP6Ow0B*3-9&pbHNbFL;SnU_x3+Lc9a)8KXK{7 zkfDa5If8N;LVFqA^tLP#P`5{G*ch5-W_M107$|&o+9<0^^ga+1xoo;$?QM0&XpRY{ z$pfsYAGgZoH+14vWAZN2n5^3(PVC)5YX|&<&J`Cr{B$}YrEfyd>Fe2T#GiG$!h6tM z#1-@AQFKLOh|iBBpH2&36VrwU{3gC;KfL(mw%Fs+C#Qn=C2Vh&m5aXPKixADw0};n zjHoG28O@QNK-=Z_-h0fe!bw!h$JxPljINmDVwIs@1)sb>_A05EFZAdu-RTwj$*(PI zRMxAsYA68Q#iOgle}s49f_1$+h7A_J=LXLj>g#y@mrjjqh*V$or}l0-{OVD1fP7iv7%N5G|Q)C$OhX^OYS#Yp?EgiPFvwf z0^bMXhRsUMw(K%wjW%hGQ!wK>)J)(+2j(l}8BnL*Twt~c*5$|@0WiQWtq8U|cM*Zd z`2uu^xwvVE$B)Fcv~;6jJ4=S-?a}j3!$ay@oirzd81*YO?4piD8H`(201dvoQL-u2 z&E~?rV=Taf0fd~~`ByS&CoxQ4pEa4vNsb+-F`=7(JP*+Uup=GZg4N9L5x z?NKOYZ0cMexzYB|_i4&4LCfXB@i>;()R^tEnjpf6Q%5C`SSCm-o!pX9rp&2^&80J;Va! z%$LRvwVV_0jjc03%m>MrR@r8}`Xo-ueKA__1+~`EH4;`DzK-ct%=;+JC$1;XpU}F~ zeRLwHdo+NF#tY9>LACYmJRbM+!qilkYWK)$0f{nA7^ny;6bz@Ot>kuHi^6+lm_h_5 zsv8U5NOIWBY_2}0az^^D1I&xi*r3-c(5Qe_j>V1v1kRjaqum3bVjkf^GyupvP2>ay z3qUX6Sg{yupA^7C3YiCZ0N7zc42jj9KaRDX#-NDLF#v#xGj(-$kFvMyTHX%x8uIHv z`4!uN72G^CQ5??1P~8fvx;!WZUr(Vx#>!0F>BIuZ*m{P6WL-Fr7 zZ1{W=#haC$Sth?qy(C|PLg{7XyT(uBDtj@=+?w31h_`trjq)nyUFhyLd5N3xuv)DH z3=1c2O6UBcIaG2pLeegk+f?(+5ZNuQhul0^%(kpU-p^DD9P0cWXqqt+NPN3~F%EtyqQap#t1S8btO!Oe|7<4o zid>%%FDnYA-7AIb$YWrwr4m81!#6j(ra(m?mC5FrLdfs>zB9iIhOnvJp>fEB1;8bs zY~khOvbAC7Q8q7W^RovCv?C(Uxe5(rJU2`6*06;Y z&Bzex>VjN#F?7utkjNO)>cGTBVe58=6A+k51IXdjK~NB~%zha;Mr>ID)QPJ5yl;tQ zSmEPJ<9GBXb>{Mh#&J!g1SW@KVcuJ-RyaWFBJR>u*a0lZ3e3~igz6kscAefra8uzV zzwi$V9sX`Dtpp-9>_aRiCdpfSLOC_n7>J4a1vz8u&ANP+;-Qe-%mI85Z(qOTa9V}z z?z<;?qg(o;hNB_zGpp!h{5D`TY$0Gf@I`Dag%8 zCeCKcJ5}7=lk!6Ug;O{~?Jx9;Q)|VQcW+_BAEj3k^{c0uE{ekq4QG?yp|^%>411x%Bu+i(VrR$}2X^%8(XxN^M<~EXO zACi>i$ZiyMfn!SdC+t$Jwc?C>g;Ye{wXQOqV#GUav^UhxScF#0b|xrjn>_KWrXEaJ z987Sp)U*EHaq@fr|NA zc$Exu8@n9;WH5I|6Lv)4W*y{X2%IoDR#LtW763XH1Bw9Pl7H%NGJldu7?8IFR%1F3 z2SJ~h+c0B_uHOaOHN!xFjeC~hj=vjCp8$pirNcB*=5dj*Fj->7Q=dHOb)W6Vs} zQVX)31`IY^vjFyjvXsE!>fadt-=vj^waq0~#B8{U8Pc z0E39oqoXi3I&aU_fkwZm{Ybf~y}#cHlCPI1FCp>JwHsbD8ZzEaVnP!M@#_2;C=^O% zK>%ViVsPQU!Xdrx`U2Fldxb$_e>V?_V8V%U&e3{0I!2AO6Xd&nH+3RNgjlBCKYqLDBd(5eM;LM&etvFjJAa(|qdl+d;0}n|D@OcFq zEejRON6(NstCRPmTcxuvdgj@eH{3D)qxVtjQ%qNa*~Ka^3FOOC&fKvB`|@rIx#K8tdBzF!-#ZB}-u*~vCfeE1qA6y<8t5>a-Y2S~Mq&}1 zW*MJ@am`ykBSz#%jY<9J4a0GLvYp-3I21_k9eDeT&r&HaTGba@5l$V$_D~*~A-Q0} z6|k$BAT-65h|yqRs5*39y#_Y*Mx6n4ZyeyU2!}|EdYSp{m$2XcUuWGaC2!;p<#3^O zQO(z&M{J==!7YEVB8b=Jt2GzIRrro`mhTJQ=!P#d$UIzK{P_YNywP-;a`Sv6(lYDt zb#ztZ{V^Nejg^Exegh8;X_~c~nbfgY)UbVtJqhjCPn@i0Th|wEWc5T@8L~GsRLao<1N95zqe`c_)Dv2&YonJ~=4lvX{CK^zfHUSK;{Bp|@<670rkS;|=M{r}Y%y@0og0 z`L)fzjDFggXKzTI>2TFgbNci``;Jc;>AMVVE4~OG3ov6+iYx3!b;I4GwPpDDV?7NH zpAH)On99#}r$0l8?mm05NNIayOv#NEGef{3(613zH<)-3knv5hob^`c($oY3m^znYuz;9YgyA49%U{BRXuNV^ zLnFQz-XpV@@9+?$76N0~Ya=kn*9Ig47|TG~9J&FDC@!JQ`0g4IAlQG$)OjHFjmH^O1B#k9xd15W>2fv+gk z5zFL6--gG}H*3mzeX4~MTh&u1iDwjmFg-|gq*>h`Y5{hDRD`MeJDV-Nk!TSm=t}~Y z`{$FJ3AV%*^0;aF&d97#ubgK3^rl7QNFKT^=4L2EP_0?$aC${K`h!Cm{esskCrRc= zch=DDjCY!bYr>~w_}0&uD7MvCu;yA21ecHI$8g=%Am!>z6j`~CmIioU(Q}u?7AJW97aTC>-Eq1gZK5Uo8re#-7@T6VAslJV(5^SbbnUcTwd8p^(DVwHHa zGzr~Zx>8p!!mIfHtN76zcde4#s+p{Fs@PRihgEcFB(l9fUx6L?dBETRx?IL3z5H-Y zcGRvGC!2Ts*kfNwA5HnL3XNR*wk2x7CnoY3d(gENx29O8MD z+6)%ML73ZXP;`Xz<&?g$yGdpbDs*oPNud+dT8H~gr`wF0MWJxf2uHh2PN2Xnq#8)Q z8Ue4u)C*(msli3^tre~Wj&o~xe-4;(b>)SwmtnvZ6oCMQHE_=I%)o`Bu9%GtW<$~# zcdL}y0Bt!D*+c+L@vQnw(_pl$6p63{z6W0ef;v?Yd#h~bB%(8CENHW3iP2F%q0 z+d%+;JG;~sXpnbt!p2J1-~GHhHQIrBm=Mj2M_^{2Z5FDIQo}|j1JC_AlUVb0-R$~7Cw>W?DWt95 z<2sm!3^e+`J`CCDuU`XI-KF3M0GtcuSQ3rAN_=hQxv5Wb#F93rSW^^xmy_51D+1_& z4m`aUKh2K)>m5xHW+LE+ETW&Z?vTY!@fza_V(HS+3Vkv&}4%1)>bvY#P~I5{;)!CvNABX zBfi%BOt5aaCW07dH_?N5+<4PH_}Q&>O`az&z~PHG=!eu3DjkBI@`|h0)$?*bh8?3{ zx`f=!wM4uv3_NV|MrTkr<@zsuQ;Pr2$Z5?oil5>a9c~HQl`BBw{hlX|Ww6On{=avA zwxoxRp=T@TIO4?c4f_t83q&jG7&GfxfUfjXq`{GI$1}fDS6DUQ_^eaNQ}wK%^y=%d zuUobfdHZZFyEybD(bo;fKKVYrG=xO7=p^M4Cxm;CHE7YV< zSU@-IHo(#ix&&PXjOf_tGa+A^5g+}fMdOsuk+dX#cIC9LUDo43g6*g-`z0XTJ9jWG zLG}7x$QCCuOSYvZ zU=;&}F4Pe&9NL&d+ zMLPrr8{MW7r$uT>Jjg1u3o#tN4`9HeDz*Xc1=2iNce#+i{!_Dk8Ui3BpTo!~&CYCo z2aiQ@$yKyTb?o=G;%h(d{>WD37O&*5f!xea@{XntWFh;Jn4;OeU7Acx%bz7owiS?t zzDSRaX`@UYZ99ZVR|^|^{dKSKelIpya+hw6*C=EM!ao^8fTzvVX4oObHoE_{`LPvE z@R4_Z?TP^+s-x-?^C$!k!-ZFe)nEe#y;-JYPxRarmJBB78ylP!Tf)i&VAW4w(S@!~ zv!*sVI0A#=gqbPj1+vljP@lsFizv^Q*SHqdN7`9-tr8`$7yi$YQ!lQ|rvKV7dN|v2 ztWg&7jmClvr2N7}DKdleoSv)=tqp=CnM@iv8@E|JbLY};Lzj92l9W5j7R}*}#0PPY?PJw)=RehqJI<37- zVg6Pj)iJTg-sCak8r{_v*(1F)E34!=eWyzk%Jyxwt{csg+|V`RH09A!@}hGPQ-WyO z++2F-U=1+R8TU}eGcL7UYG`3!Ql8679EeEs-)a|>v~Uvk;lms8%`siiHS1+$MMq^{ z73(+VH%cli8nFxEF~RFSWks_WvQIbV(S2!1i?V51cgpk5q@xNL1l(IbG)j7!uQY5L zh2gly6uw$lxNVFRQV~r?TBH9kp_B+IiK(BKk2g;nym-+mJ7@!cEaW2kSTZ;LX=cL^ zf8oZjvMH!vwC#oOmp-xJ7lsrR71b>kQ%^VKw+sOZl7a~y;MLv5@=sl^wD@4juSl@F zU1(vMYpj1fEKK&^EBn<{PVwD97MzuOF2$ZUo3tK1?5-`e2?=bL zR!A1t`czj}4`*`hI^Luj=_m&&XO$RV&X*fj`xzTArTDRT_ef%)=!j2MF`HCX94}=% zF{&4-Dt-U1w+f{^PVHG3iO)&EKr&;YO~Te|v9EbJqFgGrs=!7Mp5QPXfYPU^tM?}< zv!4#y%055G4xA~0?++Icpaau4lC?Et_7j?cz|8Lz)A2SWjbk0bm;b^Y6&A;7UbxJa z&Mvz>s;_!b++$kD$%YBn0cT)G=nAE8z8tg!r`v_E)#uL>oiKpL;7O+|0W5Nk2WI1E z#S?8QvmaX1@CBPH^81CF1kVMO9K*=?@8*QY@^q0$n3dYP-KUNk;=Lh&tqY=(nPj_a z1b$!?2*`q~JrEHfe|vkNMkYs`N0{v<(`at*JR2IkA=h(6g_!R8c9wSsk*Q8x?*q`! zNVWnO8UYF;{x=|i1&c)h2At_<`gp(sYw3FcQVPaL^%?;0O8CqzP*ysfireb_p0J8%FSio<3rF&)o0WHYF@A5~cCIAEGl0Jb#T`p*i z@>7rh-9JXCFV+8k+{(GulW884yrdQm$HqTu8*c};H(I+(ic5Gp&Ney?&s|)n6mXqE z9MBO8klyI3*4o0kGr=ueuWl7JlzMu4fYh{9&#>CMuKa*r2M>dnT({u}7~Nbv|v`pQ}i4)wkgjAJ>XgS=5SCaoWMC z=TN9)my^HOHXgs9(-kNlbC%9{d72}P$*%z z_}N71lZ*sy0zC?(=a6kV_4$;m>JvPD$H-{%`2tDuNPeT*>e8*=R^yi+|+347Zg!~K%rt`&=1PE|MiuX z3B8TLBR3VXs?yw&GiE_S&yuYY1fC`Ama zrY-^IqI?mC#dY+LDMgw*-xViXhxGS-oQgOtdg)k)U)HP@&PgDts=&ZUhY@a@>*E;9 z3ngRw5JLr%10VTX)aO%0(x%49n;Kn2Mgm@8 zMUq$-$J$hYTQ&?o3nHvF4)~xzhcJN6i(&vAFLeD|itB7xk}u#O%0vh(WJF*VJ6MPX zw53Z^3*#j(&|hR@-#2j&PaP5E$7{b22CA=t`>vANYvL3#mBPdkY zHL=@t0Z>(SeTVv}BBj~|YFFn*>|*e|C|usvRt(vcsK(vcrhtYNvaF&)+aBNw!Q z&Bhz4sU}!<)yr@V3C(SiLSMwO*iwW~%}hu(W_SD!NI%3ds(t++oLI4z!- zGL`SU-EL}fkZKT9Qe+A0&OdS_u3uIpTIg)CP3$7UO-Vs2_V^x+qx)QG_Vhv1SfU$@ zFsI`Z;fBbVOQoRO$ybnHffKL5DS{E?v*(&Z-~Q6oK>U}(+s`te70lS;w;)KEM{Q=u zh;L8=!yBe+$`RyIKzmp@U!VQtL}>^j{&t#3C2ux)&ch9F=D*HCHi_bX#~0Pd)Tbow zY-)@8kA{m3ZuzK4Y`EyXs?>GmV#op3k!lZpp1wXT>;E#zr%L>udZP2{M|R(NbICUW z69d-?c84-ewvbLOqj)K!ggKNHW-c$^1??mYaWy*Ajmz?9@8@j$JgqyD&tzi`cCW^U z;n{TeT2bbP=o!8EIBydf95MKawqzxP$jp(uqu>^+UptT>X0hyx086YAYYtWjq+ICL zbdU1&D(0&-%Xl2?&YwJ#@odVpGD0;|>`8j*i>&r%^w4M(95CvA?0lY! zm6BRX9l_>kV70^d$_Ka2^DYMDI)6-D5%m(|H_bp&gdPhmKQ>kpI_pJAlNUX0a{ANP zY2Vvp!upi&6{io1Nsjob6pD@oYsfxQ@<}l5V%7Nol3Pl*4RtT&dth%cJ}P+j%&`7c zuam}x+-`aJdz;U>jS&OGrpAzZ7)ua7vehzAypie}o_!x?DZ1%XSr{1%0Eufgg;i~k?J6Di z{5i>MKJvgZ6=8FDtWE1jecOjsGxVmMpv?*KFvblpe1^~(-mRP95bB5- z*gxLn$<>(zPLqn|RfQg}`Na9rIvIMem~5u3mbH?1km$JX1k7F&voMOje~G8LluPvm zM5A!`JL`H1$*Y{+PrtAu(BB<52OW873*&Smw zlL}OTax&(nqr z)7Iy(VG>wnIgZhu5ARijPw?jw)*gl*t63U2QQyqd#AVu1eTgr@Jhg^k@XBu5Anhy5!}bm>nTt)|05%qdBI^uG)9~rFs=iW zEnkzWg~Q!>wd;XyG*-1@u3zxn;0x&&Lc#QU8DuG?gXbKLw3ow<_Ht7~xQWHSZ-IU1 z&FL|Cmx)H+v!(fYnvnYDfjM<%CYEPuBFvv=qnQqEIb@Gq>^Bb-e2IuUh`MVM5pXc> zhLsgEnAHMzD}H}HCK@Y)7dhC`O>wq7q68}8)XRnM;mS(;jj`;Qx9?jG2Y6;C%jH|X zJe_X|S?M{lN>Ul7=F7)+Rx&D*V%(Oo;9T3IRZkh~>Ujmy^!1MyO8cAknVHpTJy&k5 zY3CNK@#-&*PL7rpV{)bUt$XzFl`JT(-+AZtvn|(!4n%sEBN3lzkKa!K(d;L{o zkNM|;p5Yd6gjzM6TNKRlqvAPW)Hx}9fb)U@~Ss3Yw;-qGq zuob?aPmSFziD(#x!F1uo7JMHF1e-q?7yyQ9h&{^+>n2TC`}VSR`$V>3&R*x20J+~e zx`k=@!2!D!z$yT<&1;M=rO&48cq~|WON+eJ;Ev4rT_)528i=Ym{Ag>8%zx&qXf!G8 zHGY*0vl#4607@}D9xHmY9=~q5b)jkyY_H8Srh{#uCDE`re_OXKTa&TDwAR6tHje=r zqw!-|C7kKwDlkv?_yu@cgi{mlIWe&v)J2O7|Mn|r{nTN>cAVY^EYF$n+Eqh2wRYC_ z*L-a@X~QC`A7aj_MGoqXFrihlh7=$%c?i?mapEJ8t3J$LqWfvbweVir5}gml?IBnj zKazf;k|Z%O>1G&7^I1A6^uJiU@2Do$_fhoUuOfofhzO#z&_t?qL5MUFA%Jvg5kVy& zAa0tpe1%XH=}HwTQWS&;QWS)2n!v^aL3 zf0^~ZZ)TD;>q%yw=kuskKMHS2d}U@{c15szFBZqzuNoE%Kp=RP5Qsi=_ik6OrskBC zc~6e!&06TCm_~e;vTV+*N{oF!6?o!yGfTYH-Q2izkVge?2ctEd=L~mLY^MJq_-^{FbJ> znSi^bJFS-c=PmM(~Uf&*tjs;NqC3?-TkEXxW@3(ZRsj);|lFhXI^+e7@F6-3&L0Lgd zKCSH0tl^4yW2x5zr4=!MR>|hg;mtHYjn`NznV0TPH42*A3dsJ^=q$3zP z;zE3b8ky|bYJu#>SG_7WX{a`(ShJ%0`BJ@7eFtP3T|fBU@)J?A?mUq+qAqA6Ep{|M z=JVjyoUgN*CR!IMlZT#EEQh(No=_gRX?JP-^OE$e^~ORDUJSYGlf6mdA5OM0@4@%+ zj0wdQr4|^EC!n>7rtY0;Y{-|YAmM>s_;#U8Jzn(&qL=j1B%4u2j^sx0LNGMbwhm265;jzYmfre3)$)WyLcO#EA@1|tu}h|}pMg5w z#4`hLZJ$Wm{`6Fs>W>8g3TC?ll#Q+AT_C)Jl_a$3L{7Y zryf<}L~JWOGiD`j#OBfmfV>s1>J`v(YI*|qXylYVMJ@ZJN1B{gS`?yx=Ol z$y|Y{uw-ovX8N~v%&b5uFlODeY3+%P_5E(}5psJdq+14&W5qe!1m^g<@ zV(a0E-egD@kU-o@wA0S2cJ_PLmOw>9#3h~0n1?RJh=oG9DeLUyVYTgSS;MrJa}fxv zNZ`16)5Y(r%;4q4dy6bAfzgIzlFGnZ(H~aSY521tezJvPQMvuxhsy!0Ai14oF0eXn zA4r&}=~3CyG*qsX;k|qFhh%T$e1=^_{WvWu%-w2-5WqYY6VU)grlKAARH_QEXWirN z!EZJ2aQ4wk$9%ZUctv(9E6Gt+O8d==Y7q#*aWRBo_bIbr;2Ej;i)$?DI1;J%_M!2i z9V>1e01AgjexDN3gWgT*`GMOXpCM2~JKab*$_eFcWFh}Zm63ETHcw?=dT5O^T(vA1b zscMV~>IOfTd6i%W;&_tA)&9N52Sj<<3$OFdb?hr*EK&w$E?i7~QHlv#RW@6qrnRw5~}umEA5Q&VxGD(gH2Bx*e^LW zU)v8kJic^pu;D4UjJw>U(m~Gn+mBoFWRDRE@lkkz~)=C)yszE8}WSQzg;UyBvR%4^F)&^ z9C6-155CL+=48L6gEZ;dw*#+3o9V{ny`mKE*tq(cmpB0AWQ7tiMW9jbBnt!K7GI`r z13>M-#p3qVUpyt!gM)r+9IN}S`_ka#XTINaWD!2_a-OcB;GVE|*||DSLTinyqIO_?kD@2i`^B=+WXxuB zdd_TU+m_W6<@DxYZrsl05*7vnTnBd2Gf7dHho+l&9V7iKqx^WoL!<5Fap-utZ6&0f zp7QM4*^vp%P6 z!FQgwbhNOQsexKh5~y^O)bLc->Z~Tk-lp;5+*p@5w`T!9%6(?fHiDefdtWEmJbklN zk%uP;bb>#RoxH{tMj1U{Lj1d zn>DFz3XwKBL01Rd&%{=TVVO($o7ORJn@KsNx{!W{_Hw(W|8xN8yF?S=o)l%=YdCi9 z^h(7^W6q`EE0joY`=}TngmKvT-sdREUrdw1mBbA(*5FY9I_^oHvCJ}c`m`;u+a9od zipqYo@jn3 z{F=RNu=~CB=)d?$dMXC~Ld`bpK!<)~@OurnrFm9_IZB0O;gX6`Jp!qD%K5oj|5sBS zCElCJ;4(0(^JL4CL3z;f!mnuO@k+|87t8Xi7 zoBk4>>M*Ev2ZMGdx88PsmZLQ4eOJ#i#4OR^ej(rZ>62&=^>T91)jrWbR zgyB-KS~CUrL&1kCw`R>LKu{GYY>Sf+|QDeN`#11Xu*Yo4G z5TR=Sudi!LN^?p&3+&jW8rAS_l_7ffS>ZlorEWKXuT7zkcD8xO;<#Ne69KKkD{l(G z($pQ}gDD9<&U(R2Qc&`I*Lztej#_IV!hmO^F3#yyQoN@0&p6!Yk%@`=uM;2*1b?WV8ji4(} zUtn{E9WA=-b?%T^Tp~r~`j>B3)-S7P+>8+uSCsC4bh51WxL+>eBR_OnzR>@h9qE03 zmhQ*|d0O+0b)rni<%cGIQnU`8H8Y&-M=6pEdQ3&R;QX7+axEcS^YlIu-rTbnTXzMd zOcwI(QXET$#Gjis`n_y)^@ZGchaZg$HS%cBA`YNj7OoyKZoGPww=_FS%2ZPnsiweP zj?&C#eil#pXNs?Hg_p$ zs@pGr)xBdxcS9GeuR3Cy)y}e1G$6%G%?s7iy|kmR25$~+1XqpXs!!K40thW3PUCri zA$QFy;IWS7wBP&k@KHWz^MhPcza%9;Q0^UzGw`^cn+I&?*J(u7I`J1F9i$OA)beDB zyFR(7rcP^l?|~~_7>`gbrlhI+;T}TX4eXYYB$*_MNr;0quUi737gXJEUqv7gCU7v72vcDh%&s8|7ptMq z2iQyysT&@dl0$4he;T#&GM^oMUMbQxFff(7u2&p-zYg0(lo&xQOa~1G+~Acs{l)$i z9HiSOP{aRbJg=hS85H+`f8ZQ$>>Q7kn97uRY5@hk_%yK@iZ=Y!q0rJ9HMJ=Q0=QRj zL0Nj?kWokDS>REWN8VnN5ViUG-FZwX{A@$n6?1-64_0;^?lWQY*Cn~HeL97^Qf9kd z|Di9!ajKb!>5GjU-msl~_Df$m5*}}ZQrx*~cxe=iM1DOfPHo@PRf(4&fI$st z?%ZVJ?!dBa?qgLo8p}A)2W%gof9M^ZxbD;rp|BKhP9c-?8JU&MDJkn$c%^B@hA{6Qyr?{QV-lqIc6C_qS0k`5NS zuUOJ+U=#>@Z*FdJjA*r%Z7D~yzmnZ_UFNx;>`M+|u2f5oJl^?=cy6iqN3E7v$293< znU0SGFqZb1`l@g7!6|odDM?fOL*j~uWCxc2B(NQ!Tzw_;g+G6#hNs<*?{kfJPD0*K z7xbxCyl7+P>#AS%tTCu`@PnU<&Si6sZvJ8uSp&4lle|c@!B#t5EQE`fN)VB$AencB zqA9B1#@lZmu!+CxE?2!?xb)N>S8YXECk(u`g`Gp|cASR6||w4o}8WuM`( z>m*<#nPMz3zZbG?VHlID85@fVfVNh?pjOym9^@7lLS2-nfY(s^cM`eq#%NbVy{xIP7rTrHCS~p3D8iA$UrfL)M1fb7}y?5JwPcEf0>t z%t;NVJN*7NHnlx2R`jGTNBmupPw8^zrsr$=;B`Oa_}dCti9EYl&(rnUfshJeGWjDa z<a@{q!fOf;Y?kArU?SsMj#l30 z=U;cHBhSAPF3mz3Xb*DuUtzu)honJFwON+p@WkkDnSX@ zY?Qci;NJTuGUq@2Ncp0vkz_5v^XTYLHnCYuYdcoNuzWq2 z6NbYETP!kG$G+k+sCq)CWuOhp%3>_(1IgNTz^Df}*4ijJz&{aJ$7Tci767+VaJM9= z_HJES>t^?W7oZGAx$I0HBX;K5?uIP%V<248b~|7azoB-(H2`pMNlrMil?s6EFzA4D zz&ey=5;mbD0LDz?R-3_IL&GJtaSR7vN8HArL;?|DzEc52+@1ni7ON{jSlJdZ7_ju; zl0AqZb`W=T899w7L9X1_`xqjXxDpL-Ke-A1_(gW{=()`Ve3-BEJZwqNt?jA5VLRPe z@ayLY17Kbki8HCZ3h=L*q-21^J#`IcP{Bu+O#i9Nv^TjF51jPZ+wu)P9P`)fQpeIJ z<|baiElSgb(jiH4(l+_|5ZmexdS{LmGou-V=TA>C=@GG685D>ffu&1WhRzRenY=nC z{fwu-ufaN`!Kt$^Fnak>M5F0UzGL?`S6YjWbm{kQ&g*_=>UdKf25D2@hfudotfo+E z0*Yn7R+JpY;=H@DRd_SA z&~l{eJ{T#}yj^is?BEKo!`lhMj!&4knH zDfvNKJ%;jJnrKuU+i58fymbaFKP%6W`9})?d7ylIM+2lzy zpU-JYZL{qV%vVo9YmpQeNRFSeHCT#&OIv_{>xK_&!Dsi*UWWqzq@KNP>;eX!j;thk z5lQZprdhnC$YT!fUiCtRUr}4?ZDf%6P{i`*g=Y_DMk4=evpFsGt@!l~Iw!uYLj3qm zY0~Y-ram?|m%QOlW(yI#*o(VpC?qKhuIk28+~sLm7Gvjg`j@k zn6@ChDm#aOw3QASSKruN=BKY}>V zVPPQ21O&oXP+KsdzYii0-bb-Pf(w0ySBXCvY)fu3Z~%(hilxv2m>|s%)kV6YEy;B< zIC&W0UW1X~(r@jUjeD?nvM*rs%w>8m{Tx#>J_xoEfBlh2PV8uv`a;`+Q(;na0w@_p-v2$}Jo%bC> zQeq%RWqVuXA;d2k$UZ4+G(BCFkfDpK1~>|cAW(2P3g}yDU{AT1d3_*kG0153x@-w@ z6X|o`l?kzo*?b*T;PsA&P`dU6l)6LY&1dlikzc>8o37zi@OE(Z)*9?9C0*z`c-mJT zf8yhaj`rOwE_ws`7a6P=0d^JDVqjM0N{0J8Lp?)kRIdxca6kf+wd@>>*|H zXr5e_6Vk(X-g;TYmV2;)ylRWT%~CNT=)$Q?j~z#KDd1;b4n5e3=a7o z8Ct+_X?;3mEpLLYDxeu^Ej5ORbEWS3lttO!XI&PIa!li2@G3IHTilasJAGo{nU3cA zT`fVRkid^WyLiq^Fa0^(G#rA(i+Q6qt;6$S;ec8QNoCClb@NJl3qE6WLm!H%vHgMJ z{VLyzR-&qVugi7vRtP^FxwFzXjP6h|c;$vIW!ZX-=$6la8(#3K@G!`JV5s`-v9C*o zgdpkrP`MZl((Q+dK=ph+yfA;SC_BQ2KynRn$-+RoTTH+h(G7HAxQFMVzYm?$!|Dw3 zb8}EDX1rLTZF`=ymbR7fXC(|wl7@}+;y{}U=_|lsU?NBshdUt%e4zucJos!6_4_;` z3e9Q(ULC*|;230p!5isI0-CGAp8D^%NECp<)<6OnW)b$U4ORq%35Mom`nN4a0y1_( zsDR2$VF8?Ze|Dl9upJWJTAMTn8N0!wOE?DDf&g5C9|ue}Zng<7(S?UEu;6O)MlTV_ z0+{SXmjr}6;0Kea@X#9&h~sbx1F*>q0EgfJ4#&!GUQ3i`d=X(5JdX{&H+$z*rmabySuX^(CaIt&1&8BDqFZ`|y!xc*~c<8q_;V@3y& zu-4MS3g}-><_=W5UJIqArKbA$fB+^oTk>@Rm!Z*=4yk%iJbY_vgyTx52bN06pyMWk zef#&*I7w*jCNWMS7gC0Muq6m83v2g26D;7=v=VLWG(5LlR65iodf{W}ejlZjl$1mm ztN@lf;dU6?YkW+ryXvV$&;AwJ(2{R!JQb*-aQiGdElF^6--1m^c{qQBlyJ!8yi2;M zX~kSqmIrZJ@yK@~=qB zBP3J6ATm4Z@bP1~Ou^&C%=a0H)ZUCo-}hd$^Q5|anB7y^$=Ivp=J=kjp91zrWDy?- z3M>lD4Zgpwap1t$m^#O0grs7#Ib!eLzyIy;{<7W~X(WSt6jN{$x%UuRBC}+6>SD$8 z3EXjE5A(S9HCd;05PeJL%=bAv8H=H3vWC|aC46Ub>q>r<`BQZ=rMfanBd0#kmky^6 zy7*rx8?kczV0>8agfz9+%q*Azh(yB6s{@R*hORHWEau^hy@G_R zcP5ph1m}CC=Cds1&)JnDWfpJhRXo2i+ZQjxz|J61Ps-T+IhPZX2olaneVOO~UNSF@ z@HV?AeC02UBy9Z_Ha-@IKJ^N}_W6MFJ(VkqK4*Jzi)!nCk=E819n*@{i>t@Xa2t(x zwcfsd{#Sj3?nx^3-L-}|=Zh91ZX(-tcWpY6q5*6U3(WX1$Y3nKs(AFoN6zFbwxEKo zA?ESM2VHkIYMv~=iy|vM*EnNNfrzh7%p`wYcCUis4}qy4m!Ba|g>{t&#(U=v0Vs(p zV??s-)Iq~8oW6lp`dNJW<)?TXA$f-C_ksJRaum}Rn=2gCpzA+i# z)y4Mba&~HjSK%i0)zA!Dvs7a_>H4p-SQOO1ozQ#Y_+O`9C=M78py_y*W1PATb4aAV zG?@p-E~U2b)#rlEkIS(b`mU~)QN#td(ECQAt>X`JMQTSTMxokep`^1+4X56V2Dfga zcB%Iy{b+C51t-*2u)?2AjZY~&lI*=WoaD>Vtl?y@*odP@UYPB>H20#mTjm9h$|$A^ z58a~Tc}nrA*?Hf+5fmz=aZdej4USLE{>C4{VRwCQ z{A0ab3=RsFI)7eD4Q(%_aqb_jP7Q4-rK$dphNFfyk+a7{Klk^GeTwJ*B6Ic+@^38XtfrLSKeXNdIji^2y8k;?@4r5;|2?a>KX3m#aF^oK z`{zXU_7y$*|HkU+?VsoVn6ujdO&|Ju^#2!q=BYV@3C2{Y5bZdQwLBN+)(YLbp3;6}>%Q4g# zO@m@)^!@o%;s$lMp4wjg3BGgS$43{)3tDZBQw#lJPV6_iwVct%^K;v{$T6cKs<1{O z0(>q2(~NuHCH1@pntV#d$DXqTZZJ6D7cCLre%8fg4FH!cJ_k;smht)Bk(PCYm$viO z&K=q37Cr|0v^D?3u|K0Yy?m*3MPX>v>YN?m|hi@%uluP@``HEn)6MQ-BiMX|$-8G3}no{b|XW#!FK zlT(hFS!7&X^~Ql)>v~7;_1!9D|4fV*9=^9~Qbvog5-a^rf>P1mn9E}+S-f+iq*+Z7 zLLN7ub-xlmIYri)Zy6h3`j3*2g7}VO=&8d;wl9@Rgs0?=$EqQmw|ecKlE&V(bwZ%2lG8Q(4oo=QHg739^QQV^|LPn!zW(PTe^1lrWp%Z1(YVJ7hl~|<8&i1a&XsYOArG`kIj-t`Xkpo&7BTuKA8hT+wc=g=eXP)|?q!#MSa@>d&!bYFg@jfPE8pGn;hSUr7%4}C|H$G`dj?e~ zSi>DxpQMG%ZSZ7?g)E4qYt;wF;(jS-2_101ZDTK*t9S?=tvcFO)HHvJ&xiZO+?ViW zA@5wZbMoKIzDqn>`j_+Jim~xV)z-$$<|G1Z5%s|G>9z3akn&_;hHptJKi;v>cBts5 z-2JVb`vLCdR}xx_Z<>XUv<_FQb4{v?BD?(i^QX>Q-<1%EDX82zKC5~r&E13G>PYUx z=hEv__4~&7E$&nv{r=ve+rRVA+aiD7Q#SLz{Qb55Vpw3vujx8*|FcsjBI$1Sq2YRh zg?Ha~P5r6EPWH)~6-G{WzM;rmS5I})%eJaN$TwS+!4`=-I9k*Gmz7C>&ZvHlMUsFL z3-df%;-u+Yf65z5rK0Z4rn`96XR}~dT5-j_>#6tJ#a?=T>-Ih0Rpi+}(S5Tr@X5+; z&7jwQ*!JS^jQ6ES8_*G_l$6hgGE*v-3^*`c@U*Be{o09eeL)2UXFh4wso)(hjLvxr zdPTcI;L!5FWWMnTxt>&L2*Q+;)5}$A-jyAxw+u3gJM$)RTMd_eOzb|}BJTWLj+$+% zGUnv;PUM*ovSeg~rGUk&g7(-llEA@f7blrV3!jm@(LXp%%WNGB1kIW=e@)(#uF<E84W=8)DxzDw)^l~F*+=xyozuVM*siTLkCR+}fOzVW|3;4Z#TT5?g5U+o*RT;K@ zpyNR0SghTrbGQRcr7KM@;Mo7%t8$qSpL#6%<8i){?P-LW&YM`ZY14?qmH%Q%3=wn9 z+istUoo#&5LwPQJRXDmW)ai<--2>w*k7h}C{*>WN6T8=I_T;TVi0((-f-=^Z*8Ika=~{I|&;z4m+Te>s<5JF3ekm+tXLwRv&UIo^B{{)&5Q^%LvmXE_yD zpR00;<|8hqr-ve7686BfDluSp9k|Nm2#)7y`)`%&e; zN1Fd)UH1d!{~O@?_vHUI(wtdX)cD7_<2k6QUi@@usFG1ol>f}%@6~^E?uu#;v;H?n zvmcHBE5`jFICq-=_i>t?*s?!|FZdqstdmBaL3!{#y(~jj`g`=ao78v6rY;)ji6im%joE6 zo%{dAxzihP(QtkA;6(O}ukZP;@93R|&|RL}>e+n2ek3yZ0G6NeLC+ zE&%vmI>Srn5)%9*rQDNJ$)5l3C{ z?3qS=e1K!~x3MviN#a$+L>Ta};1e9?^i5(bAnZvJm@r_&8_EeBUSR9Dbk-d-5dfk{ zG5{tLDu6*8yllgOI8aGcFp~Y(j(ad5&2(P}Ti;XYsRDph=8oG>X|0V0pn$^z1;(nW zfL)nnEGtq?-dez-0zgIU<->hOE{-t`uER4egnnz7rdl%cP4jz<5Ej zM;wF*$BrT-nV!G$V738gI~I^LGQ2wC0WsQw$RfX8L4i|Vmp6VAz)Mpa<1gpEi^O%o zMl%DT$HsUbejqOdjVBQL0x^3yNuY7EIRI9QSp@~MCKZD&eZ3L$gQk)mE?^;GE)b=u z$@370O95anKE~8w9$ZyQZ7wTV)VX~8qrO#2>h9?sxOGESX6tn>>iy$Itg;0F7$iLv zEL72Z0we%y&}|+pG~B&X-ADAm47y5TCOo3a1BG+3h;H26XFU&d-#2kw)dOvpB8id% zZR&3y0^CB&63Qaf6R#u*76|jZm(o?w?ar0pJaBtYAjAdZdJ>FECS(K2aYxt?0P>(^ z9_#ovde8iZdH=?^gm!aww@hVcVs3%n__9>bgj)rl#x;m=kALyzv|+}{NV>P zo=pkgAL7!^i+L+iJ=5E~Ipb^zjz2QsPW=#g=CKr1%QbvL*>_&^A|I_utPd)eijOdx zeeokARQtA8my*?lcgh(YIudP19BU67cwra{H;`u@7lS~;!nEBduFtCBIap@pr%Znv zC?L&%GhdF~)o?@z<|{S-@+Hq^4zyoH;9*D>K-)!LTRYDE6* zDD2NV^pHKZX3GjM$6qoItmO_hDoXkxVuIPJ5K~0 zzNGy~8$Q=9IJ1)wvFPsP5iVwFK*kq(Uq=d>wB&G;t6_%iNml=KbggL@%Y^#7=@8^@ z7e(brIMRSPCb+%aQ<1O{SRo8(4=J=7u~7`dk|=86)O5tJ0dcHP)&nfa3 zZt7!rzl2CO6?VwHe(7wFyb!Xo^Jl0uz1` zs)XIY^%iHou^w*JFbsu(x#7L!Njua270@`#vuCl|K}f+3I!pV^z#CVR=_2p%a-BQl ze8Ko-U)APQhgR@4o}adMA-8*;3Kr}YQXSov)UBJta^@@?-GX1(PH_~t6n?Qy$qft_ zviZ@r{30!w6xM0hY^|{L_QvhMc&c}AU5072LEl2$y8PU`ApdT@X|YLVtaxzOK{SeW z)6~{FcO{@oNOL%fQvD+o^D(nq;9{~bUwm;yEtl5ZOtDbXgPy`2m6&*sh6Rz+$ap5n z`V$Al_-!=a@zvq-uCB;Ny>X6mQWSU6Wi#W_X*IN6GD~&%{9`Rr+L^jGu4B`*rWdP& z-lf=1dcX<|zJ(*!c>emPlMS1{$~sW2VEH>>fJ@N0^JZ+-$q}FSBXqNwg|{(LOq)(IEUvY3p{}() z9?gU}+Nw*u{`mFmG)nHEOw&_`)>^cBTl-=BvFSaXEAY&YvBHm}i(l$w-P=ox1n1(9 zA&+8b63J8uwbJwicVPmf^*VTyXv?5Xc@>Wlny;Sr{o~BkVPgIoNJ!wo*q--XriPw2LLdwHT7iD_mFdPR28( zFutNhUB^?JL0=c1Yfd>@N0`fauGJw!sNE(i30&%lhhtJi$-luJ@mXgiWHIxQ}9Tolb!I(obiPM~hG=6!mj z3E|BlVDy!G(pT-y&68%!s_kb~7M8V0#;!HJqB1pyPMKZg4e2&zFTVGoiZ|2hOub~R zDm4kqe)6=swO(a26E1THZhsjZROTO#4s*^isEqZ_k*G&1^54h5HV zFx+E2NFjSoq($tWq|=7wxHPtmD{lRe%sM=Xlgp%kc2>r?8GhX>kn zI?RJ46h?+#ogwFa?zl0h+XB%NNj8kR8W_r6dt z%S{SH&_548GoC6zrC@f?xK`vcxWV3?cqlFp$E8LkEXy)4pL~l6HXoPm1}t3d@tjC^lredl?8tN#Uig8Rh8$ts!4`<;?>xi zUQZ2zL)*tp$Ak>Gdv%!?3xnQUDY6_I3i#T1rG~NJ##uLwpT8~9?mf<>b+RUkzAMI2}fd#Qj=c1 z^=oIBLoPnvxN3nj48^%ycmZ2?V8-Y?_q5ZHQZIbl1*;?I`}+Pt<2Ds))1U#3HX5|z z&k8r|6+FF%5Z5j)%(Na6HFQ8n?FJvN|6&!%=F^5^OP_3*BA&ncY0q7ixbzlV9yFr+ zYf|`dSro}Fv{QoXG`+_=1-TmZ%&0(DMAJkwht$bx@}$vNaqKPf_QWOCnftG^Od?MTnC963r^Ch@}vbI@7zvOHZFCt7Aozcu6Z@c0z`a z13oF@w5$LQlH1&kK_0t06fR+7G-K$QSpQ`5_?^qjk6WNQu0Az|57dMrS#W!*Sw}ok zD=IHIgTWx+YTR+tQk{@JH>sK!1x`w+gg1AH+&%IF)AU(?0`*Pm`FM}->c!u-NZYk| zThf~#(Mz+-$3CxEPc@qeFNIY;kbmStuIzwqpf$=x#WwDhE%H*)l8u*r40M_}##$saUkU6fmAw5!9-SvfEP60ti-^`NeN4l z$cYy(i^+{-tE5r7YsKhJ@|>uhZKQEAX*xuq z`SA6U?ioFAP6S`PwcXbT|H)p1mSVM(V7N83_>MQ%=G%&KI>LJ?bCcQKHiwkv=#@Lx zb9vNs3f5^0BUa`1Nn>U^N(v@LQ%Vzr2TI4Yc?^`YqiysmJvaI*JqhBc&r%wW9reIr zMBHeRR$Wbbe5fm|Z4v4()8!U5#yET#`TcFey-Clz+={(wE+F8+dYqC-Mzcq9j(16u zAxJcsv-b;98kkXQ=))^v=UD^vRMw!KPq~N0{ zjS_>Gej1LajjMjUD<{dHdLsKV!6L+2NZw9rI#7EYa8?v@QwnoR2VJ{3h3?hiM|Az( zZq7Bxe|Ij)ls`7YG40H7&q*^9`^ea~tcw5frkhVodg-m7)`;#VP3y@-6%S=h|BV+K z@pak|MH|sA52^mhD4Q8?N|n~8xZSxh=-PFV%fLK+*JtLk#I3sFsNiGWb#T}0A<_3m zk3ZcCj=x!u#KNxT+>3fD$)1*GJKf1!d42x~@n!8FS2*}M@rGieXd&@(AJ*M7qF3nF z$2;E%Eu99u>b;*&P3w6)GV93vD5TjPR2a=3?31T$wFN`UYAa1oU~ySUH^sVD$=v02 zf@_DEnCi(vgVCU8&k}8k-fRHF4je(X zeB$XMc5#%%b50Ju2{S36Cj0pG%2LJ%;*%Gm>7(0{bMYV$X{c5eP6hOU(89Ecge@y< zD8b5C3f~0}8(%!RM@N%%ODw<79xxskyk|*%+gLtbIx+F0%yPVkOWh<#lrW(3%c*_O zehNYv(>5uVtSH^bS^Gf5M*@6^e zp&mFwcizuIzK|1O%4@RokbB{wP(YwGpf_(mA*XVMD>c>D%kVh{#K?su38qx^9Wg13 zKQt;X*RT>@Td$}+F*2zJWLnKL3RLSXlIo51*?oeF{b^=s6i>31d@$m&JK;hBM^o%KbDR~c z^lz{+>B&uJ1v1%+#^ogKo#>Ss6&cl?*4g-@qjHBneJc_cC`-PvdO0n=SDFATE7yLR zPea_FJD=n*Y2z?2m43H4%VeErQJ$E=Sg27~-^dclOzyvSKTM^I!)_;KFZwTh`~2sW zlrPDV*$Q4VS{yCO8FII}4lnY*O=bNRF+JD3;T$LF9U>q@-^mgC5W*CY+F6L2LAv$U zK0$Jc4Xi6JH)Eu|h2}D4_!0i6Wl7@~Nll7RcwFX?ZhkqoIj2_d&$yZUI*;P!P;zPN z&r+MW9wYW)Lz}8j23#Q1U)y-6SxK38RHKuIPg)QsKPuZjm z;`vu_3;iF~j|Splu4>PNT~I(E7ZIu?Sn}&AusB zh^;Cn*k3W5?Ez6kNQIp1AEijP_HL3L|>Z&ti4Ev$`8^Q;Y`RS^_0s;3zmyhl486$?-;&nn2wg+ zw3*E#1Qjc=h8Leh0vMpU$;(2yVe6);cd52e=sxW2+5UZteUxM1j+wmR8%{wijn==E zzj|>wAInw6`wm)X(E(xRU2|@P)%&}S=I8U#fi6t5>2EpHQd>J1nmqvEMmiC*V|26X zo-;yo3*Rl!g#OmPZP%lE-#{i-N5Fa9gsUqN-~fP=o7lZ-^2oZA4>`C_7)5(VGpa1N z!nW9e&Fa|~fB}eMZpc2}^!Rc}Q<%%!0gW=7;in<*jD&FdswiN-Jebuu;rBSO5gfa}TE^U*DnyR(4H@h)@5v5NefK=B ziAW>vK!$NdP#vg7US@roPTW?4psG$QxwWX^pyD`149=2Y62mADVFCEfa{z2HR@8`@ z1bKa`+sX>dc8f6`9oGc_d58=c3_?vcuY!2rbba?X^#lXW4HO0g$m2wqy3tRi;lS3f zTeUdJ{uL)Jl8Lh5x)_M0GyPFBl@vZ`o)!Fq0X5anb)WKDoyChfilVhF8xV0|AMsC# zjU$8QpEx?RbD)2d-Ojvnsp$k%u?GjrVD`y)g$ zh}eq0Efj9Rf>^%K#CWA816AK{1NGGwQLhRkv9ntzWl>ocO=1+0{l3K+MNGi_HM1PI z6d0XOayQ1$$&g2zZ*RoDZbR2~4u==6bvGao!rA82%TDn)Nf?k!WZtJf&k8MgltC7@ zj$@&l7J6c|#3ZYb!|Y9XP++<@#G8wbkSyr3e#+KT5(Mjg+SMt0cCQ}dJe(}rSrUeO z8CmAN_YP;mD2WYJugYG0Oj@09xC|_RYh}*3+^A8hELf(S^nptmr(#mRSjF}DeBuwJ zfiV?18D4k-`|p4!q&@6U@#EKwi_EC zn-zmOB$t>VgEDwOCu{Ae<}jMaxH<&O{vkPMCEz$_U_&yS9_$&>+Zb?rAdT>QX=K?g zVrH3hj;Gg8W=^DsgocD7kQrw4wl)J)^s5K5Bx$9d?o-S0+*K`w*k6qytnjwbBJgU> zw&+;5e6M)TPL%!qXK4j$qOuZ&G~&=-3W0~=psn9-ri zt|#$;ZY+Mx&^Rc0+YNBh%kn*&cJ0VWDe|w z;JeiCQ@nLY!n^X$rB=Z&+ac$qBSQ>8m>|Df$y57e0c1Um> zRxhC-%H{#Cliq&{=e|nv>N4cv=tc-LBP4osPvvE_^F;=D8*-(jq-3zDX#%m;)m4QE ziT>Hzz`Degn=hmhlDmAhn{zUQe&LoY+U+LD%^nk(*U1CV%cLx&H+B^^WbxNUT2~$p ztgQ>kV1&GmU#1Q$C0t1Eb&GsFif>{CLr`ePLUjPU*V+B-T{|tXjTkxpBHQ3tYf2Si z$i+kn^Wfk+Y-PpDA8#B(H4Tk~oIca;M^O3Aj#VAx( z44*tn>uQUgk$Z|zaz)mvnM!5PLwYqIS;~^EM`7LDs8Mho!y3sHlzL*FzSyzzYR~hrC4vvxoN( zyc?Nzg?tXqq$c$8qcARAnXuJD@~|fc?zon&Z@ZZOromMZ%Y-){%vf#?`?+9Q^B5wz z11y9i-4l^n*`so~sY#X%d6spE=bA$WdR+(6hC<@yv#TeZyYgzQXzRi20OZBy8WD-` zvyuvc=hITrW>``C!72b?bPu-$%UG1Qq(crzeV3P_5x8G)dU;tv` zPb+EOk&{7!-ki?_{oEjZ52Ilyn1#Qa??Q9tdl50wexj^pk6Qy79-1zQSp5=E&LU`L=wBHTkjtzMYHf?sy z4}u@R0%I2c2Y2@#4ORd5kNo*Zc8Y_Kq0YkfQ&sTkfR<#rYu1$KKp`lm&Njkx>9DZJh+n#DsX(IVlWg z_Q_uTFSnuwvm_Nm6tBg&^f=BZz36ro6)c6W`SQ4uH#0N+J|R)tr8P19q1%?`6jTTS z0Bm*w@U%!6iGVDQrA=K+ob#g>Q*9r(&@pgL;9TlllyI@HOL*qxRV)dMPlDr_j4*`# z0SJG}Qu1SSo2pZP(R|!1cKN5_yIe_)%M(;Z0O!3-6laG5H|^c@OqB`*tZiu zy;yzbI743QVa`!d1_~{m>?{ zfny(QF07T!&&v6V%d_y-gZ5tf+Ut=24qo9gkFzc$yeIpTOIw*r+y#|A2v$~kPHpno{z zA8oX0>+?o2F8X+G%dFpssfTL|mrvwU>D&cFMCg%zB3V3ukc?N!YB#w65-1WK1=SY;x9fcquDh>uo_pasB z1({v;mm;mRhpkCAzHP&rB(@99uBYr$aq$V~UaOV*?bhkc<%UF2<4`2<2Hz%UJa=yE z!|`63y9y`eqqWzfTK&_6Y`~`i#+Sx1Ex<+o&f%y~BE}Y1M#9iz$_C$t=&sJwxhW9y z0Ci>zUPv3Ac`=TLqRmR4u3uA}#pQx?TJ(hj{pZ3SAtnIwiUA+n*bE)ZL3Az)MUs%_ zu04p3Bkj1J+a;{4U!Y2GRXG<)5diiqD+r?79L1@#p2hoHW|_9}(P#3|r+#ZYE0jha4OhG%1fbRk1%x#7M{a->5^s4w4}@d};(p#)l}{zv ze~eXQgY_`4KnDo$`OSD?<-O@a*)p1qk`B68X`R!SK>`57JJokNKFt}93pDkW_(UdC zh!6mYf)((N*blcmnJ_P^^97@<$NW`V^b4#S4eUY7Kl1w4LXSIrLrH zB9SNZBE#_{WiqX#FeX+m2ndwJX0@ytbUkZuW4z`XiV263N*hJ`!;6$UW1KKiycqVGB&Y zh$89I2fD=r4lMuidQ)%oWp!TPLZ?PJ=jQ{nCNHCl7Av$)D=T}fNgrtkV$S@!;w);q zZGZMPH`{uxIOQO2!n%(aW4todKO8dq#kFJ5%H?)%iZ+f0kl0XXz(x}B<~14>7)3Fo z6fw2Zap(Ls)4-DFx``0CD{Y`q>uJdvP9w!RBn(DDeJKFKxfR@wLmN6+9ylYiV>ZcT z=eW$l9M!UsYj1aqbTPT>I3*GpwSDZ&tuji0ku#1ydeY?jjP>kvJ(z^NAec@E9hX>NMex0|H!C|}O5{IJFx2WhI^%!=wEtH@Ng4b6-4PC~JSs&Lqg+Xvwmbo)- zamATYp-lS0fJaeoKY#%PY`vNqkuEVCbAe3M>Q?$|*w?&0H6=4&QZeKX#qP_FtRkjz z%qM*261-D==$a2)^_~7Gq|{Y^$XQ(8VsB7Yba3MJ83VlxtJ3e8v^dxJ;3Z*wE7}3E z5v#F=QvG)aOh1#9eK&0{op1ZYTTwkA#UVsvsbyOclL%5MzDUC7)rvGvfVQhEylOc! zYChK!R2;AWRv{q>Ai_x)#Up9#kFAz?278SwSmp`q-C4I4LxYdD4_*J7o9cb6tEfdC zBzo*n1XMPQ^9uh8MXI^vL|*5pO;m@@>`9O{2>}5EpzX3kATrS@eys`r`oTp&a2>Vs zxu0gq{o1GpMa^CJ4dIy-00d#|*o)qlMsdzxN1xtqC{?EmeHMrPzhVurOWp+#1n5Et zaNQvQDp!7fhmM)fun}I+I0mDhJp5{)GYP=+Cg%Wu))sty<2-inRm0mZ&GPPO#%du3 zql$z80QAiP08}=y>yY^(`1;skzKtIS3gN_Wyt+x|W#R5;O0HwpzsqF!Rc%qSPA+U( zIaDr@{vFZd9 zt=4yNQ901)p00J-g=8CZiXw;)L*IqM%dcJmI=3aY&{v#f7uA;4Sxi3kEU#TrT}bne zcw=gv9Ju59X(@F`Q9%s=_VHY#*P5h7yvXbE_N`P1ogyjyOAwtS2%Qhwrp7%OCR60e zD?>8teLO!(SC`IOGCwzwaEq&iTh_ey<_}Qn<%R6_tdqJWM zk+GbZt5CmN>%pkJ7vc2WV_be-NszHlm&di?xX`HPbOxQXXRGnPd-p2kB{?UI-{>Yi zzcqaO_usJ+fw=BKeBM8Ajb&88vxP>3;+K1ItPm@DL#DNixLkbvS*Izv2VzDk$6tDx z=ch5`D>4jN_oUgcB_nrrSa})DBt_V7G zt4!s;G0;>i&uqmc)50cO%`Ena{4ELll~OQK2awb{NTeA=BHYvXo`TyVp`=@x8K+|@ zA69U;!T=; zZNZMi3VsJ}7ijqJbOnUTn^T7#+T39==|TWj&~cRcZEm_-M%?9CO=T(ibLq+Kj4*mV zD^S!*gr>kM;+KtcyEW`TtwymHzh>%;Q+<`*K5xwZHgjguDn)7&_OaXgcpRP{{9V80 z^OoU#8uSk!zx;T=mi9ymsH9oh*29{5|4xZ3Do$gk(mVHUb&tt;gT{Q`rX zy4$=?SkL1O2JMT$%0u>qFM!YhsJ^5|dQy~duHBQ!b{{brO0z~hCw19!FoFjt8vwM6 zsY0Yh!a^eI{mkCH{HU2L7sX#_-VX#sj$@DbB0y4~yy{nQ6>3{~CQIvih|5v34+~sj z20EE=^&lXA$o~y;`5G4&0{OiVB()}3ldx7`QNcC~&RBe=L?|Uj3#Qi|{q2%Rxl(R-3pT6^6;?uQS*kI<*E=!`qH&|eXQf1 zM?caolrTz>*s&spJr$A1L@UQ+DTuK2JQpacf%Z{xIdVoK1b7qPo`+B+XL3MKV|=?* zbf9tY%??8BJ_1DVoUnK}M*k#8oDGW$BwUTL;dws|)3Clcd7H98Qud$z_ELgO=G|Gf zGO6-UW4BwAXf|2{ON_4Jz^lg7J0`-jgr2skq}ZK9O=g!~+E)4uUR=gtFl*{a0+I54 zYwwK!6EeIM|1u#np%Aa6m!JNIwC(x*9ef=*-_y;` zU%Xl&EkGvdNCdqqtcuey&xT{=;?FJXHH>r0{sAg)G+c(Gingz7!g6tK&MleD z-Ww?KIGNVo%*(TK9#TtxWf$j?FQoo`bIsqawjSp{zmjk&94pPOs%qLlU(};*Mkue? zIlA!dMc6bmi)6sDuzMru7#MyXQ5aO&N`2rbSSTAtBE1tK_6j_**=&FIuN|RcOWo!h z{MTM3Tq0b3FCmfEv}83L)d~%#F1$#r@`TQnQj1vr4(BDX()Wef`xQFsXw;R`(W>^j!gAx2FwHkCXf}z6~R8N_{~C3;)?UQ z?iSCy#jE@SD!TrmA7q_rv|{;A)NbF0FyiW;FWKXXprx7ZZ~DH`Q_1+g@KMMq_#U6o#T;i^MfC#993V8-<8xSV!MF(X= z;{D=kr1u6o=*W@D84CRj2A2s6ses5>W4f3EroZ2Kzj`)92t=JG08t?>#s)oWSG%H+ zqb^K!{pj4pT_saVfQ?)tPAgiz`K2{eUi3^7HNJn z{K+M{m}ww^a8aScB10c6Qfcq&x(-?4gL(dp)a|D23Vlx_>C01o7gzTx9?!6>4ysks zm60H`#HISi!SOKIx~|GML?VM?JMM=*OL6yga*0*0jdzChuHDm|JlJwOSX@F$Q?Zvo zaKKD!fv?AiNdIWK8X+4dQ?n;Hy0s3RGefgt9&xvq?$oz+JodWMWN|7eeA-UHjm%8m z?7gm%q2j+V(y5PpToH-`fcpswd(Lpnvxmk5SU+1!tk#)J8(8YNQ z5u3a&54XBB1{N)WmAB!)b~^|?&#+nYsktfRbintD$z$%&Q@{;+XMKODi6QsK_{#AE zrFG=pX_(%=M?-EBgtXmucvt0IB2Z|V(Ncv zW?iDx{`5THD|i1`!1Xg&#c&yOmxop%9~=2br%Woq%JK*HxgYpo??grAEo&Pu+q?KL z;Ak%Tc-KND<9Bvy%Uqa;;30+^%oU2x5DJo|D zE>ZF>qw>*OQJIzhmKOGKZX%Ey@uKn>WCNQ)QH0%YxESLC~;hewTUXww2h zKW!`*0$>$JAOwIqa36ga{w1!1P=Ddn&!xv{F9VGp<2Z36vEm*_QYt38mWsc@fUPJn zILM<^A*&aKmirg`M4pQ)ZOw?4r{J@aCQ>Z3d+VA^GYpSwiFM(fo=s(hHzNdWkqK%EzO$p$Nl2;}`l)rLh}R=QAP|nh>VOWw6psNG z5kJZd0OOb-QcAteJr!3b0K%TwzQkhWX|$rkA}bzha+TJv4kTQBu{}zQo_DxseYJX2 zBc#X{wtVe0CkGOUscA`RJa#iYD6RcUX@WNqBw7$xv{A-jF#5ku*2TXw6vB)d9`Cc} zPtElhsJZ3UpMM82f_JJTIQz2hK-IzJcePz~2R#gu1AdE0 z?zOcKY9)TvU?ndqxmG7>A2?wDiJ*JhQ#e=l z>e#DG#2-kq|T zDv4lh9l&f&x5R%L->pG7ZnATOb=gndIGwfKzLoYX_p5=^f^d!0EpcP+4A~t$e`(y6&`rNgG zynLb%Ab|6wr~V-*d7hh-ABZztp|#NA=cY}UJsA9B56kF)h(LVG)-P`b*ofza82)oH z<#5Hs3i*(r%tB=Yy}ak%tT0i-3m$~Y)Zf5O8{oT z`r!-SQo9a|VZ%u_DdI7vZp|vkqNw^q@sgcmMHg?pI;LcR2S6~?HKYnHKwPK{wN@7M zPiWm4tHC<$${@^qX-fgFlZHa;D}r_5C=CT)>8p5tc0{b&4xh%-%>jxMINFo25JkD6 z!{)RIJ^;%tZ8tptuzOBmaKTpw+z5P>1q+i4mFex-S%sl4`_?mMV3@eRgKJ%Y6%tv` zL;Pc|DxK4c>S+7JqwJF@#Z^);v$hQn#=YZo)xocf{Dx=G8m~*<^|3;L$aq|mpJ@@C zAMChH)vytOx)1==5lhe-<04w^uT5GMdY?Y7Qy55aAa@4gJFBMR0q_MV=LfWS{hc8T zib-9bum(L6M(ckeC!w7$KN)mFAPu1HNazX(@mqa1IsT(iT63=J0iN}$hmx-j=F(om z4Bq<+&yJoIl)ieX`pW^k+=v}fDG~&NLp5L_cvvU|<13$>4f&sDkUYU^S~x~69Tv`; z7`yDb@(6s1zl@bO*Zh9SaFQw$s$_%3 zVZ$r1SYw@DQC?Ij9PEv6cgA&N#1+*nv3T{?#^In!m-Q%{+rz%sy2BW`YAl>qTgQ1* zPluxff`hbyGDh7u{G>wORP>TliWjsizl*+ph%GfqBxGu%-7$1ECrt3ohtQBuhfe9% zQ6~qChyCpXM_gwWR5P`QFLxJE`n6?nG*oM~x)3l8^PW5&e079g_w{Q@{Hsy?B$&(c zyvfwZl5E?Fxs|0};oJv@SG#IJ9v(gaXnKoerPGd26Pll8gdh=ux!mjk0E8fa$l53B z%7Oik=jPj7OXh`Q!_n*|!nK-q%Bk18)9nk#A(sE}FjNIZcR+u-|6B7jbO8qE@M}NG zCIy=-vuP~7*Pig6&0_EJ2KpSv+PTUTjwJRO;O|!t0LcDXq_?3Us3bdnI7svD(Nw+k z0|{8gl1h2c^X2@&QxMw5oy?ny24jauls{lk7`0Z`s5kXrj}8Jg0D)dW#EVCb?*uAg zxBH*ZK1@=cT;v_nxRf4L#r}Gp$DI^xWw4>wkfx+~fo^czqqtKZ{^w@yXr4I-s6u4s zZ{L=!dDa+HQo(^E=_FbUp+B&Im7|J1F*lJPRu(coH5C*E!^?Be`$6!#N?U&&A0wIz zE6Eu+R}6<&5h1}9wHJT^wi(tr-0A3+k!T+4)?rzH?@hjHeAIw!x#S!yKxrhho3<6I= zF*8iS(~J5Ux^O-GOCn$qSM4^TYkoBX>OfjimryE#4w1$}%j}xKwxs z&?it>ohO>_4DricEUc6#lUEDFljNKGB1Gx{@IyVKhh#yG&y>ti`87R#Ki(d=(0qx=-%!Hm;A26D^s<+=6H@KzXjJ_$Ex&pJk!$g2F zemns}X*PSY95W5_cUu_Hv^^ICn2DKLt0waYr$|aiUNi2A+{C58---_y&@z+Fig(6g zwG@WR57-=@kc~`1^K~qBmHpoB5ev<;djd zBrMi`f}H`hz8uS)zv)~%tAB7YPYY<=q_M);I^97RC93*F$(PFAHkQ$5V~6&(^$`?F1z-G_JwC>7i z-y{P;!lY#)+l+{C0p0v`l0@1xmO=&K*VD81w{!)fV9@e9|AFq&?*Rwal8tal4w@>HcKWlz)Cc`|S8KZGI<)(XJ!Q$tV2h*A&9PS5_M6F;8 zLLIp@K!@2=7o+xG@4xz|%`Ul1#ed@N7j6IOnx0hGX{IQAbGJP11z-$V9}ETnwLVV# zMD+6Z4T1oQ&V@H7Cc%h2g+23jltZ1~-U1N$+jKx|705tAIw4%q46kKbh?9*bC=lqo&6p}`)=A^vr{2_GOg*VeWk zBs_b@Zx!zsl19IB&z=0JP7?pp`1?aHm3T9}zn5CJ#T4AjOk^u zF;W1$K5vmTbuc@mhpHTtv9^Jzg;6)!dV-&`b&{eO)kX$GOY@|{esne zuj&gKzipT&ULXSun+Wb6xsOr3=0INQV}+krPC<7P`#TfoQV=t4p!G)dsn(7N`?05u zzXE6N2VVK?FIKVLk9p-Vu&mPUA6-j0?*a!aY053xuAh#>s57xnGn~q8Kd%B1&Sx?J z6YI2kW$4~@ew7-JM`i*5?i$X3yIvF#rQAPK82(iY@sEuWJxTqeC2TetG*w=j;*;S= z3{9UUSe?11M*zKcb0h;pX8eGJn^&xd({X*DZg&(2#~jbo46-)PCSWnIr+g1QJ-s3= z*Lkp);J`V(404*)EE5wGGW+mfbR3+vMocenZqm+9lggwhq7Gg}aNhlmm0Zf))dUFA z=_NnQaqv6$tLcg7wYD33EfX@r)Vj{v%DN7G!J2tWC@Ydn3Y?rTqIM4p zdougxjt}s#j#AS@s^RK@`Hjo>IZH_68|C4_pq8N`EFuu;bOxAx6fSynJNk2)6dAlB z(f0-1Sd}C>5HT^RO}_eI-ZGL1?zm& zu~VPC!#x4GoA-zLHllUrB&ksmb$_q`n1H)J1)6*O#r|xL6>KdVVj%MR?ltgPiU7c8-Tzk+}=8|jWMRwfqeO~2EUz_#_9OU%SLx*VJ- z7%c7Q1inb5E`wa0gF))*2~>*?X5U80Ho*NnE_nCtzC3#_OA#ZwM`ZVx6sB`NJQiu( zGv${Q=;O^-_?ZvFzpXHsNiYw9HK&1}S$GBz5scs&AhHB(AwBy?M>Bs0diP~(LH+R+ z!StB2*lA(QGDdyy?w|*sa{k!B9CCAeo|Ov5_0La7e_q_*9~d+{a8mK}DsA}n=cRNyB?c9 zfbBj1yXN-Ok-8$s_S y~?uM4s)I9>cVHba_JKfGd#9D4J^97Z`bZ|^~_23D_+Pl#zi$06q}czz8S-y3*gDAd?k zqv;jrCPF9dKG_DYklJCVc&dr#{RKfNA)DMiujpUZcK}A+hs8#N&a&|+C9{`;a6ZU_o z&d==_E4tVsnWyaK*I0j9wCRwc+gtKVJvn(k+2+Q1S%*I_)Xi_r#PpfpZYUr(dOg_s zraaEJ_Ur}yJh|^e-D?5y%dzbP^?oBK1h(pmi3Pn$a)WV$rW^A7&8BBsWq%K3v`|`s+x~>nSS{(!iy+yFF*T&%e^^_YYxT zMxbveCZ3?^P{_CtbXw`4 z#;=BGDzYLzh$l&PM3-Bg47_9g+X~tKdAL^RlJd=% z!qPSE{`kQwW0GeWG)pxDsLXl!nZlT);lJMayJwnWEWdCz#u zi#H1VCN5bmLlK99Nk z+AcnSKj+l`HGN(yT~SP4`_M*Aw*&U&+Um)^yM8r0)t`8ETAxntT5~1*rr2I$GE$$A z+9&+9ciHGzDWrhF-p()Sej zZw`1(rCzK5>sDIu-!6%-uUDM0yksY1UORnYQ;CJ)`Hap#(W+}7A0H<@{xM3uJ7n?J zLhGb$*)tO#8*{0)dR*SM!5_m$)zKj%qBcwe>sN8QiQ{slWf5xW6MgyM&YqyZ=ZU|G z|KnOYC+vUHU;GEb_+QAYe^t5lI`+RLum01M{Lk|B|4m*!_^;$u^Csc{dvE?#;{W57 z{~P2L?mx@y|6%g#fT_{J{~hF2PRBs7vFEM3=X1WSlUFn-U>69+C_|Mb{xbW7?_{22l1G;~w?n zb)Y5+7A2O*bg)>7sDmqyv6e#zNpL$cX2yL20zx1p5~ZSHUdsXiMCzJqA_ju#F|!u$ zU_hUZc$~4=__PIwc!#al2mz5rMikR5MY!!SRaqTm)-kyd;8ABIDzZ>OWdfp4V^-1g*el56~)?#@DDz^#~z4w2`Azkd)kY zhuC|pd54%KK-WBtt#+aZEUBYWK;VIAF=1|eWtDXKG0>Z^k@ zgE0z)FhIL|Dj=2~_q)1~o@XCsBbk8N&lPkUz=#{02dDrR(s%6v=*JkeT?o*8 zDjSHhGTu1Q==3*viE(lOFoe!L-ZXW)1O-OoIc6BJem;PXKuh@u6;9d*1CH6cj}4*A z0KDV@!LMc*0b_8Sup-MU%1l=PK$e5up5i-x08j(n-2muyhy$GfT_S_m<1qA!mp!uQ z1eXq`vH76B$xH}dszeLG%0nU-28t|z9?x5UD>-*9q59=`fW)9r5O*R2aLfcu7y@8f zh{`rCkIMa8%jAK`W-K0I%Z5l$fpAR~YH7*rN5O1F)Rit+tVe3j5EjhGkoi11m2>FU zh#vV%nD*Ft-F*1oRv-WDty=pxM|fjC6xleCXI&3VEURA4d0^#tUNx>Bd-Ng}t1Cw) zHxH9L!Wb9~k;$pbZCV7>qeq(#-jnBrPpg9ZH)cRhi$PR@I04VvN}fE-RCBP=>b>jJ zhB^>J5{_juIZ`*Ljq)69mScazaJgu{)+2ZNo;WA1a(>N1kbbO~8+$h4R8mJURjWEi z#OnFI!4982+>rIMHGNnAY=nLS)Spd93E5}g_PuGlkfltD=s0bIHJtifY{=Hk!;{IG zYscgo&V%!+@^-EmwWj9G&FM_un(BduM~LjeSor2;S8}I+BxNXL6ATGZwFa!%9j*6fhGYS`|X*AuHvW@;8$aIap*td5!% zeNBCuV`hiX0C$h~22eyNnuju;ogi&@Ab3lFY0cRPDO8<0-4tYzMaJTjcSkSpC)0Z& zuq=CCb=xD30!h91;PT9xu>m1}fZvcje|A@}EWaZQ?&p|k5&J1~)&6Ar$b>BNxW08+ z+ONk|-|iL6T5Ui*0>~c~aD)PL8f{wpIc6kC^4?wvazeDsIqT{bz2@TKYXBb6<%Gqm zZj!*UuJ~-c9++s+Bu_elO7B`Tb-UFz%H@mfaL!-ahX+g3vM-O`Oo%n5vFTujQTYJ| zixV8Y%xoeRf&{33mlh&AyfyN|9Hsi%&VdDJ)-k0GWlyXfGjfcVx+YjP?~x_j$)fw} z;n_*NL@?`2+o_&YBaqybe}uF=&@=zp$XJ{Zd9IbtXr{S}l5KW3EXxW}9)KnhIRCeO zNr=Zy!1&fJniFb%3)8Bxg2SfOzWA_dKbvp8aAn_F13bn+V30!UlSWT;iWjwA+F(DU z70^>F1LVgmtDp4jt-$JODrS#}5f|Tmp!XVCmvv(l$>f{abUw!n`qlD4D_L~3Nn=D^ z_vq297hYkf=@|2UUiTihP-Y|Ko2+~oU79EsYmt?HWg4GNN0&kNi2UoQjx*0YyoGcO zQLA2aHWJ-88v)YK_(wTtNl^6GA3EHH?ao!fl=c#0Rpk!$ubUK<*+`HbmJzH~uDkIo zUaRuxwKg)GO;@PRD!r#iy?bh-$@T`UW>fO?jhBix5=MoIB&YWc`9! z+IIe3>k~oLxNlkb)m3KI9m1o^{9=h1g0hT%zxhoA4OGp25f&+C+Ev!&aDvKcuI1b6 zM*Kcn1_S26yp!VzU)-Yl^_g*3A#-dic$Bf)ITSZO3NayNv?D9?=#ye&UefvF>1A)iPR^!(=rw?{Ch0RT9Qr6Q*C*w!ivUM#%&b zNosT&=Sr=xi0DJewTz$ixGkrhXmJUFoW9mzWWp2UeBNJZe<*W$Hln%&8=f22%1FB3 z(Kskefjq&QDXPV+6E!_aPiQYRi;!nSQ(-mHLQ|EUtD4yn*7v815wV?4n+IQHX`1)p zqeM|PU@GkIAwj+@kQ^Hx2P$ErtW1r(({w6|?>AysuKX!y_1y1f+Eijm;7;^ z6j4!KP*pUW0c&nzQ~P*)03wM#?JnJ4wexj)?}|EdYOCN?JCN|MJ*x`=pKGVoM8bj%EWTexz<9#<+sc3Wu zm3=CXYHbAwe&wh;c-0@RiW}K4@km0Sy;P2o64Elit9OP01T^Dcjh-I8Xj+?fQ}lM* zs_l+~6Qy5rpNIQfGZ4NnU?6L@2dxB*Yw!M6(dbtHhRR+3fs&%U-+U59W_cZI$?vwY5^C^^ZkhBW1`4G z&V?cZCPt2Tz8H_DaqBl4sbB*>gpf zp>ZKnw!SHCbE{7qX>7OL!sw+r@I>IM!J!t=+LfgwpH^TL{1$GmPG7 zL&TrQBt&vX*6f8J^CfdxM`L_EYMNc? zC(LM;48?p3T3}|M?I?B!QC%j9m&Ak6(!k>2kZky!Bwz`M=;5`f#~raUxerHXFTClK zz?t2?uih+OOegw62wc%F91e5kU`R6Jg@MHAwvOE8#5F&G8<@~GWYx7G{*xhL&u@t& za7r$kU(>T@9}awtIToeP7j6w>i^{s=7(XFSXpP2O>Ezf?ySqvuwku)=%L>*?@JQ(W zKf@TJEV7o?qi&f)doCB8n>63ajb>pkM!3G$#^;l*x3g=A9!n z3w3bivstJe1OX=&06yVSa4@ZlO~b0W*->AZV2ot14x&F|L|uNL*|W z_zkPf56aHEr*E^n*KS&?h6R}YE3`$HDH*i4yg9U^i#J|ZX^#)wK}x|$?NOv}?^gt_ zG@EWr^xRJAU8-!Ksd5aa%OZ3|NV6u(p*JjVKDLMT# z|D||;X7HN2j8$63n(EfG$OfTgLV35bYB)xbVaL~2 zNM>-Kk+pw9(MH^_&g~Oj*G;FDTm@;%7{E{`!o(O#u9U{nvcZA(VoDY8pt;=y>lC3J z{Ib7XMr*d*hwx^2v(R;KvA4hfE`#g#H9wKht)ActI@UBs!(5+li^>Q6FI<;bRBTVA zcivVEQVbz2oHqo>28+ZsRUg=S;9*DfN|CETbc%RjO#6|l@sGQTp)Sh0kx_;4$_;=z z)5o54oJdoTr*j*?2Y{xcD{HFar|Wb<<|`SW=F-W;=khtny{YQmK$y7pAO(TA%xPnx zqIaZyQ{+-{T1sSdk*G8F)EYk|APYuRUE?sav&6XCts4-^q(L<}xKaisO84OqLYBG%EZQbN4MK z=w3t0#|N6(J%@Mtil<0eo?{NFrC8T30FK$#w?-N6qsH#Z;(-BIUoOh|%KGK4xabc< zRYSKcQ)pa~Cz!U+zM`>y zOC#cd&&UQ^kK_0iDnw%o>nCNmHfRQk0O28 zB)i|4aj75XO`xd0$>G@DWhp{{phW_1=k>SRj!X_)SGlqUoYxfS%JzT-7yy8*4X&wf z_q|U%AZDdO_(KL>T@?Z(Z>~!&)LsyU!i!)Lz3(Et3@Y)VYTNIXY+5P$FtdS3r4cf~!CRaDU08s{;WC3&Yx4BH*6DtX9VOq5mf%k);a z_|X{@jJ>pKXH=x&;1(Z!D5@}V`O?7KaGfEU1D&URtjfi&8KtHmLq3jo6Mx5mjW&cz82q9|H@!1ve7rDXL1~=I+nbsnnr%v)t=mISqnE! zjmXDkHkA>sJwCjDkYd*}m(}`nC(pBj31epWC_Gyj_LMBg92Tpa&3i?vdDnR4o$py1 zvKCg&11MO?t$@x;-N@!l#Z^_h2PG>pvp-_3GFuD3S(k1u#6YLbiAPNY&Mhz>;wa}t z;9nJ=a=~iZ;O4S}l#-XJe>meqjd)DDpq8(xjX>4KliCbqgq6*@@>x^D}FNZsmWKb zE679>MduWb>yBeE0w2q3C`@exC>W29Q_pF>`$0$810^y++)txcZYuejuPNNzb-z^r zz|-huAX#~>rPuKT@!TgX-gmv85PV4HvsDEg7TdK2=0P9}FQ}XMn2i)m7Wz=4(N{D? zyrfE6j%+784Wk7_0aWfQL1rr)#8cX+OEifChc?F%!^Rhj?bcK;D+slDz8fS61V|3Z zNRUAwA%;FM?*L{P-2)3k&LxrDZY%SRy)GXd%6r5YOY+x3_KN8$*%)T~ zpC)@A%pR$HF);5qns3+OX)8f`5qQADQ0{7CL~UDH<5v3UT@3Gq&Z_&`0skhMZ&e#{ zanY5ko{Gmv9`cJ0-7>hzg&#Na&OHxyBNn5b4i$wuhz-H*WHiu}8M3JDd+e)haQ}yN z)s0Pz1>!d8<{yNvfZ;$ht)qFk|A)KxjB09K`+oOc3o$4N0i|gu34)>&DT07RAP^7% z8%0_~K|w^yqDh-u2oOLBh=S5V1r;HPG-=sVB!~sff+#K0mLMer34xS(pTTUuXPeby#_GdO{{%JY*bpuFAq__bXR!%5FV60eXwiD=(aTZFNKF);@=~nZ?`5h zQRV_Bp{y|}YU}YXCdDVgT8V&@3R4(QJ&;LrRX?{F^8f?7I`E5mBE);#51V_ z4MWF1eW!?Iy)t&7H!MrXdFIxI*Ov5kfep~S+$cW&P30)WsCO(7&sE(Sma6xNsTeSC zZF^yt*QHH$Du2g#x_R*e3?N=0c-C~%9d3GPiAGP~?ge zGm%|~!p_-&&tkn_0W2TGUxK1T=oXbW3&cTPqILB1%0hVT$)Mk26yWfH088L@4jW!X z`(H7*)-G zV9NI%JmDxOXCa7ob^v_6YS}dUp9yVwRlIgmgIPX*=-co?cRAEBuwxQ0X_=VmWtIFXW!d9&fu45akeLr&681~%6m%{|cXF3_yb zTD0G()~9yjd;ZMuve&eH5&8V9mssFk19;?(ac-FT!Iyjc&vr>#w?wt+=ayd`H*U|$ za1+l>je#GZOJHj`Km2rDN@ZBI)GGwl{qOt@=)ab73a{@Z$~z$9fl$!wwN)`y+AuaU z>^tF^7z5>b(pglolH7|h074;aU3hZmz76JKhU0<4-_XxP)&Dw^D*ec`!*A^1xnZ6J zf;wb;GZz3Jf5_}n$@9_i#Mqd~lGI35~ z%=B7Nxd{=RoiBb;OD?~fbEfc6!1DJjlbt*FDyQ9Xw8<1r{`q0WBX2eCfb-(^Wi+M} z89|~l+fWC>?1Izko!~j~vO9XLWhk>sxK0J&u_>mmtqL9vG8klF%93!?jEsF#qDhtl zjabt+hoY2!c0_{Q{@}#B&2_7JQDA z1ET%qd|SAN=%d%1zhUWw2S$@2?sIRP2uuL%jGv1vxoY2Njgla(xz%>k+xy_@F+l+K z1*`>tuoS8RoVGKn``lXEV&!V%1jafXUV|LZnh7F-(?FIX*GH6yv))0QkB)^vGTgDf zNp{rXXK$btJL%@buF}t|#ZzX3V*z91I)tnUg#oB5rf^kO5Uo2g(Ihfr-;sD1Di7Y~ z2f?e}Sia?Sy-8iJWGIQUWel1GxfEzx*tyZs^e9@YQaPPU*sgB?0|%@FvfZYoNrFRN zfR-ou0dzjZw@8%ObyvFoC<+Ln4Pk;-Fmr>5JFkSdYhw0eg^eI6ec6<7FT%mV*ewHa z1PPpVIy$Rhds?}5E&h@kyht4bAzd*BJvf}7xf!+!K=I`PJ@}lVD4nb$v*E&Nm$2HC zVJ2aO$QBX_#uK)JL=L9ieD>!udah3QqnpFd_N*GcnuTu#)3_nKhkh@mEX%7B(t0v5 zqW=2qP+}LPVOJ#ys`T~Z#*?e$1UOX1@YJO8sG(L_lCFH)nDcU8nSqbY6CqOuCu1O% z4yl{lU~BP~hpa5tmY35`_#GWTL0e3>}j~4 zW_BQNtdM+8omdbxs-aZMyeZpSi+5c)^@PO-w>4lYOcmJMSFmkyYB3ibx1OyfipX0C zCss0&)s~b>N~@xT@tL#XcG9EqoVnH3fJtiX%=URnL%D+3ZhtB-QjQn(;N~L*)K#f2 zNe7uoj-dTJmjJk6WMy8NCQS!xh(SJQ%+IP(NKM-IC<1yk2~O)?_^7`Xy8EF@z((5G z+=RxybP%6PVEz~e9GEd+=}x6wu%bJjJbw?`9N7){5Lj4*Ur+`2{L20$S=jjz+M+Ee zqhWoV;nnHkWDsoxTt|c5$8TC)TxiT0ag8@^f35?ZHY~GdXHE^nySs;F4rmd)z{+sv z$<8(~6F~evldx|W=} z*WcNH6|rr!vBNq64wKOA3`kHFh5lI6Q5gU&ZKFC`XiU`MxzFH*Lr4VsvyZok;^fP~mj~Xe|hvPrl zAdiq@`Z^3-72oc@IE;0|O`<#V!3cAWJ_bfcnhFqA6n@H`a-~)QhTJ&tm!(!jQ<$xt%V?^ z0#>ow6c4nin<>XcAFGMlT%R{~f7+g>0s46qBF$x;9tPrwEKITDaSqax&+#vdpN;{f2wag%t+IA1Tij zS5?llTIu+JmmOWY=+)3QkHcB}hGVS&S6DW3WMbX`!$xj=hG^>1&noNaY9`_zubxSG z3qf33PQ&1uNw!@oa$+>9&7ykG5mvT^5bH>{{K~GBGN3#BZt$A6kk~DPMl+<35^>%~ zFi!>E_{|4J~n_BN%wc*L3|iiC9j~pvvG$chP=v?8QYjc__UiG{3g`QsB!IMi#R=y;YdNnX}j3oztcMXw>GcK_{+&$0(O|zm`)qkoN7P0ciaaJpDfG z7>!~olF?gWr$V>Rb-Au+{SBpz2rAUQLmZY8XfhhRd&>gupGd`D!yfHz&t?eAk}ew3 z9RZax8;(Y!r!OUmTIrtZ+BsaDR!6dABa9oq4yn$!RD?FGortoxXLeLpZ^__nZgd5D zFq|6iW{#GM5g>uRiIdoi*o)zreZA&y^~KfiR8=hZn|sZ=hHo}?g*%RB^kCm!xm51| z*r_o$OU!T1iNOb7sNN`wD~~{%e=WWyb;v>Vocfsp4F%P%%Jl;l^9Bbz0?;8z?#-@k zRbDR^n6kkX-w5pWyF&HFUR2G9D`rnMH%!*sH=iqv$ zbTB*J>iiQ3+))OD0hF8}Bl{1G4Q|#$m9FTjI*Y}C%_&pR5$v$sJL=U;t-C`+o1OmB z0JxOKA=MRmm53NF078mu#sasJ=z_N_86_fR(60pz?zjH8wkw{Mxj^88KEL_bFMJz%LwHOV0mMo|KfYAR?#hp;$4BAPA0_F zPC#d9F$h4&36ngYQf%0mLVRM+LMWv8&p4{etyiL!f0v}Z17N+;xuf#YUMT0K^{z$A z@WLXzj^*;9pQHFh4{8IwKvOw~Pj3x(9P`e5#{z&E|0wyc+UkqzdjIYgY1MqBwC;KQ zu6MqtE8qwI1-w^Y)P2lBR+eA}P?Ji-?g`1<1S%tAy7fj9LN|%ja0Kl}_yV|#?RRhm z{9pHP@fi(@m+x(%5N!wIg)ttp1~L{kO}k}<7u*7f=)=1X12B;Q9G9azHj2xUeOY`Y ztK&Y_e0{S@!q~61%mOIrwL>|QIL^t*dbX$>oQ*%bN z-y#G!9Dz3f{IMS!?%HI}hQHFR&Q{aGlp|*N2O!Ogld*^2hAQDbUGPp+d$}Bj5}q)# zh1!?x)VMl;inG4$*&5AK!V@$tc59&#x^AD$>a_|)Z4X9wsV`i5e(x&6pli<-O8SG{ zn@dE+jh{gJR<8LW3nHp)=-5hHwGDN=cUG+S_RVQ~*gh(j*~3j^dNL^Ap+3m2|6dkhXYo}LCZgn47f#L30Q^7oQ_ z@EXbBFTHxJow)iL;c>byul?m?UjQG~@;&j_9i!RsJBto4iXQqzYOc!>K+3B=s9`x& zP@D(*@V9We8UeZu1iIe z7iS|t?(S9Ql|b68=Li;&^#-+D1V5gD#?EY^_CE27!(k8Gr^zJy#>Hc2Xy<30ZP7Oe zFy+?|n4>@bGgJvr0PrgaLwR{y*~`rKyjdKXJpZ7w1Z|epQsW!Zw`P)H=d|)FFlUhJ zovz$BXG>d%k%Ad=(J&q-fmJ$kge>QoRk&{@G!zM8DqgcSZ!m+xOpwu(oT1Ts-a4=E zeiz_-(i(Gy!Zc_^B%<)(RN;<44SOQrNL!j^5lJ5fI0!TA93w}b-FM*Qz&z4w3x!zH znZ6_ftL;ZlH|GqgcdF9`KReOvOQ_J<2re1(RB+p1%ZjX6W^1E2Tmw3~doi!+7f;Ir24R$sflhQfF>{ zR-0BNBs8^MY~4P9-x*^&^CoX^UWnHlOym?v&4Fwn4DBnggP7#m3kPQ;y{I#^u$%S7{h^!P8OV3XUPC4wNQ&ix~qj3{UG)=b2Xo_5DnnAGB} zFCSuG55Yyy=5em<+bHQ?wp)8v3%qume2|oQc+J>f-FW?IIomAFLkVv^6d5Gua%blf z&URA$a?x##wOUz3bXv~KAVqEbMa)v%eI@Y|f1O2WkVs@qg?r~g?3&L(5&TRBZ61OT z;w-P(*sQvwcMb)2VjvB=PL@77CFW2lXt)&(IbZmGFeaNcB$4n(t=H zn*;mFwK^C|AcbvexOLtN#^W979*Ovn%S<3RSgD zcqPc9_T@0PtK-ep%{1bgu~enC`}h9AEgQc}Zqa%-3H$3TH#0Q51cT(Ijhnr#W%Pje3D3<9zstCMZIQ(<;~5`Pyr-$OWf71O(RBA-M`$sAuH zjdBRbVud?BM|JB2m)^fsA>xv+sE~({*U!}WZg26hs+X)J0jaewhrxVcV7u?i;Wd-M zS+qo)HBgdWGuFnVogX0tPX{&ySrVMDTOMJ^Z(h_!2-GF$ts_|s-tRPfRcJsYm`{{7$i zJl`9gQMXYFvj(xp^6_2t&Ew*lW&E!dpjw#@NLpAQJnaea^om zrCXAU9FT*$q@Q?8w3!Q@piV$>=pG+ngC>x)F35g@v>Ga9%Muf?U<8}P z=r3ZQ;@e|hOk;D_c6IFPxmSy~>Ukum-Ko>}ca9NAH?@>_W+leq|9*Q=VJ91PWz7UA zZ=s~@m-mgx^^|B!$*9Zq8a%Q~*6}}zZMEvL{psS3x6FQNTZy+?h$gczwPsmaAJ0J~ zsuG^CwSz#&84CB>-GjTWd>H4+VDzNDJ3cxaZj<>+ZVnT{V^@MT<3HXNCNw9YzZT>N z?c9(a|CyS@c(hj#AD?-$f7ct78+p7`Pm|D)^%#>8=kbEklE%7(x}M!E)Z&xh?P+tT z%}0@GKR>ZU-+y?7LWcXdkC9H!!RAs58q&ZN5aoc0&9oxkl_ka>T|kaG7u5ifPxU&5}?IO|ytUT8E&~C{R!~AcgKRLlBJVL@%9c z?Tp8?_P*1>_l?)rI0-(As&XU}DfMp<`jDNtsuEg0l=UGz-G z1bPvG&yE4KMJMu0Le7xK2S9q*wd0zV4tvT4L&a192Qw&VxEn|=+#l*X>ey!^=b4qA z+O}~~8^)yMKX3+0Kwwu|27P~n5)C+14WJINE^)XDSXrWGV#X378cnc-5!`nnaaeXQnbymV#ni#lt{BAGZS#U+( zGpkxk5JCWwi(K$+Y&P^!1{K6h6VdVn*^Bq5_L`ePEKJSJ%jI|BFmmU^>sM^z6*YJJ zTF@=Z6(x~K*9TASG3963llarS7x{f0n){|8iz&>$fg6MV@av*2u(z2+p(ktYR zPwQK|EhBfU44UJ;{p+4uuF335+WSC7E$Z!%+S@FbrSgwz9BQV|h0Qjqvh&7A#Pp^i zDK%&K4A>-r>65{8p)Zy2c8Q1iGmKxIHob>-nhqiP8y5%FtB?l}OQp@ECxc1Ge}xcj zq`NKA*aNRmpUDoy)EGjiWeCi5G3L(|p~@f@%m7Tqlgv;hdstms8AAF8&W2;(!FXp1 zd@!W6J(IG9+QoxG@eiO3g4ZHvHC|HlJVw;|Z`q>m^jMa?VIQYp87+ zH}rd#R19t2I#~c^n=L($vwrY;6U;_XOdFzv6o&+zrg{_1-0u`OQpV_%AgcsHjx!-B zF>B4TNEQ2p_hi_}EmT}Wdsfz;c^8iOV@)NLaN$9y@PQH?WRGW{B&J-JnrRjyz(O$I zrJc2gZ9iRs@Ln^KrDk2gi}Aqyk*dDSZ&1=o7cL%4V6@}+FBa98X=6G|JuQhNDgU z6WZzxB0)Us?sc@e*8xo=TUn$B2W^Y`9EVFT-8olgzj{5nI6X=7D;k?;!3bZ$0OVV# z<=#S5qTp^qq(PF}4|i6@eZ5Op)CikwWW2(zJk6X_=2)fBe9IHuG_INMgP=yObL2Q;LdxsJw=2_Mm= z%3LM9)xwCc<=@JPez(E9&vtp9|* zimuA}|2x+IUw*Ii!QnpPek!^u65E9R|3LQtUboE{dZYpzfvqt8An_n z;Q>v|BlS{!(Xn>J8eBxMPuAN|)aOo~dAMegR*Q$%l*<ZvdL%-zQ=9JOcUIMB!De;BmaxHUGYkA*1XW``T808@T`2f0XrXS@i3?JDK?SGF83?) zi04emxrT(4=%D@I3j9Lvy)XHYDmyeaz2_r zHghbh^Zk^69Gs{gFgxJ9V%*gxubv(BR^+|RLvEDcue^^xqwEi=UYST8c=S@VR+Oaz1aqx|EjUY@cr46os6zmikDY+jXCUpGm$65)%Q7^Q6Dq4>?wg&lvu{A zU$atH{AWrpEc*`&Z9nnX9a1vb&$t6mZNbO(r>Myj$MVLkVA%VtK5GZY$mjKjUB%TW z;|ArQaTgvum0xq+yxsZM1#>fE+!PL;Exg@TmHtioW$<}+RW;=%v z&m*S4b1q#EvC|8@R-4?6A-W2ueff0l`vTx)3qwJP_uQ{$0!+W&gl zdCgcmJ=)`Lwr9Vp@9$T49Ju1(EI8#1@6!Fp^c{-(f7771r6Jp0;=gjy|EKKZf5k=r zz4(7_0Dp7Q$DDQlVY%Dt58dLTfq|#2M}-edZur0WuUxdv&aMCEYW}NG< z_5Z|08=cTo(XsUlxb7dWqNiu1r=nvS5dOzmzc8!dppf8Oez(F^j;ZKa1>Xz~yAa}Y z)o&Yqjtsc!hY$0)tsAWzrVFL$5g!jFMaa< z)`7bXq^+DIdd_$AzGWZvt^aW63{BlG=ib@qMlw9jv&{joq7||1!ks~)Kin0wWCPo?a^S5tpVs0#?LwfrU1(UeWvH69tfZCg!3F8 z80f;rm*sQZ7{WM+CEQqT213^r>NXn=sEojB=3*-yJS6~bC!9}U>;y1nqmiNNl>nFu zIg)+#Sf$7aIm3vU#u!cAry^DCCqC~eAzSm0~mh$&?Z@HX`%opui=Fu~JtQ?MMh zhsxzh04P2fBy8TA>=^zz+3Zb~Xognp0R^O>xDYiMJpI{&Jiq~NN2CDEzXgP&PbrHj z6i_`%WvzDeL7Om!;saK=6!0@Kg8y@sAY>NUNAVkB>cw>B1&AHV-BvggoVEwY0S1ic zw(&Lr01IFQEPC^xSYRqm04zBG7{DD+M5q9~uM%!TWI$yuG9WJ3R0D#`mE?XkWPqE{ z40v;I6flKH-cdjsAS{4SANPTF2=EuJ2;Tu%O;;{{qy@215Bq>Ha0UEoyla4^2=ENJ z6aXgh?8k%UV8EUMyg&w(xw_#i;{XBbk~X#zyM6cofXwOyFcth#D_w@#Z()}~wSZRC zHYtd8`ZI#M7(MfsbtxPvOIB}=w6f~K1EmXB;v?L>^Pj$0{IXvC;=-$%tLFeH&V080 zSztR1_9E|*Cc+pOj#aR65BT+MO2%pKNfUX8Ba4xjon)@M+Em=_V^q<%vYf!=zcjs< zJYPK8K(;5&5z=H%cBwv8o+@Zay$@Lc=5^DGtZlAVV% z_&QW)zLq;_Q+28=Wc^H({xb*Iyqq%kOipnJ-NCi$6@XJa-T!4tR1__KiM0)<@P$cp zm3jLNzzq+U5Wu*?xhKAUCi)706)8s4t4tZ>G9^L%$)ixWxOrt*0CynnRex*$*Tyyg zde_hpMevZd47iMK`#G3Q zh#w65%&Ceu2LReCcy?R|z{?v9Ui3`X)3P&%X}^vm<2w?|Dg1>uSE&|Eo-&gve3|Ic z2`BLx00^O9zXKL?O*Q_hGAyXiOg^D>ts5MTI-2NH_J_z|0Kyf+ z#C{JP71tEKROetQjHizADG69G3aB8xl{b2=$E;q0sE^ToE@*zehagan82xHWow8;% z^P@h3Ag!N8x{rJ+iTKJ=SWy{(6~KoitA0EP;Q5B*kx0>xMe9`#;=+8ohn%s|Xz z-iry~5S(;~3KFb;;|!ppw&kQ;p~2vvwGFDP3w+y_gpALC?A;zR>Fr~`2OG<#sqG#c zo7Z#t_GppCqEO|wlXRfky6q$Oq>#mLI9jB-k=FWWamu}50Pja%Pxtmn7PJJX>nzUe z-uGDHTcXkCo+c8|3Ii-N=>wmz03H=ho@{L4#ofM2<$s0vl2NsVtd0gy?eN0K0F8wJ zXyLlR0Pz19Fl+NJ@YhW;HK0Ot-mg6ylHrGR=Ze>+xL~=*IJLv{)Ib2@Z?Aq;GX=oQ zF;(TtteTb1cl+~;iTi6J!Rvz2m0<)4)B_fkML3EFu=c`eOyKuddjJSw0)F#iV{?0@GdGxfX0=y>9ngYsw8n@BPS^pw*6 zPLJPauRnS#m8UwUKV)p%CZUnnf<9P0S}D8GidxKTF)seCR30tMedb#{K)W@_$b0;k z&71QU28sccwNPebD#HO?EcHRkKz7UMK(OV+9DOh9cUZ(UPUIyLkz$%04^ zcigYW*%#h1Q**=XCm}hev51m>tHAea&0hw~hNF_+6AJ(ao75%32>n!-!u2Or;l6iz zOvNg0ebW#tnaZ#6ZnB;N;PpS@8RkzZUycaI;WS;Way+6XvzfsqtVO}#Q}D{jhk5*f zv|b(EarWG(L#k?;aAZGlqr7Iyy^@$rLf~xNce!SN7;=xSccR1+z%7UORbYK-Vuhcw zOU6IZ5Me;aO?*_iT~kT*;;#7&Hjmby6=qyv`rmnl%yZRIaS**zRpr*&xe2#|ritWD zm@2MavddQG)S!=OnrVjJhdwKgpsfaE$GF_OdKHooO*%^B=2@IyE7p|sezO+}05G*F zzr2^vci6R0edgxV)KA^IBu9ha>z)<92}#=FNI&Nj1MJ6pN8zblr70pBb5Y6pbqn3W zHGfa3RM%K#HQ=70R`mtY9d5Q{tau;I>}m1Y+54zr)UNFddnl@t@76LC`MhkXgQA5=pfQpw9kZHeaGXmAeg~@F27K&U}j~B zMhDc_D3rfLB=z28l*&Q4)SH=O4#z_r%17>`!r%Hc$*W!BQlvo=i3C3PS5fF-3YuG! z1ac6yvjO+|zzEJ}eW?>pj1kx72-~gVDNMfQ3F+Jmj>}MfG!-ZVu&gyM?_hw@>MHRf zD)KNW;Sq?<@N5Iu)fIZ8&3kr2YYsoXAOEmHoB!mDimB0dw6e(V~DQWSlk0eFZ zi@8F##BNFd*}$W2Qn&VxDhr|U#8XYo(GVYm(057Gx0H1a)j2Xq60#GGu-7J*yi6@I z!ifazL@r8_f1=N0Syb%)x8Go$38p9_c&u?Spj?^nV6Y_-T((V-EL16Bln49{ckS`O z;0HX_qAD#cR@?_7OV*caQZ(;8u9%bDik3y_o6Y1sBSsCYjIm^1)FnCW)Uqa)bkwUX z_Dcu14o1bi(NEQpAq!=q z$acYwat{7R;U{_OLY+klL3uccKc3rAy1lz72=LPYiJn7M6nl_oDE#C_FoXb!0K@=b z$Gv{!fwxt$#Osn?OjGP1{PSdjDrhcxNarnxC}9}WP)n*%E4KEK~oe?F=qA+rD1F-Vwtz?mbt}LS|(x&)D zfPJJw47V2B0l9aBA0yR?Y2e03uD2;@uWAQL3MA{(M+c< z@y}v{h*lvMEb^hE*r^w*BZ5M)v24TK^n!$pWK8_YTq4ZRGXYOOPP~Xr4%bwAw^w!Y z`=ba-Y;^nx0PO9|+Hy^V@&mMi!e&dCT;*qpFQPBqQR|*iW#r09U4PPoc8gkyw$;c(<=wV)^N4%u;NNU&q_h8_!>eZxZsA zIbfB!#$%{z-b9-U^2)Wg zqnMjim6)MF*;=qZR3M%`kHh&D z?Z&0LO40Mof0oEWOfVwJh5MWwM5R`UM9iJ!A)|mjEo=&-f(23=U;m-XS{8j|Y>|lE z8tjUq^@a0Sg#a)%mal+Oe*?5bT70%8LjT|SDVMs!3or97Z^Ce=&`J0HEs!FWK5z(? z{b5l(>Ei664KUT*J&R(2t&9e(J;k-e+u7$u#F4v~)};cLE28oiKn}icIw`ImTL=$k z#JA=dpD9W8uQ4>$JmR?SAV|jsgPCAS5Chc&wOL{=UH!yX=o7JclGc_{c_$yo0gP0C z<>SD9}OFXZ}!GyEkj^H7OJ|Ag&(RnC7Zi0>`Yt3?$`U? zF<;o=^|>{&ICYQ(_;2_bSCp4DBOQtuf=9B&RXoSWrz}YT)(l!R7rC-YPV@?qYyM+m zM9V+2EVEdZ^MUhj@v-og_}BOL5APJ<@Q-$RUs$Ltu2N@RBeDp5It1bcUa=PW#^hF& z6y$EdfBPFZIPk>29g5+FGB%BtUkDPG)vSp4smB#24Z|*OTk^b^F~DO9urS}7?#5IX zN6K_N+L&DV>Lk`~k?&;H+)RjJed8z_P@q&@EA18^y!1AGX` zH^5kw-KabD=)mFmzIR^T&+mnaSbe*NQz}qjkxH4mF0z5ETHG*;V+Lk-wIrIBixU&4 z^j6DMk}T0^dG$>5$ZL0P6d_mj^-``Y3-EqT7T2~625b;*h__v`Gg2{1y`}ytT~(dQ zt`dN=@yC^!EMX7MB5`IwX^=J%&6S*+tYd-LSMi1x<;b;L{#T}2q0FQSoe+o*0?OVZ zc&h};S7@aDKvx z%I9lNu1ty{R?8KeQ;DvF;YVL=S0cXbb58_m%grov2K5FlX?DAQut_-+X-p zwO72%tuBdk$@n9J41gj&erlyLxV+G>BFqsBj zVaMi+j@xixvI&Cl(6ATghS3T==zJ0=myj3jgFRTVQrW4>Q3*oOI*2gHma^KyC9r~JI z?umvR6Yg?gSnWq&-@@*On?9Xu54xrB;2MNbRK3jvpqVfTe!xbP&v3+9+ksQ4>wXmn zu76KDTk5c+5CH~_j$)a7pV)?RobSip-G>X@58GC=2)S_&=ct=t>k9TSZcqYt@3W89dc5BA5S+&*wwG{i?LPkZ_JNXpMX2LCOv8#{48Qf__fv03Zc0xRWTB6jIpVjN`sD=&{YByP`Pt)_>WFL*6h!PEz`Y=%Hp0zsN9 z*y;7MS?_b^?;_$FvKge4A&VK8w?df!)@(|0YQWgy!zL~`7r@JXun|-~ z)I{zz2}i1qYOC}Q?eu*dyU9Pr^A29t$r$yy{1%bUA^v1dE_0a!|1SKbL;oriK1qh0 ztXP(`%Hv>qLng?rlakZ%MTYDv-_ht%+sOkoMxUG)l=ifb`V5TkpSqo~G@iQbn}Wv3 z4od=_BopqXJB}EhNk8G-41VrU_$nOrS7>sR@6Td>%L9(%pMU|h4?l7 z*8I7~bQ7>q9zMs7>A*+KGqqFe8H5u3AoIj`&DP#kn&{hG6|`Oxmk9q$jTA7GOiI&BYUsz&DR(2#SG{Uu`EzKS8z`K zM@)UFfnq>!^6Yfl82tF%k)->t^|J#OC>W)(0W4*5r(?O1&)IlZEFauEP3pc1mM6Zayl z^!D|?8Gm4X+r?e%wq%egZsq-fI-S0wMPznNd>e;CSn#Q=Io{=aRiI~8=7S)6 zE*&p`!lr5K00+BcqGJ5oIlD4Ob4PqIVM*^tb3=mm8V-#< zwvqLQL2v5pfSUnd7~NToD(^ayVV3+ZNn`IXgksp_sfYT?FjmO?Mjbn$rzArB7yS(R z0NMW%P$@olA(15YW#*GqH?9v z&T0S%0&=WWnN1RjRNl4eV6YB5>KUyvc%Y6N2rl-w-{`zSlS;*Wxlwd8w=O2KUK}Gz z1?>NWyf=@B>iz%!-|vzLF;QgSqRrYU*~YH2R<^QC6BWtU%g#72OAN}ALP{u6Sq2di z^Rk7s$i#@4Y-J1v&6qLcoa=k@d4Jx&&*$^~zJIsR_xt_x_q+Z)bFOop+0J$5n)~B< zcdPT*RePmRSZfO99KWG|^WbuE4astbPJQH=j-dyjuBTOJzcv4DZ~Rzs;7LR=EBLE6 z9mJlTGR_(cMSTf7Wo1`CM-6R<-?gnWIrYL#_i?YEXI$2R7c(8h5wvlG~*=(f+$ zqMP}CsrmhC^%TIwu-nEUP@5dgdW;>T%if6O;LZy`fG6vP@M_JC*|o*rk|G0>rTr{z z0I`mzB8L_(@2H6HZOuNuKP1^Q@_G__cxSZ1@ho4wWptX*2cz!zGb2meOTCqDIhcrO zn=8vxw=9X4R!k{R>!)Dzwc!4{`5$s}#LNaRoh^^>J>!`m_DHtz4(hvi#18SNYoXVR z^u`YPI%yLMe%PLIK^KvLu6gGpk^{R+tQ;Wu@bBen+&Mx=EfvAn9A z(5+wF@L}CLU9crq3bY_;5)Ikyx6tHv2Mr-y37(eI{j4O7Dn6EI`7S2kSiQ`$52N-C(}! z{JR7%52%!XQk5=mTC->q&+>-ZfD9^rf~SA9Fo><=&SVR|gVnYcITU`ULsCNJkGyG$ zNlYpm>a&7g7}h8F004z$FgQYG*Y&WO()?o6 zDlRwgX%kFw-RN(-O#ChloZLHVxK}|2c*_8w4}8Y`y9B#!c$NY7ZkDM7VKYl^Sb!+N zuScX|R-;+z>}b`qG1HF%CD#(mAF9Y6Qm=#_OODZ58@SCAyAd-*4}}IPvt;3+C1=It z+%$eM-1#>;6Z|R7$_5an^m}G&o(=d|QEMe?%b@t#yp9lvk1>|nB^K%5*ISZQ{BYB4 zQH!mC0Wg11!=4l)ec#7Y9_A`L?Ub&+E;3NxO$1RSKn9rz+UR0Lp&xp1EzfestYS@P z{*hUJ&Ew)AE`1}CJ|6MOv#DNC^t!nHWn~q$;iIX0L=5S)76=dl41Eb&oamvlcxK7E z6M@Nu`9V*V;19C><56E4y_8wZpwE@@yn|V|Zap9pBxNObhyPl#_T!hICA@l}YN!dY z*uas#-V*W1!ovPI#o4PgPWd(#04#63E$X%5aBXMEm4;-ZsHRcfd%2mOEd}gG#&0TM znI)@ed>DV7OB0$EK0pM(g%%Uv!+1SxXnukOGr~z=+>tQ@;0jb8&3rj`wbrkxNfUsF ztrer|Z_#A){e_8Bco3*Af>4*}Fsp&tiIN5!9Onc=x+;=&`7L^oa7R1~9zbnXkfQsA zw7@IW)wtM(5n*){paKMut`HGr1fm}r7kljgkyURoQF1BSve7jdCQ8dK=Jq5jt1QJC zj)(Odmkbi7K}2E6Ac5LbMI(GuZzSBdv`i`c=Ka{%Vi)GOlEDOCi?L;N`+sRiB@X_l zM}7rdPw4pP-VgRrDF6^j05G=xf&Ulnrv*vjUu^zILwsMEL%apdR@I0rdRqtm@ccy% z&k^-I(hu;F#_GzT!i_fahI z{lbtWsCjHW_dDtt;8CbE6$Ai&s~#gz4KFy|n%=5;`tMCw#0LDja@}aLsX7>s;xsYj zeZ}HeKirf5k!hkX5uN?M9djt{r+Gkyysx~63v16e%`06;TizvKzG8JXq2$ zk%fG3Ok+FG_q|sLnSILB@>_fg()0WbU9)fMn3TPw>)KAM#xD!{Gq1?`nd_%*>we zu7)~b?M7K9;Z4r;$()%la%!qUy-2d9S+W6`9ldcYH(VfKbHHVnG6rb8?=g7t^91y5 zPGh()@nnR-Q&kd6GcgpsTTEvOGp*@+%(wT>lmv#6CUedIxLCko%}Z!;@v>X+4+8x_ zMqFmgWo476w_3AGZYQpZ!{>%;L2{H~7n zmbL6(0K8isvwwfZ{w2WskBKPcXR zblBSb-%))3IKcmm@m0Bf44OGE)-JPRD7ItQ_`EI(vb?b4=4hGm>?J9$jarZA+KHwz z%}%nuOZ)IS?Ka*e4A+aZPG$O^hC*c(v%9A@<9>e(iE5M1lImv`Z;)bSvos}(1!jC% z;YJH4u&%sdJ@>f${oBtsJR!x$r`UaqGkQi2blUAIL^!XaiM63VPf zGkCqS;|$UF?=g6fVx2$iGYFq9zY#5}_U!hK>-dW73z%blIGA%Zf)n`x*FElT_w`st zL4&Dq$b)!f&yo7|gP#>+->N#-26gp9$Lor`Dx7`m7{!m*BY7Xm$4&h%Dz%&RW^NAO zV4(Vo4X+%|s&3@B38Io;Zn7b{977|27SXTOf@L){o->VJ`#LP`A^_$&JHnbhCeBs0}~ z7jf;OXOHs-Pd#4_c0LJqky*T6+U2D~ns2WQ^^D+(u=B;0-fnNr#bWe*%(b`Wzc}3- z7IS-2c5KG6zwwPxQgQ6PW1R*wPb`a~J8z%^>#1s24*xz~)*-&DQ1Sc$=YYN!D&vFpb3FZqce0|;-gGGPCCmibKDwC_Ub`P|e$cEQm8u8Os zHZA1GYXId!k9P!6<8AIjvJ^TqG)~B(sC&xj?dcdsg1C(cRV=N{O^~H2iTSD zKlVJ1fAZKeBY9P`$S-(ad;ZFlYHaYGOYonQ7^f$t@RGg~>!4ob`9%4+X9NzeS3W~n zX7^51?ZfK|_ai+lY;mBX((D+m91=I=9gE^?#xl)MLc-g}X=2r&cg% z)T#c?O?2uB1>fH@q0+TJKIsp&lbSUH`QC&b`bsw5Yh~oBl1|gUKYg9h=xAZtwIh)= z>rPZp?2%)-o5afGE|u%q$Y`NRo*HYNIMe4lP5oyPy^b*_d!D3rqsO^c`e`pmsoy?F zEZ$zYaM9;nv3^yh6my^C9|<8lmVT&M?`|$n6XutGuc!Wo{D__YyTE6ioaHL?=#IJH zfxG(;wC&!R#rE5CN}}Pn$M2V&lp$zI?15oqMp9RK$~Lw8ZNEk&p8dT^!+hm6Qu{cn z^nU#I!*J4AP1VN;JyEY6G0={3i9f6EJ$i10(Z3q9`d6*#Yf-D5(0+xyFc+`Z7u!SN za6Nfg>#x7r`r5MoS7um8dn+KZb)oxD2=hNKlmB~HzklQ_{;QktKgpd`Z2t?yT>hUR z=0|4){)Ni&A2Y>2$NoQ{n2-PW6tlkG@&BNhk7=X-?~!}S41W3cL*r;9=h<;rTBJY)pMl;vbrzI$?{a3 zUiRq8?E`6VWU`I)zGv{?6h6uS; z4!=H**02A;3HbP~zDfxtYq@_(RmEIc_@%ncMSfM$?n5UOqi%#7R!JS&`z^#@<;h04 za&LzKAy+0t_nytZExYRZ_ji@Iq5fJ?5$?*4Qakx0d-nUFgGj3Eva{?>xjuKpr_p3_ z;d7|n%3I}!lvOR2)#{4=UWW2?$>*=97{l;oct{o^k?v0@7WOH1oGzWqs;d0%cPY|A_K$f$s3 ziJn&8|LM7|M)|AxmfQzNZm$Tmgi0x)iq@!nPNr#zT6dI=-jvGjjyx+jJH2%}gMBG%GK3}aDHv7@++Sz?k z*2o5hk}Z|Is+gRFzh8fxF#i@O^RRyvg_0BdaL=wU?b2*?zk~T&uCH$D_cVph>vyl; z`YkYey(pi6w&`0{I2CNT3)}ETE~l&DJ!-K<-^Ok==iBYUPuB68KXLhoFIbz+YQ)tI z66zZczgN;Huq{6w9GH?Y`W~zD<0*NrFWEIXRQ9r=PaJ92*Q}gTeY-Z{Y2^pWHm)jU zlx#vs9SXI|e@)3o*)rp@K7o*ujK4Q;8GG&K_vK`>cZH=WR459S+Q%79GRpm&w6&zz zL|`f_D<7;*>)1H6U7-U7$G(NG7>xRMJ(;Qf*b&HJ!fK%df4tEdxz#b4S;Wp+!=w@( zUHkF}3MHfXhY&sXT?Rl2r^r@6vv>e5a#(%yIw8w#)jNukl^7BDF7H0B~_tgkuZ*h1wh{6Oaf&KHHTe9*@|n^m(sYolA0kYWMB#6i*8k&=+AX8U|0XCyHw(m{l z@v!5+*&MomOMEMWxr6vNB8y85(C!QYFc{tlLF<(YfP+wI|0Y`4stS1b*PDHnblY{# zx3MCC++F>Qw-8zdJUVx7XY_zzhjs z<8&h0VM;LI9H_+u5CcF8pxAl{LF{%akA)|JC0sjcQv-n6UIf53`2cdv>AOpUu5Xkz zZvBwo&CCY?0vs$BEWCgKytR(d1{eqlP{9!3f+j2*fQ8>GPv%GQY>1PEkmmaoNtJ*{ z1r%EV1Hk3d0Zd{eQ~-#8Xm}_B0E7e&v0(5c9Zv^_24GemgBSw|000r0G$An(RXA3n zEKs_oVPiofgN|E00RjLKW_WEarC^_JB|bnU1Q0eH1p$}@7)@K+p1b}Kn~}H+fRhh&P?lnz1*_bYiz0Fg%x0ss_j0#FLSvt^HhJPU$FI} zzzHQAGybKXi)5P7eYY6yX;1-aP*-h7#_a>I50#j`X5Jf|P`w*_Q_Qf%@#WUn9t#5^ z$8d~mzmSpI;^Ht79$eXITLU=NT3HM%oRirWEkl708OJvTKC>NK%+w+*xtW1zv3=YC z1`lNQnYI%Hnual0xW6s~ln_*c1oLq|Fa&Sulo?y>uGpxqBCp*~nM*WNDAE z!i)B_yr35nCV;08!0(Z>JQ{nlJ)e_B-?WiwaA!1HdMWK}3QKFXwcHc+q8eeCMREY6 z4dRm5i`s$LF+FjZg7*)cq+xHk@>)~G23=4n00P+y3hb8QmtD3OVF+$Z$Mg7wF7~7x zDSJ%?4Xpug0jS|{8j|ngKz6`n1h_o&097_9u9s$UdFzd%RI)?M@b|bdzBbv?QsE`! zd$v=7(8gi0+BPe+gtDT)si@Em4~E8}13ay8FvPCDQOW@bi^Z-=mcV!j`cNr-DK;m1 zX_o)o~R zkc6}dze_#el6Z22JFVChyadX93AES z*f?_90vGPcu-6;nrYW*b%*5W>n2Yy)+W(_UI|*w!(Qo3Q8yYbbJRn#6F%V;a-rjZD zE=FCH#6fc0qETc$Mx|^ zuj;eO$CN#+5H`ke5TY%39(?`q!zB#0s}~^m&l0(d=UXt{y_WGfI zcz*_!MxPv`j`O ziV)cF-G9wp*@v_~d>*O~I&tWf)gR~h63KMuC6{B`mGEGoa<8x=*|9C=ih3mx+UzUK z3FVVgy(W1$$U!VxW`;5s^G%UPcF=6=0-K9U$@_D%|4ibO9*e1btx4vw@>mSOL%gAq zp+Gd{OT=UAWyK#{8hA2!PUWf6aDR_@s-{F#5_t(geZ6I)%33J`^7HByy*MCn0x7@3 zly|*p=9<(NEYC=#XqAE$Qh@T42kGJy=dDOPbPox%_qAi)W8v*knEmnr65FFf%oU( zV<#WB=}iIt)auJF6Pyz!Od?$$oZ9*zJv%G{>~(k0XeUo)rl1tS zhW4Uj%(W}!Ipvp@J5X1p{bN~<-tJ4<_GnfEWsFy0-H;)dvd3&NK+>$!pW_klX3M0G ztFD<9UKP>6tLLVw?+?w|xW9iJZoBx)!f#HdIZuucg_w5wVQ)^$bKUyZEuVoHLWrn_BM|cnGol4%lnNS3LRYT z@E5L48Qoc3+KKeShF~tUjU<4XdV0>5&vIHT)m2=ugxzf%dAVUz+GXIA3^8ui=lbpi zv1ngy$(%pbk6DVvR#Phi*kE_jS$q(Pc-Y2rq=Ow(+J%yCN1^z%ajWtC>&I#n6uEC& zI_SYopwQeR*cQ4vSw7LD9J1D@>ZJ!OGF0O5@y1PniugByWO*X;Zmh=`I&3T+6)n@O z-L^-@JDU-61H%;ogNnY#*x`0drfOnnS?}*IBUI#(eDh)qw??*oFqr!J$_ki#2!`SX zD(o>{Xi8OF%)00XX}yDUEliX&f1#SuLfpI=G^L*+o^mQfKszB>xpf_$`w77Ksw7MT z?e^c^FQK`UEg~TarNr+F%&AmB8$7;I7U9!A()sf;d-e1QiD9&q^R%)GfyiURBoK!w zA)jHTM**mMJ#`3?3T*Qhge3;qlt` zDdOfTglaM#50d~q3UvyUKz_2jS@VZAki)qiC zz^oa_9sBlS44v`r7^=DbIXdaSuivNg>IZvwT27~Ryhv{_qI5{d8xZE>N?3U9j zsSa$Sdd1cYg^#eOIUfZUWwaj7TZVY?mWM@Y@pKfbh4cvr0)JgYWIS&R4q}8=r!h+$ zq!TDcRzVZh@exqBHi^cWLd=y7)Jv0vp`R&%s)XzrEnK`lpB$I z>Q+1#%TS%9AL_s~BBU%*Ck$<3j(%<3xVm?0Cs6>sG^hXif|c(Vor$ouKAj8O$hI4r zVPgKt!UNtO^;PeMOP-t5!gqtu*H-UzD6q$HX20K9N%Ge={qRoQO+Y)zp#~|!YK)bT zVG6ivL-zZkJazx7fO6a$RoctpC!v;81C0uOHsuk!zUYkp!Z-{f9?SNt4Et#kpXj;l zMB&9xsuGHGrWNlBOlh@+kq)I_qDu$O+W-##>r%Oxe@#&@pgX+9Ov*lv%#09zq~^Mk z)_f_+tYU1vCL_(_Zlq+^_X#?V3>=q>?J-o!Ei!!(1Cw}9EmTJf?`nQ?I;QhP%S${` zQ+LTm^X)yKI#4qTMJ5GR^kvrfiF=>McV11tmKa+hVlWiG$|9z6wVGNX$EMZj<3|Yd zi;o2M-kS9s)D5jJf8^z#Oli6Puw7=ey%qxQ#$P&uyPD3dURH+DJTiZBNh9dS2*cS z5pX@p$0yw{n`6Iy7g6Jb%7HTA#*hbABu+3QGptSJmVRhVNqs^ zG+{^mG4bVrcIORr=FW^kWb|be*6fx$VbnIB)U*U>2=Y+YA1&Wr2;$Hi-@<_&aZ}-G zwPe)FgLIX4fnvvY0lXTs z5w2XqYrjQLm9iqMIXLY?;e8g#mNqD{76BQ+9K`KD+=BJ^Xp53lZD_Z+ooAV71BjmT z9J3Q;kx#uyHKlMoiN?)?*=@bR!=j6qrO`q>yVJCN>X)RDiMF5i>u>N*Az#%7y$*Z)S zQQz(LoJ||jnC%oNIwa*n2jtGtdyyx(zKZ2OCY>UNx(9cbszY+S9HC8`c+TTXZ2QYJ zG8Zfdfm+kfP|;S#s1vXZg_GL)_CPg_PeP+*=;aD4*a-wvb}B03^!IQ9`I=*jr&9qU z^Ly3?+ab1I8x!A4G;8Ah%vcE?1j+Nz5BA(Iql9+i)5KrHgOO!`z4^8YOatmz@OmX; zzPrGrB|-rqp)vjXPk82aALC+|^}rbWkJQB?>zTFF+e>5{EZ+OqaAv z`Ng=YD}5Vy1_)*khC3_;8d}h~D1H!>i?+wm)F}3P1Z~sKEf|VcPKr@mA=?W~D?v=B zruBo51_$+;tLspm-ZrEXvJiY;koFRq{%~){^erjJC0uzWzZkq?ZDFw_#B=TRv&6S2 zaBxm3Daqy+MthTNyKRIxRU>U$R48&YHpb8xbhJ|twmjg%?35;+%LVU@k;voCGYI+k zonwCMU?P3sM|w=YUD0EqKN_S5loD89Ej`V+?A8yfYlMTU+uiNF)%{f zWH7j!wt9bi%Hr}=PwI54{Z+MyRUr|w?BguWJ+-YRvq)GLSWJrO*9s1pFJ0w3iL)=t z@V@mZ&Jt4{N8pOqdSW+lE?Rufmya;$0Pwhgf$UNZ=i7Wg)B}*(6%r7=aJ>+3axqQ1 zFfH1VmYR2W;1Ekdro7c`VQpe<@LXp1lP80?FG2l;lJ`5ysCKz$9=vFYAGJrrBLxmj z;XGZx2G7&F==~+kM~a;yn2J1a%fhb}m7ce7+tO3z{1Tqarlm}MX}pohK|db%Zyva5#l4EQGI^k!y9;rNqH zS{aySE3=^}$IGRv2GT!96TziUr5}<5$~Bg`!xhx|<~0WXO(mU=h-N2N)|Q)wD=f|!~Yt={C{cM0r%()GJ^ z=Io)p+qC_oLi0bSaul=i`wLER`5ssFT>s?u=$>^;^XtyiM7wilWBz60c1N%|Auqas zHhw4UMus+m@g^gkrMCi4e`Im1Y0rc7V8h@Q=grmaP=_7EdH)ir=hj3Z|M4S&I?iOV z0y948aADM!U6+XD`@qXzc)8t1z>k3QYlo* zfb-DYbNC)G%f6c|GFPUz;lPLyPQGGXE*_GWsqj^OeHe4JBa+r2x6kmvRR_cJjcaZ8 zHtVXG)BU=F6-4r&Zyh1bQ&;T#%(29sWE`6OfwDF*boD8@Z_?rFgVq}I9Xxuj*D<`@ z?17`coza*61T(bK0*&_5-%I@VqlnxccMx%gD|4LGC>jH`c^hD>`R7O8zf#{{(q=+b zQMk4+_rr9th%6*6a4srTXnDTr?(0)f3E7dIFGyQ?-Ao;G+dO{$1%9UNo0E2ufP78i z?%&2Yj|vj>#xC6p!QU{?*@;NqK*@qUD_4hWu1KLjT=nqF30LtYO{sG{xU6_B zs8~Q+m=j*%U>B)*^4CQzX~B7Of18f+)|GMilX}#pwK4ol>jyt$IktA$pD_b}FQW)cuASwR?l;p-5 zVY+I|?>wuH35i*$dj@xFws%zFsY9$|IMS4IFSBSe`tlH+>7be2=ASH??$DRID+uZ0 zL&+A`ABP7|)lE$Cv!*r1%DXf}aYABMzKoIMq-V&yGMk$+ggs_VqG>QcV;9EG12?}@Q+M~a^o(!e>t5y1!-xYz#IBN2q`1nm3Gv(e1^x~;1 zrBr*(UcY>y*tv>IQ6z1C%;LE~wG3xzBDP`387*Zm(6z6!lsCm60c~0rOx#Jot@8tfuY*C(kgMETE5?G zlEN*EHT4~N3e%EsN;!+?4|SmQk4=S>XMI|YD7lUH(*^FsN%SlF=XmQK$pV=K2DJ;v zS6r-VPtG~IZvwNzTxba!#y_JW2bBQ`m;9Br5|-lwn~3Qi7D&t7koo;NI+t#z`YwCD z>+;^ac~Vfan35>*skwkEZvD9-e9OM+6oyGARpF6*hOpE*UK4lM<_91$)I@*0WIv(= zyFFQEDy|f1=kFZ3da4}=D_VVed#89_)t&8>^y)o(UsFYjc%ajC!HdX?Gf<2tW(bT6 zs`G#|(h_|2fc)@GdJSph%#Op`%#f=$xm`p7)XlZ`GA=%;&uhPM_$&OiI)tkCU+7M`RyGyf{4OUs)Q=^-lqOVrHBZ@rebH8UHuB z+rFaV<4-F)?a$-N3(ffJgq2Kt)G1`BtUUw=aDjCHis+Pr>awRSq8C~^MSt)x1);BqHjz>0?y25{W_Ct}GKwS^)Uds(s=9|ugQec<^8siT&- zbn`qB#M1yN979Q6Zh6KKb&&Qi&y@|y6+FkP?`^D2wuY?^Bbxf0dDVRp4lpQdBRXaO z7<1{tN0yOVyq+z^u+La5_S7h)Uh}2g$4|4#tJKs=!Bf#^cOiy*c^>`ERL-?=Y!k(tR4XZaH4f=fi`~9mgF7ex2fo7;lMEAbt{ks zt+OfogQoQ^{0hyAgt_*K?IpS4me^wZIpM2WmYB`vulIseBx%f+_5K}Ntx!qs5-%*j zhCKiCN&EPh2>PDX1wk9(7ApEsD^FO_@(-%AJ#--rd@9Lluv8 zyOJ2glvJ4401d=-@FEyWg{DDjj5Comq76N`HzACvO_0)RALrW>R9=keO(>4OMjtek zkS{6|yDSF!YONLKHK@$|^OmsqBUN`GU{sdB%JOau@Gs8?C8M$KW|A6;!JJcdR8vA5 zrhT+wqD<`at$0D5b4#^_{&8o-o=6lyq^TpnyTP5vii+r-I~Y(#S(e7ilX5?9hf2(X z?SW`ZrHsU_ZFQ$waW83nUfLI56|mCsHXc zq9&Dd`i@5V3$+4!LV0`QdP_K`%E>rB*LxWK#6)5-*7n_V=u)nSqjRFLB(CG$aS^3c zA-3(vuwF`?l#VotLT@=5E5sC=K3=`eo_3UQqX76PD<^O*Qfc!#3*EsIRVRo6*kK+A zF%Xbp7C&164>oU0!aE+swG}9p+g!wY@shsVc&XIAoGwHir5isdwN=kV+&gbh%H}y0 zcoo78Mge29S3SdB7SgPYQF!n79%2A28yUI4r01p4sIEvg zK<g^Ay8*j@wSH^EiVFtI2-rO&S3(32Bi-s?lUDl5BZSFz&r%`92Q!G~`UgmLvsp zPhkcQYPaV`lDS|Zmq9!RW~OsQYQU!>wsYApIZ2lv(!+t;kAdN_kzx1aeuJri+T?K!K(F29Fw zbGxCPDqDjzuK3`Cj7g9Aot&?Q0*TTH+ecUL1tR7pSKSugvV_ znQOp-%o^DCCKV4sSSofR93}z!M#34vNps=)l#G|~`F87_0u~cghmn!W%F0!`C(m+; z3c(=H>4Fzkjtdy3Hta*udf1;uI>C!K8v=u%7qIF!)vG`RZ5} zA!E}O(4$YdUh~CtVI4LZc4FDeeRyL7<&3`P^1F&Hd+|e+9J5-&>70#;EbN+#BGVvX zVbZ~+&U2+?(3aC(D&^@ic+!)EG3FHlnu0 zP}*t6#<6tdU0PSB)?(3fj+g5awc<4XWnj6rNnzMHusn6kkC6SSll;qo$CBp^JIx5h=~V)%K#5mYTCK5 zc2b7~Z-$FQ7vlk>I1W=9NMiW|EH*QL-xx{(F+f)CI^qMGXeR3`Rwm24 zRmQifpq?zsdr=i})PP=;%j*$H0!vx}1Z`V+a}oBaqdaLtQ}@?2f%ap7u(}uU0E}ZC zr7;53bl(fbxirq12ht<^_Pda9*X;Ij%2Hrg*i&yU$S!tG*j)eRa3n&C@8I9_P!M`+ zozH_2D)u+p;_%!(v9SKXTz>M42QR3AsEgpG8Uu1$&R=`~OzX{t+Bg6dZpCmVbbWX? zrM*s4VlQbJ@;7i5g4Kb4@X_*Z@%d!>X;5>Yi!_p0YsZDM79c8+T*2+L@PIkFmnwXN zDV0-tj?ah_$l_n|rb8NIR$m?z`e&-FmJc?Nv7)E@o`(&F#*@IOUz-K+h5es{&YTn% zA*PR~q!N|>HnW;}N}Sm^dqK(=LM-2iMVYUV>emCNc4}3EtoLsZFm5hW0QcG-EiVBl z_8@+(BQsf1YVg6nP?zk=EZ94H?#%uD@1p%oV3RxA9IXLY)6l(T+0U+=wFmSsC zHcoY7Srjlrfi^vW2_g8$IC2TcpARt^v%)06W%H6YRqeUd--`yo16*|PaY0k2c!Vst zazc{=6i;EXcVLKeUj~e@ZCk-RghZzT$a8?rY@=>shh}@BI8Unstnr$0wnBja47X1{ zFkd$@S}^fo$lxn!;VijKe2PYxZo&2iuTs>s3U_1wDkFB%w%9J@iK%tESUi{{y>A>0 z2*_e6i4M^-sNgVigaNXE*E#nK+0u4XG%Uu~-XOmOK%z`zdHX0#I=>H!!+vuBOWcl5qZn~}Y< z|L>B6_!)C84G4lYjQx}m$h8SJE4FG-X~vjXzCPreCSyKq2j#*SOsi=1*y#% z*fmEkq>!yiTBXLfukmC38`A-W3PY2oZQ-j_zyK?x9OAq}9}g>ql>-zQfWAE{9CuzX z0DV$P2)P#k6&rG_?Os5oOrFzal=_CRPLuk`jIrr0z(M~31I=LngLjA>cz)Ojl`Xj z3_nczc+;G+N<*WvHZvq08~dc%^H6_Tt}?KUS^sKI)t#CoMU{IoeS=*52!@DQwF{i6 zCG~>7CsRAefC7MLJvYQf$J_yz`XNW^(}BS(g$?n?D2vpd#3-;~e*ljGbkJ9ux#GB3 zVcSE@ByGJphX<%?V&dhPIY0F+Omd5iq=3zIQHX<80JDzqn5}Z55ZH2t18=aI z<{P()Czv#A7dUp?fPZ_cfQTThwIM#dZZ`IM{XwP-%W`JY9p=DLn_kY1UNEdYzxXI@ zC{)n6{9WqAw8|KE=)%6uA8Da(_F9rOq=2=tXg$&&n%3KVKzi@Rg0 zd-XMc+ls#DP_pSAR$!b3E}~wuI7bJYGl&!F;Q$_(4SdwMnqZLgSI30Oq7qisAc_D! zJm=FmQQM68n)*DjLr02E8vU8j`XK6B!06lbC)4!@kz1dM%~|*6m)ylxC18mm%CA7a z!)HD!zjY?9`Ila1O`fUK_|wFq2~CSXaiyik^XAB5k1Uez3;q}M+YSA}03h!?5}=>f z>1A3+s;`=1H)eGt!MlrwmXA`52xhPEfmHzwH*mDvbLe~)PhlfSG0o<}-7&$I`WqH@h$TGw zpi=Y4L1&)YLcpHyf(jqEOzl<|DRbpDZ+{J#im{<|VY%i?BmhFqeXZe)hzNENt0*qrKG3JE^})A|Rs6A6`M*~QuTH@W;CJfkJZrHq zwBsjq$L8Zx_DqiNZ_<6mYx{``wRxw0>jatb|62H!{E?*n>AZDfH3eE;$ZveVIAr4a z2raEl+10T#(DZLGcGK*%gh_7k&1g4o^m~8n_nsDiK4c8>kjfW%r|g4n9d`33`DS7?>xF)NOj&y`t3~@r z3cI*7;q}E&?ABra(W1nIJNDTpJTE(bY0rLTE9Znc34zH+XR)Cxp<15}4;V^ZP5bjr zf;V$`;&>A5=dv-~U7P&M3Ek~e9$hkx|8n8|u}iPkn-VX0Y)iFud1w;GdGfLJ&8n^2 z88seFXj#nSp4*R-NYk+N(POOt!P|RAHPx+szx%#LIzm7}dI$(MI!Fftp^1Rfdqhw` zM2Zxtxq$!?l&YWzQbbT%KtYg}O#lN{Btj5{2n01o2th(gn`gN9e$IK`XY4cfdB=Fi znV;6mT64@RD;d{XAJ*^xYnjff*czRDVD$%K|LeTrEAI@3t+kU#q|C_t#QHkdXeD?3%wv+-W1HYV^#>gb-ERJ2spx(^4P&U9anoKO*K; z_pQfP^f{ef0~L4@QZ!juA~Torw{jJe9MkMZ=33sQr`O-N`lB(%2VE_mJc{cQ7a4gg z^nSYbnuxA|%%Ey7j6Nhb<~8~lT`JQ!Gj+UEaa9HtPIliX@wD+IM7Hk&^^x;^g!8S& zOTS{Tor>b%X!oi6l`*h!%1)Ei&_7vKtpPLFS z&rbNfX!Pd+{1WvYMq@zp7m4->uz6da%;lR zD$`SY2nXkX_GP}(`Y`x$aFA(pi4*o`+e>k%>gSVgg5IYb@5F!W{nTc27W_~_KPK9E z%Ce`r#!tg-)dh3_p5Rsg?C8Ul;P-lqWg6I@SDnzGB{N?p(6vKKE`5C5GwKe#blV^~ zUUw+rc;Wo@M%teCu30hlpv28Ryf|V=S4G^e_C96(|`A9(K;mk~5K!?Kq~R(5oa&i5ZRw zD3pc7ybVwp=zTZ>)fW{GI5GYuT-bL{R!6~&B1JcKlj7K6-53PI%gsozc&ylM<5)$g zp}igg2Gjfb)>q#o2JQOgb(Uv&82C`=Lt>9nk{^Yw4gTA5=51+N@`iZ`}BqJ9r*qaw>HX2wOCvpbu+6j@) zg(s;zqI}MF9x1@wK-USx5zHlYL(N`X-_N=0k_sDkNjfT?4B^3V1-It=@_P|-(F-t* zlarSv3SZS?em3kkiAm3SJN^bzX><=A2>E4EH8woDqa>TBk8t4=qJ)_5gTdUF4*3}# zg(RX82>Tkng9-!cUlnriOH8=f>?!V0t9rL=ehS8jxn+F4LZIX`;-CsdDd$!~uCVm# zskkdi8hmoyg$TXxcGl*ISh=>0X7}oG@@vyj`+it*?D)~g!if38_>+^E(zBv_f|XS< z0k$gq_F{k9i`5%{w(o>M4BkB1?JOJhf;zkx!~_fJOMFsA$3ir0Cv&Amn^fcS1QB|z znO{DR`P#mG(%W?S>PZ+H27{fm9XGIs2#gV}VVjyFqjm>ORxpL57dFatDj>gRyHu*a zE${Qc`-V>94bgtcs$-ys}&nem^ z@0GNbY(FZFCyUq~GiwOEKbmB^1XEj*A4MR1Yb7qg_s7^0`Cfh+FiGTo=kX&N2;(ZoWrXeej7P_MuKS{}^`;IQVe^Er z8h$-Tr!X@s=3B}7m9D_Eeh32?3}%eEp#sk`-r~d>hsNaMdoh@s7);)a6Aw4nWEBiB zbE=d?9dsmGQ*v%_5+71*OEEkFcMxo{zN&rjq8=j=rZZr_VWuU*cV{SHVJrA${0S@B zGieySn3%7Ume7W@?ZHnU{(cJufhg`0ArQ!UEuf`mTHb}3)p1+8IS%Xibme*t6sG_y_a{uVI zQs(^%ZVr(8200nZpLV&3yc#S%Sx+!tDGVOZE5pVAT zgTdfK+YkWxxgIW*eqpgx?EjIOYxpQ>otm{Vix&_S#1AHWvfgU_$_f z0|RjqePdvo+=c=V#vud|ESooZLmLcni^$By{Z=FZ=)YRwaq%wR>;($x^od7K>6e;I+z-n+i8E~z@PFgURvX8wQ!)1f^5rCE4 z7E~g$c_5hOvxD?U`O`S1cVly30p#>zLMI9!=fah_s9m>FBp4d9x0VMeWC8dVTC-q} zNVMnk2?mrlk(Lj()vd2^zfH@%b^LT*u{K0Jy&nLdf@r|o(geJ6dw4cr=ZuzWgRSRM zlfgLB=FAa8z-+Z)18+JYE#d-sY!r<{&n1D)`(*$G6yC_Dad`yHghK@mbvJUC((@Z> z1?}KR&(;qaI-sH!`r2`T2e^R1!vVFs@3`q1G5|*#RwHv!qbQJ&te6g37_c7z?BISw zv@|x7w}}JTB)|e>E{eqhfcq`NlSH2bfC&O=Es+4wmXYjq0Un*caY`d&=)MdR%(r2u zIYtBCOn_SB;Q%jd<53G>E|X9|n)Ung19}U^(+l^5q3lOv^LlN?!T1xm{U)Nj#~aMrUgidf z%D?%x^rhjPJbRQ>cm6vMY1ie8W9gG;>_np4RP1asSjZD^#W6yUv!hyu6Wh(VTH_Id&Wd<{@5J;IFUaM`{qR|>K^&8%(q=k=d`MSq zYoX8doq-QNR_Tdak&3!CkgK>=!R5_OlO3s>H4#;<3t0GS$Opu8H-nm#e#>~53z$)Pv}=d?qcVF4}@0QB>axjQL??$5f) zQV)1WQJ_A}T|*TU;_6m3B$fxJr)kvm(B7@nsGlj=eh+L>LZVy+Odvx=ew2vsgGAVShBL+m_6uS{&-?DN5o38Y9h%yf8OW z#6tPHeUg(PIveM<>TNb~yZr_OJk+Py#ha0Dk2xSN$8I-8ZqGNTABz7DIg5c>Go#y2 zz)JUaUsfSu2}OgOTnpjKZmvJ zF9jEjYOL6tErO+rIGByb1xDcyF({fk&F*9+r(D#+92$Dx`lFuyAzN@d)9>QRhd(b62B5@4 z*@w=z2eT7+)vdSdZ#>sZSG04`HYoFw)KE0osmr)ah}eOnW$PM+ZNfZVLibY$jY{|h zt_40^CmUgrD-o8pbj>Zc#xDHz#qdvRmf3Oiaq17|`&c%eIA}n0HaM;xt|v#^#$flm ztj|2^b$O*oY>FY;7OqVuN`xPTFO#^O_~sEUDWSP!i6d7!*tr$aFZ+SQ~7l;BbxQ81WmG4*mM)vjKNj&+Y^z$@_q)3ND zqxM@XMF4Dpc~rNkw$p^TtJos$y)j7V=O)mWm8RCS7XTMU!r?&s+-94(AsBkM1qzSRe@J}q4!aoaK#fI9>V|%ue&%3ndQ8O%Y zg<4wL-Rz&EgtmJ)S65g42(7!-hTYGIbFE2ro#KVsz0YKG@81>T7tw{7dv9(F z2bSI`{C-k{!H&XUt`c8`s|=KVFgFD;JrCIq0m*K52i!JQ*6S>)i8o^*N>40Lp%DHD zFyL@Hr?o^`OJc-o<6#{H)<=myuCl|RIIUK=sy53kb&AlroYK%ZElaeGzmr4?fMHn3 zfkN~tJ}u;-UTb9t|3JPeB_7rZ`$WKQ=L{6~mK~aa2_B<7Jza!uZJhDWK!-X(AV;1W zNj!O&Q>5B%Rnit3uU8{klIB=w;$}O4KT@^Py%R3LKuR9Lv?d=0V_?Hn-Hvhed2)K! z)M#W8@_0QZBJRLgy1l4fKRgX# zIO?lEnz&Pl+dXV&Bg2rJvG*-)8;IiB`*2SA@iM`=r_b*$bOwaX*h2Vo%UpPej5qN~ zdENE%^Ag(2w;?LUZ>wd*YBS517G!FP&T*|TWyN^aJiI7$G8KIgjuumYU78zi*Kob? z$iFleL5l>}rI?k!D1sukQ8@5?$9*2Ivqx|E3wfb}830wzqdp^TaQ{_|V zl&D(vE79;O==R5w5;@Vy@ZM19oNEfx<`!(E995x=m!AHJ6MZ}A)^3|cH$mFB%iKYetCvHYaDWYHh zHBJxOS>%@p7Vz~tmqn!zsJBN^wb^_`FT5x;4BzlkP~ZBng8J)hyeRZ_Ze>_XUr;r# zC!5Q++x zYk}MxD{-hY+@RWT0LrrvGeV!;$)2!TS&>OL_BvqbQl&2C^6N?G=@;QgwLYQe1eG_3 zELqI94AHnfeAZ+{ z`=So!zL@&BuCpK&c7=Qs^sH|)08Vk$EhPozvDQzI|L{(T#889nD%|JD_lVI*TjTey zU^`fH{Rb(Fj`K1R?zUrV!v;j_sRT;A)%H*u06l<=-8U8Ae{i~KavQf(;7Q#RZGXce z{hKhy2=&t>ef!+X^Z5|35r#l%k@lYg+dFINC~96GSAY#x!S+oMnn30jOxTf-(l26W z@E=Vu11FM|zrN?|^x!#ZKdq$*r9&<;P=vO*={83|ASI z%0{j8wyA3~i!;PQsU8_Qh2Y>jiA`qRE*xdN%ue(y>J?2a!-X{)=b<&xPH9xvx%2GIZ5-+CntTM7~b9s{3-TjnAPNB)*mte-(d^VX`>9s^>In$KH zBT^}H2~o|d6Gu0*d@x1M26D8PE$+1jp2w@HKoy9Bp$pODr~3Ws3dwYK(CtV}ckY3x z3{n$A{mb)eYLJ8vCf^!%Tm?ntm7$iSGKf1TSt7#4G*v8<`9b>yi8kpcbO^;_`2p3o z)M9pBKS>xYzze45cx9YOzUd${?aGVcqxP!J8YBm020N%L);GTD!m{9Vc~6y4BmbGx z&+~?0_}@8L7dFqNX{V$WZ#{ct3)muQvC{1}^a=7cY{?(GKew^ti??U)&2;*YAi3ws zgvbl{(Vuq2oU%iOss;XpUtO4(^tsx%KakkdnGP1A2|Ot`KAsxZ_@dp@8882)V1WUL z#UqV14RZmoyz!Y=x9gPE;Cl@_)znTW`l>T1@j7{32T#A3uTT-JtBv0tu#MYsHh@wm z&)vO)xHm3I;)1p&mH^jQMq)#kc4@mGaYD)rih5aVNt~WN-j7>)Rx?g>8MQFKmOWu} z<6d+A#gqAo1$ijNPhb!@i)=XGGB}NTS#sgRFwidJza6(x-B=d9M^N@oM-6HfY;#RP z<6~Bu&VUhVF%P@(<8&F$-?rbo-QI={dbn)5*jbJGE3AItb7E+BSzw`CeJKmhe32#Y zn%B|Z$>mKOaW@yi@`5gJPD6NT?y)I*t*B65d^dUe3w>w45!YDVl=#Tp3UEo|G&Ip= z6v_yYesNDwp2lj+GfFB1UCQJH^&j#mE*mvay0XFK7qqRLb&fx%9ylkC{rYOaC_~yF z(W51@Wacb#^L&^#uVxYKJh90dK-k;#d~)nRv5=i&Ke}K50O4}rn>iWUVQ)EpBE4$96A z^1-km*lBRFWd;Ku(HY)nkCYVY)utTrdjef4j6Lp9sr1>tDE}p?wCd;i-NOjo2!5gN z7v0+(UX&4@0hJKZLsi*3^ZxocBjk2J`dmnAhzRuqhg2*7c?z(3!?m7KV@b}}w z#GCPrVs1`cAetR+n8i|u4Iz>s+96GL7ltn zk9u$KF_1NZ5w1v0WHGlnsYGt-YRdMr%7}(8uhcwACUKusNk%&v8wj$B854vc$9-6ie8C+2+&TE>N z8t4!2^>1q|3)acDRFt|dc!W`H;EyZu?7{h?-hfZ^9U4+hYY>pzYKkL_HcTa})E#Sh zj-{w?WbrFkI?_{an(Gz@JwFH#glJ;KXB%)`1PQ(gF}aq{w(|gY$HJnGzunG4JHc^I z{NO1>6nS19B-RNe)-E(&MZKc`ROtL{xM>b=TdoKI(3=nq}4ZlMj>>(2P2*2iV zgNyO__y>slISAWEA&wuj)xg4lYpyZhoB_{M&BYP$!i=*JiQscHGt*HHKdsM8X^4?G zS%NXa`-njw_78Ls!F#@iB0mU30fErTBeAJRivZ%wF}#Q{E^iVnYU7`a^vRcJ;f1tW z;(^DoywB<3>P#k*YW4E(ul0 zDJ^r6S8UdT*EUQUiY?tcg?Oc7L2E3A^pHIQa`9xpKf@?kcc%%6YUu3=9Jt!myum+Y z?{jjjHghqgddd`$cfo%@&mQ4^CNoPE8r~DU$5MaMy=l3zdTsC(YP57NqB(HBVPSJu z<$KiyLcBu)vn;NN=>XkaFpQrxzvW3(Mu?4yBVeVfAv^g`g|$t3dXNWl-Tf#O6VUbO0^ki~h=Fz~5-QGnNlkA&kzq2Y2` zN}cVvE192o0r9Jm{hr$;lgmS5?U%Dbc3CVm{?y^B3uBknWty;`c9MuiainVf#6i@$U~vz`1o@iF$hAs})WOGq|>Hwz}G<}CWpS^1lBVL4;ul-tdkcG)Oh1+w6DtrL9sHj9duU-rV$SPL7U?r zNt#{$!Bc~x92=W;E?XSCB$ZIhn`@42dPJ$ot3NYfoGqBA^GK&MqVb;F75|JDG0c!$ zL}TT~m7{kk@v0fdm@YGn6$}g=iH2BaBwDYR1`S$yQ{pY-JW1*+{$q@yG*ov_4%P=% zGA*d{jAw={i@VKu`jn^51nYQjo}sVu;m~e>=g?X4bOYNvP@6y$#AVd5NGv#K!&pWk zsVHaFYF81}w_u6mZI~X5-pNw&m6SL$wU5QKw+=mik96B3P@VMx`aNdDRO~3@0Gm^Y zyY7K2?b`HP!KXqrQ}$#WW0F+s=X`cbZ+Kaiyce<8QtMO~TpofQ*E$A@8_#Rqw?BhG z1;I2Klz7I9>z8~5+0@c1pV0WBB%AT?2qc4cOmcY7s%7sswuH1(`g)zr2|iw!cU?N5 z5R2JRD_7x6c%~iCc@RFLTY_&|HDvk)7bHq-p%LcDUBy_WCco_LXU})AWa4Qw$?P45 zI_ojx>((?rk)WciT7RtUs$;MZd??cF>CtaX66Qfv;zLyf{HCnTg|`!9mimaO?{6p2 zLUQHzToU$|zf3e(FqLs^tW0@+#>|ROzW&PCYTW&|FV+fh?Kzu^h6RfzXY_SlzlzxQ zkD%o)J~wLFR<|JQI|c%3Yr5shkNZ?uT{SdGsIIjOrEXE+d+$J5x8)3x?v3Za20gjy z|KxPOBVOFJ2=FR-asmr8H7IVBRg}JNZN}CU)7FANV_54a9}wDfPR#_s^3+ycO^5j_ zBdEsC{8H~@US^&iGte|D?C${i^qogreW}9FBn%ukqAL{MaiiM|T@mEfcZ!lxdEME3 zfljYrC9OLj>=go-TnwY;6Q@Ufyw?9JIc`1AErpuIum{h|3 zOLWPH(6Ow+7%;^nQ?>7_1Bb%+B|J}Fh_8G5p`wL_a3uGJ&+B&@u2|vlq%UAtGc$BClrojfDrb9;hkA&O+^&Ke_BlLwc8t;{n0BU% zxxX6zdW9`LRAL;(#M|N;l(+UtIKHCdIVS|OeEU$`Y<`iYSIWdSX<7m60P1SRPB$4i zV)yJ?;th#9A=(Akt@j_N589SGu1%*W~ zDpaxQn=RO>d@S2*t12p;{{e58{^@ZD&V^%@A;gG=KynZI1e>{(2_`;n7P2#w-=BNz zlDMe)oIP~eHRbC<-Q=N7WwwHjwQ7{6cf-u8TTj12xMzAG_TJXReq3ON&KLr5COFGW z3SN85Yx=xo$D`_JT1P}6^J>oIV=|<674^yp^`1*vopjb5P_1t$Q%E}5hOp&7cuEvH z8KK@H3Z4G*Y)3Wgz*3tR5fgzfbB=O%G%y{jE;SX5R4o z)@@2$_7?KFZak1tJ+gN?u9@yMs+NRed9svCh(TUk)~mk#wb^O*FJ2NTMGjUnoi{v> zAxTJyh$e@hP8s&rq&Wu6xAELqsMI9^kh+604A5A19ktQz*%of!&o8`W^aahn_1+!`;V-Z@km2 z`A%jpjIw09EWd*R|r)6A*oO{!0k)CUP#A>8^{sE z!k`YOp_O8$V$NaXeJ5HV1L@37m+w`kVqrfh^Hg@@{_km>b0JMlkbcfWb$c8Z{hg@U(tUSob;8ERQ5a9d-S?lN&maP_Zp4Y z3+cF&RGy?O5NoJm{e)SyF{$>bw%&tYm-TP_zbVVa|O+VUL85`>a*!Dxq= z6=rC+l1}#A9NDqG<&?$TCBqcAF5C;IP!G!+I6p+;UBu28WAep^(FfsKLWcg%XZ%IP zMCf4!)I4OC9m+n3EdW>F9l16g5qO>`d?3}??X(BUpLn3}^d_!wt7lUlu0673P;Q*h zf6xY_pDQWUHXF2f__1-gcS{TPS=6(}pT5get%Y4Joo5ePwlzn3H*v?J4iy@YMQ5nP zPrE5LltJpm#Q207p4AMin`|yh*F|heo&_F;gg}(iVS*U+J4041z7StSfsL5*WNYPk1Qd=b2^c7GCX^P zD?|(>Ei)Qf#K~{^NI@;vMoQn;R&7@k)275*9jfJ=u_P&vQ)M z?-VrJc}bbcbAwG^ChK<>6?ZvL^GQ(q(Q+3|;l(vwZzoDjsJF^odg0A!?y%uA;rfdv zZCRqP3yTm0QB%?K)v%DuKciDL;-{nM4c<*`uK4bkwQbvqw6OB5k4~K-6;M0woQB31 zXh2>dG zebB$gT?A(Ef-(X;iL;Xpn@4gsjw?zPEVN5RpjZ8m@(UK|q-gyCrg3AMc|1uHUC3|V zY@G15pxcEtnS|PqzW4g|!i+pe!uIogbn9!dIJ!S#NnEJw^?~rRE|zuf z@o~S^B;4M{H6q8xk=m7GEzVX34xQvidG4`aW9)D>Fw}u}@|?W}k3V7+975NUC3hns zsi)o;@+394(egW&p=G~}a!E^qIBlz#5eeL^an|kuS63Mc-^!nPf>6TFA;0i0X%^mQ%p`q^d9yMRMMo zk7D9_`_J6BYNCHX#^g?Ve-qhufYMgnrbN{T`DWxeYGdwQ1Zl~xh6PFu@58%3XPf}K zrfKUU{7<2+Yuu8Vde~w04m@>=miS0>b2IOUX2x@RON0M>^mmISM^4Nwv=9Vx2Cw)C zjxO7;S+sVPrX}=AsN=)(S>>k7E2%funL>ake~JiinENqsJYnob-hy1$yvrrCZM;bz zzNckB+HMSG9$kK=vODck@+DPw||kOO8vQsrdcRcn{j1wS+9CXv->ZRzWk@iOW0Y{mHZC&C8`&~tA>rOedQti??=El5XbM~xb7 zZRS)rOzuu_Wket8#>=CXq|D?Z5oGQ*vG$GVhv(76LoF{;-oE(OptQDw>%xbPP)~S1 z$x>6gUgX>g{V)@p9{T89W~nj_n;vd}Pd6%Pq}|&74(C@}J9RXfuC>Tq&vrIyayxes z9j;n`WuAXgfKvdx+k5j$Z{Ck=j%=e+nYS!2to{g_CdiU0e#1STCQdK1#m~&57CGd@!#uX3ct4urQd_US1io$$8B8 z^ZuMP5QRIv5{nd-P!XwXU)t|0wU;4KnqQMpe}yvtDv4N2g#Vy%^#n9f=o_BoRn!QU zyc+H8IM~XiMNV&>{`?qyE8OZkBsT5ip2Tv&veInSmaNGuMGwO^_+CXZ)BJPKgeK+? z%UV-mN;K8FkWbN@?b9cKW7>OE1Y}+*%7!~d;~u6`86@w5wxsovI{G=@BQ-joEj{~O z7JTiLW8UuFS4uS*43C@cgu*U%mHirXW}+W)xp>g?kP29B}K*>cDxqanU^lhiKx8E&}BWzD}TzqVX7Fun51ijPHXTyo; z^SSV*+vsq?yjE(T0J=c&hoGfZqcNsv+TCe~x0q0tCwD2g@2PkcN^T8XLVUKpLNcU0}1On$5 z?jXWzvm(O{1trf{25%P-5^`a!s`X;-{vMl?9QWZ)A-{av$$AL|c$O)Z|A6+qCgMWj zXS;(OJwi}%ZI$8dp|PAnHC1X{V{~Jw4|ZDhsZuF&Zq?xN-rOC!V*IBu3s*JCJk(el zO;ke18%WEjZ0$937*eUm4?szndBR*RkuYPAh=9BoJb%z>zjm;>k2Pa4G+~>A#P1$J zsH#3Oc5AA*umN>5#ws-_z)Yb9ALb5+#^&~7evbm7^BWC8J3J<~M9Nt+T6cg$dj zYLuj1!!mI^+X~f|C2e)&F=tB2VIPue-8Jm(l8Q8y3cKwol*Mq3G;eU?bCQ4WP-g^3hh0{ zr8$1$^r%}=_iqpfOR(yUYcKgfF}Vgj<`0R8zF`tq zDjjSi7AMnDY?mRfCS&dyz!Z4`)gQ;Ob&eUf7S@jbpD|%2ijemg_DD@@EZtSM))XM3 zhbBp@GYrWq0<7Gr87XZ1kVMEgi(||X~IWNTXp(agYa7qQIAh^aYpMnLF1RvNpiK9xd=w*o+#)=We8_Ra@wn8GmA z&tSz370R@B*sPj_6Vq?8OVVRdt)leo;2~GnQ$zOeUS!>h5_S}?Q;?%!ZXO+<+b($z zk--awS`^!L+Fyjkp4XqS!e9#gw|Wa$yQjwKS$ny{`#P0(eeK5<^}bXUW_K~C^upx3^Xv`8H80T3)C?Or-iL6B3`gr^3lM5#vS4eAV)GY7*!B@#MFYL|BDINIh zI{Nw_e^gTfj|ZKEL+^SQ;18!2=3PH(D_F#^?hnYR^Qi)(jZ=8vvqf~M%9-PT<@8W| z_g;tOU3YHnCO}m#KtA7E9<4>L&ht49?RJ zed(wvv)+Mdv;J1U$f<(p>dLzc?vXr4Sq1&00n%pCC6l?qQ|U>gH&ymS{DfAG2(JDt zB`as{c45)x5=6GkX?U;4i=}x(@FtuhLZqM zTt&{zaM}iA9of9w8^`W0`P$+W&`*em-@bY{R0C#%EXyTaU;ylt#Xk{436n#1oHT7t z7GE!XJK{$*i70qT3`VuOyx#v%&NV%m8N3Z>+#K)9r+z%EqMXCh%zkdkC@k~6$m=hv z(+0GBXUn_@K-Z^3dTtNk@3rY&$)VJ6?8inmtpM!%w=5QzShrS^*$@`UGuNP-o3VC^ zXQjr!w+d6$SsKdp<%Q}5uI2i$Ei8rro^~Fll|7KXR(Jsv(7_T6rrMShkQ2*IyQSXJ z50+HBBbvAojg`FOh_WItTgalr<=3Icf9JIccI2u5ZT(ER#9Nl2T@gcaFPj9%PMlYR zC~FxUXwtS87BDPX=;QS@AQ)10RTsvL<=CUP4Kmk;R9lnw-A*0%a}rzXBVwI)7UtE4 zY+jj`#_>MIXX<3NpYo;wY3aF>i+dTsF=IXfNy9!H3q7b+0q85C+JWQo&1-X%JP;Zs zKD57Q-aN1ku)FW(aoo75AhvS<#`HVD%G#?qFn#Fjc(G^I!y^hDl(TtCu+c(|5cU!_ zFryr{wVhobGqsHzw3;YQqOsdESKV>Q@vp@5Ff)%KH#bJ$(y7UX16tbCNs~@=kKRbZ zqsyet7Un=3pGRIJYy7)G;_+395s%i#OR`(u?K7&q+1$%2Uu`khj?GhEhfKH$)^W~1 z|JdxqJN4eB7u}1!?ZM!pZa3PGFM*u`2FP0<0uye_;9DX~yi7G%dw0LHIH4$6I3Q&q zF(zltQD0YL=y*@}ci-wbQ^-Lml5xbvB59dKW`RS#C1EdEV(|db$9Mf-<;jc_4#(xG zo9IT5A`s9!_90G~BGvqh8PJ`|3MIP|ZLoCASI)M|gx0G6y7@rf(wuN~Fy^LorbYmw zD^e)N5RQQ@ea+i0yGZvCnDy8g`pDv~UU%ev_lxq#L~49z{~BO)W6QM(4-Tk<<_ z;JP7{3o(*%&X7;S)DoO{5@Df8FvNN1?}J$C_Df~qb|NxrOf3?R@%F0&@Z_+f#I>-j z{NCVnogTky-K~WW<}MWVDe_(^>V=>+=?t?Qg*OY42>-*9r>4kst$}>B2b-tLX91-~ z#6d-61hg~=Toi`)BdrFpib~8X8cR=%39U9XfGVyr+5z;hef24ocP^`cZ< z5pXJ*%on@TqGEOZ4CcN4{8xTKrG6^tUO29f+jgYHYxBUUKUP2m2WYK@_aKo|%SBuk zHXY0BXKeu_bK;`i39i;LFh6uBsD@B9n+nuVryak2l&6W3i^Sltw~2rf?=^9)DJ`=p zIKlYQHMGP%0tS$G4eVt2=+lW34Eiyl^Fy|0k`?uyg$RA z(~=b>0;+na8T^t204OEOY3{46WkAu4wYaZ!XwpvcTC-2=^2;S!6Jg^PpFB^nY5g2J z$f|YR*Br%ZH)H}5YbBy0G+`6Qd!=NasVj9zStj`ip$Oc5K|1u@75ihSi07932|Q^y zJfj7A#{Du*bfS=ym)|Xi<4l#b57j8)0H-qYz(7&yhXhU*M(5MgaVUdwKZKH|vQxz; zboH;CD(|;%>|f#+jvp$bACskYWS(Kj{OYxI)Nx(J;voLymqDFKGljG^XpKZ<5oLTq zCVSiGAC&i@$mn23O&|%|V8>Tse{!8{c<*(Y^Gr%wQN_ilrmM#h4(A)p>tseH zRF)2F+`i~qq?+y6n`~{E?|5U`vNu26;O$#>N5LvQB^+_B2;i_~C#zGD%QNr{t7^ii zRS8MrNvN=LnyjdCfIaUNNy&K+sO>)-R~Bhp1OS-@d_4n#PI;@gomUGRqtiH*T6f1j zUjwX(^Dt#eQ`H7}hFGlBlQ5puEgVT10Nh`-}2c;)CDy+!L3xm^#(6H-AM$kl7@ zV@bdT?^6)4rpqQUw>K-}Yv}1aDXG z?G%9x*L2An9~r9O6>^+!tw*amm;b||%p$*ip_OPY@GHvyq_r<(`5*eU5vk@S zD=;p%JN7eK5h*dUJpO&l9&xSc&fC@F2n6ExMTmI_oJ9`Lae_cdg?&E3+|c{B{ma4a zlkE!@VHa^bxHgKWqWAuBkbZ3dMF#_aWnqiHMQ^@tE_}84^SDHs4O)I0nW$t(+VZ&V z-kKg3TQZktw&!Gix}Zh*cl)P>5>ct)=EmiUj2yuHcCM0}{^c|3yMz~{ z9;BbQNTR8>bh4MZw24mbyN8apQM!>dPWaD~Kyf-g;qDLvnD4B~TUH~@%@9dB*hk6y`V%+c$c5ec zx`1e0S;)Zx%=JBP(71>!uQ(Fj!^x7 z>6W#ft)cq=NH%bTYCG#e_5X#`YrDHa_5Wp7)^`7W{=ZOrZTH_3{)zu&xN(! z-G8s}Pl>a(ySpP)&*XPtg4^#MYp9;dZ!rHKJ9<$4fARajouJx2uIDdZ2>EA`j#0s3 z7j%uGy1M@a{Qvj!1$6(VZ~mY80{`ub{d*boKPLX>TYu*Z=>D^EUEO~cEf)Cu=lXq6 zSNHc9{Jmvjp!5I43;g5!-=F?R7xX{o|4%r!%ll3KCmo3)fsK9j8hJORoHmLAd|qDh z53eYEf%1 z?JIBSW_Qv{M}}6y^484lTDXi)oeM_%_de?PHSQ^+{h-=UfA+!-Kg9Qqe*0SeZDh3s zYW{S+^slRb5n!5{Mgb1eVbs6MKXL2y5)qf?b?iH>XGtTSk4H11v{?yD&j+H2sWi8R zc_o6yul}>YETFbG3yzLFQqyx2e&v8aUlNRA_i=@)dJqi`h{&f~xfe(}?swB~irt_T ztUv91@$#(pvd6cZ$9^&Qs42J(bzyz1Qh#_fH^~3#4KbE#GyZIF)S+7JF(caFV z+_zG6CE02w!9roBK1S$l`o4$O`wVS5B~Xsyjvm?;XCRVS(_=F#X+6l9bH`orc*j7i z9fy$ol6#G&ZUPHu1ipqOc-AVZRqhY6RygA@;Qn1AT+avodT}Ano#Mcsm9jRix*DM; zpb)eF-nr$p!t488zFbx3UmC7+77`KJks0^*u_(^!Z0k5HDL)(yKgB$s7b+urLf6|b zYU=#CZ;$!^^q8H}l6v>;S$SjG=#>ZaCrsTPuD=v(j)Two22@dNKfisZ@13J4bVBt= zilnyP=%NEvK4(?us+^$j(N4w7xG(1(so8RFm`ccgc~&xK|1ML_ zO2aBEJj4pwdnwW%R@nIt5($4e&imNx&KS8fP-W z-||`6>wmw{)0$>39QttuZW!vZC~)>eqpXU1dCc9xc2MsC%NwXKk;59 z(gV!)H*c@)OKCYdsS!iSiMctmHhgE>DIv8?@}C>RKYQ}O(Ie}6>io_6f9jFz{u?cSuR{R*yMliA&i`sg{~LN_21Injhm;%AP*28WbLR{u7N>Kj&jFcn)qf zia=zVRgbFV9LqX~wh!KOOgR3c4F-d`sgra2VqBqnajK!PiGzNQR&Je3&TZc>&86xT zxyx&(L@BzV-fG|A8v2d4Sw<=Wnc{cH!xb`<%#}h-V&G+|GEO5H!~cuB_l|0!>lbjp z?-d~k2oaGk5Q+^c(o{+e1OXv{3Zl|P5Ghin2|_*~Koq4aAV^b+f)G%ew7dirP*fyB z5QIq4*APNzA&@Y$@8Uh@TlcKH&b{ZJweDYc{+l&r&+I+3XRkfa@AtHP>%tR03dnc; z(x?#k&iaVgcQik0KqNlUMj|Ep7l+bMeW1KZCL@tZpR`j{+Vm#vDKmoV)v<6O)+AG6PQ>beZ)n}M^U$gHENmJG?MW{ zp_@*(9{lveel8y%n2VL1x$TuTl!2NNdx$uLy{cO(G4y6hOAT>IK_!%y5VfnIQPSw| zA>{qtQJ1&E%8}3Kk3_xNqFKo;WOUzDEDkpBt!?tIel_r1xfsB73l!RtBn1 z^nAk?vKl_?>iSRC?{$OcTW?KnGzi@(pQK7Bu?51`M!SheIsW-hW^3e*Y50W|GY)_Wc%D{61^~~) zF9I$JylQssni@<>1ex$XQ~YWNxL0?h3`6^{+bL%G_hDr@sJjPHh1*K9E`++ zH`g*;vpx$L?k32J?MPvR8YB|Q+5}Mj>4(tB#$3YD4e;nFX)0>njtQ9rUsD2}8_pw{ z(fGc7bO5;k5+B6NX_Lss55@rKZ#u_@Xl#p1<25|;#{K%(?qQIh20U^`ym_FH6srxm zDPsUYOyC&}0G`BQ1CA{OlL5Yh3;-KA008FmdOcIV_Fv~h@j`sC?P==)*|nkXvk$bw z&0;bs>y z+$|Fg%E$n}r5jBHcrf1sAWAE+UGD((92n|_fJ*|ImMR_#I`Dwsyq$?}uHp=7kq&v% zZ_TxU4jvTm3BzOv?+KV>7Y-nA@4^B+fG34`asiDwu?XHfS(=TV2e zcd#YX0N}Z7Pu_?FcmjYRPq4Us@`NcGfI{J}NRYtmzz-%$GrK$SmEC~j37ElTu)eh* z<{wL52K-1a+jHBk4Y+^_AWu91tY5YwOc09)Yiz&+B+pgl<9OHxDwchsPVDx*qXZA0 zrun6YrfK*c-en&vC*B=_IyKaGpSG!Rw-g&WMr=AjGuJnYRm#nw_?h-q2bRyEPzK<^ z@JR997+xiu?_Rmp$iO#O^2qOMQx4I}9}JIFID=uH#X{IH{gwC@9*Wn7_mN3;4>kag z2iR;TiF4T*22fy(NB&>?(g4W2;`!mkQ+4wfuO27i?UVt~_%Y*Sf2Tv;YM`;UX|3e7 z+g_q1f?yr?)E}V}3)|cT*Mh2m4klzL;h7~ zy@6f8LRpfEnZ2IL>zPD?=&Y&o3>8yNT7Q3fa~&!2(Ew*WV$|Ghzed*kyg7{#3K9_0 zUmOYx{c`+?1sOa2#Ax81hYJQzb$|iX-sZsRr~sEi#~M?ZYI5BE&bu=T1`(wUW;v!x zt|^~H(~?>VyOQS9#NtPhe|s)xitrnAyPxEQQVt@Ns$b~LLa}fz({pT;PJ+P%;8{5X zuh99#81|d*2PwZ7GX%@@s{Zu~zzR$2%JQnB*H#{5PmVsz$Jsn@fp(Kz4-U8s- z0aFL~6F~>tX2(btll1XeKVw79xPgo{bS4=tUhk?ZY24rLFgoGH3W~!JBCn!Qs6*=Y zBzpCDRI8UbjlrlY6ca=oi%dcy<&CwT1sODbc}`4CDQ7*~9xNdEXTd|ao`Ta~Qsj^_ zKlNK`*-G0F@k%SjxA+g4l{1;|((|85rkm?-2KmVwk&oE5Sc(^FsRHuc*j{}nZHLOa z@w;}d63z9?0Kk_D|MH5aYRCy$zK*2gjFqZN*M5@czOA;G4Qnh^4xkqY(wycVTj-R~ zsT%5tW8cFZ?#9b&BV;fHIrf@7gHesED&4Bo`?7zjBt5D{rt3V;8?aotOu5@dFzUp3 z@{xOqYHnweRe$+hN50Gb(6s-I(gFWHtr=Z9$#x%Q4hMPx_<=um)ACpbWc~)81o3XyT|b@6R@?CZ&=zI0oC@&Ybta%}uOw0B`MGIy-&LhZ zGT^QnGs>u280Iu*KwJ=XZpJ3Z62uwRqy)Y=Pe>eoPVcHHt#opK_5eE>j zMMY6nlY)ngwu(EWlmN{0$IFG?IHv?je&V*${+c}-IpynzZ`RWGZ`MMW*DKtM14Ecr zU<2C8I0JIrx`IS_dpK~CCyx`xYkGH1Aan}M(M&ddeeE-^=4}V}}>v@r&mTQy3a7mpP?;*p=S;bl;kzsZJkqe=r>_Ki{$ z6BgWjdmBG=2osKqIH6F-ZOCk9ss!=bnbKPB=wT`4Np66IoWW}#^KXh>)wr0DI^DfuZhOE=*_w?#($iZgwptgA)Bdw=) z+=7PWMl;)d{i%H@vSD_X94LKxZ7ZwM7SO8%-BkMz4d1><)Lx z49i7`lX|0*1eLg-@6UY#)%n76CAl$d{DLWI0wS{=nxBLw&Xre8Df6jt&jkhoXckm`tAl)iwyw|N(w6X~gx>Gdu-NAG+jpsNB^y!;{a1qd zEWib{G=|WmP?sTx=U-J*x~1ge6V^%-EZQ&%YzbfI;Rr+ibu~*ArS8csFY*?(gU)xi z5122)op-gLkps#253g4RK~g9d_aH0A3)dVHGgfhYZbrsjl}IG50~;zHiW!=vGpZG} zrvd)};MwVq=qpwgiiuYOu!bh*MmMdo^eH5dO(}8y4-m%?64gjX=)9_uF+b7@(;#Ln zb*Tr@&?+R-3QKm3pOFiTt7=rR42?@-8H{!yP7g~lK{5h+@x{f8R^I-j#vY}3QBCtp zg)b?mBNa#FTY8vNWR%1xUYJK&4AaKV@%qskQ0Q!*8hfquz zwc5eqR@g21*=o9cb#>o-2`=@mo@_zv4GjsulcSuk7^YKdQS$G&Z1ji+)w6k|n=}Dv zX`Jt!{58HUws@cyJAJz&x5Zxf(Gd|L+JWN9G;MOL!vqH((HtwoBJo4k$m~JT8`b4} zZRX&O2i^o3$F|!tocUh5*k9sHA!Vn4(CRGgq~r}U8~Ef&u%`4Zn#vYufI~gsivrZl z$cqZy4Iux1SqN}gT7TZF6Tkn$xD8mF1_weW$;>Uj1P@-nxmpaQy&V0^N#22&Uik5J z=u*fhQF-!j2|cw;s3Gso@v;=%CyrB^Dh^uof^ds5t;BA!Lmh+$v#<`nxw`6k9lUuU zXa~N_eO^8y%SR7hW1;=43cU=@$Y2OEb}HbKgtR}Ovs&7k5DOx6 zIiX`+rLjOD=Ke$1IAO%;lHl?@SRQ03bE zGpVg%)P@3_bJK`1B1}|Fr4zsh6G%?JRylAbogEP98k%(vEsa zs@zW%QDVe-EMkm4mP^A!aD&gsx24|`RJSuYZzqoiUxM|(I^f#^%`cXjn(v#Gs1B2x z!KK3wG7tChBgVU%a8JDi9aR?lTIX zu{AFpGB>}O-Phmfv0JjpThJ)QjRD0q*hKkiuLDkBe^Rh;)I~s8JbDbj>6Te#^Qiog z;zvc#$@B0u+`#)uUOe+f^u6%D1!anuhz)sBYGBI#VD|L+G-fLJY!ajFrO$Oo8y^(F zme_wgFxuSu7Pxh{0$)5uOt8>F!#HkIaA@s!gh9jloxa7*p5$n@)gO_r9>e}~VK4xl z`rCSG2JHUj_=o0=2PcQdvk{}xlWAHr@?aImWN9Cz){#8S#>peFtoNh2`L3?_zs`9w z{P0t4yuBr}$-wxiR~kRVXzu6h84D<#<9yeb+@GvPPNT2z$#5v1YyCSVjXk?jlcYszt&WQ|+gdf~K=5;`m9qlhQEM#IkoMIXh36`&l@HrK!IJ1JHDV z{SMkhgfz0aTLZ8wnkvyd% zLOG(!UV?YJ1Pc=i19>aKC;>4_45o~-yGXdqOE5Q})`5n*a^F9K$^;`mrSu$Wjn4wI zNBez}4-5JpT6*@_0C!e}`NX2h{$MUCx3hTJVt9YWr}x&%)V#HkKmp9m9gC_~YjoV% zS~gg@;+u@P^R^cugQ?1`;s#aSxlEGzeJ)sj4Xt8a$p_f!*B}{n2i zOKRcjU7@o}q;E_#RQ>E4o5>pTM}-BqJwF)hRsAnzwt@8CQVG*B zlkdRwzq}~pQ8RefN%dNn?XO#cS*ci6rjqfo&SPlNPOD=qq?OvQng z6B*WgXS~A74{c6CN-~mEUxZ2TubwIPdZ5;pIfFu}lMeB3q?EqI zUO>|UfH)&Td1YhL;K>x3y3ASTlhwqfKX|z?z8QWx=>P0qRZf=`C|=P`Q2lAZ?knah zZQ|6!RtnE#KyH!l;Mq_8hcWN{58XaFb!kM8#4@`S;3HNBYUy7Wgk9t9Mg-_J7?W&? zx*Z{N-=B^s7q*fyg_CB`->7Be>%#&E-m0vk#9NSiv(M^D z^kD&nPO@!HM5ADFtE{1`zNj)xb%#PzTYpwbe+cuku|8#|Ou^SZ3GOhtZ7i(Ii=gjp^`sJS-BQt(z4kayRakk% zwES{?|AQOlJ>k4F1!M-}O&BYc0#A&qmV$Wg{xyz3c4k5eR_?)sajDU8J(Bz)|Jt#VdXES=)3(vfLau>@5|8@$n;^=<~qLV3> z)M9YM)!LP7k^G37KS{wF4JpMABRnQl-AN(T18)vo%ed{dZzgP^zk#}4V3-Q zUj&_gtI_B|b*DDtVq0(8Fv@bBaXQHYjIqGId9~FYHu{GtqAE=j3R< z%Z|02irE&?9t_{3xp|p_6JZf2qjL7O!iRQ?jqoN-{p0##jhvL9;$4Kaw7W$ z21c-~4pr1&8o60xpDdhLuzK!&sj5p16_+~US$D!`*DFZzeo$*xM?fJ#iLUYUSVfZ~ zc8_pJ&d$GrYf&HHr&)7|xlLzmfzU=ADX ze#jGqyF6hYm`)HY%k4ZE!k2v-g5f*yHlO-7IIwqJgrcGGiDvP}fj*BP$;i*{$0-wE zjII~*XG9w9H8qOk>&C~61e9ze%%FI`*jhOaR=T&{;DzI!jB()xN~l*r*MVw(X8U9{ zCg>_z{GvaBf)T7q%-yMCWt_D!c5K7ZM(w3HRF!-|#{6jq3%?xo0PE=8U_RX_J>S-y zYsb?@R!NoRBCG@HEAhZNbzB~v~N`H#AxccsAgLBjIozJ zV|L$D0P@0}A{`4b9}W^u*Z$U@Z0G)lv&U$y8oYoK$&f1ZlTLSq1=*eVM%UQwXAmZ) zs6M||dekC0q9{5YBdM6<>-c`ByIK*QjH^m+hvvDt*BT2&H(b9fQ~ZG^`RIGmJONxn za}#+3M()y-i~kk-`+>f_LMNlZOq;yY*Q%<>>@sl4O!=AzzC^#k)I{`nmrp54bfybE z`h;e_By`1`0cpu1`E=>cZ@Y@F->eYgBUE%loyzn{ETgb5ED{ zjiilU@d=xS#ij*Hr*)T3jo@3MgzM)d7@fxa9Vf+%Wh8+swxR_0$5ul?=P!`t}D@wI)BLFL$&i;Z2O1ii!eyxHtY>^mJ1PF-W`X`gN$XD!(%I<@bj!jnp}< zK~8$=(3R%tS|?S44kZ%+&AII1ymQX}9}W_g7nzeEP=&u2#G|XKD=}=1=|{pEIk!#_ zCPL`*lH{tYm$5My(xad{Q_nnhT%5h+Aqgv)b0=+1;#x{12RbFZ1pNt2!1($4obj`5 z^>kjYpMt&$vx3e>$ev?eT_ltB04VcuLmGE}yhYo^yCCVhGjqNWmgMIWO)|_neX6yC z*6epYk4c;>uiB>>HolRxpdt?JJ~iTpCqQ7fQ1#JI=%vS)q~!T0(kLY93Xz>p%}*z- zXi1UBv#sbn8#s~ns2Gn++fty50m7cRk^5B$Q#}257W?x@c+wRj;Z*D}+eQ6bsfG?eaVtgy#co=^3*Iy?pvT{R{w5T(Z3B$I(n0I2mo1{?u=3 zDvKCxV+clZAL8O+Mgrhh@&VYK)t8Ul(kLEizu3%+TO_vvp4PXg!AuxvCbx4*WWeVj zk)9Bq!dlA#mB4oHd((k3GM+_c>;%r6!547xcpnbqw(_U`x3>hIu6R?yZ;f?+0N}ea znos&RU(8&S!91E4BBfkf()qXb$tAy3nn>K#0Sg z*eMqno6w{^;IWgBO4$&d%@-cgf`>rV8_S69uD1>OB7t?>=iiv|p+rVQPylKXbk}w39+7iL zzbjqPAZtF^==-~_|GJ)l2H_L{Pb0<>u|KY5ikDMtq?F|bAb*<#3R8oR55xe{-`UD zGu#ykX?4X~f2^QWf%ORiH5zbNoZ-HIOX(t>2Lf zBF$5bMu*UR4(KA+kCHW}uf_w4*hq>no6jIICmc3|rSO$ol1kp-x>qfK13OvfgVW+T z*Y``opzJ#;C7q4KzpeRgwSkiE@3bgj)71aaXk*VJj5`|LS+?j>9vIHKdyFLCe;At7=sLKxY%iraY!1*oe$18FnR zdPyMbBYKO?{Cyb|xDz3)7rIh(We2`*trdc_A+jw9UL$jPtxULXlpIjk zR(az*%T@l0`Q$* zBFLV$zuq|-{>&c0JO4&+9k})^jtxV@%-wf-`#>5!&mPZni3H=oT=lL44KVN{yy=|@ z&2y7>s#{v6j7aBU0DR7wCCz~Ets>WB$5#|YaQOBzHl9ISESA3g`y;Y&S$a`&S1OH( znm#L@ScP_V0R5z{NA%)Sw>Y(v)!7~IpULoz1opp?s(#;Kv~ka>zBzwbb05eW-vgl& zFy#G%+CYmiYfH@JGP$h3`tf|8M~El7E5#ze!DoL=3lNY!1>izj2qf4F5-MLmXx-$w8H|TO z)DeUWIioe2IX{Xz?ulcl%a0skPFxu8Xq)KaPQtW4GiFs+I;U5p8Tof5!{<*26wkuv zPvbK;akBic`1gJv9iyIZZ`*3zlH_!4>HNI{z~LFP7+oR|CDH?e|ICs^85XU&`;4=!E=m9$NS zHkit-xCZ3q9tgGR?nB6#mqzA>DH9|H^p04Us3t2E z?W_2_o2X+cpxG}bD{J%U@afZDgAZ;-loEJQRYV+08zkyvF)Yr_bf zf1TqIRdGm=5PtI@XMg9dhqvY)Nn3v9+7s{&LIJAgDCN5;fc?fw>9Q)MJ4s)>}PkT z-jYieY_h+DnDVxJD0t~#@vpPSY_$~H&WD9-DYTsk*V^qyTn^Wg7rE;uPxz476Fd0N z=?7Qj>yiZBq->MpFy9nZBHUDny&1<<{!qC-pUVih zz0#+{epDmNuDpJH`p=|UEqRewvJsXTOz0;!ss11KR#Gh|;mhNKr{tfRi`MQi{X-+Y z-$(E%vCKzS#j{7^;B8cvUUtv(ELV#=JNposb8@o&)u+!8O%i{65AzbqGLb3)u!3_6 zR$N#>)WSzxaCUC;c!u@Aon`+wNb#|Mn_T{9q}cHI|DTcK6Uw^B{)6fL-y_Ax{!Kpr zZFNKUO!40b{2Sx@e^i$JeS-fh zQ(WOPad*O6BHn02Ne=Bl_QlRKLa`w2V260BqNq3eq-f8oFB*V)ePz5lcso3-wLBk%=(K8SIufXmv@hdU3_Iek)n`aL=zU5My!4 z)_$Tw-7UI;$?UmWlK3{n=c~}I(?*hIaj3`>xO zQYE=_peri*U(wO;($7i29l7#dq5XRg?iaF5nMg2^h$Sfrzom&NDy(Z9lKIvizga!W zzAPE`&ou`^kEb$K%EVNJprnO)*Ka*&xAU*2qg^V{P z^1acPWBF72OzR>JOYMEKZ>Pg;2O9uJ>z zFI+WM=@)wx@ME5knL4x(Rcj!%`(X{Y;@~yse;zaV=f|Y1(mx6JxHEO`_I0J-oaxtU z5<-Ul zsI?awIs;wD9{I^Rs_-JUv#INbdM2sLqOoR|YN{d4A>jGxgLXIdw345yDJDhdRp4GSUz*OBpw`%U@qNa#jIoJp zS8G4jCKC&0%?=yW*IN<46IU#LsCm0tlb%6VL8Io;c7}-HCkkqePK#=K@AQ`K>&%sY1=5Fhup-vihId zlOB<9MULQYROpiz63<^=yb#m5=2-K)Y{z@#$Diu!4{ja(n*2gFc2*vY#9rIkQ^GI3 zTJ`2zF>1Z!Fh9%fwzs z)$FgTb=v!os(x3+9n~u+9Q}_Q|FD*;duS|O5q>HQH+8Z&`D4cwfytCM<`v-ycT3fl zIHkLpJ85bXkNUD>YFZF(lh<`k+vAe(D!l@R_Y$s!;!1*t|I$*PfBHFK7Zz=zsh{%K zlkSjp7s1ZRSiKOb7YqMjG>qgli}u(2H7plIiR9jt>tAE!-PF#J9?|4@;1*UN&T(`cp|z$eKQ`EB?o|0Y#yubG|te>H_Dp>*YO8nG~#` z4OhQ`KSci#zavHAzX6?(ZO3|S_mKaUy#Bj?{eRbO{zs_De?wlsa{O<|>*xQ4yncKQ zvGc#XpzTl0zsvq#kk=>vXY%^Ef#LrLn zU$gRwc@z3+8F#SDiEh5n$km>K={iAzOxLyc+HNDRDSVLB}{Zh_dkbde=j$WFZt#w{}RPw ztrPF4?n}F2IMm=sz}=YfQO!U8@^`p+iq}O8 ztcHnawb*VmlY-^G5TwEv#X-X%;&Pa5pR(8L?nVXo_o$O$z%BU(1!-^<74Jw)P3v@1 zFt~;o6#gQ(WT79qvdf!*vVQYBQ~BC%0@nIe*qMHb{UXx`(le}S$ThhznN%m_l}}ER zFUxJie=OOH`6^^kLJNo)sGB^~Ms?qQ=|^sEwHc0wR&MiDpM>8yqbJ~AaP8ZE)ocZu zXV(wj+--Lg6YAC9rzIwIbGK`5xc7g?m|2!LstvYl=ifW67e;*Nsrs|m7em5wR30aA zx+@OKHhy1d+b{B%fVD6`*5*ijA1{O~mqSVqI0bKK!bT!*r`{mksYvtESFQF5M`8`r z2aX|ml_g1~! zo7mGz+42Yf#Zrhdv%sdy{72*@N?%pt6v4q;G|a0%Eb`hUqVT1O)iDzft@M}6QJ(L- z22b>LTM0H4LD?CV?Sc_I4=sFd+~0^C^EOu>$%;p0K2&)UW#QeS0tB|j6{dH_bI@0J zt0o=#rqK7>s%JAZ&X}f^{^Y*xW}$A;wbfg1!lb{335x%EbjWHIgP0b1Y2v0Qn}+Hs z%k8Rvv!G?ajNH}%Baz`hPmAi^@a%Mdz}-Zg_?}y~@XQ?Vqi&t%w~VyTMC^;Hb;%w&8bRU34l0^qPCXA- z8sas$bGU`Jp3AK7nQ1+Hbot;$*vhjYbAYd$(bR?*-%ap%K=&MH1Gp6cKnBxMt444h z`jrw`A*l~$sV=eT@QkEU^~PN~)FWkS;{uq0HDL1s!3r#{9v(>m;0_DV3seHoasr7D z9%!%g;;Y?PN?ictA*F4dMB{pM0rQp8VPfCf5RDuO`ariT#B-+eK(`h4FTju9(7xGx znax=__@iH@q$^={_w>)pqDYNgt~|eH5rtBswol@-slbE0DLOB%qDY!g3Gv3q&pL9U z$j*Het7vw>ifs5H@i!UdK9C8LRB6|}J6@5Aze4aEoXyMj+|3-?%E=e8jYxK@>IS?F z`Vg5Tpt}vezpWkTkvs3Ib}WO{!}$jB!b(c>TcOxnd5EGObFJC z8#*vq_;z0O5}8EwQ2>y3D;eB=*uw$LDgaGJeVP?xgRKAn($13k5#3_rfZZ$3oszOv zOPQi`Jof75yYMfEy3#!B%hLn#yqq3SXRxl6khj$@*MkNl%XmEB6;G%2ipAr*Epx>I zZ{b0b_9Uot0lZ11kBvuN_wYS!!0EwHO+*5R+R-z3E^odRTxNR30sc8zJO?&X;?ril z0r+uOF@X%f&*U=e54AF(5fT~P-<}HCJP4P1$9A0rn$N7ZPOumFYl^ zr?K#WCkI$T(PZc}872duo~-(62Y{ZKCYX`I48@hym4F6)Fx+WC;w%M%ZW#+yDR-j} z&js$yw5=%cb%wW`2}tAFhk;Bfk`HFDhju?PGl2X;)Kg#?mCQNmx@VhG9vXKg4INph zpU!DA)#V>d#U`MV?p2NAZHKe4!G`gI&vctuSZu?Yr#~G(5V9Q42Ar^dx+1bM;G$4) zHp}*!;mbNvpXQLhY`d~2#dTJzwaWt`hiPXs)w6rDzo#?G!>UNAcPRAAAG;nT{WEMm zT4(NYnZ$8oruuFB&Tz!jL;Gg89wwRZ7PHFIQWu(CaqWBmD>H6Ic*KK+z4gzXhi!H5 zEx3HIiBx_f$>j;XPRHP3ACT=*T8yyPdYM`Hc-VFr_4_afIEHxMqg=e4VP_JC@+ z>$u%$-BsV*g(Q+QHEub2ruGUkR<+!fp=uE{VRP`gp;%PWa_2Ia(ER? zycTQSDn2|+R(tEO(PFXi@N{$})L|Ao38I!fW6LI*ST4i3M%xREhsjj`!#R~_7+k8q zUt9dqxEem_FOj;y;jBGhtBsmpa%mi%F(AWze89$$AkG9Upt)n-tljh$LeiGDc_0Cb zj|Nl4%u6No?8Mpmr?jFjCR|AOoQwyyfWBU(bY7gZ6#OyKRv`;;0TsM;bq?`Z6@P<= zJ@H^`mBj2Ox8}?MlE=ff(6x)~W`tQzkev;hv~{4FI|*WMSvqtb1`_ZYQ#=WD{O&oV zqTWtelbg74PGfpLcWs#uaq*U!90y@&ga-h}Gkv*Fi4+?z_^{EsV}u)GpL1W()$TJH zT;PMOS8$ivQFOZ}m|%_dFgtZ}B6p)^*HqP?wYRud0%l7yUK(n4YK&=S^13M_jK<3^ z)IG@bxb?p8kO)6wHRw;-O^Nd(sDMp*Q+zs7p*#$5+> z>kOmsv2&F4VMQ&K$vS%q4Y@xnkngDyb>T>~r?CJeR=%9o5|VvLUzQ{7C3@OcWVg)O z6-Ts})d%~hIXBkbWj+|3vlpMj-OV;~%xxnQbHjEZjMl}Q+-_wJz7)|@H^Pk$v^_;A zipOe<>$P46dtN_P#z_zc1zD0&QJ2{aZv6R&RT0O+g|i^-+ieMQT`)BMxw;}$0wmCY6o_Dz*IWIUYmZn#8#Y&Ap9zZo&gVYlVQUY zeGRPf>FdGkGRkv%id#xYHbQ`B2WT<92pe(z-(g>UQ_wjX$f7^Cf8Bhc+qO9i@+ONO zsNQV~A%zy{9Di7H!t-u4oy)kOAEQS0Yn;q2p8AF>SP*nKW2C0FNK4h_?5#785c}ywf`VyZVJrKNys!Geww-R zEaO;TXyJ7)-JGYp6@wf*v3T`A_&NwJ^j!YEmV1W|S-#YeL%kN1-T7$O#vMffvIQe0 z8=T*i`YLFl%zkDaeC@MGtk{hBIBevsVa})xMBVsV;1&KXJ-vDW>n<&L?DOeIy0-(@ zl#nY~#b|Cd4^gmSe>V^>cjMWyaD8ioO@UiRlE=EA>Z{uI+E7F_2q*DO|EkgnFp#j% zHRYIKmj803Ut8w`Go?O?*uFI!8{Z_pM7e!i85?zO#K>G+T~>aXc^BYv29-zPHa35g zo>lSl(jS6}G;t^ylJ2>d6IkU^C-JRjsknMVeAA>igx>dLG6^-PH$5DrZx?l^z1a(h zh*f%mNY@11xPwE$6ph8*ESfv;u=ogeYDJe(BU~XFGbIj6WJfrY0!j)GbP}o5Wa^I& z&(P#l(Ch%MZSK0IrHrZG;7kuIU15N!TvPYSF~>W`@bhXqI}Mimc@w~Q-W}OsY_w~z zB%`(V`r2Y-Oh?JR!O!9sBIY4MNzY-%@5nR&%QHyK@v4$ENH8aOE^W+<)7tuDz4{%M znksdr2SEgV(>+3TpofQxa6w|;P=eAOF+M|J|1HC6sYV+j@otg}2;uUn4aLJ^5x99W zUKD+#Jdjn9p8EFf8|4wheD~X?U(6k#`|dU4{v(S;8$n-}8evLZ8AT9bg%Je&sp16F zCK>bRXk*2wpz$LAcXv8O49=w6A`E${G1T(=>m`y^ zfBuYWN#T5D+s;~eU+LLlSgCf=aneFK_BPhiOK@W&b%SdR%W>atY1G=XfSia=$I8c*UP%X5~nwI;)vC?+U0#RF`2~7xysx3 z8C#b(ij#m60P2C7LoWR}r$GA7Dx0FP54u_b@TK=ZlKl>>Dc)9U#R1<4$hf_$e&dt&G*x^vdN$m<#`x)bbIUi+WU!Z#tA_lmUw^Z1 zGHzHVB^SLwkHC~b2fGh$sq-xTkuS$Tq#dR8!iq4xmCQjZXizLWjL+g|77}p4$(gcJ{#M3t%akXYV9Bc>SBg^Cs)4^w2M1 zEa|T$Pq|lUTk@UL3G%B+40kOr!MC(B?6O8)EZ z2!qypu@0!gZde8%+rbs>=@nM+I(k-j%%b^%zP*xapaVCLn@wJ>2NPfde|#}hi{_nf z&bFBDs*i2 z?%n(_q{3;6Ck!RqWHj#lj~+onXctBGau!wkaFcjlRj!+f{fjeXn5}}+ zN;LF3K4x0*d36`47T<8-N0Knr5;V*41L09D{joT(5%N*Hmd(P;wbGvdwGl_<8e+cP z%IM>TCv$%*Pnd2*Q^a#fXF>Pt=&P0>ID_(v1(C`a={cbi?e}-eVzI4`czk*pb{Kf%BKVw+bNGK4`pLyKEMLvD4HP-W)^UpupG!pFrc%sS_%_s@|p{AxUy5HLZKQxJ}E5={<_pr06 z7@uTo@Pho=()DI14rK)=K73`_dwB4%ZxZzb(d2=@Bc`HsuQ7n;{LfYYHt7ECzOhVa z1K8%?+2Hq$g<@&;k~nlLsea5b*iLB`zxhW*x?=GoS(Uwz;q$7NXGO2WY}im>Hyf~% zL~%A66j2Gi;}ZTS#q{m)AG!>)-bJ0;C%zfa7BvVB;SYYE)f=$wqM1XIv07_N3~rY( z0Ak(O1$lIbY?C44k9qTBH&5yp9TrS16>-s$3F2dfs+R9t9!*`7!6(F&_HYDb;vq-; z)&bwxxa#q>p#U3j7i^tqpN60ib}eAUq^tcX7L+uX8$ZfcRiw^Rf_v~jH?`5JN<=gj zdR&L&2Oy2E?_f5JNT$6B!4HSVvdMs74Ux&5IANX=l`&aPGFKL|Sty!ZJtz!Z-0gsskt7glBU@AyP_;8#8C&;PKVuJYULQMuT95wA(Xu znYC+jtPF}6zL=3;zoOOBUR6vOA~yflSVK;c`~24nzgvAp*KA?2PA(Wh_y~`2JLNmv zBvl*V@cL4hHYqTNqD^284_SGAXq!~2hwH*FW|p;^JUwQH9*!ZyT@B`-_CoDiRS_a& zeFi;el9U9t@^&a$^vglTk32NW_!fP81|7Cu2^T2i$v+<#+ErG#l5-<338qJ#ncH17 zSEX7~a%u*1{@SVX9T*aCC2K{NAQxCw7{`@-nU)*fkW3NNDLxtQ-Q=3$sbt?}07(*Z zW4L{oJG(7=MkDiQ8K<9c5YeqRgI#KAz7|f##yd%l)v`zq37-8jU!N(S?9oEj% zebgIDTd4yArFb?gbgmEFjLr@<|M^=6cQV4w!-n}%dH&&8Xy)W}+OJa5D5w^yURBjV zw}P}ar7HyDw_L3nk~#OdXL&_3Q~##?z* zOB)X8Ju=!fnTS-lpLKN(T`cp9R{@UY)zB{IZS3Y1(T?X|qOQPTqMFj|&8LlzDTTrH zQX(y$M?fSUxeuCz$IVAK$9#IjI-?&1R^C#tbXwX}@&FT8(r`4QA38GoUybY7YO#Zf zB824cQxsx#yeE6K)>Hd*H{bA~$swy#{s_`4QaSRM9~wB%*S=mku_*y_?rD?0T!dOk zE4=(W6A~F~@h;r{fe~e{{-6(p?4S+q(1=(tn+hMeKYVes^tdztp44hK1I@gAv8b4Yrp1 zb*-eTu@9DMMZM=!J)5HW2Im~s*EfV!EbpYJeI8EP*Z26X z_QK^;d9qK_Rc1A8bS+B{rk`o!sbzOm21#x+-Vi$e$c;%5iH{3;ZSL8fvRY&CEoW zXMMe<@B1Ws%A`#Nsl@A#HBs|x4O|;5U1()c`^Z8iDi21%+q-sRyd=`<21eXBnwKo_ z?wkUX8QuHhz}0xOcG?73+8S)nHXc43zmHilRdJ=shr?zJ)Si;&Aa$}479?iqgMP=T z{iL-*NAVR2L5VPwm!IOO$(V?{OgD;dH*zm5L!qwDkIv%4!aHQ$mdy6^kH#e9kcn_3OHyE^|ZOcB@4__%!>V^B9Br z^m!+CrlIzZ&-%?0H`c9pa!=lfN?*!2AZmM$&(SaMWgO4i>U&-) zv`nP67^=pJv#GIh|czyh0D@@F=WqegX0QV zH97c*5OoApfrh!Nl1KJ*{}E5(N|2es)i3C>(QnpKF84*{A{rA-&mErk$lx%%TteQT z+s+SjG|msrj-WWUa8bxgFTG5g`SgEHPZ_&cSU7fly7sd;WB(qo%) zMl|K?Tc>PTtZ2^IP^`niCrJ|~1Ya<#kR#qq7jBPgOwr5D%N8%tO4eBF1eWw^s;reo6#$LU;%V-SbtGlUntw}@dipw!?V|7SU#6uIem z&>Qo)B-L%-2wa%4O<~<2a&cP<_6x=*3?H61uDt(7eX23%xhF=8YS~Y^S)#$9!uexk z1?lm@&t2ji+#!EI)qW8>S7xWHW0bdVEY;oBMXHgR7=M~G-5wr%gFxlF|_aK48Gp=V(^*zI^WNE zVaR|_yN^8eTwAY@x4D9ws~r%%Z;Cmah$%@q*6Jvb)%N+rbIEl3n|l+a#NCy*=3MeK z1CpZhZ#kqnvV9lpTMtD7(P7?&^-o_A1{*^z=qE_$_G^}IgNKIADyCYvderEX(6$41 z#H#1a=6s;ke5g;yS8c*0k}o)blw26=MqIb~DF;Zng%?M)qRweVn`aQuY*mK+Qeth-X2d&AzG+ zPD#5`G;t{|Eq>(plMOa|${Xnz4nP4 z;~YWoBu*{B{iOZ61h+2w$nmc<2p+F4@&DD&C2ZCzEz;sPDh2*E#CoED2w`Mz`jcS6m8RL5T?kw6#Och`L<5It z3|<*2Hp!jI-JVOsKSUclt!S|``qnb>A}d@dJ<}|v;boJi;)EC0x8uTDLQKcOCV?){ zw@cn)c}PIh@iUZ)sZWiMY>rEoe69T$WVszaHymC}*tuSObrDpsXFsQY|& zE3KnZoeJ5;BZ0FQ{t|y=>u1s~P@BD=Dn@Exh4kat`o&J!n$l*Q^XPA?4y2JtSh->< z`}*0_v0!=gPrwj;{KeXZMyDQVxf zxr#wE%BED0bJA;g-Ny4>)ES<3?8=ugc@V^ApY?SbkQW5|#8H(F5vAxh5_Y$F?`1nV&D5eNwh^G5?D2 zH+vfcIg0_+gGrmSqCv#d>AM@}YqK3^^ctrsE5Eg_*F6nt-!h9~Q-k8Tq#cn6jRVsB zzu)r$jv_m|JB#hhn0gJ3U*h5~*uCY9PiF9Q0mvZLAhs6O0sr)fJ>2m&mEa4WAA7PZ z3Oc~#WdpD@Jq{F*_(v8x8A`d6won2M|^Y=-N{>uWYoGZ)vNbL(fmbK#rs?9U(Zx>~MB>Ge9_ zQjCxv^AS}F7XQ)x*oDZwLR#wtTimPSS`pyTrA<(bynSX+i1d0!%|(tx4(}wFh69qzy%ttL-TQif!uKJ${-?J>$}} zha7Z_c}Apw_2&>}s$$`2Iuz?WKz0d2HAWM6xQre^}f9^0R?&{9Tvf*oMMalDF zd={@|{O%Aqals%@HF!A7?K-9~B*_H<=J`|W5wexHF4cZ)(nKbhE6aXYuDyIA_Fl4j za#Vh_ajdKZ+rChl3FdA-Thvu5~ zgQcN=CA@FvKE>E##%3wsDK+X+>(My*NFq!hbT#K_K&6*B7kEMyx=NR3mDZ?iuwcqi2CXhKfXa#0 zd_`>M@H4@z!jIZ`V05$~xb^!i6ZZ;|aRtalNIpjVWz3vCq zH>i9I{z363Y#b)OtneR6*3-5y)jjo!zj<^;Ps=~g_W`ndj4sxU2){1l&NcO($Gv=Q zwX5K5?9AAaP=WSIUkBdPSJ-IhtkiU=ze?YnFhbwSbd`)wp(Vnf6$!D} z=X^b9x1yBaOq?I#0`pOIId6xY#Rn<#fgVj1NBzN9xLHZ_3Z!zFmrFJ90;6hNj25d3 z2OT=GX){Qc-6b06Z(uoR&z&-4)%9A7shkKBb*4tTAf)M=BbjrSZfzW4x+J#`g2AFr(@bTrIz@q2CRElj&h>!Aw@XB;Pml=oM4uC;#& zgJ*^k`kb~oMPJ7eKRzyhCg1;? zM+9pt9S9svjiH5yt}N!1n6`BFp^^2~3NmKlP&3N~GowPR%N`Ct=~{Cs z3&-Ox+jOxBfi{S^TEfumVs1)Rnys`>e{kLSK`?Z-^43jb{T=`_#df=L~)&O-~ zGL&8mU~_U-FGntp0P;*xd5=&)-8sZAZSSSWfK#t?BIelP0cj;v@4eXCAJ>hnrq0H% zSV9|natRq(Lx-(~GL>$RUg$r3%K{XTMhA3z9N+d=ZKFN_v^YQYD3w#(TQ-j<Iovi&l^x0YxgIrSyRheN&m?^!mD*d~wYJD&9aL7h`SgP|e^O<`u1#V?hR^rvt6q~6{55I{C`|GQfofycT`~cLWGOZ@QP4fA`&$;qXN^VU3-gD^M+NQ}qKYc*0$w(FLeqgoZBJ6$!ewbj9X(-+b9v^~EkR z>Hf{^_re|ia~c+CuX|dlt?oA0ZON(=VL4Ycz2meA4>XS5Hi`#*hr*_(BizTC>X~>; zn~i{{sZXx#WLH0Q&U)niQJHY&InmN=$Ut~#(Jw1boYe1k=0~k!?;%#t{rv1eVQ9qm zjKn6j9Qc&(w-J~d#|?L|-Ze1>g1Zr)CRYsEjH?GiO&wDUMluizXi^5uu`UIi0e-C$ z6BWwy-##d;jvp-2AkL~tzsS4q^r6QZdD1jJOMKwPq2B|R%V@X8<}A~9iM=|-FLD-A z>LkrI&JO1-S=(XRuv=y2opc?ectY_y0--WOm`f(4Bc<`?Ud zwjppbq+^=+YGC|Dn;RKe($*Fyk~nR`eL;P`4D_+tJYhq%_`DMDb) zb>AeIeY}u#xX9^kd>jISP&Fdl=bf7qMo1q_3>N!|NW7D(?6;=zP=7P_iEJi;K**mr z_!hiEEu{e;t(Y_l|!=?tiEz-Tw%GIIjC2fe`;rHT|ax`3W8U{|9RNd;9-X z$p61XP5*ZSgy8MakZYJg!Tq-PpLx8$DRW$;ONJwKv%FE&<@E@>H-s=Le@{DMSw8y` zU$@cs@Xj}3`=g(|K0RHZeg3ge{hRvYFT5|+(|-PXfU};vpf7)1G#SVC4(xx7y=x(< zHcGiunctOagLo3NzdQ3P=BPN|edT70YJTOX@YnO^=(og{cgMZx z+E#4u@ZMrXcUZo1BHzgkHdi({7sidc?PsRZ)be2J_uTL6<6r*DU*ZzOUV5SHe&~IA z`#PR6xcl0hk>$_RWyFY0s_EcXOpY6B8teC$S z4ttz$*FgIkXR#tp_R*h|;xisK60NmmgiW2^cznJ@%T%q6V_DH@Ir7cFT zNrm<0rP32oHd@Ayl(H3@5!mG2`XBWb?S}LfUu5tj-@cCyq$+yYXk{8+`MqeRB~?|b zg2GH|r}QkIdUlM)VRf+BSq}au3zjXx_6o!<#{qQ zdO}4ny-nU-tTOt(9`fO3+nw^yd|CfgI%qXgW&X{0B;Z%WBcxsZR+pLO1p=liDEuN zR{061ep=Z+4H3W2Qu)I1O0$7@B>!Pp*X{IQ^l9Bc;N+jd{_lLw-<{%rsRR7I`~QqJ z9-aT8^Is+-TrK-IKIcKm-tGVDg#ImI=l=trqoe)b^Ev-}k`ay{*VQ}z-|{*C3(*Kg z`-_x{4(<<2{lqJ29BLyVa(FOcpxC(X5Z}TPIT_1aBZvOAb_^w<92^?>FaudHLs$>C z&q~e6n%%k6_C7f{>ucggLWSm$aGwHeon<(nW_4>OvfrVD& z!nb{2<&}SYy7$dyV29J@7XLSj@uvjJ4*$)Z|6MaBgD2L?Km45SKg9F>gHM+12XyA^ zd&feawHf_-@dBxO9HE5If}bN0Idbl{nkQwg$`J^WS>!P#ggD+(%F;T`${dNDRrT{c z{ShJ6ui2P@M`|kNZs#tv>xt0+S(bkPmWQSc-}gJ%fTBHS16s+$|GNIg!d4uKJmJc_ z>GU9kXU{+JQvakV$0~(tAoFeBwR`J+v`W`LWcUE*p_a&1-Ky zoY;Tj;M@2UL1wbgKb*LdWuqrzqja%V^+&q-i6G2io6Y6BahmV@=03$MKfS7F>l$7< zq>H!Sm6pfTZ=BWshEP->b?1$b<Wp-gst58>$SAB{$uzy{}sO<+hTK>eDSW(2~jJ-xYwDAI>+|yKar#-HAH@x8uBe}E+<6lduqtx zUvYveIq6J{lj8}L#rlIsrP!6>$m4ay#imNY$=De&F2sS zmX;Ph!nVJ?84((3?-f)>gl53U=4wm_K`#T|e} zu8J9M_3L~SsR>0DemcjEpaSL+iJ3?TU<(aMAcji;D_<>0TjR6{;tSNYD4H9S4O{4-Aoz5JE0GbQX zTnJ`7iQqzX-_{}pHryo=0|Q~`t_=F#v6Iw&T|dSANnk2Q5?Z-aGfJ{oa9%c^iOCBG z(Koksgq`7n2(Us-0&HJEWcT>POJO*eyN&6DneKGz$aWBi40loIz*-;Rjsy6Bj)0x> zAJ_hw8o0d!O&`Z`VpfPh?d?}3A==UuH=3)}xdZ^DoTUaUNc{B7il27pWYOvr1HRzO z??%)XqnS1AdIeUt3x?gyB6fD!g%A}o06aJ3rx7A{r1oRxx0|;<+hqTuEK5j(^9LcA zxgp~FD4;z5WV*7i+d|5*gQTv?emd#k`1mO12fELnslwuXzQRnbGtpWia$-3UfbA+y z&hXvSzIfN~UEVKrzJ+B=sVXAW@pI+aMu9?F|KnKhk5|Qq+Nsm+b-nht1^33-@2;Gr z#^es7>#L}(EQjs(YZvpbzA*WEYC22t0pr0N?uD-bG4FnFwANd++*@je?80KV~2$<+-e$QG}|gpF|uw=x8nj3LLz~Od=pwh z&@0@EW(Sw+&q6nlDsuv#FS5>cte70)!YsJ7fdu-2&$RVk=H=$C`j(No&U&@XL*Q8t z09=SuyAK?F^Fp<7>dR(FYgLAQ0d-$H_LhxY#J!$82sWXDtwmUwsy#oAR98XyN1w;h z!WO0a4!2eo6oVg!nt@>y#3uFAxrX$t*hv6@={XC#nCtG$$_r&r=V%Z-_G*qoaw5mD z;QDGzzMmfix={3*Y(4L;QN0{HCZ9fimI9a=Tg*DB6N!UYt4ItIeS0ZpYr5ERvsRUD zsc`HL&K|o2e8J??Etu5W%3>ftyyxw5j)Gb@Gf`t-E_bRH-+Jp@iMN@mB!TA)Hq&>x zavi)r-%1IcS?^t56~7Cs)T z24hq^{EU)#Z;%OUma!H3F!(_HwMuUwr{R0<@=5RYrGt#{D#)9ENBBkg#aJ#ULO}C$ zgLifNtnzd*0fcQ7iuvU7ogbV%^ZbXlx>oorJA$HxOGln0$e8EjZb~Q&2HP%`-^Q!XQ7rW2*6v8d}*O$%4C`q_Nedb#lg?&e?1D&+p?=a|xeNYP?3XYY!3* zB~3Ra>WRz1+omkGW*2>I3Ps{2(V(NE-`r;VR3@`|Xx?i0Jz~#raDO@r zfWgz2kDBHR)K5k=CB9Vfz^7`yv*(0$`BgbuU$6dY%7lQHSqDsi4{E?f|8r6odj)Rt zr0a59$mbtkj8f<`iojMEDq{GZ*!h{~BE4uR|MfTY@zuBYQlt34m}~4eS002$lgd{q z9_J`Cc&S87OUv_ZfVmQo8ag)IM3y_srg&n`68^lal$%T%O3D#^vq+2e^OXq|8wVI_q>T`nx|^F+2eV;0Vep>u9yyYnTeP?BO%y)AMef%j;P#Y+8AOJ7UwyHulaT z3z9M7zh870BPt9=0&0=Lcp9kBP4aM^%HdlW5)Ra(pv|g_!Jx&9Ook->qRun2b-fyo zfQX-7iK!B$Cfa{V(f5H}N&bu5`o4t@6uy&94EQ3NVH>GxA|X%RHXFG&&Zj3;=oM&e zzGc~ut-#U!R8G#o0 zU`~O&ed=)P#(X_qIv5)=y~5?E1XIzJ#*qG_%cyl>wooZt?B@fm=EM*7^FwO@w99po zxTG#Jh5ji*EhPMVcX0IVysQ4(CEH_cq07M+OLU0!RHJE=;1+ zNuTCe5PCa(wC@Y(roLSW0^OwPROK1S`_Srk#@??A^FlZ%eA6}V;rqVBdYT&r41q!taoa;y|M#x%PT6qbzIdxg1*!CIK z#r4#Qbp?dIJqLPjnOxe#-?PVjIAu}7>|UBCDS927;MruFhrM@eyvc|_sBI7xr1|&o zSq8;1sOY21SXZ(cqbr`#)zvj*U}Hbh)tXE*tO8WCy$kdUp=P{xZ3nsDZ2OHs*W(gH zK0>lx?p-4ci`C2RZ$ozEguaw|h!cseU!~Im3G0k>Ce$=XNQ1`1`R<@I+3QZqpcS@U z-Awx4sW;xUodE_L_4{R^jVtu=^|wmO5O}M4NL5g)n#Rev6dww9w2LkKNwO2_8 zk$T#v-}By(xD^j6-l#6RIIfgw_7q!Jvo-Sr%Oia(obSFiS*U5dnH2B!RxYpA*`Kbd z0oFqYl*%5~N|liXRX-hH=LtPEmoeP=IOvu?4O?^>ecK%Upz4I49Su03P8;mZa6JxR0ILy?=hzlMb?a6181WYp|4M~;Pfp0~JFf0^H<0!0v*J|rulT=SGUHS=T z+WXfgXfv zux)@}N1{j~pZ0SE0yN9Wx+!!x>J!o>HZ}Aej%ml6;ibjb3I>X&s*8Kf;t)j6NdXZI z->f=FAS@-qru#6kO|m_gL=oBqv#z8r!Oo2_(b?5E7h*7 z`~Igg;!Y3VCIh)XKvqG>N*H92vZ`Pt^03mw4awjLY;|5$gyWMuV*1x9O}wS{pN}F- zOG|V~Ag*qkeL#6bkF>p_OQu$t_*8%Za+dC^VF~7^oA2yd~Ko~Tivu- zLYbpefmv?hdjUm?^B-PlLIW`S!6zJ_uDRYj>8^)`%+N=VihnD1CIR+_z>vU0tUSd8#UWd)FeY9El29EtFcsZKzTqHnP+R&XBM zu=O73OQ@_20Jw9LCk$$g6UzCb~b%aat)SsS)`3Xs8ta`D^RCfIwxp{ zz_KD`U&1U>+00}Q6kT2H=V9iBMz*CRkxx{@OR7NCQ{tGYtzt=xdJ=0#)JeqL#t!PI zJnoD!U#?+@jR+h=EiHSzPP?dSv3j%i!M;+5_VEcBHjhnA#It;<_X!3y*Ml_fMqE~& z4sZQ-C()Sa*VWt`8rus#+_j{B`XUJ;Dwcz9F^+GuqAy56CBxsl{Sp1}7C?3_@za&t zfdvNwfK#~f$#_O*^W?yC*-_zRBb3(RovVaaEj3Q)2Xa}wGsx615tHNGZmNuMQ_nCu zO%_-_n60x=VU<3pqoxz=hhi{jwqA{eW_W4G>XLD;zM`jDvc^|c>$qY;i38HS@iqI( zD0J`nUfS2Qx)vwf15Hi_21YgK$P<~yC1!igc*7-frA~i}Ff03*a8XsvG1TdB+uP)J zHLO@moFK%QI_@Cmi1MXGymeHQl`VwBwx`F8bP0 zZ^f6zlcmF?*VB|HljuXeDe~^A@34h2#pSE5swQX=HVpb#sO-H!@m*OrZ;qe7Ijw1R zL5+&DGEE8M#c(5m&mWu6SCMs^taT{Oyl#vB_8*kW&CnzCA z+WEN;IX}DBiA-m7UzDT1C!ua>V{g`n!Zxzp)A41G<}PXRUdzzzVRQ{hj=*j`)1x@* z(|kz>#Q&t&nAIQ2fv)zO5wlS9razDL zTDNiO;1*eC-WK>TDD(Hm%&y#Xz5`%G&I?hk`ESmACXvuUwsL()CVaX!X@39s!Wmf& zvS6jc!tG{6uXkF#wI@g~EXmEjoDzO+|8?C{-IX%Xe9wmLS<8ibC)q~E$xTfWT~Pjn=K4`P7ERQ@aVNdl(k zbyxIEQkNjWs&QK~&A_U{N(7w+?(O<~ty<_8}@$ca2K>l>sOe z5Oz%%{iO~nuppqkX}?Gv=iaE(k|i)79y(BbrXilxHhK9h8xA?{2)aD1h^jP z(|#bJ^yiPE2TRa@MGHIeOuJrd-Dml{fNCsWTGsCnO!CL@CM1A0G6K*P0(@%f2)$tjlREwuTyQ<0j zmDe9Oj_q^q^uN^HIitmp)UIOOK`NQ;KRc#XV>NO2@ZF!Ce5ceLj`^MPPb}Y~;LR%; z_ux^BB!tR%wHh_xsu?bnq#bKuLD@)?;KUJ-6tU zbHXgX0|Cj_jhCv~d&fkqrcew)yr>Yx$YgWa_BqvT?~T0eCKevFjwv0vQnCVzYDGb1 zIiN$ZvQv#ZYRInnr7u51x*#qryseVZ1L64;>87Wt-{YJX-bF<^yIHUT=0*&@SwA@E zB}qiAL~vY2;-i2eYro$T zt^rA}>EScb#gH8MFz$7krKLWr#v^ytc(>? z&-S2%4Tv4S-b}%hvCQxiHft!t3325`LA%DZ2!=O? zM?MF`8}IxL8EiRKF>|8?YAl>GaJ?GGXIk2&#XRS@Qwp3j`g>1m^c)=+PM!T_XQYTN zV>}q8qaxKpo#ccLx+~HQtNFBY!uY53hUrZdZ>|{ORBm)6ty4dxoE_SlKU*Ds>Fnu` zy}>kt($I!t)m8srbmYGnCfJ0_BXVEvC_de^GD^^T>gv@rw`55j=ns$aFNh4odaMF6 z|58h)E1O%EGP)L|O1;KB38Tpw-R&-5U;J6?pqjG1YS<&gsy zg7?;pFEP)kZ_+d^<vY~KKN@2ZnOM@s4a$hlr^R`)Ig zaIplxZ|~i1Smw+P9A4p~^>oJ>qo|o9(cGp~tx1kbX=zk+C5gU*t7px?hp8AwE#kI6 z$KVeiwHFqR=22Mv{Aq0RgoRr+p}z8d2RG|dDr&}YnA&EC;uwgMOrzM%r=kr$M%v_S zM66NL1U+e>x`)G1iD)xq@s#{}yY@}xMugek*6_mgiHe{Z{FmWgb*xy6L9OV`Rv6%O zekX#@&*9Ql)K+$&$2e`S?uVvZ4nv<#M6=XUz^PYl>|#V$#_593+a zv+vp2)7^InWmmoz1iBellQzqkEJyv0rX2S~J}X{iK~vX>U<=N{rWUd0vUol(0TFE* z%Qyk0H?02EoX~>L=jHK!x5$Y2gChzn+t>*#kECZZQa!B}|MI!bS6n?FdH6V!2BjZ8 zc1p@ATO`gb5PofQjzYN= zhpI9zagwURk9%+BRAk@ezY*kYZ2#g>jl z>QqdeaFQ=YvnZY*am0O)l)7DgH)JG`H{O|H8=)!NdNZb`*K`7Ng|v3MGh9G2t~ka! zIm^|)Jo;pv=1%EaiMOpjv3u=MRp6} zHai2ssvT2h@Q(f@7|1cxk80-;x!Tn4v64}+AYL?DL33>_D`@hpS?5%WcckM({%y}E z^-ZHZg+!Q2Q+rag9ch)p;9m4+480>Id%@Jou@&QU;~X>6u-&%eWP4vtr@;pw+4T-P zFu{pK`p3&KqWs#$AfTHxxN z9ybhm!tPYCr($7UxI|OzZa!DUfqn&zJ@(T@Q~I0zpHT-!970$0&x~G1YF}=5yi}Sd z5xAeoQ&^(~i(>9*$KnM@$GIH$M*OAzXZNDg5)bO1*(RjoJ!E+B zip1sC6~5Hxb4zs{>kDT)ONMQ+Jc2}kcv=JR6UsCwfSVqXwyJK18`f|crS02^(-KOX zA`z3HmvJk^CA&(Bxfc(egUP#3%wJ3ivRE-kNJgV3aD71nBB%w+D74?58v)r@{>+pE z05r_$`Po(1Ox_-M&kMQU!K2VT98`KN@$Q7%=g&@JN21=x6uJ0dH>Pq^%klE9gRczE zd0o9xVr{1M_oE$uSk11RS42<2d6gr!Vmm@>qWBWs!J@yRP<*K0UE3pt?`D5J#Y>u% zamlJHVoCbHH@Gzpq27a6Z4Eu>DN8v!j zZm5Aqq`9zDq342YkUXE3-7CaDs(+CM;wmXA0OpFNnV5E!j!vLgn&P%5_sO6s$nH_f z;?Lf*UyZ{h+J!Q42gojydwnHsHKOBrl_Y=CXBy2U6s&PXP0c~$cieSwMlXqOpMNq5 z5~&7JmHWW=36BNSl>S*^r^1WrDuxZ2TAKn3KNns~3U4b5Ppt)rsBqTUwx?9QIcl89 zhLLn2Qozy9i-tv=>C*+Hq~}C>RmpZH{k?oQjCeMNgC#M$w9#2FiE++uzt{ms%Bf%5 ze`lN5*QqJYU$p!JeWnIRE0z{f+w4iun;X$;j~LIRw^9PnR<+l_Vl4{8I>AF091#^J zpXpkVh*dggdn3y*#yC!s_Gz|KVRG77!IGMlT|%bGr0V zk{q+6J<2_@K!HKR=n1NfAq|u_8PxTNZ^K$M>igWDKX*C(%-wi@F-9?-FBoyUzq0Gq z6pGorcWE?Zsj|JtTsb3(80fyABYL@|r7;ep-S}rxDO0gqFqPo!i7!PL7Y99n`tGE8JX?I zG>t%9)Y1rpIInJY9Z-r~wCxZ*kB2C{=MuDxPP*w|13EHumraLUXKU#zX#DW|c`JYmR=5xi)j|R}w^3*%gKaf`i0xmJVF=!08n&mv9fSQMHu-VIhJY~BK?qZk2I>*H0 z#sOt~)xxv?E&XlA9H`dXc9}ka%u&tP)+lOx zR&*wTKwZOlXbK9?k-!QI5UaLe65x`CQozpKKA673D}s%LC}5JMDXk_PO#)tA(u`53 zW;?bVbX-=hLyyL2;N#p`_E9${d?s-#@t6@9h_4oa_s{NLwWp!V$bBXmjB#v(fZ{d% z)XVAsP{*kN{5eMS9}&c#`v6Ep0O;K4zjYD$(Gp28wF_pyesLgTw5y%gMLNSpc|-oT zt3|gm7@Dj}R>7Vw7Lx>6R>!oqz$VKcYyq0^r{{KWsH#7&aVH=&!y&u`zz-~EnkVfU zj~;EKz&J#$>xU|b34r6e4;sbMR74>fw3ew&=kDDx)DW&L03%?@#tI_ZVYlH@+z$UJ z_p`y_FIO%Y=st-W{5l%LNr^YRbxI1wQg|EE{Ylg@lIl4dJ&+oaP&-3{`-{*TA-@l&o&+C}$n(LTju5-5YHE*cG(cgF(j30<9DXR=o zPat1D6bcoG!Vg{G%!qYz<#;GEsukw0bGb}9@z*D+e_W~nkXEzLY^aA40Sf^5*Bi#a zM&BW`KKY6K^Cj+jWP22IsD9Yx(K-N(bq?ULaU>E5fugTHK=#Q`W8Wo-x02`Cbh^oS zj^0-WWCW8-xPZfj6c9e@uo0dHhJoFEP(;2TQ1v7ulsQ=XgM$U7n|e-XUf_|`R_k#i z+cj7enjjdc_XRwI81t;YKXW+OgSzJuf(gWr0X=qwVjC*UfxyX@%xSn_9<1$E2snX~ z0Mb>f4VO%gwFUbHH^ultO7eEfkaxlegTv*;U=Hf%^=;jZiZGq1M<9^HXDZ3$HKS5+ z`y(9;f0F+xQ4V33jzZu%LeGDK!=7jG?y6TiB*dzT-Alhi9BA+m0G*~wFgiM9^6!oTKWGDISi7+^J9#T5?$ z`p`e7=KpQbIsdZhubF}iuy`!QfB*oeNfT67yUPXxf`0u}?er^?{cAA(I^YDE1pmi| z|8=zB0IZqA=WYaMb9B39O2ncf6o2IHyjBcG;j&eUl3KXZg8p96nr4%a&mPjM@t1=r;Z zb2S|x7K1(FTfI=9m&MWCzk%cSu3vRfdutTm!k?@VKjn2T8!-DHp5xc)ay`4_OR1(a zz&&5{D#rqH3k2My*uU1Muh$;^Z|GtPm# z{zk8g1ju{za!W^4 zd&C|x$NS`;zHqbNa%hoHu){071B;lthBT2wBM_=rOs(o+XNzwGA7>HOcZ21epI+Da z{Wr0Hx03pw>4pEC;QT)w7ScQ-e?pzDpg`6>F7Q);}2eBE@Yn z$tdGFzbQiLnDle?YSDL;Kg6WfzEX_LYqupyMy0fN$wjU-J=}fm;JJOc8gEGftH7f_ z1Ha`W-_xjqmN%hm0E;ZWpEz3@x8eo$1r0`VH1Y^uP_DDXLztytk#(>!uj9Us(P6IE zICAG}FR1*{{R?VtLB7A26(7SMm)WI^M~$H+VEUidBF2J}Bd1)v>%! z7K*;R&;O>?cXFqCZ;gFuXX4O~&c^(dHbmq}yh{Vlh;rq(%8A^j7VC@tSH}&vXU*^G z@YpnNaP=Sjko(DbUX{6X=~-!X2u)T!?)7+nSkcb3GC@pg*#Q(c`{<@ru>Fmz0oQuw zETg0Ou4Mm4+7og`XEvNLbX7bt$wjvp)q4B4IrN=og)N%~%a&qyZnL{uYhU(H?#h2} zi+!^G{l3U=yP|5j9PU!hxU<`Vla|MRZ{uVhqU40-9W}=7_4orl zp`9-4KkB|qE~tBEgxySBJod;p^mp{)JMps=&9S!;Z*$NcJF7?T+Pytg&bJ=E{enlC zt_OdLz2+`X^u9HxBw%#q?x|>XG{xurr*3(-BRZdt^N0KBX!u;PEAo3>y`!XlQ4SGi z70jXt6-qu9Iw;mzZi~wwI~#KeQy9-}(x>eY!^Sr3+kcvKEwpOq!M0vb@%7XjYy+!w z_HMIx3533b7=?7@^)s3opOpT59D7_cu>GMX5YF!3PjE^_tq5Mpz$(v}`J zY<)o~xYQECxw(UlQ<1xK{%iWO%q_>&Z>P>8o&_A)cxX8F<;|b!dIc)XpRu#g&%F7$ z+}ncVpL+Z1WMFJt@J5{D(zt%8OYWYSM7Q(5ap!;UhzX@%()dyCnIkm#=JuRxKjFJ+ z)p}H;MeLs&7jUV~fhrkGn;scK8_^n zK~y7EC}n!==#O*pXU%3O4jI;5n?P@Kw`tkkm`_+~KW=U=$>q6S@Nj<6|8qzADc||= z=}-}?z@u;5yfY><=S_ZWxhVPS(Gk*~qTkEQmA_}u!t31M-O_28>tY41=Kr?!H(rKY z=D&N<`b8f9H;?pBr+DJTe>NNbLrnf(_JX{g|IH&kR@x5#n-lu$mE)fl>i@nMqaPN6yww$4TJ$6pI9B&VD4?LZy<_D5L! zpUdyiF|n^t_7O(zmZOv0)pipR6vXGi#mK|nGe(HpU%jf9-(A~RJwPB3V!e;7?7O~t zn06gVv7Rx9D&^kWcvPBQV2wx zLP_?HnZ0J%A+zv=)mJA>OwI%SlqrQkZ^ zpz*K(!KBsPj<8{bgyT%B5r~cx#2lDBX~-2nyN|#Ipi^6cMrSrZw8lF^Cx`_48V3tt zKm-wyT)1gdyn8aT|2td(AV8Ur@BO0{Nd^eKFQ7RXgGm6uA$`(1a~g0N=u@;jj4=Pl zkV~4~Gj?PyYdyc)TlQKtlO&3K=dnkk``XQ0r~mkYrmc~m#-UIsy&vtfqUjPFwzW&o zh^1>B2S$WEIWpk1gwc=JHOVj&8%6+ZGTgcdSW)LAXy6BILShazwVF)=!0y18j|F** zlelm>fWjOA0B)^-Q|Q11)3)7ZWZ*kRho4oDjiLb^39<8<|H{#vrLn-8=vgwE>j2U2>Ofp@_Xs0gPZnaXNnxgxu4mH08U#Ygczg>i z%DY2$Z{dPEEUSv)MhfCEVI$;ndn>t;i+2I8ngT>@@vjx0I13IqY~{_z^J3Ja)KKK)Q^(>{e}KRh z1Q=og_|-GX7W@PnklEA-G|-ujETebE(XJTYQqVHN>OJm$7wD#PMr@I^O&KAWGDV&+)gxfhv$_(IrFZxC`$V^*6t3t>J~6clLpPUf z1}Ug}+&&j|bASBhs-N;{D)*k8zu0;H;+jh7ct`YMIR_pd&jc(s=pImztu*YeltMsw zQku4zEdeL7N}6gFMPH<>VDWfpw-FL-DxEmhot-5yhglDGHRY+3$r(3c;R3`7d<0`7ctB;scr4-db& zkS?KnCE3#SH$vBP{pz8-jJKMGu8;C*9VTY5mvx>_dfi?zuH3mBYO!*sQx-34_1pSN zOrgjVjt5fIecO`Pu&8{IgmYdl!d`-iC6ljXf?k8U!t+F35P8f+a(-4CUq_ij9RwN=Il}=G@|3i+~FlUa}6G7s;w{(pzXWs zRD@D>^DKY$!y`^P=4`d)S%kQ8ni^dOStcVf7*PAteK2GV+Fx#=%!;Dh&->wB8>LF4 z#Tu;?Bs;>^ST%fnR-Z;(ep$35C3pI*EzUsy26RhbI%VY^c#)cI){l7VB|a$%zl8V*o)YBb3dj3 zoH3p}axV6#u7HM>JXJt@IY)RVC(vhu^iy8<&D``3v1l=GX-r9u@K+aWBf)knd8)aT zK;f$5gVcKx20uup@RQM-^i|x)qdiT-4KueBIu_muhDFwD-<+Pyt;?QlIIgxDFmiJ# zEqcJZ$5hGK=YR#5z@-KqrzW@s^ik=f)?krlyx%YbMm75eTIi(>!fTU>^Pye5%Q5_8 z+*&#ZN#%C2zz;XGJJ;d8&C>XT^2yg+|M9e?L^K5rwwU?JB$nJEQ9>u*@HxLmpXuAxvu|IvA>G&DB zmdZLDPc`?AkeMux7`x5MWc=gPmO2_{bTle{aq9)+<>w>hR71JpW>bH)fyJZK_eAeq z(5BMIIZ>nG8f=qA7N#!8ucFkaU_f(XQ9nT}L@ZHk8jP2;=Fxpey+h1{25Kn6V)G}Q zjIC4>1w6J2##|W|^PVRVrcfw_1I}rq|Cp{9!xj_;!-(zO6J`z_ChE;u!$vJ$!5#M? z4UiV_td+WAT)|5v?Ac?`sa5+Tc5%O5%h467^i1?}0};)`Ysyfl=#DUABK4HQWp#Py zA+h~ygn8?2dg*h9GUDD^A7}^!0;{N(v9WS+Qwbnl@us3(;b~t&9M<;4dFr1{9#If) zRG2baUOhhDJy4D=cdG3x@Fm2vU*5sVNp*9&Ufxy5p~Y4X-?x-{KoJ-*OJCEdKK!VN zPBzaKW~< z{3{P;>FO8f5zIXAW}~EaLe3Qh*)+`df;Cq9Du%GUMs*9a3SHSn)VI6lk!4-<(eq7# z?k+WHDt?XnNdJXD+i}+s|8qf{?h|g>-ogug3fY*Veb433-EOkzZAeR=-D>f=rZ7kN zak&EjRV}NAA8lI=59R3khJ}@>9q_9ZSG#XpLp{Y1&{p7<`f#o%HqK!u!=3JKvwpZ$ zTl(buK+RqeB}|!U&|Z)27qYB%g2rgJWNbz(ru0W1=cy-+%e6NTRfWyo9QjhuP^ETv z1q{1lW;|Dql9scqwJWrp79}};;&u0LGRxFH>Sv^Q=QY?GOPYB%6~q=DDUx4)a>D(I z(RvO?NkpEDb+CCRr(RDzL$9d_r31jLwDb^9X}Y;+{%kH}#rW(PE}n5e`I;U&DB^aHgk9<03J-P z$T||1VSq&0s5jwIBXS+8X8{qgSZoXGAs|J%G!KOJDwo@D%Rr1}9Jc3O^JGpRyT4xs zqTwO1IK6>C(GI?UVE_C+0Yt!%9(ZO}f#+YeRWI<<`ZzgJ$P&}AR79$Ea_-d(Y_lxy0SHQ z-fe+9QIpkyW?QSx8*be2KEK<00QiVEA}5Qi$BjVkVlbw%sWY&(mCMB9s~RCvWnBh- zxnFnh>Go=q#e1o`hotV6WMSf|TtU@1s+DrUfQLq+@95r$@j~DFg+M0DI?`IZcX%ks zP)^)>C)GN7pjB9@5IHNKYppHqI zTMw$C8c#k-JMc0!5iv*`gbg3{f1yh*T&3Du=h@O$_I_0@dv{FDN{3* z_QLX%o%!*o{?umq1zx^SnIx$!Fly8XbQ?R%9Na~9svTNtF`TD}h$ob@FXi~sU{|*c z{OW|=aARUEwZwFIUJQvSX z1YiuLFSX-0zlnhFRCkJ0 zgijf`7d;wC{)uiHn-Cw)^!IIV3Q(Yh$7jP%bh6 zD}CA>B*5rJ=BiFCy~> zEzfRnAX0q#K=vNIM74W01br4sz2@3&@x;`;CBEjBv^W=A=IeFE>7JiJs!`Vzz^2zS ztQz5VRxOW6TnT-A``)&dg+lu3adG+z5_YtFzo5QQ3Hsr$PFV1;$9$Twos}U%dw^XY2 z`J$D1_~aU8r*B5UJ0!VLL~_Zccgj0qc))AZrjC)OLO~C=@LjtSky7|TL`k{(@!hvE zH!7t|F2~6p7e=XPx0TZownp-7(+Rf$Oy!`cU`^tj4yH*O zG*kp?aAt{NkYYyj+1*h)$Y|LqGTjaKc&ip879LKM9SOu%MSImD)MImBCYcpseYlE7 zfVdHL`&eTx*EbZOCfSiLNgDLwx zft>p42$&WdeH-xemOFWc>jD~4(L|!?QVRfNyzTk~3DDpnqpIv|#J&Iz@SVQ6f%#5~ zq`vlR{~oB-nlnx zXXk#IRBdHt-y1gqYi(Vawrfbhe(Jda=%eFhB~6ueIjnn|yG4JD7Rmgoq{P})QG^x6 zyaOmA{E2N@d2wh48o&z`+A~zJpl1`zSW&1S9!V;HJsHZ5@(?jtasY8b7 zNoC6oLh3H_{f{8!i|l#6TmgAHs{khg1on%^iSwRAO641K`zzFiY8m=3@I@K=<*tgE z9A^JPA9yg0n>A${eHcX3x^rIaY;=f;lg7%_$(5&+&^sPcV3p=o~l&;Yk1 z$}69N;f$zrpFk5x|q1?}*JlejIus)Ded+8`5SG z-stL7+}t)B{IdAl$3OCJZu8nfEkua+_Pz2{xKV_zdVfbxKuq35b zZKhp+;JN&Aj@Ij%*GgLUh=7hC>4D1p-e#xoM^MML-(LG^Qbh2cyFUN9;$)BGBpeD`9fxV@T4z z2hpw;Umiqex}OGcUe}xscLLfTxPG6yh)V^FQBZJK%lSn=aoMK<9|KEGXHGl_eZ+3w zg*k3LEqv&+c_vNHAh10G2h`NjvK(9MMfGHw$hpvr+hJhu4I?f{XbB>Vh1o{&zgS6S zPj?vT=C7*s5J&Luei@cFsBh_2!yuS0bYDlVb{zs#J-k1Hi-X2MC|Ee5lpbTupw*eK za@x29iI+IFK-j1)5yXlD!%Gw3T2kwLJA4|9RkV`HybloXgT90nqOc-jVD3)e)i2P9?$&W8lp=R7}@ zlUu~`ogp@4NDevRw~VRh7JcQg&2tkz_Y4{^E%F|2E2$jrABBI!`0XJ1Df`i#>Y=jM z))!!Wacrq(J#Q|eFL7d>gk&>;EIyvh^lR7C_%s{x{IN}MOi4~iT6C*+-O;kkFXk(= z;zS%5PF0ZF1@M~^09u+p)i^fsf~W*@*7HhzeJjREqrM(S4!pZ_l8I1UEGEgPM7gmv zL^3`&LBbsSGe zQ^E=zCT1c+);kDsxfa{V!U_mqghYqwfuc$}q3BVDkRU&R>!}0IGSRyRFfH=zHls6x zqC>p96$2No=Oel&>Cno}@+lbEXf}Pc&5|?DN z;EP=AdMXCM|P~yqqrmOq180)jMhC1t$AGkc_wBQ z;8+`Y_V*Tl+K1>s{};R>{gU_YxBR$TP3uGapEUAbRIR7!NbOF%ez%?ei=d8v3TF2a zs;gaOnj9o-*PlC$Jbzvgfr*r`u8Or%e5p;v#2Hq**O580r9PE89y-vkf)z#Ns79QL zv=bo}g$BY3lGRATC=>f#6z2YqvJrq8R2yy33g%?qQ^|kjwc;Gpsn|7bNhr%>Ysa3@jjhC-Q8%dIh;MY2qhxk@95sx1PZ0Osm zz&JBE>%q(abK(OF0|fP>TBw+o^{~y%!_ndw_H?fa)GH)QgX8ytGTw<-?=P3 z{YHo`_0a62KU^0qUp=eU8I9sUWs#Or`cTWcBv_`vUp%@s*4OIMsDEYtOIl_g#qX$T zQ@eTALUDxJ9*bSV1)G(x)TDyDa?s5Cden>?1r*V80qwmJbX3IUNyQ#rbJOF4H=d(0 z+24@XGk=y`juS2AlRh~RVG}D@z=>9swD|6M)dpW8re&~wJ-?JR>I*SAJw)tAoXJ6y zM9rR!H>$egHVQxHzhEa2dfvG;HoEt{8=fxqrCtlUJ1+mF$>K>A%UVA40Fff`mYQk~RY)YdhH|!@QxG%SHF88iRXyEK zz6302bR248FnI^YVd4F|>A016y`J+>)dMH&H5xW0cUs0@;`I0CrJHlN zEg-)a!Yv76sM+!jkGL37Y+DsZTI$(p=d*YBMdvp`+ZN$W@{b!ZsXdN-6rU)l^qtPc z7R*VrCuHaXh}i3Q$P~UCQF|}7Lww?&-htSFn9u@dJ0+Wr*@|oTL7P!7hsZ$MGBk|h zn{_ZaUf=`;iglyD}3n1srieQ zAw-_p;4Mqu;p@r0$Vqg}yA-F9=OtMMAvtlogfEOGh-3Kn%8KrJW~I&z(@x}E$iy?a zZU>f@DlSm1_YW^~C0YfK2zf-tWsy7_>@fUd3-T2HT>{chSB2Xz#lJMMyIjtJ6zj^% z_O=V0E))?+Inv>E?mER*B_RZbirHsk%6~KoC0@XF#4dAPuyg0;mm$R%V}jinecgV4 z;-Cnp3t`d1H`=2K$xk#5c+MNfaNRR$UGr-1+8JQUNkXEIxcLt2& z=}p+h_!^^85dkV;C5Im1bo7s>_y;X&rI_W|GWHmS0n^B(YnFQBFo8dPH<(*rWMk7qw_eRT+VsRS%YKYzy& zsh{L?t-B|;p(`+a#%MBDU_UY+HBi`-@+K3~d}$taZbv=Iyc5)kou*F$OmzO_pzQ}_ zSWqT)&ctZ85Q;<0P9_dtiisZo+Abg;`*SvdRwHJb%CcsP6eZ&e*mfhY+t((f-TM!S zz+$KS+JVK7+l+B_dp1dyY_nEPa{r*-H6$L|^&us|AKn%ESf0JGOFKe9f4(DcO}y7S z%FORCAbKX;SNg^dA$9&i2szvQxm+KcR{1nL*<%O^m=|{|2 zqQm@os{Q?6(lKI$Elp}uJk-eBFCA~QS6DFy6CW$sVTXx(iWUe&U|LtEN>P1><8>ykcp&)?``mTKO;|30so6wyP*aPer@NxaJ^S z;W;*Q_L`wEB}pWLvR!h;?*dK4XT;k(5~j$hyb)56Lk};L=>ViDVAq9+ygO1TohjPJ zqZjbS2Mdd;LA@Wc)jK5VsVC9$Ps}<fGJM9S=3RqMr`f&@b*FFK*ETE(c7j@C0=KIPFr8^arB_ z>63-qJIMhUnTV4U8}i8yK@Q?IA2J8urfD?^T$UC~eYqZdm!L8DJ{#JGUten#1U9k3 z)8JA&A0h^{RmE7J=>H_c;1f9ilaj!yN%y>GyK^meP*J~D5LA%gy}klhW`H2s{d8OW zX8t@F($c3gt1G~!;ZeQlG@DN&qyhh3s`Mw4P<77nI6Ck2nEeNxi8#kIW4dGK{mc?} zX&Y|X;v27qvSFRklJBa4%*I3NoF6s^@#U+Y4O34uqM)y_q!ro0>+c;OKMyUk9+TM} zaPY!lE*kl@x@ggG@?ep8&G4?vWREMUtC28iyXTGl@f8(DKRO+;MMJ?HYwe}Q{llx; zRzdqbc@jzEN#46IXM~7(Xp32kB;*fZ;x-6LeA333+P3l?RN(kiX@l0mwbqf=I@TUB zi0fiRRMsg?<)rQ>d!8KiaPU@W7tlBrBl*C@?s8fZN_+%6Wr#vMCGi_nHj-H;Cvzh(L_noqilK>S;?Qrg(NRiA&0%wq&cBDS85kSGyS2VY+rM@NU@69B# zyVuicDrCpA=7}Si*@7I#Y!90kAxQ}lTlMt$q7kRl8UL=^EFsR+bJNarl*<&HGD?da z@C-{6Q^5a<@TwX^nosrjUh}klbg6$)y>|6Uxc81LCfNeipDypNPHyimGQ-YXKJT37 zUco;5^>)s<1z&ng6*X}eR6*VR0#l)DpG-g|yt*C8DfxAyXv zCZ6Ba=#rIO{20=6cDG!N$X7zEFwb@3u{=dso)ds6phN)kT$Me>$3NIOWFNc#47d8y zrxebYVwd4Z*}NO|Hu9LbJ)7H$Mlb~f2{j|u8hOP*cUu;|3G*|x8}HPjo0@S1xE2=p-`^ zY!SP&M>^u2h}64u^Wm%Cz=AX?R&SYZe@EI#y9HBq&+8d1ql?*EJ0n7mqml=d#~?l& zew}(0;G*{Pls1BGfe7sz{=ixp5H<)%Pn;z8OUpBPGJJQ8+FF8kMT_ARD1wrU&0m+; zm(u;$Vo)`Foy7pRwhM&m%3HBYyPt9?UllQ-^)aAGjpR9y|w zX2qnS8Ix}#{WG>_;5U+6P$46i@`_@&A>8v4T*r09j`P}okb5d`6dh1j+P`YoT~0();Ram z+6By}PT(&BG#1%wTfpV3#(z82J|mQ!vN9#fhU-^m__jpDCqK&usop5;#UrFxY(N88 z6qRy?rc+=lDtBasmjybbpxgIQhHHkDY5JylLoRvzGU$(gYB142Sl#lw{k@rx)+gw0 z29Xgi?rP2;qAc%TRkl?5Q~UA}tjf2G2;A_3kLAs&&(~A1;QpSf7h;#A>DKyK7FBx- zx+o1I4|WLk@T@ zjm-5>>bJ?Suhj5uy2x2LeEI1TNRT3Px_s`(JEUKV3&o9!2qbrsI>Pl-S=?v_q{HB{ z;>^zJuCIYfBU0fa-u;a&y*X27%7C6FZIej`fHaPey7ZOBZlVJa0oCQ~Wu&5itRAk9 z3dED5Tfj^iZcqr-fT2;}+Rfpov93v;Q!9WDYC#TX_~=SFa_VI4wGFKXO9V)F_AnG_ zZ2*7~zRM(%*af;PLDHr~UmvWtYIq`|y|?DtiUa`imc#?dO{AO=*gP1G^az}}J#gE_ zX%&m_$h`f4_{K-rGVTPH-aU8U)f6}D9yE*wyt|}kOC8f5+m|lvzN0Fj^*#>19~FJy zBWf*|!BM`G$Oz%w-Gu^31LIf{Zz)D~1hRLP%9U6(G zk9s#s=}7o-)a+wZEOn_Rm?hpkrYwPGW+HaoQY7PBh7g5zl0iQ@oU>l@ROWUI8R zgs~Omu<0p2#LFUz)nnJJQ7$6g0`0Iys8BR+vhnLJg?M>O&$pMN6 zpA>=_(LB>6f!ro6Saf*X37V6(>|_Q3&iZL1kP-7zBUZp9>he({i%na8WO?>>LN6xQ zOkhKInZTHFJ@)4biLeh3W(pjNhJ-d%RB3>|>UkfzE?)1Zy;e;F?vCoX zZ!vgVTO1Y4*CXNbbuvdZbTj>D$5kVc$WzRDSw33dwPqDC@k9-fJ$&fnIDB~gdJ7bq_8n$g z_(Lb+pU!vatX@pJj9z+#0^JIgbXV-KX|xec-iYY&FfgQ5o*V#onKU_a&lz1?!MKft z%oV_fO+W5?Kb$cTd*5T(0~3hsk01OBuPP_T?AYL80a!f`dG@wUX>R%5arJ^a*EL)U zQo+yQ?@IJ1!G|g*GSTHzP}~aS<&0<}BKgly!iXv#)#)m28j!bW)a3krM4S!$jvu89Fb_%B#t(|aZ~Eb+xy{1xM~z(^*9AKkw6@E6xfqhI(4** z>yUo(xq;{gC*r1Fv{dx!1eG~0)>l#d-GBF2huh6FNAL&2t1d*JIezn?)Hb}p_3E`n ze45`Mt>7GUg9uf&LhH`}m|MYvF?+eo9EfdMQ2|$VS|;wpwuF?2mcgh6MVrNtGapmF zyWXjY+l!DDxZZ3d;3jXu}WMdAv4XJ0m^ii1RWtnw3KsUxaPQ*C18ht)$ zwRkSY#1YIm?-Qi*aqU`SRdufsQcs>#I-qB@=shtceEQ@`<(J(~JVbCu zJlQWzAulu7h)w!=etPpT62(JGyW*M7Tg_qu-I++*FTR~oc)_#=i6k;XM$yWwBAEzC zY1YBr8_jt1?D46?2k2 zC*DU<2$Zg`MY2Z|?rUhkxmG`b_fOQPPT>qonI2xiy#~N0W1u z!U9zF=vkuo1;y?~M=)}#`kS!}Y?Kb4c)`S^Je-M0^7HX26GDjBs+_<>c=l?2UQzE> z^|bSty!Ytrh<^V3z1|^3D}e}v#HxK%eAlXW1ABGFv$&Gk&TGgQYDVmr3To@4#9%`>%NQ=^KI>nv3IcG@gPq^m6vqvd=r4+fX z)a@D7#6rX$9j`LzKjoX!UJ{v1h}YwwVmihZrLVprb&{)5&qt4X)r!#$e^j4Bq0Y3v zfN%h=9~YG`xvB;mY_*MU60CUI?Ge!tFdv@r5_-#tGjqh>Y^mm&rcqWjweEk%9lYm# zCUlh7<5)d=abM46C{`M*yTlx3SG4uo(YTYRM8R7c6u5dLlLo*N#KxDw&u|cc0dMjA zSrEVlZnwLI&h}@}zL|bZPf|~Un{!pvSL8y<)x5kK`+|$G-#t!6gnqj?`!URs9dig2 zN;c*gA?aX^oQd~iwMA+3?x;3_MI&MZ*?n^N@n~u)FYRj%;yIBgb}UW@XWO;urVjl? z?ZR_e(~AxQm_56b@t@Bto46~UP9BxmbxOZnzRZ3bc_kM8)J?z^y*e!5o*R+4r`S!#@p=3s{?%h}CHc}R>FIzu&U~*~8 zZ+}s}|A<~)@%Q=#M2=|xv!(N&gUi1ay#60-o@vS-(f)^c{I7#c?ffSAj4`O9^WI9;K&2IcgldDZ)CCyql z66HX=bi87+xx7N>p?2_#o3dvvfA?@i9ayo#=RWW;P}xE~P%-B$@n(CD*z=!C>hE*+ zR@T*a4q9XuE^~NUfh+7)g2AB*8C&D9WAf=QbF$R=W+XU!%C39}IVPy#DZWWzsNWi5 z8Se;|J$Nr6=hDyOEJoM>Bb$F`{amWYheiC-*+tK_-RhzsKj!Bg7Brn1QJM-}wzTUIej^+1`Lx_KhO4##-G{JUy~DO%&(pIXzK~PaM#Gs z=ykgG3T5JfZ<>Lfz+>MD{3%S&p>r1bab^qZ>Pjwo@e8MSQ2j%To<1@!ys+%9??}IO zK&xQ)^wo!H`1U{cC%Afw{kFRVjo9h)V`ewsPVvhH?K_VaM-lz(Y`Jxrrjac zp~Rg%7ICizVf!CxSKroW{-#X-l5(QpE!1{X6CNi+TUL{{NRr;h#49KV^r1?f$Qm!vB8;t>|y; zFgI>H=ii;s-vRi4fgNi8=j`ymCxdoWPh0!Hqk@*+oYIflty$9lC|+M)Y(ZKl`}aL* zXieum>CSu8KbN@4^_#BF{dsJ}djW<1{oSQ1W7Fvy-#jw;(pM15xgW>FWz82J@4HEN zmK6J*rH4Qu=I)^6aOnNLhzi7>cMtNOBHks&e)czc6~l*8U@JVbNlO+mjiXf&7>s>i zjeiTfhK{|6c+X#atUoCg;h2|L5I)*_DP@(9*kKrVW2xLjU^-h_L~zS=+R#3e*sUEV zrc<$k>7Q?>3M06R=bqd><#HUoe3FuDx{2u78FhEz#w`V*&llWx&$ijPI)8Z|s>GM5 z)vhZe^r{Pe3u9yQimsLS{@X3*idDn?a^Z3v+M3Oj8z!g!T4FDU>6U+8{o*txR?=ha zs;U0}3}^i{zF#c}!xbVBG;wt`tJ`tN%j{PDW*f?#5Sh}joR2j0+dcKkgwJV83j3>t zsRwV)c`JK0>8nzr_6RT#2w8Sor1HtCJNwMN!uDs&)#g3en#IRS3*UCo*At!b*WF8N zr6LM4_GHKqmra5l9`7?rG*0VCO3oM-Jj}4s+#O&Csa$_fO(PKV8qV+8ClzyiRV=_^ z?W(B7^gZwrPZua;#f1dP_fT>yO?w=h?=b;l_db6WK|w$e z5QPL#aAHtKMTrawhyiDiDMnBU2vKBE5PHiPK>d*RqgnpdWVRi5e1KkGspb(-m zL&{Z?34GCW7i2`}Ez|oLB7h1$z^rBwcp`Eq`;as8iwwyKxqMe$06;1E_nMRi7NYhr zxHs$=zm}-7^216+(1=c{u_>bt~X;KB_<<76S9*vCw?u{xB45Qi9Obiz8q> ztbq?^A;42DL0T#x&{7MiK`?#At3EhvtbCH)PnX0YgL72C0{{lV4gd)N|FIaOQCcM5cm502Q1EY*BdAnxahtpa5A*BI9rXoz4noavgw>-URWf7f0Op zf>t3R491jq-iv}XeyV5fOTN}O%YJ^+>*rNH>%Lt59*uiuc6YW<)goWEvVZB1%5DEV zHuY%W#p_j!5oOtpRnY7vj&+WEBEXu-FTwfFzKmU;pL&wX+? zeQz)|RIhP%f5IqZG;=2Lmp<1Fxu0)6HDKl`|LMKsY--2vnmI$a@Ssg;1BeZY!x5Y$ z-h6ibmieoDE6XXK?+%|;tMxHoS6h|k8&XrmwwvC@E`*{(g@QZ;Eib~7L(KousP)}_ zqG6O3N1o;TffBBOjTY5*GN~fSh34gm5eSOCH%G^m4C5-8mmB0y`_Bp?VS2wCWL7>~zc&@|uy z1e^%<*gduPWek@yx^1F?58!-NJP^!X+g*cO>}cQ(9N81VnK|N6n+Gll^8uh2)H1r` zm_cwD#75C?Dt@mO75 z?xmQE$9xPs?=(K&n-JlrkuN}l6sb=4jMfq2FlxMWO)x3Cr%Ud(EC8QK-_|mf(90Bc z=fgK_ykBDH4jb=r?0!_MioLyGM)O?TiPqh|nkfUzcEL;{XBgmAsP|sfkC*xpYO5-27n7zJ^DMtJbe6Iz=;mDV(EL~250 z_Si84A*e-`KPEgPu-PmCF+4jO&^fc^qa=zsgJ_^EDYt&R@mhSkn7E~Q%2k~;J7rRy znG=#t6pxXKSz8HeS(`a$)h5@>82?&5|M+(Aroz9-IETAz_Ir2JbH_36l1F(2MhLo( zd|FvMX6frm$I$7d`ga}<<+cQe@Nx1vZQ(B~=;#Fdv`1SP1crlj{PY=>1)pd2tBk?r(jJ*eK z=gvDc;Ex2*9MFC#Mai?bdb-7~>zll%MTp%!Z)Cmiv{u`ojF$nXK+YZAQFS@E0__p>9n(RI^Z^wDz*!ALck1%Mir3Lhq19a8j`pMO8INP> zALzNO6@bcXfeX0!SOhm7I}UTiK;Th5GB~;?us8%?+1(oS z<|sFO=mMw(D9S|bBOw7S7#?;;=R)y~KdCOk-oB;50x{5U1|_Q$jhln}GR7!dKP#-s z;Mm!6$0-JVz_earpzwd8g{FmtKP)s;aF53UaVMAlt!dQ@8huDyxJk{ zD5c{qV%wbb@TQiO1ogc{Y}!~+2PsGPqg7ZSs;)uFlOPdw1$O1VWP!Vkv$!#$%LRGT z*<~BRsbv^VVUbi=;R0CbBEScBhApt&R0gPnV8HPG`XtRAn?=#zJ4$GT@mhOz+=`3A zexZ4UEXEJpvaBHhaCpt-9Qf2}!hx1+QL6YD-7s)q>c?}E!aVA@&Q5#M?SAL1%st7+ z;@JT^_KB_8FLsR`Gp(94q&dN>!@Z~TD;_3{>P0$N&0R!a)?U-l+Qn)*CWis)iD1g; zjK2A~HF#pn%Z#GG)Pt?Yd%X?p`z%RyXu8z-5z`vwkNLPoQC5VSP|j^V?XMoOfSH|7X{jzTeL>94*nZsG{De8I(yfG*nM3v=kaZ}Vwj4iZ5(=gNhWH~iLcdH% zV?w=mqes)!6&Hzu>v93}x&ik6I^Tz?;R)qD)8OeOMFdTsdCq53LzOCby>)_G!fPNIG&kC+j25Q*i_k%f@HZ{Fsf#U{q9figanIR2cG>}8j8zW14$0`ESe&n@$Uj!aEmm7?Fe8#x?@I-Ia)mA@VZOjfP_mmg-d~-DK}C=1=np)>+;@Y)abNC znb4->O|XQibf)n2)DF-h?QlNJ`z_jb{@cYRPL)Q-PGcbpMqj!bwCwPH*h>8njgLtu zifs$kkU++2in0j2qDDvgl(;nn0`UfQ&TUt*ai=}Tt z9aZW{1@VcWt_AyHr*h$q+ZVW1Q~jRDid#!>wCQ)J8i^awzH7>m=F>?f^y$VFujhX%EX9?~2MXS}^J-ZI zO~slVkXjn6KA!C9b#0w(MWor@m)84kVu=O=Elp*)n`Trwi@q#?7ujd+o`g2 zu7$YKK3xjuV8I$3EI$otV4UFsqlSSw>#8)UMG{MMk%$`1l!MA2w#minDE1nhVa<7w zSW;??xBbdN7%u*Z(2BV{-(^Y-nF;I&PUJC9anPMl!*a)SZ>OpB1zT~<^OPr~-3lV) zU+ugl06+Tfvxg2h2)D=~Ax)+G9NZ5w8=g_xj;edGr<|0fJsCIng3b`e$^B*M*8;t?6dxj|Z0&IF4g<>ej zj1U=y9c@(orrF1C{T(SlnJ5zm!ZA5%F6$Qz{TWN6`*_#df$?mx;5)mxE*!lMqy&Im z(8kChI{CCpFft5%&jt+*y?!t>H7cYg_Fy>uWHiV0Xa-tohXfAwzR3;h*m+yXy}&NG z)arJDuU3ZkJ6n&q0muIlCZ*eP63DD1+j~ zjvezHcbdJhYVQ6%QXxdDzplb)P-u_!emJ@r?N5^`C@PfHY}6}}{1742@*zS}hB8En zLlXMq`ZuEcYG98-QbGEV+j)0&lQ_G%q2j9*Ekpw;-xx)j_^sY6QMYAfF=y=N3}`NR zvF8^lRkY2r^x|bD^Q<$L6iS?h28+0#r*2m7j0Y0ytEwKrxT~pezIth7KHFk_xWn}>tGh2Epk{XvSU#$Pk$b_$lCtWHThERaQjmYuLQsHGMp1oq66u zlW?TID!x#q5=MU-5`EoeI)yh*?W&nV8!fwjoKU1>`2U+##-0{ z@va#0OxEjw~vS2>EEgIUoa(@y{2=PJsKx6wphaD)L|IX8SIf=ah}e&s;2Tv#b46 znIV~o3Lv=9;bNq4&hfi5yqs}!`rg;76z@j8iWcuT%BriwVI5#D&@$ZBnc<~ZQxgT{ z5Ev(<9w+1$tz}uAfKZ0eg%B+yNW`^DL`lk7&g`2rwNN^sXC9>%4L(}kmX!!bg3)JE zFd)>{04c!l`AX;096)<>LZ8rmnNB=xbTIr_KEY2TmMoPy-oYvI>xPwq78m*cutqTdxVK6WB7IO%vaxO^lFQC&79pwa^eCtx@U|H7FWqZlN^JMY;f34zt?k`%wo z7Y`XS@n(XNt~$*pXhM66FKr(eudXTsReibP7A0leT*NCXY|Kb1qS?N&sm&d)rIDr+ zJ~^Wq$ZEfYve10vuFo$YZzxX=$Y^-R*0zw;Bt-$d=^Vt2ve@>dq|nPvJBsH17*`Js zZ%YXfvgYK1;^SCA*mpbba@o3f4qwOOn^zV-=$N1>KO);$4NiI&(#?(81oW+VjP790 zo<*MYku+nQ3fr)yBLHFrE-b_LO()-PTfc8aL;9y58QsyMBk>F9>k?E%P6<+WSQZ!spJD zj`@a+?yo9ok%)G|>s4)wQBblCgo62nymTpJKa=9p+Cv@|>gtiQAFa*DwiY90BLYNQ z>qa#Hv`*DC^_APINl{U^n5P=6+P|GM4+%(XPrl5+U1XlBD~Ef|VXj|#8{R^z!fiJ? zxx1Wb1p(A~^Xp2JnCVnUdR_0O#KUwmC*e7EHq?qZR-%mo=g zt~szR$m*&KjcU_ecBxJuZE^=pH%^jCOo+~Q@x9MK|JnFEB@EXcSeVqQDaYc(mlva` ztoRu#+qGSJ?1J~{0I*rz5dKTBrw4-Te4{neq9vtw!PUTC*}N3_tu}7<+}&Uj!V_ie zsvY8dq`@)_F6}u+ZxG)zWJW!bRk`JKpm8X*S7fx+6}SApURxS;R-7v(ohL?$Z6e2D z24&QLaRjzu&XC_DcQC#Sh`s=UW9xM>antirQb^tLl;s5J8LX(PE%nb&NyTO9&C5H$ zx3>Tkf)>djPR*tpkS}v6zSbwyJ3Y^o{&}!UqsbYR3*GW{K*hW9Z-;()-`dB>oxiI) zzqxH){5H3seHjWy`)%t-3WWuXn%IjqruZ|qaixYAoi`IbxSk#Jz24~yMDfSj-^1%x z^rK_clbXhgcK6E*ITC>_<64USIV?jL9!@6L#CXK+Zlsqsj8rLddwSm+aZ0iM#TPpg zEN4F{!voQGiO!{Zx$3)%j3>Ld9l&A0vn%z_E;>EFLGqU_3^OR7etH#|`o3SH?`K)< zyVq4IuixhVj4ya$&;IuE3Z+P?cJ7!~3A2ioAkb!Lj|l=!2c3g#kKjca5A@vSuKY8| zgXH6AKiVCbYhF}vg$u>AndpNjw{i@6o2y(J96ry5qeTds5_!&80KkcnK4Z^6T04<3 zQwJ}-G{qfA!5c$b!MlUNjdV{@(LMEX;)?mn&Q>%KCvM1`QpC3C0r>_X;V-AGX?0Ct22@8#ZFIYMZ{q0AhJ3%*(1CJ%Z8Mlb@6>)<~l-gQ=cQ5pPN znjqRg{r;6Pw?$gO%6y$yCHa2YX&%76fv9O2;1sg6Kc|S2ZaCe>OgZgQ$3&VbE*6f0 zVYNS|$_eDE4(i4(Wd%g^E!)_kf}$C}FYPyIZ%Ie=pP|a+mGRCe$@t7;I4U z`a=#C2EYxVXc~-yqy(_q zx}MD(7b^+|4r9&nu{wrxpen;1&;Vx<(Kew>@|(`ZN7#m)D+x#*8?2GaE}l;s@zwnn z5bw10nOmTMWOJ#a?vg3j!zV_j1E5X=)&PJ%m78$S!gLSB+zD(lc29xw?9N8HrE7To z(M|r*a9@T(dAQMEYQr)mTU9EUo|h6PrxNhSr5F(D+|={1ZIkv!u1lF+jQ~(x(1yI% zOuFDS&hA2$;+#tvwn;lY!co9}sf}p4H(R8eQNwPLAy6L6O%?x0WG<@%_CS!UGLGqn z=1oB1ReVGy9s=0_ydeM+&&cWI+`02NRKlM-6c*Mc)I^#Ct^i%}%L-HURSb>f2tX~N zDVS9S&&@%3pt)aGcIUa~G9N&;(JiJ^Q5kdHxxqBepAXFRk~bG}E)v4lr-A{UW7P!h zFVf5v^UPPM#qj#gmtQsW!!*$>sM$s+V3#I2dRY&e8(0W&ifV14o@Zpw$1{ES=n*lu zdwW9Mp8l%l4i9Ob(J%bDLYaDSEO*0;2S18LaZ&WSb?eW75NYRS_2aQ>d56W~=_nq& zyJYc?6{QT4x zh?J~i_}kUNi9%t>tbj8q-To6Wh=PBogg0$KVf2kA|IVTm7l<1u_d_it0jL5{?yWwP z?02fi-9kbTK*!SoaKTe36V)pF=8GF_by(|@TuwFQZM7pg1|*ja95`Zo3DH$sh(3R5 zUdU_sU9SF2=n>knb{%9sKijSR27sRy^8dDSto^qj(Yx&*Z56NY2uOMiLn*4Gd(KTT zL4G(B6b_ET+@|L$-PkUut809nu*4n-&*CC-F+InolNz|9P!utS9Sf<5c)T4@<`jcG znB|LvU*0G&qgz-^K(reW=dQPJI{FKlK)m+G4S=#xBAT^gW5y1h1c7Rm#R8u}io^B0 z=KYivy>t6i40>a9Cxz8ZOP@kdFFvtGUs~?%y^`cG0%UVE9#$tm$dFHx0?8fJkgejs z63Oa+7Xa}~^#U!-duh^>hlnA4g~Iz50v1ntpiV-e?N5-rOWv|P^}850=;$4)C(Fh690VZ&UbLl`%BRPXqz zQD3MYTZlih<)!tqTa_!(gA7LIpuxdr9;})ZHKC3>L-cNRvDuZ{Ur?6!e7S)n&mrCF z$9Hg-F#X2Z7NY|0?T~eJZkjMT(#FMdb$+)Ya8z_rKVyw)-CDz(DoKkjzIi&wD7* zVYYknI}_BO>$huMdzvPvezBKAdB@i5I(OYXcuLtdg5!*?#Q5x!#R(oJyZX;bNv|ds zA4kknhxE~*yN%K9|58uor##W(a(|w*1J>7csq{lM*0OH%QCA3X z7Qymwm;j5cgI{a_v$IbW%;`)zJ&x^~u@#7B_bU1RwDl?BHD|#VB3TFSA=y>U;p1RGXI_x z{y+1U|4G;I|3ltVAA8X7UxCN}54`2SDJlLdZ~33j*#84>`R}3ZE?B99hHL2SIqX5h zHM;Wu;4KZ;%p3p2W7qolAFS*@zwmzrT>i6x|H@XCIwIb3<}v`66zn8Sbo|{uGAeu| zZnRISLfl>EK;M~ei6;j61rfRvq01ZY8}t3H^CpAJte+gOYs$#XT>U~e3woPwzut~3 zjXFBgx@eXB(>67NBbm!ocf3|yS+j%I?)~wnsM}MbXJ9?+n$QC!=)udXl>^3?rm#;B z94_7O+bqnOmD?Sf);;EGaE{aYuC!o$bk3Qg$*=QQo?9LNJ3UTw{aAeTFR%3;$8PNk z1zUGt8X)Ev-SY5V7f$(WW&QfDJ<>_KhYxq@QZ=p_#pIhuc%Aj24Pstv9uW*k0x3j-IYq#(Gm(kY0?Odg8JaFPv)cfI8{C&O5 zmopaxD)leh-!08o*oRYZTX-1ebGxpHHyYP+*PqarPurF%pQB}3yw~`Ux87=S?u&}; zjwh>jDM`wF(eK>r1-SK-^Ciop;G`o7t~q?{FPH8>fEs_v$`Np4~(LhZ+~7 ze%y9sz(&IFIlJQ@H%qynPH#+7O#k)C)w~YQUy|;Yx)~xT+0=99)LCEU?hpgD&G$GV z_vAuen0KC6WGJfDWOW*yxbS(?YLp&Q;dHkc>9 z=Q>{6l=3a3)KudGdy9N@;btTOrsu3YYj@_wYDYQbw?HNaJv3ZqxV58+wsS3yYBPu8p>PB;xBJmdL|USp6pvBUSe+wTUSSI!H!bpQ4+N+$4f!J(AEPmWSsN7?J2 zt*Gx#*l~tHEl9!rCHXh}>5kF=W;QZh1K0m6Li*3~@c(X@`&aJ$|JGbl`kxTemxsmw z_TP2rKlz{j-yo#=|1&~rVrYcbwYf&R;T3>Aq_1ay)wLi6+&Od2-;(Tmi|lvJF93TG zt7}QVN%lW~i|BD}4HOL`d0eyhC*H$K>7KskcVkU}aZq2+@PA}T*M4hlTKhM9h6`2? zdl2jPf1Icn+S`+RNl*T8yDDl#+U}H=(u+_uysCaN zGDP+kXV#xk^C&9HLjCBM%ReKhHecIvNj6c+HS%V)+vA5xZ`bKfZ@JxBZXS!R`?>S! zPJhd1(+TI3=3O$o61=p;c19++rT5KR%ig6#;-&SekgRNy^+}HnvI^%ZYBD!&omNwL zuKjA0f22f{&8x*7Uo^}atwI0ZE6)QDwVyNfMAmkzYGWE*HcA=~CZ2qFS?BpzP3tM~ z#ATYRSy#dtA)_>`^k_t7(v8-`XWU*A<@0zRsUIz-?zyFER8$@&m6 z>uXl_li`DQqgzzhP#$%If4-`#Yk(YSa3Bz<=?Qx&hh4JWbXA*coEA08X9OTHL&5%d z&ElaSfbRgnPzckw@!|Gc4jd|1qp%oW0eNW>hraJ;1BR+Pj?1n=_I_+CL_2ecvYSq9_!8p z4jiD|&Zrh5OduRr4kIvuKyYvC^=*BMKuCz#bN4vt-~-uBZ+ixGOY9(?k^em1iGI>3 zc7;GdVGzf01j64SnCBY?p)dhVa$^wzf9dqzC~MmgdU#bYOn`(M0caZViPEbV@>d=Q zfG`{YY=%fDYZQP(>yC`{v&$)t`+&KVDfKOPcK6y!6>^m#ZbLgs*R1GfRxvH_v8MP>{Rhh@V+7+fJF46swLj{;aE zkM5`j$D5X>qyWI*zRCpEE&wdF0#w2mu<3zwP<0IeOEDP!a#;WqF%wxzqv%hJK`TVy zrFF6q$a%t0hytt2`v9a>3Z}51i0;hJ{O*~2FCtVkt+b88Tf!~7zo$^i3I>OP?4Z(1OR%v$wJ^>M_;>4 zT=N)7YFSb+dwz#JW{_(G5X*$2KE0`U1!8U(x?3Fy)IG6002kqj_wR#IPp z=SCnj)$Y*{|LH}k`X#cO+ppcGUo9S!m|ckjrVe!!N|m~S`hHc!$_gSJM@4#R= z)BVSrf@QDa=6k7u81M~3sELUGF8!Gg@x6K$%EKNJ>zkh)&{5wnN_Bl>*H*5p&W9x? zJ9FIx6BTh7#ie~_o0guaADlM2d%#JpeDBc*;CQdw)88v`c8+YjCl>j?7rg7JR5zWY z1>IV7448J-clGsPb|#7-(L)h5B_TVV^qejWA!NfFW*V#C!ndES$9p)ez@=|o39Fj* zp8mg*sy{jc&P)!!vBa>#HDr*#wCC9|(c|(9UPe9uS?snOZrpRgRpO=5QbvM?cO3Vbe+Orz19{geTz}AJlN; zrc)YvA?QHx6!va$csjn|iMbJLAAYW+Yy)tH205@pSDns{UE#Q0HuzM{WSt#1!wB!9 zw~A`@X#}@*C`_+aO`mqZc`cxL`@S3V{jhn>v$DC+RdHFmNSEfo&2s{5cJa0tmxZp{b!kW&REYaN+mWsYI>>ogjb~0U-2-ghHC8e9yDA zMHhGCA897)2l*CzXI1=`D|Vv5)nV*i93ISOg$mtZ%-hXFrH`b2!9-Qw^gYZ%~Vs)%vi+cz)jE+dnG@h%n$C9K%lv2fhxxx53r zvfirf$~cudb#)H~Fh`&fOoJY)pS>uM34_X*)ig>?mCn$j4;LUM1Ung~!W>lWThP&K zpVT0<hq5w z!CbdOJ1e)cLvZc7&L?!N4v>{Gk*EV~_R88wD}x zAG&Z}>yj;hO1dcJO` zvRBqMOA7H-D?R7CzJc*a|9H!m`MD+-1^9FKj|Ry0^2PNc&C6v?{2hpcsZ5nX#mo5) z&x6Dbkg#MGxhB>aEChBAD0ECS%PVR2P@vu0%{YaJhut9bPp8 zxI`F*JDSLD!6{vm=NytZfCVOECl!3XHpBKUp)-A+&7u;(&vX=gNX0^Ai+&m}ry?NLVnBxF1G{H!lf2&3L%w=V(aO0Xa z+LmCi912(UmYu@L3XZ6b!9V*e`j__{jIjydeucQng6l$NeknUCX|HwFyLG0nJFfN_-YCY9%K{66I4&6 zp}my&#j%%Gp%xk)+|maX!ov%5(bbLCFz7N#(0x2x;%dFLq0BfDl;YORL(l{a5K!jn z)?~JoJA7PiajN+avWWRqH@o*h__3*zF797q35sowON*lz!*_#4i< z-|aY)QJDIxbxvW{{vFJ(a+=fZGP(O^3DyOudMZlsQ6c zHYF5zn%V5a5Dnd@n4L_vc4s5@!#as5K3?wD;1T~jRAg!tztk}bLc8HaNA<+k&SJla zEy*|4{rYZACmGo9HBOWcC$nRWJsccr(i{l7dTiiqk8d;ZNxg1wHS?i_WRSwhGwYnm zjHL>DPg>j?yJxKQz^s>)10_~W^MyRn_(gPHBTv=QPNVYRi?~SJmJmp|kvWSqJ3iX{ zTL#zLoKB+7cbVZhAoM~j7!W;`N$|YnRZA+=Io4feQv|+9%q##cvlMBe)LCPs$*j+$ zyVkPYm?;#X{Gw&J&9Qv5sklvVr{A>NrD&F|sXO*^V*d1JS4p3{<46ISCna=TuY zT)Uj|_+tOI5e}FX1Ya01UF!96mIEbN}`e z3T-Eq%L)`NaA=namebrv9>4`5um}*Z)})T5FAQpksAHGjJ;)nhCsB}+Yd_uEZU7{4 zVjyI_)$kQYfm}tTM3e?4!YOpBWW92Dx<8Yfx2gh-tWHXSGFp|Xd6cAf_N%Jj>%dJp1~X7-vz`ki_9^=J95+7Wl*5a&>58s zF!+A>D3Bg8nX|Ve9exQ{rOaT-P#yrcZo$DqmkYR!aR{|P3{A>gnC9w|ftcva+qW0m zZti0!)SKf*Ks}lPT7!z{6=kJX;bp55$_M{+S9}0dKgaIhTb8vP7)v5XDINc?MLjiN zgynQFLDON z8jF8)8*pbKSwt%&)M$2Btb9t9(rIjqVv932W1-m*2NaYShC4sPU~LHFu3d)dg8d zhxr$>^dd>&XuctT`SR(ZykVQJc9|pO^|wX-Nj)VuHQ^b52}M!1m;MJ!}?MS6~NWd-{Qi9}lJR?Mb3| zeMoa!g3AO#DCL$xmWmT@n$N>b?En0z7-kBky|06!zpf=MTmc}P+#{bp|Cy=p} zW~llgL`&p7nM{pWu1!I2Pi_)Aqz2@NpB4{eB&9mpF4HCrVM+uEb`iWX{` zoo3%CX_5-v9YDKjb=CgH+ed6Pdr2RUE$?3#q?t#VE~WHzO-p8KQU#OfV2fAaWM-s1 zwl|icvs?b9d#gl_>__thep&QHhbPm-E$@wYU9^gg?6L&Q8kny4m#m3l=MgHO6Q%n? z=2dLD(FrLL?Z;Rw29Slkg*Z&l>@HQhaVyk(7nVE6mj-0yJSe`>O8*nNk;*zc%R?9t z0&!AQ0P?bd)6|6uefK!D5?;u><<&Y`3KFv7y6T@E1asIxB&WegHOQSX!Yg7(g(92g zhD!A;)YT4bADm)3Jq#PGY4Y;-3unj3P!jfvm1g`y$8YPA$-4`)Fw&@|*x79D&J-HC zW6sjSM?EUp(Q6W)U^Y=rsns;ON zQ{}a}qxoy|@zJ(S{czr!-G@QRU=L@a;j0aEdCRynh(C~^X zz(Dut5nkl_-z~B-XInV5^Lot>+vE}i%;sV`CBcyTPKvRG%PJ--A(ms$DaF7>cJn!R z+YyFEnh@AzRKZW0xzqG=T#&VXSf!tG#wJE@z=PTi>5D)J8dfH1_BAcs%`7X*jC?H8 zIsq1#Rm*fQ%>@+1B7x(uer6%5Om|93`ksv36?DWFmiCs>`><}k`rh3lEXpARL3rtj zb7%|GK@9w98Sbh+HsUR7OgcMOcIz$EM;hTvh2fk7p6y?mtQ8h(kL=hc-*!H~`45&3 zc*zcfy(~+eE=K~!fA4PLHhiSGflcJ*QwJY#EL0lf~3qhoF_(vUUQ8mHJZ0j(t91 z^M^124nnb@>sga8cI(DGbxiD(4P~$J;Bfk~c;fuzbUI1&bfc-}@^+gAu*|Qpd`6Ns z@5Q?M_t@j}@S?Co#O(HrRRzT0^gYck@xqeYl5rD!l%%Wzu?#7#%sg7_S@u+c4Hmnx zB{6%AE=Xc~eG0y(G&rEg^Aacnm(odmE%6-swxyJ=`rs%f>{rTt9agSipD`j`i)<|V zOV~`enrt$ZBA1`QltnB=%DYsJojO9=Sg_bEy$Uam8oY9~W!?0 z;!~Y12jO=IK5QflxyuY6#U>75)`A!C^c|Dg-bZaX+4ht|#;Hu=Yc-B)_Ok`cAX=_q=v6S*FKUKb996MPDRF+jEu& z-j%kH=%5vSD~*(on_e*a&E&qX_ee;~xTp^F!kG@CYjzpct=0SF2^ zPen?ttm$LZCQfEe+z$<3H;0do8`a*r@>V9z0Wk)Ed_mZwo5#2K;+7Lr zYnx^=8jR-7jBM6XO4$0RNtyGoTnGu?PnRR6J5)}bU#L%<*oOtRJh`gJu~(BB#4}!D zI+pW3)9M`I8Q;eV>3lC!_a^#WXWp}{9rnGXsKM>k>or(z>o(slRu#J7#pEn0(d?X6 zS(p~HSyF~Fz9B!MmH};(Z-x_2ouSm@d9Fi_i{Fgf9-A%8)uPp8G{7;te#fLUp)t~Q zhU20P%IiON=0Mv|UOw$iO0hPXbQrI?qhTXs)0d<6@B)`%JSlI$DuSE^pXO z^!P}@!*;i-=zirNKhdfMtF1JE)Cw3hn=|;%O5Nu1SRwn69XulBamsC9y|B62`fNNn zW(S%*|Kx@9xWFTEPAC*WUP*s6iXB?re&2GRS@Ih=#-7>H9X$Cd40+ikR!R~Pi3e>( zv3p{DcV8XqEs$>z*|#$f1lfKx$=q4;2kBcbJwInK04>X1c@QDBc_c{5ye&d?ixS>I zLv*LQfEq?`yF{z%)q{tJ4jIVH1m=?cPR`wy5|bfr`C7}N!S()eb*$_UzEREBa#*<@ zRj$DuJ|C^+s|A{KS{*JhxN8<6b^iWMOe1q-WhMXnOEMT)Jp&J!n72aA80PS>de0B7 zhH$3K&&2y7TT-Z!xTDu=9akJyz;6rjqtTSel=G#|}vh zXB+D(^!WZt^T|O!7~Y434YpEoAtD2uu(NOWX277N3?;GREqj^fWbjORP|05Dc(0x% z#WgrVNlis}Wd(qw{U2gWWel0Kx?CWFn7_QhlfQx@o7l5ZguB8)-uqW8?~OOPb}JH; zj4|jz)H&SD+3xuF4A-Cyik^YLE9kp$vY7jE&`xWVZpQ?o=MW(t1}zH!?SUyi8df5# z?>);Lr$i3>uFI;8M6Yp-qUus+son||J%ejhvcmuX#?C+a;!D<-xA;>iaW!Iso3c4O zEMj8m^~|APLz;@RpvgyDt-AYEUY0#GxLeNN#RCP+5jRr~`8xwE zi#e#kTpHg(G!Wu+uS6y?Q`Tp(zW33&1k^^!JbSrJ(O1#;#LeC9osmT_n}!b?CTXVKOGm}Ag1lTky_yK9kl7yH8R zJdixPRmZ(KJCaI^qYmX;qGQSAU(5k&KYR3vmxS&D`S=s^d_<^sd~jY<*O}p1Z94Bs ztdKJh%)j&uu+=}bb<7%xW6c?_FmpqRHKmhnaZwDr&n3;EkV-=WgJyzaXO4ba3GX>< z;r1=5-K#d&qh@=o+ zRJ_}Tm<<}}rN}p2Xz7y^xZQD$tUm2DbYUyeOkH~;2IX4?<)!U1RihEHV>p?{4v*|Nx_Qf ze#&KEsW)uJS~3m_7qWW_zkn~=A;e>f z;;PkL&`Y4PfTogbnzSYTd5qCXWxlvA9N&#Dr=WW`Zi_+H zyu~n9`HkOdBg@_oUvM*&RjPsK{lC3C` zB?gH}VMNT;AfyEoBVw|ZX)v}i%s9{Ee)wG1b^os4_r4zY_x?T}_g}xi=RD41=A7d^ z&f`2Dujlh!J!N%8Tz$`yo06NdX+sahA{aJIigT8AFIyzDK#wjn-d;L)I!H~9dj8XS ztK}RAW>;j#>%>njy?Pb6)qz0LrD3Vf*Mo;P`g^`dt4#jqN+mp01Gc>sCy~|s;zEGQF zj7v~A?8;OwT)UeQWCaM|1Lnq^ZM=oSm{N0FdK~|~<8S-~0sMkUTnF@9pvq68N}{Lf zXm;khS#s%o+2PymuB6XIU2xo3yq$w-I|T280$D?*tex#%bFBN(;Ap z+wyToiFF;ub_fjEv$hBV^Gdz4$-#y06#kH4F2-hI)OFMuLq#G|TVD_7MI{3?h#g>p zED!Kw_-y_JdlM>mTW5C#o(!RXwun*r9If zZq0MD3WLEiS<0s@)Gs~1M42o^Hm-@;l2oVjajSzwnZk6V=|^Ru=ZzJ^F}&k0*HW*w zI-#_j;q{kyN_&4d^OYTl7EitEf;ca<%(#~vdupjurAs8OB2{3jSs=G_2WJdYZLSFO zxq3;th+Dg_oj9G25OV6Z^`b){z$84Db2k7V*JMA zX*Qp%02friJRES(s_9@^v3lAqg9qBiQ6_J-h40+N1#9JH@9{5VuIQ za=cK6eFCYS_ea{R+e@p`<@jrrPcHpQTQ9~lTj(kqldGE{Ph30(zY1%xc;{rZ3P+;? z%he?uUA@OlaRZuwJyHRNim+K{Cpt7a?|6h`W1{Dq{<^V+>Cju_MUw3o!b#3T3l`35 za@IxCqJ330pJX1cWd$%c5$K}wB~e1 z*9-dGrQy@g4N=aSa!|75C3JLf9eRYt!Qfjq57aq(qEhAdjf%B*KV1=$f|?$SPCPx* zY+@{5*Q*(L%#{P4GwZlYg}+H)TRr^UfI z|CI2%eu4+7Kx$gw?ZOPXVambyI!n^5VeljtJN?8bu%5Ftsj%KXDy#5S#5po!YDQk+ zg=x~>+kfo9fn}X0%v#e*MW2_Sv8-&J<+!Gq<~AM^S=sQMTOSe>rqZrE!{;{s*pX_GUi#U0FfjL)MNUlpetN>fL384^(bMw33mU*$NRlrMVn@O`@lWfB97XKO3;EazRE3F z%*A&EYBG#AVFC0$DGtCX);5!HeVP$8jfO6L9Nk6 z_mmJ7_y|;orPFd9z)Mrg*Vxk!BbPRGwN#U?c^W;k$*8zJ=BcN?|L{jkXUw?Cy9;WL z4KL)PRbz6NFA9(@e%&9ENPnA_G}OEaO-u6?zbabl+2)jTA5cM-PDJHo_e(e9V2SHd z^ykY=fc8kC7qmTuIwA>N@HAx>XVjc&-1n9S9@^i}t_wxZ{1Ho=CqWA4KhyE2jU#g; zAF@9wF~&e9XB%VXT5Brpe5dYMj-dOOBxL^WUPElvJ$PzUPnaiVWh+$ z8d(k+V6W}Ygh&)>ZdD#2%|=6R{%mxo-q`)@9v6k0)yf9jLwoyLTh-B0=DpysJ=MqzaVVkv6K30@je^PUy!^%sdT!%S?O8aj5k^px45?WTJa z4!txBUgV~9;0KTCWnB7Wo8{l94lM~yU)~U*sPe`5xKm|51e+tq%iDI;p0PPhkw%^# zk(G6haJaJcA=q-xgLL_xw_^jOissyJZ&g66>0 z%9Ob`=E$`Ibb4;(tK7t-DJ9jnZbL4msfi;mdoN5iuj>znX`nAOe+zSaB=D1RMaCkQ z=TVQJLa9-irI0{luR~ClE$ZzfOhALiB%Mc5i1+tooWgS+i_agZvgfY8;pcf@C@A&p z0ntF_>QRNt_0)ipT{ZVBvx#aLDp|0uwx~ud@YSGZHOz5|!9m#3><59j2z+=8tHVS| zoVvEv<@e1?t0Kso!~Rz8)$UaCt&LLm=O`njP~7Ouxi(_j4T|gM4(~`4&Q6YKecS$! z7pFgdxV|LWU>3R=zheo!@nhtXdhXkfWmwY*`;R{D?YPN+dL2ws(GW;)y?Lr=2LHM+ z-XNX)DVPdhR3Lz&?rXyt_JAyCRNaIKdm7UKP3>=8@eoISM1AAhzS1}7;W#efQqy@` z4_hI5#FQWy0P4HNaf*pT>L?i5x0ItBJ-LVP##t3M;!-tu!hIdXBa+@V4`l?L=i9N` z8atYhJ@c#+sm`*Ig$Jww$bB9z!Txx1H{X6Ai+OXJk`2^Ggtfav1vS&;f+tF(L&VTn zX(Ql2jTQ+>K=1L6^-*?M$LELMewdMP`Ix%&%>8Mvw{zl>QQ`QfMfxFsHf$cFFuI$h zcW}Nx`XzO;FLqivMP%agC6!5qM1Qh;DC%U0`v;}xa=t9?H^Ub(-p)p8#5RRxo_YXg zE-PwkM%45&-29uDI9+hmv^^^BlA(L5aPR{BdmLGnXD6?EZ&=;P; z2wEi^l~pjG4n_5y%xniSoWv!Wsfo&Nl&X81HTK-gXT47)W72+gZkp~oxf*=<*e{-4 zlE?Y@Q(h)M2}kcKus*lEjeqY$p)9AEqo#gF<_~vz3ZqjMrk_>Z+RU8}H<>?ettasM z(Hz?6$YtwO;#cUz%&F0y=7qt)?qdA=OXtD5EidW&elL6*J0%tS&7TKb^Zwy@Xy)f> z0-y zWvFVNX_c0WQ*?h0N)wbx&lKO$wjx%rzyOoAS+CM6FEvx+l3j0~=N+PX`FO@!9>qjn zph~7YMrOpXVPri8AqQN2z`rK!pB=ALvm~9E6ZX{Dr=U_y5nZZ@&5=nki8ftNRo{P* zf~hFXimEqBIN$Z^+zr0Hyq}%=kKhFcC){oRAlWqoYQ=Dsto^j?jHkh2)CX-Cy8aD0 zrYd4aTQjE60aG`Y1P3eb#3Du~JHV>TAfd?65Q59%1Fr!2b7`*h_sBF#X4)~Ub5JCS zqG;?#aiWI1Y0V4CSxkv~-Q1SgVRk#HC=F~zBGph#`Y+kMwmM(z^0UesB;=Y`uk#fm zvM)3~2#Mc$en^}E)R|Zk9WVh0Fjn7qJI!-VNPWInF?nuP zeB{t;?e+VoFjul$%IR0YkkdBzb<%Rvp6S=;GWO&vEOl2N{SffbRQ~U#=nb)Bzt%l9 zOO3PJ57n2;XW9gPHNy`)xc$eDG$8*tr0B`54wrj>#&rVZj5DR}Sr66@HTAhi(jp^! zB&AqZ=UH}bAwl|#kHUQ^PZ#k_bXr&T)2(%b)w#tY-X;LBw|X2buJM!zN0^0_8gDHd z?qAC|cz0XRcKtoaI@Exu@DgJhuYXB5VYfpx%3|}P_d$0Dl@#zXQG%J)jXHSwqW8f! zN4ht2gtBn_g;Yt4B>uZ2WC_K;pT1C;p(nphK%*l)?oRfnog?#Rc7IQfyX#5K@($L& z^j`kXkF?VE%8V(cZBow#UiyQ09t~-OKjS*3y$_yu*^lV#y?vz2O-15uOt<5?1AqIG z@>`+DbAf!;Ro_BxCSEMViAcH zOk!t=_-3wI%mi83=Y%J3sqyBYah?1B*pcdpmJ$;uqj$=Ws*%$j&{p-O39?-N3>l@{ z1?nlkABWZLW`B^n>~kw+c^kjjvTL-fsWe7@#$oQN4!)s#T*V{hijnsru}J5POkw9| zM|L~h-z6vjefZXQV{cj`@#|%;4gN0_6h*h#BR(a~*327?+19kwjZ!`THNwVCGbLSR z^V*wp5mTDXHwRB&$&;o>gV7YtM;hy?G{Js>S>fIdOEN)^Pe#=w|L|nvE=%XBQPM)2&9CkGjQb1rHD6Gv6K?J(&CwEBYoN zwFI|3n_~XLeOv)P|0^ubQVg-ax&N)O@0#typC&%^6`H`L|Z)9dD){nTgcG=4iWv!hJ5tsG3|eYi2e-#`+v8# z|8;`@Cqy)wdf=omPIp~quSV~xX1`7KSHDP&X}Q-0JB=UxeOTy?xQ*uSfW^eS*F8N+ zUcf8X15xvx7^F5>H{kY|I`X2@p0f$^@1A4Ak zS-)TP%Xu6gxlnHy>3Sx)W^MWisr+-{83CO0)zO#zyO<{?tWPhNANSeyJ}xA0M>-c|RY`mOQsl zp*AG=!{W|Ma*mF&(#phJf6Fs}bc^dgx!<#Y?!dfwRz>pmuJh`D*lj-)GQ3UY!@HapXcr5z5Rg{v01DuKH@*Zz)*@SNFmmR!GktV>6xSHtgefY`emsE)nO z-3Eu-CZtzZC015NR~~F%c~n#-E^r~jvNKyNzv590`>^Q_oakUje2>R=m7#D;rIYDZ zU+Dpo#R*!wMZA;FJvh}E$QGH+`_XN_+`Ue#wtL|5b(~anfx}%jd%mAL5Y< z4F^8I!wl_wmCNULc+h&za(L(U=TYU{ooe;B2N=Yf#Ku!>`^dmkqt{Yb-ccL(i8&T! zvs*s<^c}#yzT3(2ZMg~UZx`@rzp`jHV=@@37M%R<)0C`DO)zAn{@{$X9w zpY~Shne@-t74@9I8HIJemVC2ZVk&vRUGhco8&QWSj}lzzZOzncg9h}=Cte%gYWnkb zWO$Nqlz7~(+vhZI_p2V549ok*vc3^0+IBMC#3C>wVr^Tk(-Db$pM+fV<626p-C4nu zdeyhTKk_Y=B-`Ii*{+g%t^agx@Roa(2cftBiMQ)0#*k=~wZe;24#UJAh zaB{kWVP!NsbvNhE2Q%5n>XynKHv2@Crq1rs8+bqz$~2HjHmk(KzH7B5p8nqnufb%U z5NU(zXMgs1-ksM6F{iAeh++Fm(pqE`!WJo=(l z5qIJJR#&q|v&)JzTm)o0))t=qLobscHSl-Qe9^^bC8_tbz|Q(h zo1Gs0hvO~|iyLnCA_cDGx4x%(X4jP+rCPjubBxt&o&31#82ntShi-IXsNu9$9X)nR(LO)-VQrY-oN)1_Ryr<-s`Bgz^7(6bq}0g);lR? zJ{faQ;ng#JS!SlP(Xf#vPYcb&;sLtuSe{wtK6W6bKKCW2f|IAo-9?aV>dHm;o zNzD&20rw?P6G6i3(-6f^=dk!^WAv>}4BO%J%(vo>GO?+XrrE<-x#AnbA=pgMhiTsAN)I^*N_?=i%(UI}Yu=rGR zM1JC>#Pk~q`aIqt{%A4yy@itA)3k)iWPl`pWCA?E7epq(0}su}#$YC0h6b39-OJpo<2WNQ{^epuq@M{gO&e5}6Uw^Djc@2v(rUIA@7zDeMY%(}35>WyGI2b<6WCAb- zsDR3HCow?m9YCwba?3}sRER3~%Iumm0%AG-AdMQ&?xwNjys@NU`;T{xg*-Vd2283! zxD&~6+I(0e(w1Dif2VQc*yBUBcIY3)g4S!zU+ z01(h8kyxFK1=29Yc=6=nJm8XqoWKYG*kmH8b_Li?O%?^|FADZ25SX-RdKn8q5V@Ro ztRHeeV=WYmuvU7GAi85XoH`AQY#yNk8r2$x+(`f?v7yb_EsHy~f=0sv#+EoC*nSIs zYGHgLFu1?<0fFUS1h@c(AtqpaOwa&q1{18*J0M`t#0B_&~I4rPb-rw@V zBWP(V-~s}63Ia%5D=01iq^(c4^7jA$7P5uk0Kgb80t+&U3=n<10&s6VCeT`Uh62!s z#SUj+H|wuJNFN)>w9Z2>VxMX_0n-s_L)=y$!3=<0@W9r#YSiEiaq3Mq%o!bb7Go33 z+4?cGp_d4W3npUzOie{qOaUOoz&b|*ELMmC0GGqzY*km=63Q^KLRc&WZ>m8gK;7`! zVb&lOoA39ko4DsqP*0|5fA=(WTX!?pAI3LVfB50kTSjqJ3f%~78=_pgj5BU#REz#5B@M zy;^XoQ5=Z&Dx@BiuQms=Ai8|eXg$mFd|%L*PgBsCV$Q}{>8e!N7|`Xt);TR;Z4gTj zBv}EnVB_GCB~~EQkwl=nSOY8#JpK?q56v6gKktOqb;0ixHFoe(b4B%t%1JQwg;?Y zjNb1ixOdUrbj0Q8W@gdP0XKYbf#psared}Dkok50cIuTwN+uKMvElBlR}n8Hh7w${ zR6>9f8XaKXRbHR%TVK6k95s}y%~~ypO)N`rMMp!chp_bGp+nnqv&s6>$M`>$E{`Wb zR|BZ{E_9!ryu8rtoI19KunuGk4%u^HEf;@O_lF&;;#TELXkpGR1mTCbsvE#efS^s8 zLJTGx3|I(>2F_4(gDQ4k`tx)?1+(&Mw*H78f#=ioH+i0MH)6cW*w#k$UA^0`uOiHp!r4Of(t5L`JEiKMqTsb<$pX~u=Qfq@;tSvC zya9RwvY&(o){L(Ch}&*IuJ~~v%D2M5hDCV%>$O&l_tbY;vLJ81CvSqjjePK`?Wp3s zNUG8SHy%(wBm>|PWe!w9z_rykuQjW266_@Jg?$k?)?PZ_W1h@cUo;TZWYXfE^P3fg z5YUTYo&dNtwKNcvs&s%aXt$-vKv1J3v;@S*<6@UwL#YIi1OVI`HM%&VL4ZBm2w?gg z)jKt>+6@o@iQ4;vRPs!BOkMYEdoDB9jRu5NbrEf%OIW^~OBysrrMUp4jr5CnXwtEU zPBWXYwzx1#bp+f|KF0MUO}^h6<1qv_!#*?z-aywp8D@H|PYqX((VEr9?V6*l zQTop71d~U}b;Jq$rgrjmKN6@I>ymVdjD$uQ-0_BiK;;F!Kzw0MqC=n0>^Bt?%Bgq4 zpGr#3Awe=OGou`_6Tloz3qz8TJ|hVI{sQ-YyXqWWMzFGf%T7*Khq*m;+TZ~NTjG<#9>IU z^~xHn4OHat_G@}%8HFla-Rryi{_cHBQ<#)~{S$f9db{oB?~9OAM0=aLk5rzS76%F* zEVx!Q(-~vXJdZg3ysVXGye-OCCtpx6%&pWkr?EEkMzWIhfRKF#W3?wJJS!9>aV@1i zUjp`hQ82UwmKdCU3&u@~e*Hlo?iB6)jG=h$^l@39l(ypbzHJG~ua&?aP@pVvyNkl7 ziz!-|o%WHUt(?{qxVC}tXc7=ce`Wkxu8(P!0}MWw|W?zPVKV;crXT-q+cI(LCzGy8n$gUrUui%7>?oPPfZrk z2L>3@rffU16(co7)`q82!^(%l9p)~O$Ac4M*&7#z~ z+Me*yTD4C@net1V$>yc9xXxP}W~Ca8GR~qWDn-*d)r8N5--_t2K=%&^eeQ7si_r`u zYYbZx634qLh9|Ltu_wDgBCA7(^c%+ER>exCF_*PHp~68zG$s*H+&V0vZrnOT8nx2{ zC7iiYJ5eMda%v6a`cMeUn}1GzUEQAh28_v4(b{tBSDA0v`3s*lq8 zlAI4}v?vt~RQR!i{@2BLK74J-v{!2@#}|fsQw)uf`(JqW^YjR6nyKZaD#&R1es!;J zU2C*@gem@+BvKI>9zCP!vY`T(P#1?krAFcRmJxGaKb|li{ zZrJ*d)(|e-vIscQt4r&ljF-6U>~>OqG&_O>qS@ov2uj0ALbD9VGKVx*sqTMv%R>)O zPN5=7W}|{0*#~#Qt=!QS9j(DIWC+H^8_@BeEvQ5Lqxqm1&Pv+K>BPEFn(ckkn!45r|D=)&``q)^3fOM={E}GqBw0XN zWM4c=+(hDquJwo~uZVLRe>*^N#J6?i>okASu$)6grh@Th*jF{OiJ5SV{fe;Ni=9h#XU_E zJ!u3AfZ9!M-&I%rjHDQm` zkaS;O2Z6qOQ-WF&0?L_T5`w<3H=} zWx-5qR1^~eUBjV_xd-UtPdjqwl=DU70*%xQFr^`q)QkQ46kowh!!9NGiTCeVUEG}< zx}jF>sLM>}yt|#&Z(}>c#oLag8e*!(AbaxG&l2Nb*|AFwmIW^eSAUa95|bD{ z!E{T`!AotnAqNV6^?K_lBA2hyngtDw;pm!xP;Ml6+vi~3475l>^ko6TD3!2+t{7-R z&}AZ#5M2Ani1_a9&3J8NE{}9mu)~rN9k|O}4gncB(%Mf3EeQl8wO=3(^w;PIo`8`g zNizaFzb|%viOAtFnfQ?aO?>;9bsMQBnaCzmb%V!OVN*^-(G%+E@jPHQCFu(RIO$U+ zZI<-7>jH?N3DLi;j*nN>)s@&*l_jdI)z53qC(3|@+5_-cWg2qr_6%4PS-CN0olG5I zGTmDE@JGM~W@AbS6w}7P%1$ImYG%D$$kO*pH7OW~$oDf$bgUZ^KSdVJb3>RFV4w&A z7j=wafb}h=T$JeW@9>SatzY{RL8>aJBX`?PSq)}|4Yo(;dE<8-=`hD9n3N|k+%$Sc*rvbZsOn8sJnInJxL?l4UE@;%Q8i z--e3~jR3G-pL>E{2@PzF6S+DX%%pRsvz&(SW{$AeMqEbL{i3N&S6dW7Dj`HJ4h$J@ zLZBny^=ZP)BN?dAAAp7P(m+|dX!*1A2w$cuI_E*;=G?39C>{%|1PNZBxZTc7&MjGw z#K#?>r4tEra)Pp)&AB5KI}Hj4*|6-E7LIBzTb_D#RwjDo^}K1keNJ>YjcYDc1MqU1 zk4r?-MWk{qcuICgaJy=DQ>T;8UO(d#I zBGL|m3GLL}wXz_p+2q~PV!u~CpOQCef?bOiMK>JQRxdyu#1EkhBL71ERrmxPL^iogW)fBLoXX z!bl@Oe=A|VWsQ^yxLYsATQ9tapjVt79z4vTAD}Qdvdow z-uylVQ#zhg8r0|0M2UE-awguE->P*_EL=8Q$Og{^%I@&^W%|;~W}kTKriYPhJELMF zZO{5>&5%F^cQbaXVY)1x7cJJCBnZw5uuT6 zwJf8Wm6va3ryBy9xswLSfjru5PQNZ0!WV*MDx921BZ3J--lgiU8jQ0(Jbs5{pt}ee zL0_Txi!w{CF|-z^)s=A~gDtNQ-w$x8MmKJqn6aZ3YG;5<-CCn59t z6E(91Q>huQ1VYPhcUMGI2JqDd_*@v&A9R!F!XPRncx~ku@ViT@Xs`~B&;_r$5WCo0 zXJKOuuXnB(yR1M!#P+Ct(wRHk`AS^ZGklGz078NTwZt_#EI{K8X0y%o)BK1>W)lru znUoZdM9r&C9QsBwNoB7#@_Ym-lGxie7hrOKP{lK7?m|;a8Y(0kix6sP6_Q#F%wZeZ zzAHt%C^Kj0vOU3SpTveS#qZ8m)@M5$=$e#2k!ZyO2CS5pzkk}#KYdGs&sT9h9jdQn zIu076WCPWB8|7fbizKp(Wn6IQ)yy(`TaasV8*&-RIOR=Z0dJ6i34~b(E5Q-fO!I%1D(n`C8WX*gu;|BtSeJd!X!DeHn zQ$^v>V1-%NgWMcCzNi)d)F+otUmPSX?M@5nv6523=%9{IKA!2VpxE9tzlc83+nCl- zq8FBL_4WelAa%&`VNnj9(no5&`rd6$gxyg9F^+I8cvg@@1Vh zlcLQw<-9rQo51Z##P7i*+FAq&%wk>T&mOwHsUvLO)lAK0XJve$HEay&iBG7@h+Yqya2xtSSh6iE^%IR!9vPd zj}b9JQXHTDg`a|mu;Tc=-Y+gsobQhXXcqW|984TAo0LlRQQD{70Eir`_2AV!3bb~e z6OLP?QoS@I*$0tGi83fxG|rUFDU!S z`I>-maXUXnxQ(hWr$}2Xo`qgShtKom*Wg98Jw`eL%-z)AU+be5pE<;ck&SmudfHsl zVSaSjY8Ms^);y;%c~NE;WJau`=e1{LhfGc6@1*gamME+mE*qf7Ta{Kx6DkmWCxg|DX|bFOECY;MYDW3Sr&J`b6Ey2fM2+$Ry1O{G zN~mGG@8gdH`{5yZF|O&nPCnPfc)aiJt>tYZ>kyYS-iEZf+_lg3YnoSg`i7!>3Q&E0 zxBP9zn9(J(Z|8Up{Cph}A9kQuu4dzVZ0%#UlP zJ3GrpaBqs7%?e9HX2@U0&F}1u3VWwfGV0l}_ZC~e7!xz+(@j67zE9hP6MkEqY2O^x z>_?>_tIrTnQ%^Ff>P@*V&NM=TPR;9imF$o-Zbu1gEC^)Y>b2auFKodl zl&sZ4Nc4{_zx$U0YB1ZH)TyyXHvc*{O0x!IiU4lRW@3Q+J4?-%;J9HH`h~FkFJ1Pq z=Qfmdf7x^ZK<$YQx%j2JJwWktxb5rQteKRBDqyPvFb97A1m*s)p4D#=8Z63mB|~X$ zaAE@{(fx%6oV+f3$Cy`Uf=47~De{2?pC~{XlHRwJ*+jHol(5*I;#3;(zH9HEmz9Mt zp%x5h!2Yu^^xK)~8tn8N^cX_>a4M$vbEzY~%7+LW%V=JZkQO-*yk5_?)YqA}{h;7f zI)Be;;)qKK#X;ESqBtgjd@-4SmB|4hw8HWJiSlr;`pnfAU$saU6eP`?T)){iXC8P{ z6C~D`kNUpYlZtP5^HI((_J}``8K8Q)^WtVxD7X4&28qwYwZTf8f-(zC7*Yt(;M+bt z5cNBbFEwIc6iVxaCod|g&vw^6@zg1kOe~AzPDv@gr(B25GK`|W)&D{Ead}DZxFTMA zIHF2XH>SYPDFhuH?XYG%oh<*Ug2~br!Ss3dA04+5_;~F$k-Xbs zm$2tf2Ri;Kv8RbIe6nNg}<5ad0?H*o{YUuXJuU}N|z$>b&+sIDJsxTC#U{uU&+qxM{=n8pGq-R)47K;xV0TH1>O=FJT> zb=@J9;wEKNC(iu-D1{T1uVMK_cSCd+yH!col}<*9fOcQ^7B-oMG9IsDtx#eWV2E;f z*kfezj+h27o6NWKSMu0)&ux4gOA~E%Po)L~Uk5fDR;I4{1cX{_i#z9<2%0%g{gXnl zdNxE-gEiRqIU^DK1Ou_GsEy(8*p=xMItWU(tzg9O*w}c%^;X-VLD#6;%3_NT6Z1zU zePna?CFT1nSL1{#NL^|)SeyEy$+yB^KvBV^)U=K>nChM%&hgZW^Ep2`QqlUgH3EO{ zqv3i&LD`d|b?3~EcA7+xFwtAi6tbme9Xe|-?)fwa$pM@?*x2^sV4xz!IUW^AunM^8 zwO6Z|fA9RoS>?A{?|Ap{^fjfV%JIGL8i2-;99KSAx!RLAeh04vXQ_67u!Mj{ALbtw zBFxTS*;i~Ck|!gGx+lKYTv%mY&e}UTARH%SP1jEy#o^@oFfW6#wIwt{(y9m~cPTO2 z7T}hIieDcB!EFr$PSx;OSJH)}7nD1w>>)$#H$n~D@@2xE>YHc+a`OSh@%Elq6h@@w zK#qsTrpY?QfG2p4W(vFAnkn;@DnEJc(Ol)%dk!CxN(^LsH9rNfxKj4}Xy1Q7j(;7A zNjASflQmhRTyAVvsCQLkAm|b1=QFZEZe5u3#KQo^@cPSEM<1u6WNbGpT!M7wnGg_%q`zaQ_nnD=iFR7LEe}{;l=d^Fi z-ZKP&JVj6SP&$epUeX0*zBEh!c+YLZ%{57u%01Qs#$?oe$0UG~EqY99FV1P*+06VM zx2ttjB99jFJE#qb+x#K~YZL>a3&z+>V*GMDZKT#>W`4~lq0o`EIZg9-2R9BFlTj)Y z=rF)1x-h`kc>8w8a9ZotN2mt8Be@;saVM+|*nc6lC*-WyL%&^_*d^bLR-FOci(e(7 z3DUc5D5KA!tAYu9y2W=8%aAND4v$dqQgyg_yCIZfHuhY7F0^x7o&6e-bB1HLsb^US z7FsXFzOl^SjD6SyoY&UsNfAC>yo@GGBDlu5>=N96boBa>&$lxC;`;#4BL;!YSJG~) znTbh6z>+_l@%h%^bG~`~T}e4#n=&|5*6I)ilbF$Pxd`kFywo+iH*s5?Yrutl7_SP? z*f_z9_9>|Xn%QV^qmkO=b*vO%M1|$oRG=G$Cm%hZd4zg#i%LJr@1rG-;SqP!j7Mo= zwh72}oV~K=owBH*s3ADhnC~ZI8gHWM#hnW2g$k28PQOb`NtN4snrt&woJl;#*xSkZ zdO9ACSc@~swA2MJq6u`b1Yw;xfB^atGT(r{1VRN)OKE*BozW|Gq)hHPfNvxdx^b1# zeLXK95N(CllIIE&#N9e9GBPrS-Jnfx9x?Zmf9x29*!TX7`+aiwiJR{gqX^|o!`6~> z<#rvclw5vCuW23>Lx{oLR8^B&!U6y;{lTLy$DG(fqmCmDq_-L*1Q8o|*+mkZd7vi# zX{7gXSb}LFojH&@(;g5D=Qfp=*Dh{|V`-Mc5OHYBRmxuRHZ?GK#ka?_?U5ZPwyglr z`XfO32Akb0TMeiX0fy-KWPj4+2|%?XaX^g*lE><^JJxd+JJfrbWOI6~YrNmL*e ztyutsH+1?wuR_JkR4WRTw#XUFkrZ9EiCs@YL_CGxo=J}TbYif_rm6&bf#yLcL(C0v zCU}Uhp-ekzJlbJ@;BXqFFGKAnf6BL0MTBKlF)U{Vr|0rL81!ZkSl(VWDr>BbDYOj@ zAhRk20LH?=_^?xYMr_{RbCI0I!TSAj%;~d7*Q)SOt6J74|_t9^Pmj? z5)0l$&Zhk0G%TL#OL|6xFSfEP)W=<>uu%VrSQ3do5DbyP0Q+}-C$yfjO2Bt2)v7(m zlC6|Rsq+b$R(iNVZ$nqNnkLLnOImNhzx3ufi@2qkyJ`C-_b2VHCi z5hhEAQZ~1841d`J0V2w3g>g6lxI=6}1~Wz4)uS`H++SCgTSl0v=7Bm5vT+H>16K%n z^}UJ60Oec=&>;vW5@sxtxj%hmM_sTUDQ(jHSSpb^tK~*S8q|-_tYe=RauDN@uV$fc zEI>{uz$q~ut*CS;K$cJmtscM_v)V50uu^Y(8j(>A{8GY=V-F*Ox%t2@ewqnLvdWVdC|MqteDTEE)tZrqIxR)h8!X6d?jYdnc zfK;q)Cy9fDVDFJvT+VIf`}Vf0mycacpAddxzT}0x5Kbzjy`3u_9Ky%skbYfFZOyJ? zZbr*C#lB5VJTCl0?oU-@DtpJ~ojX6Q*1KQ2?7*FQX&`D$E1$hH(KLOO$60nNJA9-0 z`Q0w3OdGk&aVO6Vr`&HvT8C`k9qaSd1)?7z7GZoS*v0UkkEj^X<*B~=`k2_ zGbYxH^|QiyRy-Dt14E`&Q^hai*C7CH#LruuOmx=`{*a){+)1%%Q6GR=9oTPAmgTwJ z4tK=nh8Jia)Ed(ufi=WVgb|I9sKYhJR3-@oH(@icgRYhLMPr1;c)L6r!IvQ48zA0EcRjR8`e4$_gF=_BjjBz5Sv%RDmtuTA=^H-?c1=i)s9sv zH}t%u3QP^qF6SV_9!a^AZ3E0T`kEovS{QIR0I&gv#sLsme2FZQI5aN6GWA8%dZ83H z!Xj;{Y1vz08WPfW>EaGHS@w-*{v@=qTR*rrk)~Q=)CgzsgDL@yXb#{IE@^1O#<8%) z%BStgy>b|(p?GWsA`&T0Sc4fGwL&2f-1^JQ5^*1zv$)*QLjbn8CG-H=ipF7YDgiEV zvL&>0du28AJzF>s;IQ2wn)F=_pgd#k2ojj7>>LmO8rUPHMPc3veDfmA5%%E-*pb0<*v$FsJoX99{zkmG2K`*bG@XaP1 zjd`VNB%-jp*qB~Zbr4&z=qZ?@C2zRtb34R!DKYpt9jfw=cOW&h!D1lbf_}d}wPVQb zY(6J8N6-)f3FI&ZWikYifyh<2Hz8CRK;e)|LT4L#s@wVqYx`1$<&(?X`N-$6QcAUB z=h?|&Eu-9c4|;SYH#Ud1OtoSwH3r#OJCqdW`h*Vp?Mp&SU3rF}=|#!rx(!)r{%?=qH^ZDt{e!Jlyq zDuBRJH%h$~0yNGL0D!%OoWg`-T>(~T>!~r}$zU?UR@Mp20La$3Kv-}{)D`)Mh+czCH%gs^ocv=46|8SH<^ZNEfN>0n0Z53! zYn%Q(XX6i{GNWzvCU{-EtVxSu?#7x-gfI^nGK}0ud)R=05WuoISQ)klqR9Y89>MC^ zXuyGCtb3;#1d>|p<_*j&SX-Os08DLlw*;nn#N3Uyt`ZE9R_bE#=R5Teq!nG&BV3V} zS%p`rZViAv!WoO6HM+Bxdybs}!%*vwHbm$acJrmn8xQBsAN|99>oCvKL`=h-(g4ep zb%S|Zff#Ey7s35J$zHwAZE?r6OuU^Irqk0e&)bUnTzs3XgD1V`wlDx#{%`?_IR9Gh zx6^0zg@RdN>z3NZj#e zO@XEiu_KSw^Zk#RNYNPVkLe=#!XfWV9XN1CG6OaV z<=gvWEz)?ZROer{ z5&nC~MoU}vgr?5_sgRAf>`|S6P%i&-$VTU%wRQe0Wb_0;`e>MCUWTUgiJ8eNW zTS(3S2HEKRt6s!W&7+$C3$ppE!N20+r+ov$uHKN1i0;kpM;osgCABjNKQSxT2H`b@dvw}nWj#%s8` z1IV{Zp18=!YyTH_ZypYH`~QDm*Of#OBSpfDp`-;_3mHPlUPQJ@QI;5$rEKrZF3MPv zEurjUC|kr_w$O4V6Qi+AmI{MGGiJ>4KJTN?=l8uo-|z4E{O<4lz5l%DpPA!*%sJJjd5;e-T;fKIfD)p>xJ|<9(9vAo@3)*1?VMc3M(1Civ@l-DT)8rC zlR=5T+)-BGxaU=%$IkP1c(JIf2C2c1jeqkKM<}He-}Y|#f7;?7XyMq0)qi$4yYHwb ztFD&0$!iHXuz#n+EgCsKl1y-Res%Ze{P$X)@a0cz^f906rZTFXyVt#gPv0KDQ6K74 z_SHnoVa?~JczN{qoJk*OLQ|-~v$;9aYCJ*!Yvb5xefE0qi8SceZK%^It&$T(ZO zI^U5-i7%$Sjoq;ar}gbrO#YS73$vxV=fs9CshYMK9Vt5e#yCMk{~_tqoYUNgFAejm z-hb~*6g`nknybI`xi?sPK36NZzx|Z$+~b-yMagHVp6Zj=#;o=YHfp7m7dD)#Sob5V zpFP1^HyV7u{F|S_GIPUW{ED@-%X!e9kixtuw&&tCb0^V9e?`3Ys>QtvT{M1ew|3)l zd|UXlPe%xwCbQ?lKKY2tZFBK)b557ebNt@2@b=O6ge^mdOey~F%ts{ycO$x$1?se} zWDA8Roa@+s1WJr7|1CRr(JXJL^K^N@Z=1-*KJo4jW0hCltoi7QFE$qUjZVzu_?%cq z@K)t8pU3Vj%r#wOf1YSny#`Z8#~(2xTymgeNzLoAt^FA{KcXHVneLFjBYks2efC+% zH-G1#wLrr|PYfEl%V8@GN5!Uh?a_Y`|6Jsu$*`6Fy8OvImeCJiTLtFhE9VCCh5aM^ z6vTqJHTD%HP~Sv+@cZzTj{b8gMImm@=>3leCg)dW!ZQxKyWiu#vBbSDNVz;V!V436 zitx#kShwGK_|{E5rRzwKmfk14UH5T2ZYDlE*we)QlJj7_;fPAIVNv^iF9l~1&cEH&uDnT!)Ta&erG=;P*a}2=kjl#e_mn!JHh0a9r&w) z{1@ZpKa{>-D#!nGS^1}2_-~At6HdR3mu;H=#dxXt&&JDv9qfNMp#SU*{tt{7?SGB* z|75)Ap3?Z2@uH!n{{Jl*=hVqxnL7Whum4Bke2>`HRQMmxn_z;!fRb1fg;Q=l2;}oZx0XcE#2nSxq^P<)0 zNH+LRo+j4q@PPOL@TpWl-1>qBV}KCDf(HousStg6=pvSm9d(8PKN5mc000fVk05}` zWdHOGo>(W+;V>qcG>1FhKWZlf@H|knU2!KJtYp162Yi{}L;@CqS>fv(027^fD-IU* zcX#n|K*0PQpJny_$}sSAp00wdBs7l);18fp< zjfs6BgvXM5!$*JZ@!1f}VPQd(PVo|dw3QELlA)D@o&YXRq64dyDY$)8jn7T&gxDA5 z0oVaRs}*f@LUGeuvWU)2(m0)79UUePh?6ofKgip=7R2auhLgh~E|xkO4beb&44-?B zuOaT7Rk#c{(1)Ai0~=*P#>H~o|3%$si4rK>Dd!~ zJ~u~g0ZS%lO61mbIR5ze^3Y=e@c!zMO});lEWLr_f92?1e;<1q#kpiOp^*|hMH+Iv zPO$ve5vcXH7Ne49b}(~d!jVAsI30xwDeg3^JM{UHd2lTkuC~JGU`Yq_M`NBad9D^2 zHd)nLbzUX!Y_NdO@sJJ&S?@W3JTYyR(Ck_kA6=GdG-0hgaTPF$Ob;R*XOY}>K8_#b z)z`Ztlk!fdpx3FO(sBn2%xP1F;xfIt`_1J7poNnQA&vl}LexM0W& zgW)qf=y+EB$z~#f4`JblfzjmkffB~G-i>%85M<5^vZ$h9+nYf57*M*DVDzj+ZO;&HID*Pc|NFLqBSG@ zx@HSkTODne3aEECJ_mFRFBjDjR#t1c)KELJ?MMrHe8leJ0Ja>mz|>#wC$Kg<)h3#A zC7a0)TFWw8q!rd8a9653kM(ZSIkR0PHz!VIIiu36h6B4iT3W8j*G*qGaB^W^BCv5%&-fAYFU0vMw3Q%Uhh^O4GVaKA184~?Cn9l{i`+dTpz!*SmCN6Tge#l6cqxP%3*VfAPimWp+559ljsTyHb~H7071?8bKT0`Z zHm~(Tk{9>-p$~%^=U?iyBD@5}{ptwxIj&2m;X)-lB_&?SRNeS#h({Z4Zd5(XKmMJz zlc{=af^GolpG+=XRkS7ux%x_*{xnV)ZO0=J2pJ;VOECXx1$+cea<)_$J!V$*&x-L= z(Fq9vd`WoQwS|N(w`&0q0Gvlze|{t_PA$2b*#Z74QC|>K5oSs*kT!a|2r_RU)-bJ4 zi?|+oa7Ix4a_pE>zKN2IO}_L&AxuT>VhL##EIf8Nd26;s+)GPN?|83o-myHQherr6 zkN)#T?_mx3N0v3V+5DY$S7p==qbRE61Zm^A9kxQL5y!t+BnmoL^J4(-)||}+w}$+u z>LY=IY4YAWL~i$o&q+mXpH4mv{?=9GBorAZ!mhY`+p@uk3|fgS5~&=kdVDIpG=vK_ z!KUberPFgVXT+3%*+BE(?*x6#1k>c^yTRIYJByLab%U4Z=95P&3jB1OTC(-UK-K9_ zvs^(iEp~aV-oU&BF7PA8iM%HXA%8CN8E_$(C|sj*xeYI-@8NACtv?;`&11m5!jwX; z$IGGS-IQXr@ffQ6@|(EAM67Ie&(b_J_kzT=@7wK&V@Pm zHc(O9%DU2`9(M9s>ni)#CYPA#Lt zAG-myo=&8hKDlS;!huCl*F{j>UKIsbBy4(xTQWbi0PLD^5&+|Rx z(o=@Rfx0TQ!Li$7V{}%T2+C`laAE`TN_86{tjDtDcC+X-Le8!}kw1Q_gKugYv}ZIF z^joDDW8Hp5WQ~*}#4o>=K2jrkVPOAX^cFv`6b!{f{A1>b=+dd0<{fyL@L3lOyI7b8 zlWa~n5?d3N=cf!a^Eu?rcsn;N?a)f|&*DX3?1gebh#V)(X5E=Hd9BP3$&#g!JA=3Z z(2TDd0uj(FoIsLHBQnY3HeMA46$HL7Y8w3%ExHR!r@jH_<&8oL?X$1}w8a=TenK2p z{>*A3WC>NoyBcF)l{Mq4mAp#P6#eJM#DbVeeZyI6(3> zU|%AzAQn7o5P>6i!6+&mObo)YoCvC4H*{+O03XC!N&&kwlvjvQo2rS)2wM1%FRX)f z4<7}?fc!F-UfBx7*keov!*_h#%cl7=YK^+V>7};TVyB{RGH1X_7jd3aQ#8I=P$Bbl z*+3WiA#wl?A|Ma}ewC>Kw?fGr90AB0$LSfD`q~qi);h!=Loj*-FaTV)8 zZIykN3xB`OB+mOn*70KhiA-q6A|!;79)Rs1=Q zJrU*ESrVH=q7I$etFKTOg+4Z9Uwsn9LoE7|!Tsp)o1qoHbO0Ae#@xw^zO~WKeA7Fl(~_3l zd$C7!8%9dW?d41SyfbzsoW+=cI{=YcQB0VtR2nSGpzwF{7m9k-CoDFCMywBj;9gGd zm{=WN{O;k+v@}Y~9wGI3vtB+FFyLR{d9M?E-b8Y!Tgp?;?D#3aiXz=L^76%H$G|!r zz&7e8^40~BYj!(A2cjN2o6g?rFr6j#CyZ)0JN92Fs&xif?qV`rMC8&q5fMu;S~2OD z!A35{Qj$LCb8Rk&!UbnF8Pl`&X6^4Szi0aoEnasE?kP2A_G zSOt-NCe@W!vRd-0>U??ut#0>mA$rs5)P?zd^E9%?`k)t zy>a!^3D(78#)9AHNaG#Gf}g@#H8j0bl1RRJL|UsnNL^5mH-0*m3LSdWx^ZlA_r%Qv zl8y2aLEp0}-^C$-qY-WVNjB<_TOodnES2o-`84?3gc&u2os`Xwh77>n=t^wBJe3JJ zha(b@Gs)l0yd-1-8#zytmFPG)8pEU~bFppfEYQ?Xc?`lnh7o?;)7=#HVuFFDj0yWl z&lLu3lM7>#^6E#%+Y)XVR_TOeTh&UFIUoX0SuKBUzBUz3R)$hEV~?p9_@&1~$+(m1 zI1ZHNX3H4+^3e(_Ru2Xc;=}7Q76;DcuAG5J z{Ma;TaZfm3LHu$7h2LEH-KcgwK;#IU5>uSiZ)$2H6w}4EB2V-~uoMAT4ijCrreyBm z;74-&6K)U^md0jZed^oh6{Gm(@9!ggSHd_5jB>#WO7+uz-N6H_txH|SV7`B}4B4l= zameE*F_sCd*;PqUkB11jD($JiqDgK_6$csI@Q}!+u?C>sTm4K^bOWxi-0=5=o zgA(G!gRzEBv`BWhO701jS|J%IE*=>?(~@N(YWsLoMJD!#d*7stunio52HWzKm(g!Xp?3Dxd62UR9Hq`Wi1Fg4lPh z#j**&d_n^k)><7KzLsF`M?^Po7WnT87{47I4@{??27SU+3Rj5xb`VTBF*aZ-oV@yo zuvridXH{OQ(v1aU=jf=bYl-VbCtx zm8T1e4O@0=OBObQlr*7ej1JKbI5KCzq;H3B?#9raLR*rt zi?BRl6C~u>Xi3)u5d$5p>&7X!H?LL2<2~0~|lWb%YpfOg<*0Be9pSnuQfTGa~Ga zEZ?k*pzLBQu=sBLepD)hw>yI#@25J0NAGa=ZW2?xAO?mHL5tYs_^_-l z@I@fe;n!xK{?1n&=Wz${=%(iuUjI5hf%hWMKHpi6+Wbma%KWO%%S#n!%QJdvIfc)5uStfyB2FP3tAx`3}y*8s$0ZNfOD?dkDmyU(7)wI+zX zzi@&vkzgHOFb!~=k~J{0P6@@RRaBjJ&-T7g3*m(SEfS3TnUPEPg0G!7p;y}1Rqqq; zG3(zGu8MR)^`PI&XZu`giA7A4C-^A430f6u1^Bs^hA{n{H(STzwKU?&p1hepz*E|@ zhFdf1)?Y?mD(zuPK1tO47$_AeCAtS1w-GG1S%cv6bh?2JEMYgn-)_vASnrx|1n2p;);>L?Hy+VjYaAQ9z`i_Z> z{-Pe-J`HhMgpb8{bc9gxV5X!3W|#`~ncAZ+ch;?COBRZ~3~Wlj^UQ=nFIhmvzvl7| z2%+gK5Wbo1JbAU#AQH=<+N$Z2p!tD?qKY8&SQ4s!Xxz50;X(H z$V;%guA_K%d3tMLLNC|^{bRZ>x^K%J5ebwrYYkT#CY@%Y8V zo6D*h>H`$U`jvgT0qixPu=yNx_MTIdb!`?|Ud4cSD!S*N>A$OpS2(3BMfrfU6-vmY zh!Tp*^vu#}DswMCyK5YiMSZ+aQfCw@tp^)dT=;RtHoI=YgOsrU)KC2onH>3+v!|t` znwJmdKXGp=41SV7KD91uJb$$_vPo?+J0<+sT>+{J6Eqar=@d!bt6(%3$B8_S5N_&k zi2Y^|c4q4cov+p>ZwaO@pz$LRqjOp15Z0O?`oHZ0-&`(WI2R0UUTGxm=M3YGnuA3OJi_j%OC ziM+oYyU^j)BNh>;%MqGdfz^r7xo)NXau*+~7-v*icjrsSMgW0b=Bq z#B)Rw?qec(=b6O0>EgYZsKT7j>)g7kQ|0inHJ);3(l9EXr_S%*t_$J?iWRr>uvfI)BDo~5zMd1P5;k$lbxsQ-q%R1BP_ba9 z!Ki{CC7rO-@ab_s?WWPl8uy4NF0A^grL3)TuHOOTrnJ?fP|3i)WF?)W!OQ2REt@jK z7RsEsJFkb8#PdoMgv4X+0MR&sD~0@{eSS3;3(ChDZ6HK=Ex(OdSRH#PGQ&V_v(e!-%>jK&@(hi0%BivDJ43jZN)x-Gqt@u?o8fHg0yjh zxN$1w%CqeaP0U{tMP#pb^N6)m#7Kug;9b4uCpmKaJ;=zv_k>BUz1 zRk*1Er$2a5&@qwOrDC4ZaR^$C>#U&-BoPw!jz2qM_1U#~qR&afTSN)yv#VcG!_g3_L^ z`4`h(_jZtlG*4tdIHM}B8Y*-BD#WFc7tAy9OQa@FG+kQ;LU(^jKHlTS9WUi6TmPJr zx^bv@@nKwkzTU|uU$0^R3&7zfaiHCw(RnxQ+W?(pjf&wM=R{k7$U83$<&&c0Ilqdu z<-!eKcA`*W%Pix0g5-Oj?PcS^@zZ%TUG1C5@p5ul>Cqlk+#WkcB;Bu)CDp^ z?gXKk2QfKV{_t7k8t_%B!BD7n4Dv>h^X|jWHPiDO#QVb&&oqdF@1>3512pOLT-NT` z?fWu%aFQQ#LaCEV6r*(*Lx?1^ai2GjLoFt1T$`gD<3x`2#j*B_RXQIiHmO=VpV!u? zGd8(!cgY2t^K0XA_^RebZSvA08rMWUb(m;L=U9CYcS}g?j2`!nV_TS>mvxmDw{|=< zUR71zY&sAKrE2MSZ=(xJ8)ZO2rAgvw2H>SgC_1gOm6)~%m0=7p9>E$!tcqLmOQm@PapA{Ej36WtqUsGj zBBX9QF{4@=_-BLPjNi3>{N6Nycn@>GWlFK(4&m34AFrc%oqg0#84=jAV~Q07(t z;$4znLiRupE@^fwzB5%SUVUhhACI9`I{n#LZ7`g;Ty ziyinbr!1V3#Elf&_zHt4vZ66aCYW_**v`%(&o~H z)MMks3aD2-fU#PE+9dBb7{4MxU(sgXN<9lk^;sPZJ1ETnb5eKh1}bg`^vjx@cR4CX z5IQ{RR6#n)-_w#7mKKvcwa>sFAnB|!7y1WGZ^?b+gxG>sE>u%aTFw3rZM<^wtSzHl z5KHoEcS&0cc6)t5AO^RL=|f!z6RRsRKATZCt&&KOsCAnOG*ACLPjm)TD?4~7#})Xn z6ltoizP&pxV&qCoUR6&^>7Jxsb>_*(KG+NM3dFXvZ%HDU?(JICWgT&&r^H$Gh)obf zqP<>cQ5#uC-C$QV*~i0iy3ks8?b0Ka-Nz83C3!W06-Tt{E&xg2t|+grhBzTztF>Ms zL@JKuX)27cB*esZqJ!S{5s8byQVm{E;>=;YQ)Z=&OX9AS?l2+BkNo28uWIRk#BZ1g zp`LW!TtW3n#@hrs`NI_C94G8~}m>)tWD zeBKTrWyRvVUAp<8+2$+(J8b#c-ZVm(eQE=`sYIV63Y+NO# z0bkVo3I|KZ!nyR7-GGVMI|1Mx+tfiGdXg{*bq&Ob5*h(K*blr#*5w zUTQL#L#{9Kl8Y6EJ%4`T^0r(t3G(Tz_|Mj z=(9E%$ZG9Zn4oVK1k~M0NttiMtb(C*8uK`aY34`U4oQKYXh4HT@L-emx5fcbzeku1 zm~`+N_nNnx2|58zlxaUw2lOy&A|_UbA6@%b>|oS zta)nrV(i(L@3zGe#{DN`w=yQq*?Dxd(*tWB5pBDm5FYV>cIecJiI{?zOo3g1ytx>` z0$V;84hptXLoifecrE#z%5k_LkXhaXf%yR(gP1Tg0T|S`X0s>hH%DZ!F!22L&_X#5 z+iV%rg~WMM2kfasZC{F#LwU-eHGc|hcqvW!haCl|o*=2!E*bZJkN&%~$UFlun7AzeXVb=QW1jFcrFyDlMpKRz7&Os^zAq;6&hm{(Q$qs(kQPH`5% zUB}u~c8KB-2OMpugUFvvO>2FmuGHeOeL_0<72&e~1NVq@;N`MwT*DxUU}1JR#Y_CNVo%hooF5NB1VZ7`OWVd61q=1W0lMW0q-QZQ z7rBV(s*3;%&|>&lS1zN=#4&5axCU!=uFcMhmXU~cwK>=k!0g`0BzN$7e>l2dFfzx@ zB85!s$V+E;%Cv5XTtJvyawxh&Bc{ot)ySbBTQ-lIB^DS_X~l;|6PEAhVc8R4(XB3= z&jpL?Ph?;5Ql-k52 zCw-70gKY&L`x4B%h;bqcf!#E&U6IK?VuB4tb&3osSq;@{1C?!DH!QKwd@lz(q&uTj zn8EhRAt!pC^48o{pF^Wr&Mk>1NbzBtzfvMX_AW1La~RjXPT#S!1Zcn@a6P%d6bC3X z>Xm@V@co}V9Q(11<65)*0i0TD)?`%BJA#t_!0bc_DBi+ULPx)B?c4RH2kt70#MV+i zh4WJWu=Bi*XS8!hgi><|ThiYmxeu&2t=F^FuJ=h=jOU6Q5 zj`C2$F)Z4s;US|j=|d}bgFl6hFfh>&fAP6{1R+QpZt06Y%mKj`66adWS&Zfm=!T9c zd4k;935{9rqmuh#FLk;$be#Kqb>>QinM$uD@T(e+-#+j@HCOxTNp%D9E|JonSzZ7e z9POvK$8ZQ6ns@N9abHZodB$TXOA-PHm%^K6mpr8%z>r>1)u3T~vuuMldrR?jCXjV; z;4P1uZy@IYn77K(l6CRK0I+4N*6<8ydq=f%`rE*dbG>+wEgR#EtVF>Wn4AG2!G7@= zX@~s1lL-#8gXL$v?O$8sq4#N0ThiFZmHo<|$#|B=G56>@yn7=%DrK5w@6Cr?ZVqqs zvB)PKJ!6pf4zM49`CV;XCQK%0XvpmD!DpyghuMkR4LZg2T zXOwh5Pp-qED9_=?O)^mgSzB^zrzB1AQ41VJ7)EGH@O6GI6#{S{3Jh$yE zNtd$d?B`x5QO8zr!CX;flL3~!Kxc=*82CvUGS z`(9RmzDiW#!3Y|?oGkY~Cua8X14O2__m`u@7iCsI4=Q~>my$j&FS+niEBq|FV zo0vdt1GZz07>m}#diKd5*Qy2Jo;i3d#X(BtDsi9`0=@gc;7gY)PcA;9Ef-3l;Xcz7 z;1?$%R73%QoZ6`FC&jxCtm*sS zR*8R@Zjs3m&M@ih*rDbsof37p{m6av@E?~>?mmCLk?V3d_VvWbtcY3aRX58|f``3t z4(^Zn`9b&DmcJgt(jQ(1wcN$|7hRSK))yfg<*8a~MfR~v(Yi?*DycoMEmSe5vR55K z@XK>|UvMJzX4;P1w4M9pS#g>8m-%K8uGm{+zs!m0I*UN(@u%Es&2K;_J>=kDd!>YP zcj8r+RRATh#&pMR_q#pYF4v_wITks2%>6#~Y?%G}uj^qxtz6oTPC=ab)!qc(zgI-p zrz%$~2fzMk=BuDyw?FA1JrNSC@mdYUZ6!7+iMsU!UsaTK=@JW)xWTs0(|w-fD4vYJ z80@pzpVma(daV89x1yJ?cbDu!utlVU^V1BAlAJA^PM6hubbZ%+WV<;M?wI)Ue5UY# z(5K-YEQ7DLa9$ng%~{cKvr;l^WM!)KIjQPJFN z&4gO}-*R<=@A2j1gQs(!B|nlkXpB55pu3E`eIa4w)tDzD_WIz{RCl9&2|bjrCr};I zzx}Zucw_X<#lrDai|%bRw^YKzCw!y=FKty@YVdm-TN}Sz^LGC^Zarbru}ALMb;i$hte!oAmL`y|hq z%YHhpA^Ohd23sc6B4mH%c8a=l(DRu?nNOwvd|BKbw@-rO{!uVIu5tU(PpNHLrrSF` zo?;K)zPCF^7u@`I&>-;f@Q-SG5LQKIhp2A2hP*y2*6=0D{|sVx;sOeTSUjIjY{`Cb z;kvxYUuQfA6+6+71ML2?X4duAn12c~`h&zAxuZXJ_Tnpwx|RB-J10AfW=!=;W1Zec z73wz9YSX#pBUjV(0TO<>KXNkRl>HH-`QZBLU=7-C;p*;d-;u9}5Yne)r2RS4P88ZfEbx1}~ zWxl{WyV&HHcYQ2&hAVp)el9rr*XNuF`s}(9YIiV|?Np}a?|UO4wku}Edb zwCtxQj;~Cm|`W0wA(LnF3s>@}U8?H~)y*q=amo4|S5E3JqyIo9O)Z!NE z_AP6=I1Q$~)|xBcM{#%-@>%@1v!@5lt)2^1Pfs+|96n#|opY<3cB)Du?&iX8EQdcE z?Uadxifpi5`Zw90&;M?P)cxh`{Hn758GZjpjsAaEdjF~X{2TQBrTxDNd#LzN==)6+W$^OSO^&frz572j={~momsjc%b^j-58z<$OrKj-@G-R^sL^n7ho76^9v z(VK2_igEJ#tzbvV?=QCowB&c6s&JQj6OV6F>zax0yYbJc2vd`ke?8j%^)dzjA{l)K z_jaVZq_b>riMnhWIe^&G*oNd%yGZCQQ3=HRq;zA*PmS>6^_s5$8jaqc42|scVxsZ0 zXhkH=!O3Edst%a-&)m-dTFZrL^BIW0slbQ$eFwMzM3W=g5diQF?_IuiD(^!))s^!p z{Is{_?_w}Rs@J%xO8lOVLgVzxR z-~q9S?SRXqvgm9K;D1Ww>w*OHGgkp@?(C>bAqn9xEXSJ8-~j}EJG1>nX74HFP9F$R z?yD-MNzO%!mxItg*T_=%r$3c};e>);)DkF4A_8!A0|P)f|8_H$h-1^iiml<8*~ZDV zapr6*j=+V9nd^d5W9F{kO{?!<3f6J6fJ(T^JH9Scx&pwAE|dM;M2ZN&-3jVe78&Bw z!REQJmii8m-o^#)_y-V&N@No2F<`TU58jwl(KHT(p9Wi5p=gjERt*RP6F;d_QTT(O zqM{>()W~yZ03>mcL-1HM2jCSFhWA>@&QYBiL_jA(i%_O55zK9c+*V9A?+@sVd50%s zJ(i}{*C|LV8Z~oW1T6#T;QDs813!NU48lNv3gCl2t=yQ=&;dZJ%363E-pap4l?1%# zHU5S+a8EDgLUi7}Z6X*CjD`~Ne&Y&g2G70J;VRFb^?o9~scXLovZSl#r@~Gu;2%pf zVgjD3FcC2Ae03o}rUEWI2?fTs>IDH9OTu-cOO z@FB7;LNu5Z0ch@fk~IvUv@)YyY(O;JC~|^RJI3V#J|Ir-G#%l9#Y@4Cv4rrIkvfrw z_b_(L=tUJdkquW4wLBcqqnYV|7Nm^@rGP%>+>8Z36;ELRxC4IWK{QbT!AFk>W}*R{ zV*z>rtaJfKfFB9%1%P&?E0;f}-2q;dl@%{_>G8qQf{9;j3<2;}#ytQl9Iyxg;%+~< zKOVsAr6R6ibUAMZ0%kY2kO+C=P2s*l5@2S&enW&Ck${5*fJp#zgG4GI!u-?FI+fE2 zh>8T>olJdx1O%Xe7#1`-cO3$N>oob8*0qeV_xbqq@W=gscFRgDCa5|i_0MRX{nSKk zFx^Tp&tG24Hz|oRw^6tL`t}(69}|^*1$~+&#i35Ks*xPnyMADmZw{z~iwZFFCdxPc zd6WrT&po1Za3PvA7qfBr)i%;ObBm};*=B|2r2cI$8xMMUhcvz+DzdF|{MqTb>>;~B zHp;}I{uIS*_ zQ8PCb8<8nr+O;q-WZrz3N~Svz6(Hbf8gM7&4Uuy{RnS2F*@k_}mfY1geCB71TzRv$ z4Dlrmy?Fu2!}ssq|10N3p`&v>+8}L1581Z$`}T8Z*VpF-_NvWWXhHD;7ybyqljeQt z1nPW<-f9~i0M5MqRG5L*rMRuX%qM%V54tAUUL4 zQ8Xp$r!(Q9&wI_Al(6&&)zo5wvCbv3RpmM|)S&ZF9fekYj(-db7VG*jbQ~4n_@F>7 zW3zbw5gA)Kx`H6biVUeW<+Nm=Rd(4e?MkM1>(#db0!)IR*p6jIuUwRf0O5CMzKJTg zn@%lip%vo*{!%iN15Fpx?3OEW-gg&K^%`?eRT72e52%%tN!* zMa71T9dNPavz4931C*AN{6JNcfPo$MCxZmb~JA2*-3j!JuBU@q*B zo>QPAwvh8KTJOE@q~o75EFL{J#mZ#AJkm9>9fAO=j=e%0UK)rci zVXS)oxP(F`8f=C?6-vjg&f4_wrEa~@oH^q+elY&l4M`0F!bV;GK-t(Q-3a=jk0m4+ zkyn!9wn$Mutjzz`HdzqRoEot3*c<0OQ2`eWbu3#7L>;fVH_ZvGSO^uz>8YBNOIAZk z$}-VIT|_V!E$C<^p`#Gr^7=!ZLX>)JO<1onW~?-TtI1eV0|_#I_4himqFJl~U`dlj zCo8L0$nUg3R-PXSvK@)Ip+08?wyx&)9F;F>9pq=OuUueEB`iN_$Mr&>ru3427eBEt zYCfVl#-rg~y&UKT%M_27*#f$IN%8uQH)3Enrbjo#Z-)T)lv>9Fw`OHO5vS8}5c72d zwK9g%*kRm%9LJB20CeyKHY^x3=ckTC3mt9{|B3aD8`zFvjhfHl>{|l>z*cZEOgf{Y zeenFU@?{oZ4Geo-nJVe=E0vK!tGeh?aWF}Jj664HaYv(UX>_ZawRt7b!y~n`OaiGXA#}a=R^0)nIF=>sruff!{Bg2L$l(IC`gfmdT5cE`R#btT!Wq2i{MX+ zv*^y=*6ZZ?=OdETBR3VrnI zjE2`kaZ{{tQ;%;UjATBRKFwVyY+Z3NuIRdl&yE&s$b(=iKb&jPR#D*3kW+5FugmhU zNFyfY=x(&_^F9=J&3B^K=@Dkczg`|ms5If@=@mk0D?$NJZegi_rtviW-=Nuc4|Pd*>B z`Pls1q1f+c*M`kHN_T|Q#zSF?Xk`z3FE7<&$LbE=u52ZPsUII2Nz8j$c@ZLJ$Q1s z!&i&Mxpl8zPYg`nI4{}n)C4?yGSIA?`%5&(Zv*StH7Xy+*S8TY*gnEe+Glq5nx;C} z_pz4kNtP(=X^L5?)(gG&8Nxtpge3PcnL8QhPgyVCT9u&CR~lpCFhG_%Zp(x^BcZV=$(If!CEGDX!SZ4BRy1fQ?YnzRW4ywT6p;2E-PN zkRVWK@y>%7+Beo3jud!tz z9CL3Mm&dIJ{8zMOM8wO`yUJwP>1LSC!*UhzCgjXFWCkXz!Aqz-%B5qFMxgX7^RAfU1ANUb zbOS>+6GEOOXOb@J*?r59xi3{t9B9`kHG7GZ$+Xe1PJ+zu+5K|BVjOlQJZ^vdfYX=X%IMhqQ%S7fDf7(7crfP<9>czEI2|V4+FYzyTA30LT|FSLH z&GFL-7<3X2AW7dc+V5@WB^kxrK1K(B3R}>Y{_^(o#7>Io%4WP!RH1*8If=1?Aw)re zSDsNTBwYFl!U;CLxx1R;ErTPa_BJOWo*{PKIzwZX;^kItxlLo}T*XT)tRyr@kN+Y2C3brWjhE?3E-_+Rs+SV8u{EQSTKA-foJH}uCD;z^Iqr6=%D zV&n|5WlHf~=V>;$bDDPTZ+Y>m>hQmZ2>{s1M%pcC&pRN7xThCocT%$7qe#Z3F(d0@ z6SmCMsfs+SfiIdqgaeW!m&>sat0`+O#na(fo%MIz#5+a;e)r#;Ed zm3$svXhzVwKvhOrX5GZwi&Y4gEum_n^57%gnr3y=J60R!!Uso)(7=E!pg2 ztg`g&CAvmFw(>)^kUb)g_MdDzV54O#vB+=P6j#Tw9Qj)oeuSr2Kb<69k|$1sNN#ob zmduMFWknMq^@0Gu9Tm%0XiR0p0%gzFeldH$1s@x-OxPq5X>7=Oh3X3t*QKlnZ}fi_@m&*!QfiWmxs1|v#2B&CSSDI|2Dh(%k{m#>-W8X>vvf9z3#v6fA?Om{eG|gey`_V zdq4N%^@PH7mXKoxqW)@S=#ax(;x+R6c?{Lo+g$c`A-lRJ1@wEj*#ip6|N z8!jFzzL`Z-YAL_OGvalQ=bcjX*|525cXsIS?^@l%I9vvp5En*Q)oXCeuP&bZHbT~N zz5D6hT1a&XUgLJ_TA@g7ex~B}$+d`g4_~`E=yn(+#?{ZXI#UW(dE6ilx8Yve%V=6N z<%zEEls!EKBx9fM44PQjt6f*;;mVBeWu3}aOK5p>fUOA-?pF@XB)aqqoYrvniYF3j z&SA1Qqod$H@#xx)y1cDDn@6NHPMAM9EU#W?^@Z_lHCIoL4*<8jp<%&DJuX?oH#{@c zXq(#Hmzy&T*4JnLBR5`H@BXpN@xvZwc~wMv2wOezA-zh`$Fxl z*u&t3Mg6-C8>JNFr04bUjwH}@yG%8XdH7C|VtLQKsijb1oKu`c>T{SRAAw7RGr=kg zVIV^HxW+c9>GmYxd=`f;SJhKG>!Lt1a!f!pj(A0^_Ud5~P-(cfLt0uo&Az34*!#g* z!0r!XXBT zEMO#FcbWb+@G(fGI) z8i)BQE54Jp#6a_V;@S+)TThloN|SyiKns?dY;?y0aest;uK!{Yj2v_j!fUE=xa*MQ z7fls4|LPz)X_RioyPOMg=fbSX_v5!#pUc623MnY79q3L28pdb~Ab_&vNeSlAZOyHq&$ zMy@}Bj_w>wvc#b;Y)yZ6UXz6u_&zerhpza)1Nv}6bb->}3=|85D}IggX)Q{N?XOG4p3kBOY5M;-xfC zp6lh6wV{JzDN|VMZ}xgg!eoUVjW?Db z8b5{c{0!7~<&(QUFGM4A*Ox2piN^NrYuDrrLuf1bi`P_W&ahRYl0_M;YVH|19d_d5 z{x=#S))OTMmPz;;^r*4(#(}Lx!w_z4O#0>wk5cluFWaVPAw~3n`pV7k$OR$P%U^tQ z-XKA;3YA`a0zG$s#94qy3`ef-_pr@=cf_*&Up9|5Ma8(ReBa$$*&&v@OQ0>SReftb z^G^~!mFg_XbJtdmQJU9Q-nm_mZ^8SN!QeSB%o7PBN}^M=|FH*G>>{SM6?6RyJM0%D zC#J){*@aGQ0K&xuu>|L-35=%vhfZ3LKNyZvvPjg}*WRsP!lvcHDZdQGl0wp%50dvZ zhpJ;4E6H>6+gi8K)X4cNRS?OZ4(zG8si1XD^s_oY9M>Lo{;%_yeMA>UW<@Z~c@;2& zJX{VBIVmrHs8E&G_CB%rlzLG(ot@}Y7X0}-_LeUj^Z1eu`=lt>RkI0Kf~P&`9zU5v-*9t^X4Zm8En75NW0XU!N=&LEhyC$AXKebafD@Z?c2#lw~05Zk#r_XvU+|y!3By2R1 zJTy(164Z?NS;y_moM@p+>G)Y|W_!1cjf8u?qpK)cYT!y0lnC3G1;;zfnWml@%)|Qx zh(A%)sneZrUvX`tbmGWu=%tDKt=GG8pC5#29I@9K6)5|>HVCUA9FCUWSN$A;j3wqvWgqZHJSz)szC~vSB%v9f*P_t#V zn`$ra>%Kp#Dm(nvdJuWibnY&sQI1;*NfOV<1oG%}+;lWN3 zxAU8WnJ+BZxYFWlkN97Hl>Erm+YrGbffebq{Z7o*=~&X$Ryy>^<`{WE`m8gJy{!Y{ zfkCme87<`+e=LKuKC*pyfZAGox%m!5N@U^nU#5YK76x-UTp!j5r1ZU!dX!ORJytwX zyiyVGeKOw{eT82eloQKmd-DZbgdH-IN=w!R{~u7v-oxWzdco{O)TCSs?}VRd*#g+p zV@Dz#6@!xuatPvym{915`Jke-X34M{+j@e{gqlk7$Gk^8L~1u2Qp&1YHp=N&{YXlb zj2wKy@~+R{y7aykS@@B`uQz{iC(U+SuJ3Kd5LZuwOLr8_shv^x-k!0N(t8_|=KzA^ zFMRrw&28!q&s@5C^t3E_(dN$P)>wlMNxX#V;W5XQz}*drS=HowB$fqJfj!ue#>wNf zbX1dCLIQ%$90_SS-)L5wY(B&&a9f&dipVz}-GN=6A8oLbJm3+i*0Hno-PF(Ydz6Qj zoe~}lVswxZ=Z;Kz#`lcO-8K47chcOrB|8-+5~XCzp63^ZsHi5IxRaKB`)YKs+u9w| z#vgqxA_dv;7a!)cSacP9;xhWYB6NqUta?;)A-iG4{K&Py^r)Wv>Kc6JpmnGT<-~i! zfnE3|>p0tljd~gv?Od%stuyH9$)Jak=+yd@FP`OB(*V!yO+&kL>c8K?%3G3i5a;w zHY4MOqX`01l}BWZ3}2p3aJ*%@a$1|AHG%hN5PBQ^0KIGao3C4M_Pf`ffAr>;sQP#M z1fvQ){_(*rLhJGBDW*Rv?>u>>Bl7ms?7{^4?fy5UfDRcRZ;ZMS+&K|t6oy%KO)z12xzi{)8gjY9J={fhxnnPPww-7#NeCHq z-#A6Po9fR8%_Uq9N2A$PcHkA~f?dwxf7kJS#3X`8-%ZUequGu@Tj=A1Vn*nFpUwA@ z&sRy?AupRir)pPBy0Vj$EP2G~r=NpHFQp)4V5f8DQqn78)pfh($&MQWYy}q6ecHo) zQ1=DXvU5vGb1$0Hl@_!+FE(}aUYomzmMt!D@am)262ne(f~f{fuP78hrST-h!JxG38l|!U&nSyCj zU$eEoBbD!7d-k-pr?uAc*REB?SH`m9G|Fq1RAbT8CJ! z;*-%RkWbKu6S1qDMXr$5K^UrFV6=vPUzmPOHO)%%KhawPZIozcKkrnSW9o=CxzZC` zfdhkJJ=u0FNBn(T;qlUG0}v)_-2=_v%&W0ERNA_9BOlDc-%@CZjbi5Cf(b>u`L*Y0 zSH!5@&3>l-wB0FuZCcN)aVuzWCu9nGYeSu68Glzal||1rzS9~mm(8*d3Lj;ZcyRlv zoW}ZgbG|V@os-@OX7{POWBXE#5f7IZ(r6}rxOer(;~xe5ll$H!Y8W@=mz$Z(#zIxD z>8L>CZ|^~|y>aosS8j9Q%J?qtPdEuOwn7A7rRwlhXH*s9TG$G@Yy8xi|gf8M1ubRJT(h-U$g>(c5YPC z4EHA;wy~H(OP-Wn*G73wy=zMM4ymcr7ZOM@+nHc?>l9g zsvN~E%H!SB6_en`7WH}>Z$un806s;+ApcE1pTh|^CkhI%-V2J7=UdSM(1y?4pLhD~ zX{=4R;?vWY9)zkZE*(#&i2mjk<~nSn6A)dP1G9%5fm7-!oBchB{iGAUsERSLX21aolc49$wwzs_J{sl z9YF9@Z?jUDb{h+E_EuR7{3$LkST5+LB^`*2&yI4n+45rNv`AZpaw8;#n$t+u8sI~n7QVK%)zcu6Wr~jZS!om zl{)hH(bLay#o9YtwoZ0O_0HjUJ3Xb`d6CgOXJ~%oy0hhh-Z{;a-w*BB^)=MwE~WSc zf4ahs|K9e@v?p`U_Kwm<%{hJS{rzM72COJP)Lfzn*_^&<$90YG={rMBM2FM$vZKwD zf;CR*#5HXXww-+deK_vbo`YIZMp;^{Nt@`(Q3~i4P@7)KGmy<*JnYJIXzkTT8BpG& z5%@}4&YSO?`NgCP+&&U(eI6FC3by?`^c;n`gd(jUHN05wNwdo)D<&HL11kGMoX7O& zm2WAnV2W?Bc!=GL)&TR5>UK?p?pM-^pDplX^O{CB#s{Hm{PGf zds7JMW(PQ>XKVe<$#ifL#{rWG-M9DJ%=8%r{(8mjRVMp2`^Y}Com^3neoIN5j4!Vj zrQLy(ao_fAe$^9d97XV;Iuq0?vz5Q@2ya@w^x3}5OaFei$ToBK?oIc&1^_DrXWn#_ z&k$t*I>36jqX8%^+VoUmKvt$t7C^A{@d&`MoqM@0Wm1R z0!MS(^MDt7VS#wW)_u5~&{~*J1>C6u7-FTO+uJe0UB{H3T_E2oCOQ7^45=wa7nb!uA z(hTK;3bvL9dRZZT1j*3{$QdPxy;6m;?nig+*0Mcgsk+hDrm%1J_AUj^cZa=!45k6A zSKwTHj`u30aKLnv#zLDx?q{xayT)G3rDNNSacjyOI*kWx+;%AkA+pB|%bH8bI&Wf{ zX5MW2K}zfktkn2UDd;Qc3fQM%?9F!9GsYDkBm_;G?H-FBw{_20Y~h^zLspQi5M4e z?4`YOMXLfjGT73W>oNtrH1x30F=TM8GINN3a6Z;S9Xr*_G+~Sj30fcZciyT!vgEXP z`k>JXZ2og|X;m@ImQU(3a+mjP=$xRjh5^@b3AHrS`TW#k(%E1l>_h(_W=r zTfLt7+rq1Kf9Cgu4P8cwQ3-o)T53G>$)>iGja5EJ>0jn&wBGNg=4?7@^-#i^G&~X4 zWo?`JYyTAe!emKkZ!JllB6zRJ1!s>Pgup0xO(_tHG+Z;se%!S+_DAilBtyn5BkF)C zTH;76in?6jfY2-1*siaQMo#L5eI1zS@{>51QHvtpnyS$w9Q5^MAhXSGa9c5{Uln0T^^IEUdPil-SR{VDHTXm;vdPLpV zdwP3I(@CzK5=vI;+nc){YrWsnt9E`mN=ciX(YyM5cl>RvSmS{elkcHta()A;k1reI zcVH>DBH!3Y1(O}ABPqBA>qkY!2C~T|vE@Bha@+RbE18C*{U5rM?f@#J5NiuNR>U8XbE!F3TfDcCl zS0xyXA@l74z)cs7oF8wePMRENAn1vekS$twNWdLg=uUzO*gi`_+6{TsmVjMYZJODz zKcOafQ6t~YM@DNkrzc*fa+-8(FkdQe&(IgiPyARm-OF^P?4S>F_~eGt{gJz6cK^W; zygD$i1w2q`iNR>K;iFl;P)qM+Nd2K@lF8khIg^J}&r#p(+w_B}xOIgMyy!f%cM5&f z6iZ2rgW=tD)f1o2H>{C6E3hp_x?X1GmU!p#omgJi!-$G@uzXogZ%oXQzw&qgnhvqm zq6mxH(xkNNu)tA*4KNEx0O;jAi2mB6Pz+BTV!}~s{Uo+98`7E^MN_*svV;PZIvB=S zF@e8Fz`hKpJj}MF^E$9+#myUk7u}H6)0ulqER%cD&=wNv-tVBZopmN+LXUaF_8GV+ zKk!*kvt*xNh_ntAn_)ES@`$XyaHz{eO12bNY@2}zu4!bw&B*%V8FxS;>&9z)KT66^ z%jQ?vCvU4t+h+dK#ar*c_HT2|I`vCA%08hcht#p66DW1}o{4IS$eItKSNP-xuU?>> ziQ>m$)YjGljakNkhX-4H!_S%!$zV<4&&=Vkw@_F?B7?lFm`U%mT$OiAnT{nb|9Fug zkorsE<#wqIiMgYjr^BA!`05*uT{(6#P*20dpQ#!$r6IcNoQdKd?u&SiLp2L_+5AdK z3pF3A#AObxRfnX?xlB##V&)VBdT=OyI_?-HZA{KyTk&gbMYGe;^Gw9H_rfmAS4Uo% zD3by1#r?uF(_!{IRJ1Xva^A-%#V%hd_wk$c)$Qam2NV?wmsiXk9BS(iOvmB1Fh-tV z(|@iU*r;M{-GRx_`Td#g@uBxeU3?=gr%Qh`O~O_EjJ3ADt!n)!)I_N_D|Nn~S&sYD zpk8Dhy4l;dbJKfs2SYrcV(W32^1PSjd*2AtbwFu{xxW&5x&GY7`pZ*X+Kj8RIOcGo zb<}!S-%Prk`#nt8b%;PFgEcI`g6S|PpSNi?K>DwU^ufIBZP9WltT~Gvjr$l^43)Ix=}^GKb_FF7P6rG>?iV zI1>svC2{%#0}UOi3MX2z=^uZVg4YlH`7rD;l1cw{bmVe;Klv_{iCAY{{cL+-p>y`c zQPp5g>1`)`a<3dftu`!7&Oc1_>$joWN?ZZ12&0f_du4|U z3s?4L{}tpew5F<>5m;j5?e*PyUxVEVLzC3A*i4#-(sX$959eM%H_{ram}fX2rbwo^ z04#2KT3QzKBnh+2*2X}bo9eK564Na2n%#5!<{CneObK9i#S-DEMSB7L! zckgT8-&pznxs{>4Xl2GPF|hAknfnQ71Ya|gxgV@$=66MJvk88s`03#}b;tSz)Ac|l zLoLD&cPg@CA|;PV*`l@|jfUV%3fBb@=TYP5A$|OYkj}xZUy>%)IZ&Y9UlGgqZpdwg&#u<^$Zsd-n^>UczgG|ZTQJg3FH~v56c_! zl1wUnsCX^Y=)*R(&p(3e8n(x|vB~!bWFe4%WLrg5mt+WMAS+EIVW7pQOS2>FkV|2qCZ`$_sg83M)BhDP@jq})|MiajFSw@v>_*T7bf^+DOll{pX;xD7wKv6hx z$+Jz(^2=n;O|`OiX>lptIBD^#X)DL3nFFN+IAx2ibs%&@N98Z0`O;Xn3T%!Ls`~J392kljU1(uw8?7Dq8RsCt( zdF!eV24-_duh2R5qnrMn_xns{vSU)%i%X5a$aew{|Azjn5L+!RePC29P$unsNZxtk zCeFipUA(=W_O7IPUGurX6twp^FAC^Zc_yIy<^xhWe&ek1d4&NNE*_WS7%d2V#cQ&o?Nm%PJNh2@ zb;;dpE-pR&BWnBS#3gb`T<281PK@KoO5)tnD-x7FT|=cRUqI@XTl>;TWRKi=$73gg zX=WpDqK6GK{#~&8?*apFAKutY9m07zE6ePcq&nKyUn9rOedNgbmT8B!PO;Bt4czoQ zOH|1;{Od|?zv27zlT7i!%aaN+S+nLFq9B5lIM}H4uR;6M;r|m^KeA3*{sZG2{O=s( zKf>~#K+OL(hvJ{||4}e>re_Qr>RtYUaU}Aee*9Rt(w)!@1Ck6r)sBGF0{UrcU`(G4p2$&C1ON-hn*{)Ee^XpN z__Ft|0v}M+0Z91O#0C%%dZG)lYCzI^fMNmQpsWC}j#czF0parJ!3zY?AZP$NJ;&Pn z39R>sKA$^C0{~`mA#}MKTFc5|3s88B&Hw<-nZ-kZz-jduF?^{A&??3l)lfp7k*m*I z5`{GZ00ceM_7im0>QccIIW|OSi$dC6@$LA8X1G(3q zn0u?wbUZ#N@nz@Tsa^e4j4}p;(N2HvcOucxIs_AuxJIVvr*-`Yutg9E=|em&U;qL_ zTAwsvtlv~FOnr%e&>u+tY!Rqo(z%S0MHM>*|D1;bLm(8;0b8_7qI?R4hp_Z_+syGO z0H6)x!hjB-#4SZYoHcX5a`)}At{V04HM_26Zb-fC;k|aB*5D{!*7V>7<=_|oAK_oD zt?-&UgMF8v<~HIBEm=Q9S8Uo#($CH+-x|DYwVZs=M=XSRoold%T=&Giz?TmN3T8Tk zxvK#sPL2!=2JzAKuLD8E>|=W~mL6(hr2zxQ~Bi31%4fXYIFV2kMP7Bok{ z_17(wKsw6;^cVsc2na|RY~hVS{tz9|=cfXwRMB@BfM4Cz+h$WEaN?sOTt;cr(_LqP z-LWDXU#tG%1$qxaIe^|iMikN^m}y)(5EE3XEv*|v81k`SN#8^!~ zMI#;)XiLdP3z&G;map^r^wr1s`>i@#;hQWWxPGfeTBZoIYaf7lXgdHbi0!eysc3ZA|AH090mvpF>L)&esb++5$<4u|u^Fa;G<(X&PO7Mp_Ce~xm zJp@FqQ!9<_;r;`=Id8cv&E-UKGCpJIotPc|;1{{8nI_k5Q=dH8EPH)rTC#ANHxzwT zOEyj-_0J6wDSvcGaXeqD(GGt$$W=%YU*LhCcplpeqP4DV zvGsvM$G+gtkH1M9qK!KAMKt;}Hon?5*P}jr(T&!YhCUp@HrDlEq3#1AJ?IF%l`sH} zrbUcI?Bn^4FD}wNHu571oH^VE0&qEYf3>ZwDOB@;l7m9UcP2Sm)byw;I_LV z7!1ZQ#O}OC|36?@22eSDN`GoL<|PDpf|PPVO#;I8FwTEu1M*mx1%eD~0^$KcfLOY} zUt)ljEtIvxhL*Ix+CA5YBuDA7dG-OUfAoVMgKz;VdTmLad3fE~y8!(#_02BI+i?)r z=6zPl*;)Lj?^K)A{6Pujt@r&7%Rw|pGh@$ee@7Xu3tNGM)pq+M}vG5|0h4T=8HAL(0IGNZ{8lm_zOCp z3RC;ECF8|p!xKBC)COrTxl3+w_z;SAXY!(6>@eMQWFd;k5 zd#HilkRviO3!%}L8EBh)L~5HN)_O9%G26aUZ#Mr;Wb)>0kFW#&o1O34UO}HP#fZ}p zCbI=9XDIQiPaLeZrSO1E3XFEL*RJG)0e|iHM#-%M%0Vgl55!B}D1KzOiW|F;ZpF2w z7`w%dZ2>*aq3ngu9L6Gnv>E^s2?%0fX>^+P)_}d!S(+2|a-~6h=`qy!b?H0rTPvjP$|`v# zK-wTN_D1XkSNmcguc6hE-3~zgs6C#eEF9^Bh5U%w<)9LQh1j>57ZJZY8WjeP>Q||L z`J*OF%k(gIXh7odkr(rtep7@i9&|<%voYpZ0aS>hQgHBKaU_ylTICP-4b0RbvRN2t}yaLSqP zXhf$k1b6ryawFGw1R!;FF3RFtX%Ml2EdUe_4RRs94)#wxitI z#$11@f7xT#^o=-j`Vy;}J6X1(`fNS)@zoCnNrPSwM2rfP(|5Y0nX9K9Y5u z)dd6}fXZ65{YJD15D*=J0QSzNvVOHG^4Jao7NU5G;{df{=Z?eEdZO0V?n8u{1?bxm z7JRueLBbkBE)T)7{TU*{WEE%xs3O>(139mK^Ng(ORfw!&pz_WF-_0K^{lyAI+N0-F zDWLvwanDtfM8EIh^i(@aveW4Tpj)9kV`pR=`h%5ulwE?DikR-rAi?TRRD?=d_fW3>r=iU*@y;Jx`Bn^_BNR@=7*$NXwnz;dEtq#Y&@c@u|a zsDZ{JMj?^+m+2A_j6!n^!mC1AB5*_m2lY7&L`98=oSIN%v^clQ_$Pv92xSmDqGRrB@~z3T6NwtQEGZ>*tWelM=1-AJMb_3K*ex)fz~8+t z$A2@BHXh#?{``RsmREnhW&t5@H3FJqFiYu3Mu3a}aQgFEAR>iN;Ryhs3IRj~06}3E zh(-{E>Hxl7y?DYhbG({SRwc?S_h$(A$*pa;cmSoUT^#d1D}Ow}Ph$_vD(ojRVQQ#P z{_J(1`+jO2Qbw}ZuO|9g&yLzqKHPbd7N_Ue6oVMe&(n5XS#ef>+EngeZ4#i64YuuY z_!8W4=}y6pGS7j~Q}-mE`ZfC)?O3WfoZDrTZ)QSVQ#A7UV0Yg~>|s{m{STWx=$5nR z98CrUVA0bHaAdE)zpkhw9WN&9Bkm+&U{N>_WZK{;mP#3%ZH*aI42{%QT~FzugK~v- zc&z$ZvvXK#MvihoeeG@S>Zt`P7jRBR>|)upT2B;DX8Sc4PZUq_6Z&lJOdO}$&5Tuy z`4a%U_;l9^V9y%i5@R9OpOw&xc@y1{%L8ai67Qbz-LMXO{_9u2-v_Dc82jNP_Yyz? z@B#WTn?E3&jcIAbB9SDZUk&uDxnOPEA;MyByAx}E*GrQcBDMAh-v|87;676$^8U(* zW32oV-Yi&E)^CM`K?_2_7S8PiY+)paJ_aUW)6I7lz!5@rep%EVm|<=KoRh&=B5wi) zON?AXYjZnX?u}>x0WpqM0CTe=MLWT{ZjN01hoZzbA>gutKwrH%NLDA=QxqF1E+t}4s!4%{9fdJN&KZDolI(P_B z7Zd8c&u!;)ySSQe&hOmfXQbph>fxefMJCtQVKCcZP`5~PcjC4>DS3E!NEZ5+)nOFs zK#J7%Ey)T>>ay>|9w=!jAJUSY)WDI+X_kr({Pn^vYbEcZu=eLA>S0+O9`w_Xa_ER= z{hc;_5ba!=?E~{I#5j2a6QB@*e&U(NrQCPlZpY>PjMjIsT!_mlN$|EJ_k0X*MUfcP zBk2%_!p*raT=wuxRQU@Mr7#)Ow_=^A}c~Y`FDPX zknl5H1*4+R^0o^D$TAORECswQ--zN-F!JecTZ|h|L~;l@ANd>z{J}5HVEU@^0Yw^lHyPX!SXv)5Z&;1#(HM?Z=icetl)Yr3riy{+PEGt+Q&>I=_I4pN5MjU>! zqh(cPOl0r_timZq+kiKbx4`BTxj%0~$zMGUR$<1wHk>Wr_-6_Xq}#E;oWTCpx>(?X zB7F0*ZZU-I^m^1^Wwib9XEP@~CLSzs(U$U&h>DuFsv8Lxgy6a^juGb%+BAZ@(V?R9d5XK_0XVr^E0I{>;jNvI=UzWY6~P+ZN)w&toAeEmyh1M86`SMuR~Z84v;y9sojnEdXo+*u;mxn(>bOA-F67 zR0M0#A3l0=;3`g%wVEBK41Ilku(sDoHc0EjAwz3BBagTEu&>mMXhK99lC$-lO5fC8;8{{ z-HDghqQlNXVNSF8Zz3wWmF3t<#-EX_9K|e>S$IF%W=^;6@oV;Lj+vBx6~dN{4(=#1 zy*UN+CLWldUqcAQaaF%d8C5#lv720!_|sy?@*_ zLv$Kte1P#ND~Hh;7h9VKHOj0hfr&rq;IBUcNMS-k=uglYCyfX+lEJU3z?CINA|GWC zP!tGYv<<{QX3r_B7w`&nj}@&gKiNTD9kA|^T7eiA-L)OI8(K=Re3)G}%3~G*4zn74 zb!FUqsG0%hH9T z$;VuGs|N0cyO2zNp<}-hE~)U>AF$9I@!$rjagmKX&-XiXgJFSWzdM0m&YjhD;y$uC ztbcpB`)4#74D+2!hScj^g+gk;+>3bP`+mQ0+StLFB*BQ3ItIKxcuu%Q5E6^$a(QSw+63rA zu>YOWs}G8pk_g}a02*33N(3|6oQyuzdqIsH&Wd#b_mG^sg_whz#lp)xS`4GjV<_*r z>0Vc}jh<$TL0C2d0=%713X)BKUL21rzfiX;piE$GGrwxGyKL4eU;Ku@?`>h8Dgq>SZ zC5Pwgu{Qi=1b_}cL|_xZqsw78oc9+6-sv?$+g3i7E{O6TMLRV0`{JCBG21}tG?{HR zO1OTeVZ=f#0i{y}Rgj`h^VN$Fj2dkI@N14C>JFV5{+5M1J3u@2WhX>$ow!6!+8BJs z?oxvJb|%eHB7C6Dm`Jl~A6Ssb0@naw(`Mv(TM2z8`{3xFxHuja5oZ>sIDTUx$RQLR zYMvT;tP>FJ{CE7+ZX2wCjqI6VFUBu9^VSqLTW-v>T6@wrmcaU)k;gJdzzv4`>3q;} z0uPoNhB~2m35xf%P8pHx@dVLC+%<@CFt-exM8sr(J!5$MSt{(NZ3`dCsxu6#D}?a1*=A$2jA4RN*f96TAv08(-up(rHANR2(E`?HD4}fB>?zk(zj>(dT-0e)QF4} zIqxDoeD!xV0fu1woIPpA=wvgM3)cLUD4%{&Kk8&#lszUi#pXR?YL1c&9j^n($0*xw zmck7h5tReUa#(A2q(dybMApxAyoM#XWybhvSIF@+yu8OS9#IU-o8RBGd%qgZ=!8s_ zgb|I(hN8u65+;tR$4wX{IM-LuBUvDtr)BOzKS-bf>#4HzW>Zbk=dv%67Gkrp+Gswb zT+UNovAjb7$36B|?%aevEGN19Y*O9IoA_X484g zO~wJ8;$(|kp%-BQx7Wsl(GH0>$TR3k0SHj1P$h7iekQ>(iE_~sVjsgN#0kHC9DzFQ z1?bLxd$t>;z3r_UQ@~VUvs)r}6r&3RT1Ntq7~-npm)XRl9nNE_y~&+E0m(=zLHbWO~Y4mzK6^=(9DWv;(};ZTm7 zPr&jrW}B=*3Pxd~(MYWxK53)P9&qQo3=jjO=_Lam=6NiBiN^F6aSX}bDri}(-yR>% zZPP>c&#$ZmL7qk})Sii?`>hA-n@f06{!7>WE4Y@&Y{AD+0s{-!TVezZ!P+%#O7=&c zf=C(|TlrXZjz;{bx%f&th{MU=Y)3weI|2SAB1S`u>@cSU6%z|_A2HtG*WB>x6$Y$3 z6wAE-sjxoas@q>_l2p4^rr79sLWi^w@cg7*O@cbqZOCVDCODdD(P%IKs)mJe&t5e7 zFu zQI`VM?ikzsnE(x2=tOXC66|F0P#J!LiMMD%b4UOn=N4Aq`|%w?2o|MES%mV{Bb1dWWrz!c06lUe)(qNKeUC6k^o7Pvs{T5cIV1G8(X_MeEf zb>m<=4S)~+K6;F01PK6K9{fPaO$V%Kz-9p|+C+sP9e=S1${L8k9v&SavIq9q ze2esn#y}3ll`Gk*Y&X|N06=3sjKnd(_(fTVwRaCxsld^gNoOX4YEg4!>?=PoaJvQo z0V&$G?Fc|B!$%=9nFZ|h+SKmbcLFxw!u(ZmqxM7_b57QxEr8BOHZcMazQEda%~%}@ zSQ+!nUfWoAfsUZ*s_49a$#__UKb01*9(!=Y76VOt>iB~p+6^|{d44%761CZ7VQ|g4 z{KLpG-ut8d(0%nS@Bam_?8jIHJag^j|%Im4Nu&=xgmf^w?bI2SZ2)(Q8*PHmi*nzRCTP0TBog0U{t^ zsR;)3kCp}OM>hNB80-=TnjL^<6B(t%3mliLe=L2hZAgdhj9HA6ZWH*ng7n|;iW^_P z+}lUljGSKoq6#~7?19d{I&}ms80ZMbt^~6yOIBMdVJZz~!Tkcd1E-R~X>WD_j)D>e zKp45cA~;`PsRuJ@Xm#X}-O-J10X(#w4M2@W+U1?#41}U>9}{eVfHwz&wL)hg0Dz4M z0N8)$k(Kvf@8Vnt&Q5jMzvLhe;B-g}S)e@n9TShpN2I4ft~>#Whj3v}eL}mb+Z1U0 zY7L>>QtIeCHG&W!YW=v(jb?NR1Az0`=cP^vT#y07)on9bc;Lp%ws{;N9K-V-{jg(u zL=+_!x61~2y{C6TZHI)Bt5vhjm&o>+YkxnvTG%1Bg){A`6QDS0%5qMLK}cD#UotaB z=-;yoC-ohhOD85x=)U`X?_}W&J|31|p1y2Y$<7PYpM^6>L1RsCfQMp;nKV^y~u8>2SC(~K(cf>aV8M8QLK2sAKK zU3LP$Vz)OksbRrr;ZQdVV`pvc;Ye5sJ_U7nxYC4RV%_EwNCJma2+Co^V&1_B;+n?SfQ{CxP-`0xo z>=(iOlN&_W#WqeW#i*6*J>nlz&mG0oOxAfY=t4kXd%P1V(g89-0@V`}5DKqbneFTG ziR-He|7!WG95{@#;>^IxhZ~fSA~iaX2_xDFhpglSmvb5!uf8`SI@K`XvS9)Og@deR zXeRq?)vx3f61337q%zBi(a51SUnlxn@XROxPLCLKxzP|>tYHR;Vvrl4)&(B0hdg($ z1YgtU#%llFX%Qd@7qUtixpY#jZB4u5ocH;l$VWe-p#b&wQ5Mv00u3n_=mN)R=BqOs zEpID+n$DU?G#>i08M8bk2vhzvF#=X|gHPf`hKV1mFTj~^LzUWQTzn01%b5{g69K)= zJE{F`5aG|!nVwaP)<@HOesqKC^@Ri3MF8;C0D#ILL+n-hDjkWoYn4t*7nau10o!M5 zhg9C&tJCSPey%nqT8H8IQw(~x%46j3Y?>3yWsQL)0HkN!oB?3);OB{cMr~tpxsX;5 z>uL)FW=-NpQDtYrq1O(}3?XX-s0P%t8@N3fEIojFGn>X~iwy7@rw<45TDiOum@%po zSAiTFS?C$yp`(&LY_GcQY$78ZHm%&%PH!7GBLVKZLB8&J%;39OVBPcp|12Mm`j63t za={RwGlsZe{nZA*01yal0t9&6HUxsf5Ep=TlX=}~{l^gD0zmKpENJ}*0AL7hs)kTZ zPY;#L0}P>HeMf-xLg2AJ(E7DI1;9fn5Yh#J1z;dp`)22K_X!=_2@vA?6?rK9x$9S# zD<-+_!K^L04f+pH7YG^jb=L*}gt&j?o87@uwuE_p8SFeQ`7z@$L?DzSQvwn+2X}Z8 z32!W^YZDP7A5$@bPzbF!W0x#`IkTc!=w1#00Vo|K`!3`^<_kQ)-a-Q4_B`m<2ZE_} zw+}!B1VYgUxO&EDJI@V%(C-eM83aKLSIA|-yoqh5%T(r4m5`4>V4Syva#1jZdhAyI z=y=6YlQxqVKJr8w`fudDXH-+&+V^|g00o4I(nJFR!AeJ(5`jpOW*lqyvPMIfN`mRk@30YxGNL5MU30tAo{NV3*EBi?&IXPZoj5#(M+!soVKM~ZTgh!Ceekaqg z%k!4(ccKiAX3m|GZk6?`?U9sbx_q~GcP-G^WNob+Z>18X@d?1)Q0D=vSh`>s9p~qsv zoE}y2WR1Jdq2?2%5_?oPq66(-g2ZSXE^4PiU!Bf~a?zR3j^{K6L^KRA7}=_3Ya`=# zVbSsigv3KL4YF?(Pk+rC>wElxOO5PzwUMkuwW5v|><(TTvNihh#wbli!t+awUl_;e z59!VSj>!3^UGIMjejZoX`2RBasU@wV^*4F>pM#%T|FEF{U%=0QePaI}{QP|(7scX& zpITf7mkWM!G0*=8_^HKp+UK68t)=-d9M``vyZ;Tx^qat`*-0iC4s?SeJ z1+_HNTRzE0t*`S*9EaWWmdVSXLw5HHe9@d>ET8jk)YH55K&v<};zn?b)v@;*ChK3! ztd)AZFUTV2GI?6nbMBV;@pn+#h>ySe=IBH@@61SV7xdqArERW}(e|p#BUCI-O zFIom3=sK@`;eDXK7$>aW)a2vwz=<7%9aZok;5S}SYI||wDC{>b1RZmY<*Eow$>3qsXv}TQ0)J&h7 zUQjmEKC~CJAReFSb)e!-G@H(EH!ykpP-yp~O%HBtvO6qtWn(x-VgYlaR6${YT@0ZbOR~^;IgCv( z2k6NoL)vfThVq!!gpf0DHXRSmb>8>srdwKdcI`8rXWhlUxJ@OSPhSvk>j?|$PUvJD z#nlP&UcXana4zNDJU0f`B{-CtcAHErweYM!{ZDZN^VRdBv_>9BngImYkP1HJQu59WDz7L~T5cv`2Q z`Wv75?Czc>|J`t(@Tt8=$N1Hk`8Qsi)TVX07>J6*@^O^6<3Rrg+y9LzyUN9XW6ECeFCb`k1K%J2 z?uPyqTK^AB*|q-fNcX=3K{d5i{||tmDyqj-Rk?ocEjv3)Pms<*!MZ+@2}nR@7lW zJ9q8P$M^^@2(K%i?Owy>8+b&|Jh-YMV3~-zr9l41rT%gi2~$prI|^lb3vfa*AE&hq zHt`X%cx4}=(gp9zdGccmP_ibM&jw2eA5OGS_Sv@c)ROYAKfkqK7*6iE@htB44Y|{g zqsygxZdLNdcYk$C={O-Z?R}}DJL+yC=1ZOOl(G)$fC^e$EXf$PUo+)%c!Qz}YNt5i zoqnMTY8jQ;_0CT8^lk0$cg7p@za+-!h+0e@`LgK#kZ`#u_H zIhahy)kF!qUAEl*H?Sx!J$10Ree!O~gdSeys$3RIr*M90KklkxH13OA8_(xIV`WgN zox$n?1?NjS7i|f3;}0L>!*4+-VfXq`{b$BJg*qOm3k^`H8%EC@&)glmp{}obGrE7* zQ(=!AMwd`%S&1XY!m~pJI^pZCb7IEtFv9WoWcYGqGktNk^S1Jrx*wbFN4eRW(^L8( z^A%LMp~1%=QS}v#%0H!EVe~I(y}778(HG~L^WjY*A8tOFlSLr3w1;d>cKX$lc=|J1 zWdei2U}RmR1NhWs3Q#E2u2V7>w*2+ZB&*MD<%BU$p?0W!9pagJZWl&7+caTM({gTS z$UH^jxh^mI(|a|Ernl)m*WRg!xlPax^Ee1?+iJTT^;cX<-&hO=)wT0rgIkxIe;5kY zJ9psMb>&=%%R2Fbm6|Wy3k>smIPU{b3z+5K-zVKJ7hZYrc4V4ld#Cio*VTh+d#?7! z^6f&UX?GZQ@8_tIs%CJf|913uu;YTtD3lnl+wxg=wUm05Put$QJh`^K zlPO6kvB%;B0--S}zV6;O<2QUiWBmp($^Yg3pC_=TqjT)SPluP7`}i8Fsy#P#U%bD9k9DB~hxiWIJ47ohtc_PT}s`nUG`f12h?GUQ(dCBG?a zQ9dy=18?|a9~9xZlTMt^z_a59s3l;T-uYS%AKT)_zm6a5$P#0L_Xq$i1b~IFY=j74 zsF4I{)i8)LUM$b0V=;2;2bAIzzfWc1B4i41KNaWqc_n2p#hRT zzz^W58;5oQ@aaGUsWu321z-rz1b|58a_7z7N`M3bMxBMS>nS0k0ob^{&G(KgQKj4b z$FO=Vh2X;`%kI$#&VYpVwl$NIp}>R7?pJ#2_s%p6rJ z>5D_+*EJI$45a9vH{tRHzm(NkqoJOd~`Ag*>7+XD-+xk8Z zSosVg01QCv(~X=aE{v=IBK-5VhjCczd z<9}Sc&+WxY-0!hMLG2p4Q)qNu)=;PZ`eunEgpk~j>@L65811bex8&}YcK_OmQBv#W zA>etB$#~4Sm~S)h@wjVf!5eetiONb6|<8{yc^Y+#K?h+NJaHkT~1+f-9 zS);S8$boNfMB+~D{!Wl||8@7SCu@`y8U#CHEzFX-ld2VVTdIC?^-!Dtr6|k^$tTAO zhkB@sTdlQ}r)YLRh~9@i`Zgp@@`90Z+x8>P(ygpl`K?7IHO-^c(XK>5Oj~vQ99YAY z8^?U%Q+eGpr^Gv|WP0yiu49DtU#(1!>Ts8swusPoOUx13NsP}|t9 z3GK0OEyu!bJ8h9DAx;e16AGPhbt ze;FkRLF`!YPy$fEI4O$(A#0!;!ZTn%TFM0^{*C;@LhPNkEI`kvvV&+fO{pvzgaCk_ zJhp(a0RkX^a1>w&$Xz5Mwor2|7@^U@$Qm0anbwXlmHVC6y#QCMK?lrE?yI(;BFQmQ zaxH4|XL%)nUpq#&ES53gToaA5V=Xm?gjz9SD1WGIsQCFX0B~SlQ28j!4ieix3=k^B zSR}D8k?Dq0Cl_|gs4(|PdeR3f?I9wJtr`@!*MH)h#j~S>vf$Nx@+KRmQ`jwElIKY7 z{!$Kx1{m3*BPCuDZ59Tj`K?6H{I_SF`TjZRB+!_wz^tO0DBJ2BVZxAp0ZKqVv+VD~ z57hez4~+lWH&+G^85tznJ$vo$`SoDh<(D4w11Q^s*F0o%Y1e%#y<1W(l=B{?HH5#` zeuUcQ?mAhylR^f#(a1o)TQ?Ow%hsNY(WgFg-`RXo{9C)SJRr}Biyir!5Zm$+~Kb~<=(qzDBsENQ`?Br=R~iFwCNXRDxppD z$yJn+W8bIZ>~3KAuGa7RRj475eEn4PiG$LuJboDm;!lzJ)McW@WdwP$JcmQC=d>5Q z+E^te-FGeRJJBS3OW{popYs;`DmtBF$+nnuvY&3TU7LPy5k1~tn(UrpX_Ogj;wJs+ z8Ll9IGS~HS>@~F$^&*W2CPH|k2p(F2B4@J%4j&tqU%L1H*wlE{K9Sh2lOl1ay8nFU z@>w^ves|dH4*klIz5PBvRd07~S?#;_(6b1|C)jqT4E;+a_ zWber6NO`tt+qUZ6WAsCp<-qJxw6BMk zQ@^Aa7%2f?pFkWf3c5=dH)-+&%csy|9nodvI1_o}){(00rS1U(|Ga(J&>K-Ap%Ku; zcMb&T5GYvdzm!h7)Ni#q0vt6UhCKj5RD?v?pI*yV!T?Hbcal?%g1{auJWOW_tqs#4 z(pxQ`i^Q^;K6omCEQF8%m|BJ&Nma;kGAr^B7|@U=EC&J;84w#!VTg4l2>}40RV*FG zt^+U$iqP;8z>1x~u3BPOXtjM&L3n_qQ;@QjmIw$CC&35+ES3)-+OfH#_yW*`sgOId zaXTQ=*GNkd5QHx`Z+sX40KIiYr@Z&mrTVCau-IC$5t-S#kGu)-L!^~=0Lbale1rrc z0KA}H8h~>hG~V3u5?eM8+tZqu#h#m`|1c0kK<(n%8WFul%4Ub@C4q(FwVGXPN-kIX ziW*i#w_szLR($ zQfguv6ePco*PvqAl*7=`&TsXjLF~9BhRu9KPLdu@qq4x zbaqgx3CafI29odm*<}9VP@=%HS4`E&MO$Yc5wd>tF&<%V=LVxxTF`QvdGd^%XR5!r z0Y;pgF#Wx%!Qr^F1=NI%hME8Is^hygxI-{<`OcZk?tAKrAC&WHyB?w7)65sUTx(Yu z2yG$E`1<|0g|H3w>G|kuFHqb2=li<0nr7-Ke`@b}@?gol&qPg&A-_(zX5#K3{N{&= znZQTO338RBm}r()S!wpB=#zWZCbo)8UuzrRvQ>RTGO&QxcY#-Q7m}Mr1fVOi#dKJH zLwwaFILzTekSJfmaN&5Du4~8E_*zA|?1!-eRU)z1#??=KYr3Hjy*GL(%6aJ3_Mu|R zH?3FCU}z4z*f?xcUHtIw*lQ0fybT@>a}}^!Yy}HpFhm?i(h*7eG6k@%AB#%b5QV5j zXCgwPa{{@e&`pO3h(=+Uqd7`|v)7C{9k*Box~KL#DUCy5oHPj7^Ep0CCi~;yYM_Fp zB9EUy5rw1quwMk?LnqPaKSM0qLJX6&L3+(s=XcILvg6rsFfypLUW=qN z%cu<4`#nOoYN1qHosHU7B~W+Ka zF}}|CaR7i1>u#l{5u$RnVfj8SFQVrG?una6ZMo`O%UN3s zjaBItI#HBrI3(8UP=F(*ARWty@8=3i+)M2&w}NEXiaGb>={b&zyZr0e$-ENO;@ppc(m(Gp!h@tnEiI;qN?75ghcy zrXp>pio`LyuJn1Rjz>!hSsvrJB41)Bh(PiuMfNibeW#w@R}heJ?elf3RiL*429Uw( zeXNwplI^qX^UR+hSCK7`>0Y#_wa{H6j?GPdtGyxLzY{$RsPsW5eytJCpUo$j2?(o; zTd0#Q%Xms1ztt7pYrHDgaqPzf)lhZE`h&M_+V_g9el(hAyYN^>`2peA#?prTuQcW|>OL2aMr#YJDo^9W}sN4cgZj?`LCd>7eVmDzW~aEN zYJiBXHGt1r>~_q}#zQ+Dq>{iQ3vj*yirvaVHiEUg1OT8R4p_ioQ8^LIR0NDs=FYTw zwsV}0wDSmoXO_AZfcQBCfVBoPfIux2)VtOkX-}j~tWsfr3lITOUTD$)aVh|2QD?b# zHYLflGHYH(01{a;SAdn5VfP%Es}&;AnPCvPm`zR7UF(O}PQE%0@6?w+js<{Lz4D{Q zshR}=I+X;%sQ{TBjwG_E9c(n60$3gC-yk%^3?D^&zy)e37_uEZ0uqw?Nmog+Ft%!e zr#>Z;23WOpz!`PFI1J}n=6N-E`O@GdDq!?OAZU~rnB}Z-$TZAJ+}<8vm3@-vzQ052 z?v=^)IJDUEH^b(@;bCaa=wwWgcZ>MN#sj;Y69s;JcOlJRx(W|eO;F?MH$fi8@YWkp*LvXdl0PF3UT$9Su4;AW5sS_GDnpOj9xWh3xX1ZNaX@a%pup9T z)56WcE*;NkaSMJ64gKf|3`Q0`(6%GDCQBg0-TfH@tXiGSBjP2yeD<3i(K68IZ{`d9due*$59`eZu zjPK%0cHW{OkrDT1d3@)#t%AF?^pL>tJL2Xq`g~huf|dSBl$QL&otM2W<=`Fg0g3aU#66^mx*$E?oF=Y6by#iw@C0Fx_XN!}h)r9{V* z%JghEG`o|!T1;2`aB(ZR&_1;r(qw}33HdC)>t#K91JmsZV!mC;7c08SiYsSl&RQn> z_=}MJm!cv;0BO+{Tvqv(+FqL<@p3QQk9vl-wo3Bp-v1g9lTm?ub#pPr@!lL(p{pgi|wkk5t&*61IvX{oan=*gi5^BD2j=>CF6{tzJv` zOEo*=7@$-cumJ33Sq60o0mq9(kctKi6aa^<_^!%89Az&?q1Bj!kANnu0G7VJKDqL3 zm3=JbTt*V{7=Vx8>p)0mOAHu7&}{yE=tm>v`7^*i>Ow@skUCA$6Q>^lZmv%98PUEx zm52D?0h_`EEC|VC)^6}LYIn4A)aMl_9B552;!Ozv@HyXK$D5Q>rTmtiVpO~v*}L1P zlO>vRWX~C1-B2haYv8ez3=21J(_VzWZP_gGLFRx(_i5yic z=L`DL;?~%U)m3_+fCe$vUY5AJ&^(Kx%w^gPFw(7JomvwDD8s1uZAyEMGW3h1FV3j< zc@GQnm@@QJ|IE;TCvI?on}1?}q`V zY@drstBP1BBfm?_@_>i|#xnZ!-+$}VcA}MDd-Y=sFnV&A`3UcD^DmAVa%8H}(-3o( z<%9*(Rf>s!Q6{3&>L0ltbf`)&?>5j43@kLKo683sufyn_4-{cog&aTV=3v3{Mg?Bh z&w-haVY;t$g)|?}eZdH$>DQY)CHFk6dl!jl6|F%DySyBvv$Qq$8ozh~1Q(p(9-L21wJiXd_ll9a4lp2q*tCQ0V=O;E=9-s!KVJ=h~-JQ73i_t8tZZ29g3OpIbo*=cO?psf7mbV`SO{_g}<1RUgdc+*ozHLd9!k8q-ek8bOD%r zwDDAD+;sC@-gMW=!u?PyPe_KGq$rACM^G83r{3pTR@7LUv1p_lylDEZu|YvpZeMrc zhfX!G)6=OWCbv+ce&%4tsVTW{T2%|Wl#A5^BIvosntSifgR##TuW#nsgVp*y2$sou zMXJV=23HKVrLPNns7rbl4Jjb^8W-*B6}p-~>-tL$WezJz)gJrabL(7DpZ-XHanUzd zpFKtM`suh)GxXOxO4J5!N{B%V@+>a&yFN9Er1~W}V%MYOAvPQUBEcX(6V_NIF_z6> zPZD5%RUz+HKNrH|C>*7_{e3QOjTX-znJhvJ+SVfDu{f z3_#W3-1y5qLo|B^3>q&h9)k*eS!lo+P67>!>2wwm7YBeDDkG94qc)+s>uTloM1I3I zfM1_6h@dp`QozkB3^II?Ss1kBgRDn$YeTZ(kR1{Jw0XTMEQ<*b08j!Z(*Thu2q;G( zz%m=217*TtM+{twnl7!O=_=?lF;8gfo3t|kVO@6uW+F?7ZQS9riZnU>baqvVwg5mk z`XUVTg#kbteZ`sJdKKIbq_NE4NQ4i18B{t5^{9gmJn*KGpySPrj<;z`QH)>Sfvx!E zj`m0z0K>qH%UA%44sn%4=B&8Hriukg`Z4!)Aau~bTp!M&ODO>Q6FkJMY3X>4=ADN+ z<_-PZf~?840~hdXgOpX08JL?Ho%>2xQOw<-2aKrrv0*3B0Fx;Lk!23i9#@UkeG0GRNrL&o<;!NAI$GyL(0W zW4(zHp%;z0V`B34E)PoRPPCx9q;RVzzyHnX2wtOQ709X_Y0K@5CzvC+@hoF7m0@-XEz-bS) zsANmwJ1l0xFVwUamAp_#Lmuj2!5=gNwrOKo3Ds*j(3a^Hm{mpDBOn!BP0BAke~(Yx=5&lNR+zAig1Adt zPEBrF%l+w+z$odbmpvbA=x#ZaC*Q7OD&p&_pVLnsSbOewL3Qut^N+D1J|(F&U9MLZ zRP)r-lz&PDis&kn7epcl)ur#s8eMyEQlUI^ZUJkBDW(@ypa_6m3F%dC#4g+=%uO&A>2qsK9cAdo}@{ERgbClaNc#FAS`jZ<7! zUfwB@m~(pOcxvMTvCt(CuVT*kmUPB+tG}+J5JK|)V#5G*I<=VLUBW_IST7Ltf)IBC zXO9N}p|n~`qOVC=>NOcFn;a=`xZN6B0TTT9?Rl?*aR`D%(1%stlIq*kromOOi=+KgCqdhlW?5Z0z_=LLG?LB@zPr2Nl_4Jh1N*-S!6(4LrAhP z4cOBm#F6DQ=AZ<8px+oF2?i7h*-OPI#YA;ihm#${D}^|bBwhxQ%EW`)L4_TW!*&s` z&=uWzNf4Ezma&fLu;cLD#4x9gP6hS@?CNH%DpouozOuWnw+c2|)_R;a;%Gk)tPcIa7Mb$G5W=6*nf1ynBig1Vb8gtqQL7{F&Mo@Pb{1KjvL4~k~JsOu4I3ElYlSR zn3fMa_<`rF@x;$#n?g*Sg&!R_o>|ZHa<*Il$_2k4!s@NpMF^pOY*>$p8|~69q>n!q z?t0RA!(8u-xX$)j+WKO;W8`Qk#J@lWc+k35g$1;wChoo!3(%4HxbA8^6~G(_Fky%d zjC@$gP3lGes>P1A(i^Hj7n;I|iF!)2cF5w0MdZRo4S`yc#Z9&a|G74G^WUx>%c$S( zLWq6j%Wm6`s=L+q_qqF*Sb(DieqUeA&&TGh+_16pM5--66zUR>WOiH)tS)30?l*aD zUu2r1+kSAHrTN*6~ytSIW>0Y7o zbQ)|~c`4DzMGhtNBjr7xnlm@0qW(#rCuZ%5R^zGG&>)}gIN1mYah`8W#{p%k&REdp zLeU$&`%|~i=92lM-{)N?QSBn{wLEW2G{5EYgW%S{lTLg^LljdZLJTxA1yZ(;-<1h< z=xIN^St?1Nr+_EJ@|b~#U9h!-ZkD9{uj9joi(PFzF8AV6>vj8HYZp!V6g>%d$}a9d z8UctPgsgX0#xGl)Y`v&NYFRirMU~w*Z?^CGjoM?AeGnTi27))q05EA#HI=y9>Q$6s z`B`%y+Qj#>&sy+nW5xMffxU7fHxzg-w=zpwpX03=4CCl>^g41wfehOKHUJAZ%>%m< zU%t(3O-<0z=Q!wC9Y8ZdDAWpynvo;(ClyIf0FF3euGh$VOCrMSO%OeT+K~=X)A=Fd+ZGmJkyro^<*Yd`_>&+2E;3n+4U(BGygZ5L zlE?sQU{9|0)dz&)1@uUa)711oNX1M*=GYS>Zs)-y2!zB_KoH<$&=Cs+bnnA5)_+6G zY@22x5)%0syxLbos*749&2Zc1fdB-+ zH6=C$VXt9}l&DY{5iTP#CJRG2##Y1|%}i6>Vvw2u+nv@1KL{2&UAv?wv&LZK*ZFYzqOdY@r{IX>#$@8f;+?eq4c zn99oc9rHIA8u8<0a7oN2vq@U6*z7f(jp|)yg1$Q z>V9pkDEs}ahK-jv*P<9~xL=68JU5uVyz=pStH9^|NhvzmZha>wm966?o<%u)u~~xZ zY|zlW;cNfKNZ`%A+?}(bFmf2VVJWfz*>ym)LCS_7KvI!B0PBFSq|Yi}vuU%lbB{+6 zEv6}@WduNLMtWl8YEVpz{2dSVY{Z{(cYj9?oFB>Y@7nHG`uy>U1;^sfc#%63L?Itp>B$uEP1_U;AW+(=kuo0j2)TF&^htm_+po9k;lj5hXnTt zs(0VEp*E*1`I(rUnE801Gurg2*7r|1fA^F-Ru3>@Z{LOYnJs9TuM@DkCdOC123VY4 zR~FBX3@fGGyRN@*>kkbIGSzgvBqeUuD#*KPrXuaN6=i_UlJNI%<{!_yv&H=D+k!TN zGf!^L@Yu`~$ZBEjB@BMNm~ov|y@Hc;RzIdOaAkFnO-e;`vfEzYOizt76|;w?#~i08 zS1lFX@mUi*J-<#YZ#CFJXLWt6-zp&8D%?6+RKSxy_WoYtbiI#j+>SGnii?Hwa)+a$ z>RKfc@Vv1(GEL;;3))r#|FNj;!$mKL{eps)nF|A+yl_F;kp`=@6I3b^LTel;r`WJ= z8yOpaexokC9Chlg@Ec4IcZ%*I$t)HvzgKt5^0S}%jf7#vVFh0|TI;E9{euGtX#5!s z3)jQpm_2oPZfqzhdO7+{oy>N0OWg2XGyT50ItQLH@BjkKa}BeAQWjKpzZq~0{Gulo zQ#3uYzbb5hxUX=bFsR8v!r!vXDBC}eHcRXXM6#$z^XyeD0yg%uW|f!`x{Ds29oDPk z1;yng5(@y<-fd-}%P#<;Zm|eppNXCCyavLJk~(vyCgM9VO}-xImm3C1rAroaGuKJ0 zq=X2h-e;WH9bnDC(s_W&m6D3yJtk@4fmaXN!e$yv(tTAm<5EKVJm1fJ25CCb>_#Y8f}n|yc)r*%A7>NqSu#WeGZno;95iEg!|x`ogX`}H z*qUCH4jKvIEo>S9331rAqTkOsgNE12>+g}+WHImm@-gM#~9+XU#BpgYn zOwKETUM3STbHPF+9cEFf%uA+&>+wcavVdI`hX5aIAA>dwXRiG=E{?l9YPu zvnJ&XLj#PQy8%Wkp^FZ~fZjrmk8N27cs6^HY!OT#6tH7=;Vo(oi(5n~!pR#h34KMc zc1ozsKM1QLS6lFi7+^3M1-Vzt$iTccv___|Ey?CjIE-l)Rwe7|xSE&mPR82>j*-yI)y(m^ zl19hK!7iO3xf9|T!~KJ+U07#z4B3{@rl0$a`zREu3HLo+ss#>$jpSWPoGvFvza&+g z6xOnYH?R34;R_W(kq2HpRTWHC**U9l?Cgs#jTXVut%7O|*f>WheaFUe{w}S>Do0`S zd#8QX1CMrk%rR|M?XpbHywRCKp?h$X#cjJ>$kqeQ*XjlL2CiRKDiIT{HcvB>>*9&j z$i(nJD#(dTH5+)_#((&i2Q5$C-1lBjgZ5_k8i|Y#JfX_1GQNFgPfq8L7e6iWzC9r? zVm_5&MZO4hRgDJaJbmZKUKZ@c8mvxGs$mhdNxsd(77N}X{rt$B&St@@MxT$$YE7!7 z_g2LGh*IAXeBsoeu~|h~fxZYOP1gFQ(bJ(*OE)A~@d-FcKjXtq(p_;;V#vD3!)`HZmhqWR-Q)u7e zn6569`>88hQ17Vpg1Y@^N}>o$QR>mP4oqFzbQ4~tGRE>Q?bpPZD5)P>CW3f?kRWKV za^L7IaYf}@c2%vPLXfHM+yca+fZ25`h>A1<*0Ycx{OD>6sp#7itZSUf6Lrh)-P&4( z%WrkIFY^jDj8axVVtb=klWD|OhhT~q1%Pf}QUt`LvRMi{?bBG0prGDKsFnn?pIj3| zu*5+UCwrCa^~nhkT|C|*uI&Pr_vezp2owQogx0kB;^4u>dmYv_>l*7;-R*cT?*{gh z=yhZJ30n{bES8-1f;2q< z78?W^J-nPJpwx?o0Mj=k*E^*A+L2Nln^@8?6&wwqljxT>yr_(60)%G+gbLt5Q7jV% z5K@x`Ch2st&npN9aR`9Tv2Pv*d4-l5HsbX7y+^!1e>A#7eDT>q|=@4|t}q@lH;q9Y6! z&)Jfq0_7;{R_+oIg+fWaE{Vj3vgpt-^Lq2$tSSr!8<_4{He4(qUy^%0o^T}^hx6;G zwkA7K^z&O$Qn<+RnBQnoabmj?+p!uLXii|c^D$3M@lkkRmLqn~c=)GVUL--d^SViV zvR2An++A#T(0t6ANG~6!SUSsd_*UPGLo4b@r|zBGtX)d{;& z|C{Fc-!{Z%_qmn2!pH9$`_@dZPE;8F7l=9iVk;qeMvriDUyEZ!B;d*| z`NPgE5B79Sjb;ehL5qWz@BPwT^O|dZ=Z7ZoPmpM_ejhanNq{qd69GGgB!)`3^d&gv z9nr6PvFG9El%x{gZu5@T6gj+uH!br}k7T#<8FnR^-Sgm=j1{T=VQ1{=fdokP$QS6> zvCwxbBb`7g6uME;Bp*NA4mn~M{$fqbYh$#$HN zKvId`X;f2+^N9G;5%1KLEdg0EPz!h|KL+^b*9-7SAaBk3Mp|J9@X2}k`WwaZwsbrI zBfsQ`?4Qndkk{9=mpaJ!ZtSWak%rXXz`lT07v1nwP+qyTjBZMNIzn2}l&byszTx^B z>#l6CfM0}CkoZ@}Lq45mnfvR2K#1cqrJ@o{Ke{L(K^(m+`}EKJcluGcGv|jfs2979 zglMQ$DV(96;I6d$;~|bVqz|?)Q!dD=UBj!pt<1NaHkK6K9vs0M!f8n1aJbWLILW-u zjq|4X&}a!h_j4xS`){bm-x;rcEvetf-R%9{l9o38A^dNoB-;PB#qMf-0F z;eW1R)c!}YiT_x^`1`_tDj2o7V$$={D%yYR4Fw&!KNt6)iuON^-?df#rF6yb^Z!Q* zq~F*7uTJ!jY(^|cP68QNfxXheh$)b$UE!Q_CWj0j>JX(E`5B5+fvtrYjve) z%Am@SY@xo5@|SZ-I&(4uQgw&?yB;fEek3^`o=li@NFNg2TXJ|t#X{TT$NiJj)i03< zI__49>W`Wpo9y&}dQO%1?a^5c#_&vFKy`Px{l~Y5sV)up4;mM}gxg7n^IFI*8>LTg zr2Lut@dvb{?|Y2-m8fXMJMJCwLf|Cr#pYe#XZKI@P4E7;9H4%Fijc|w0@cPJeCkre zH-Xd(t^GKkFNFA?wgSHgU{8zMGwAZ2WQKK}Z~H^uqH7aipPn56X zAe+x$!@eSuys-W8d5^?<^Xx<8Zi(NE2`aY*>V~B|6Z@0$G-l-Vmkx=(FBVCYnNYWh zuf>N5vCe81$2j$$jcSP(kC}GXng^$PvZVXE>dsl2Z(48{tF%#xcr;rhyVvK@^6{UJ z-{OLV=zh@*3a?1L%Hh4E%j1ioHhV%!Bq}~6N-9sU^hIkok><+XbZE*p`a5L~25Abl z$+7kFr3%^z%y69AyCzmB-wuk86uipP= z??8LyOEdWfx!o`IaV?1@skeA7rOyA@Wxf}G%c=9t=@RS9E!5|@^fb$N!AB#ft51BY zD2ZsjFSGT_p(AHo4(;MIetKQpcN1@Trdas1=T2x<&ucbfTu=hoQBpiC622mB-)vpuPCC`ea+R zO*vLCHBJj$D%pGgDeQ62>+RNaq5Nl_3ZJ_lvV}ihZFrS8P+Tc~M2P%@hp_QbUtN0l zmA{nQ&mLT9ZSzr)8Lz!gVks#KY@Ybww!7le-02j<@c!GSN1Jc0?ZuQMHXNnD{wTe( znf>oVGglYQ?ce`ee&Tm<_@8z9zh%|`Guh#e-M(Evr*}+EZ{}0}BfE`n)4#i)e^pHX z2dYEu|F=|!TFP3Q|0hI;**u2MkBqzDPfGav<4O(xtibDv$o>)Rp~auw9i<;!cV*;w z!qktTt$1b0_P>_RW&fyf6yu3P`QElwmH3$w+=M?a$n$5gs@RUJijvbkb^9gTTcref z{)qZx=!W1XBeVMguk_q+MHHY=(nSJGhNd4{YtCGF?5dV%P`|5_aO8aKhr1nz6fqJ@ zZRzd$7j8TecKXDt{iIlVeET!6gm+Vpd}_jHPu+;}x-0N9#z3Me+7}ma=)+xJ!nF3; zQ-Aj5U<|HA9qyTS{&s&l2^VQJT|a8I*|bw}R#;6i=ZJ|B`r+ z$am#JNSi%hL1)nX_+8Y@tvxPIN3~VDl28Sr7vBr#oG|)%OYmki?(`#n+1|~v$`7{i z49Od-$o~ARAvQ9{a9e9S&s1=OKtZbqE@aQrGofvoG7tId6fu~cv%5l?aA)j<(+}S2 zXjRHzJ;=pW>yHY2Mxjv7eDz<1HXAzE$mcs4izuHEFig{qQ!AD0)bEUX*rs*r4k6>6 z)tk)(!o9r)LR#afFL%CE3C03-`z25RwRF?L9kp-ELDfc7`)}pq>6tsF!L3)jv~NZp z>Q&wMajFCJc1grwb;1wzIcuBt76bWPzSc_T<8}E|a;>)TrIasTypsn1JY{IXR zm;T^wl!TPw9kVGvljZkL>W_>JlS*#e`Jqtlzcby!clZc??~Y61aMnh`6O&2ui&0Tk z5-Oc)_1|;lFFr;c6et!;y>%o;Em2NVd3RE@3`Y2tOMbL=PUUU~sh0fW(_1mJ?rxuX zA8)Uj!xrPU zbFO}<_?g+eV!?0u2oo69I$`A}^M#5DPn~}!s(-o(Bpxt1*Q2eOdB4*mdAFrNeR>lq zr{}@jQ-mnOJzbJoX-Z1R(Le7Lx!crLyRDqK)_rH(d~?Ch4(Qt4U#3IWZ7gfsXW=WJ`d&dLfdv;$l|-U)2~y%PxVRWqj~S( z2T8AwifX$&ywzdwX*$vNr&M;@)VIp6L=U<7#Vg&3>xsW_5TmuQa*-!mgJ1Y6pRIzR za#R8@thaAt$?I^Y-j&{if6sqMbhF%FKbaC4g=3Ags}(=t0v${DJM&me=f1VMvz<|Rpkf`8# zGwtIC5(~*oV)TzvN$(&caE$v2mKR8Xy{wu9YTUeZ_f5LHD*ig~d?sQBBGD#9 z5=fLISuUf52TD-%zf;B=76~sL&zJw+mF6~GvTO(aAKI$vd_KbsYc=InLA9Q?gKF{*n# zN{RsQjILGY69|OZSUnrl42*b8>t0ctFG5Q01>YZJMx8^UxETho|BJgfk7j#)`+xUt zRih|DO|2rv4yKyN6fso|Z7HRs#u{pD(VDUm1g)Xkn#ZaXC8}m6+fKx&-$L{_nh^dbJqFm+<$)7x>vHYvXbk*?$`BtpL|>>ZX$PCE!RuaGbP7d z67l_0@m)_jE$>V=)V|kgVNR8^ao&2475-M@0|nX7wasZ}6}RsgKBno2Zzi~+Irbjx z2QJNGR&Qmfh|7A|3R}CdSU)p;RPxMoN?uM^WnG2fK)jv($#lhCSyf^x@_VlM!zUaG z{VJ|(Xu+#L!!4B4uYQK8d_F?$*cefomekI;Eopi7YH}V-DG)8xya*BcF?W>3fDUKj zge1h-bg|xpLh8qAb5D+??{;~qTFIcY{C&p)3mt=OMyA$QAHzbk$MaF%)#U{<3@Wu3 ze89=k0;rA4dW4_uce9lBt&~|IiWnq6x5~IGdr4Szsax|D^qcaeWeWbjQATR@Mhkaj zbMW`36e5+16cM*zZ`Zb=n{Bq;`;yUNv02fUL!P{onzr~-T2sBD{*vrw=((q&&P);j z5>fXeYDl72C%T_c%#Yu0BsBh1H zZ7#JEMfqyTOfn`q@DwKA+{q3AB4aXYS$grMMV)%GOBP~=?WWvVH0ic(mv91Vu6QNDQVc5dihbCOQFRr>SUq%`smk zw1oREn;ox!I(Vtx7XXZat+(L!q)I%p>Y-@G?JBNkGdU+*>eacYdUIlfULcYI^pv$8m9O8`J=$G7_4uU$V{@1zB5 z#dH{*UO#4Qx$gIXQcvHYJ37jss=L=^eRAINy19zJ{U&hr_KhyHZno;DXU7$5yRe)p z91BOhNMjZ%!*`#@LZKo=yziMXJf&en*n0-+UD=5i$NsC=3T-%Lm2kc?PI9-PyG@Ee z4x$*77x@nx8G$4pi-XwPUgfo5hX^^KCA_PrImBF8{n`GhH3XY6wP=K^P7Ocb-vdV# zg*-c@!vETotxg|5Q;=>V*1U+|jV*seWC`mZ_V7q7(!ExfUE5~f)vW2PoU z!BWXh+ZioXV(DNhUGb&%(fnnMTw2tXYo$_Ragqay7~}XCsof@F8D)m<*`JgjT{f3^ zw@;T5+UsNy`cV>?%X#$jfwIFn=nh-akfJ`8Q!&o@6wNox7wi4Ko(=NwiNwfO&Pz_H zr%>_bTn=fpVjM(eUbyUhVSaGmw2TN(XcCuWdG55Ap(SB#%xWAzq8>UHtWF;5^08P$ z$2&GyjOhgmB#G8;w4-P!6d-}ceVsgjL*CN@I9eEBIyW%zLDDA^ z=?ottYJk|zOF=P^0FT4x4UyM^UB0W!#Gr3e_Kl9dZpD6Gm%M6~bp|}KkIDFg z+?oE#8$E?j!$09nN!@KDv`tUf4#A(q$uI29Upd~RM~z|-M5oC8s#C2R3ru->2$eXc zL?0VBtX7KVo~+%Vw^?m$tl!IAP4p5xOkok!uOS04<|xUGyBOJYHGMUA8hQp{$RaG{ zC9AqaK!>gh9%V@@N_hMU1b#pQ&XChvBJ6|2tf9|KM-?S!!By0~$E9>XP>s_kjezj6w z9d4Sh?o(0u$V`UL?p!2vTkK=Z)onpttarCnnbXS90#Cs;Ig<*vIv!P>&;ip|VyoeB zX)L8`u`hT5*)o+B#frJYYAIflG3vd~IhDZenNzfHf^D<+DHJq)KPV^#vYY+J-B^Krgr2} zmZ+(^6kh=fi<*ri+?I(qVQFOw2#~>81Q^k%Eoij5(sUbcM`I>507r%v@Fnc7R|nvk zh27~n^QY80mGI7U^;%4=9R-p-Q^$3y{5j!x2~Z?=fhyE!2OjTtSgjx_^$U`49H8|^ z@3}C|laM&Z9V!4|r^%rvMkm7e-3k7C*bOk_HyE-)Apx8@V89QOSN1iKw1ygMy44n8 zcDH0GUp^K^}0Ad&YHp8?5KxEtAjsqGmg00FH?VBxc_R_})8BvjC`9 zGc)<)sKGNYnZ&5-MgR^ljlhAbsf*p}mY@8l2f3W1j5#}JMc}G9DZ35;=uc0t!>?vCUip?c(W#3GamneXBI>6s>dC{HIEczwwIU9& zF;|$Nc(?R}VGJhQW^xpRsn)$WP3Wk`c~@h7r^6;Mst9xNOF8ryskUD)h0c`c+s##S zS+M4^I++@>z+i@P@-P@|`8wZMeX(UR_6PDIRM2QRF)QbGm9c$K*q9AK zwjzkz!;)uuqSXenwL+O2d)@*j*)CR$J2WLwL`o}x_Pay_-ic>T6W9iNGm8DjK z$E5z(n3`!-4`*(7rIVb>dlsxYd#RzhfbyZLPttwsqy5_Moli&H=VLuCW4p@lq^nw} z$f+8fB}Ad$o7xx+)IS8%;`eN_c#9!EAOX0(-ro{8^} zAcG0jXbYNG-mLNZO1P{spC z@TrD z-b~xp55XC`@^A({3`h5kOl<1E7MjZ)bSGP!Q+W!104Hpa>y#*#z-Ih-w`)mr<7o~F z#dTdtrs+fPn!-5wxuOsR0-@gly25&pq)^B|)8AGutogST2i}_oViM3)O!94e0~kzJ z)q83tGt2nf<0>7~yFxGkz^-XSe#iqF(xiniuA(l-U$nt&4 z7#YisUfu5Vf6f&(WU6YYD|V=8@kV!{*OiTN>y)>vAZ2Vl0w8Vat@4)wC(|g*)mY?W zfSq}U2_UVb$l)u~9zP4uUqA&gP$D<+xH&Kk47MU=8xQS4NI>0p%bCz={=^vpkn>tm zphb&`->=D#lt2 z2TJkac>_pF-MzJwOU=I#lj6_b{Jj3eX5;BWjoY=W+zEbYVUEn_x>x-SI5HuD9(wl- zbcx;v>SHVUcjxEO9E-W!!18vm5{&xh3e*zAqnT4M(t~2DAWbv-FS2cONSWJed zr7jg;;!xy;cq!&`9E6wpGb)01UAm0Yq^(Cpx`MjIHFm8q@3b>Z1TeQU9u5lyc6M?n z#GpAL-sJ_wI|Qp=Ujlk_TCvXkUa3_uiHY3M*ACNRLO6TPZAA@bUKgoQ?E zu6Iw^ayr?gMQLrsMe(x;06?6$LXDqH+zxo8-hVf^Z!LXgW%1>N#+|ZjV{eh$0GQ$I zukt*Iy*#MN_rPnhWVp_fhpo|gHNPN{`#}-@Gn;kp^q~u7K>KNU-{u>IxxVm&&7zrT z5}D@z7SPGFyj6B<5-t}KnRg!|skpB7lfrZqj>7Pcz#AUG!|CQE<_ik|m=~xiQeA-m zbaB9l60@65D6Kjd9>|>?i8@U?19Pk6`W=PBhftX=yIH$$=b{t{y>)KXy;#=f*CqFIU-PK$?AeK>@+u0@Z zug}9knD5Lq&YNg8CLwA$uG`SiA>3`@_@$t^UBgSYPL@{ORetJ*rI6q*@8z!IVGJgY z1vWfinw8p$3#$yRC~sQnwp>@~;vV)wApFS<5p8UhtlTat|7w)MU@(V2#>*?pEB-kL z)W#{^GK&$1ZZ}V&H8wQ^zdi5y^T*Uu&~=5P$I3eC*Z%qYIcVfg3Xr>QU**CYSAFo# zoLyOZR9Wb9^~{X{r^@Z`Y%h#hA(uGZ`yIY#``*l3OOmK9a}rS&f2nQ7`>~+Bokk7* zuE#4YbR}N@qIlq~9qD^*I*)%Fsz4eGW($s^Dy%cKw_AC z^viR-nKs_9&T|YM+&RRsjcqR5^mM`L^bJK1CkwRrKb0y(K z9Pib5&-WSJL-}}wwD~)o1$DU)V8I(EHyMg3T=(b|SiN;D!D(rG$EiE@^3&vtVUI3< z`M?Dc%1(Sa43lByR*ci%UFlKj3X8sg$`X#$hNLrTkX(0wrMgQtQOU4FRPXg~mGbyO||xdu+(Y=WEzoyTKa78 zpqIfc8qj{4z)L`NAV|00_s@1C*2_eE3VDaUS$5@Yadp>#IWvn000Fn%2T)c>$sJ3v zEhLe&a~Lb^`+nMLwgW%93ffU;prVdf^t7%Rcrp#HNzOQ0l!lqLhCOH$K#4%qMQI}5 z9QTqnuLwBr=CW%wh2$BGt>ZO!4_o&z#0lLR-z9WTL5>8a%yW+|21=u z5jFpl3z+~Sm@AEx9g;1H@bfr@*={akmRiU|yuA152vAUQx0UwTgNX#RF(SaFw#8MiQNX5MX4EVmrc>z@SyDMOu z1y2A(hAv>-U`A0B0AZK0%U~iyXwVgg=bjaF=BVYQ&+1g~dS2j=a@IlERtH8`fV$Im zXaJ|eQ7CZmmPV|ZYD-gFm{3@79c~+~pI8s0DKG$@p4P-9?zYsl%}v^SF3$_<$HysU zO-$&EIrXT_DRHH^VEs0WCM|cy0?L?&6PW8EWa94?)gN;v0+Miv^)j*}BYMn4;_ys;xqj`&Md(Z)_i$hy#=5Y7alTV>GA)5x+~r;V1g6cAzO0z*rKlgv zn&%S-F)AJuc0I4U$kXkJw6|r>5S-Rk3FA7v7B?p5rri^peOUv$L@GI!A@&Ap8W?=d zFyUw}$K(yg`!VUzlIKGbP|O$kyU@UKd82Mg z;SYA)>~}uBcGp-GR!m_LXX(89jgLnH3QYssg!uoYf&RroC2uBmNz);LH+C5i)T~9BHYPz zwhfC}rxm(43N+A8ksQr}UcHMsa!Uj25TGCSYWHw(`SZgvh20{yOcBJt3|KFYk**aa z=O5Blzg$UU#p?jy4g#hOo0|Z&L9`&@CG*Bv5?-#r-{Ip#z3AXoti2Lm@!Bwk9As-t=zqv)5ak-m1KIYJlcd$@^)gFz&D70v{VFz{T($rGB+ z;B{~N?L{`~3925rK9nqgA)b~<4%L!R?OY7jJ9nf1r!R{X@4mFj10;Rtl8Y$(V~FVM zRSCe)%Vzpx&A^47?Zw>9(=O2-#ra0bP$=}9C^>1?M|*8s$QL-bqY5e&z^^;a`Wx=g zqp|H_QOub=B1;f+Iocki)tI6JnJMY=!(PZp)T|jjZRQ4NG$ifR5PqLUG@(WgLvI%| z#4$SL?aUeBPGGi)5_tm;a$&1d6YgF!%Q^2AA0KJ?%Ni*!sF0nqG}I<<^x^hm2(aNj zF2u<_4;#ijd6<+m+i-RLZn_TpnLUfanA6a;8{;>`FbPlG9}3UIB&KdFP_-Rwj7B&G zS@hDBp}~r>mxqpKa~u&r-hZv1U-MX>*hZMxhJl`Ar6m6I_z~_ZwT};iF+&ff6B#`w z+=+`^oJ!lxTMtZFfBw;V=1Fg_!WonPW<`@@x(Oa@)90q-SyMNN~q)Y!p zji14h`sFOyi+$R)MWm=adsu$dfiEb$emqW@xOGYZ4a@kU4C}d@fr)`xV^sX0Z|2n= z!(uo~X?Nb520?iw8Ze8h2YDHu=BbN(np)779|`^9bs`_G_0IJ820@{Y++L<(Vil~x zCk!!b+zO~G81-O@^a!b5eRX)22UZRHZmLgmkvs5CPSBs0tnBqe3r7Twu|mY50{?V` z&KN`DQeg)6nBjHOLrl=eGxzl*@?mSK0x3_z4PYlF6k)NRx!!%J4xC*agn2kE%eXkz zCk)A;|f ze_vTq?2_WY@Uj0F^xA(I^ZzTo_HUoqfA8P_XX7D@;wZ*>N%0UQye@W0@sL&fKl%4H z|Cg=$lDeAee+u~jwc-CB$?~7c0{Kd9*M0x3KVz!c+mL z0Lr^8clyghcqF}i8pVs9&)W(IIh5XCA@caJ(wo^2APb^OM@j&ujIOUh&r*KiZ+k4JqX-dJ36uG-lwVneU++ z%%J2eO5Hq0Nu^fhBb8B)m9j-|F7)2hSdx@V{IhedXJkOKS@_Gz(ln?8^y{evuMdyj zizf9$x-?~)vzJ#WE-?uLK(k*lzdFf>*ZM@jXo ze+OLM>LlG^JVg$x(?7|^3z!7gu+&Y#UfG5=RK$PVAV_JILrz!ocefdbj^>-aCw+!L z9)paE56xbeV+^%f2j4Kt&--j5fQ~Ed^|^VI8D_16)@vap%$;(WwM?v{<7=CoFr9+{&Ad}pOkAjz1_v*ymX}I zQAx^$j{V&Qj0yKxQqyA-ZX<}A;7ak+zidhD7gYY5HsVWU&)nCPLi`!>_^yn2W8oi9 z%sxumEdAWdaD(c9{4u^yi_1HG^!@wKMl4%Xt})qvplQqRf4B@t7FcVZcr7ld$5Y;M zk7^%~*A{-tLc+vq^Mv&sd#9JTxIR79K0jyvCI@|IQpaI!t_V{4!Xc68;v;R{u+5(7 zRof%47#x3<{3xfK#7lch!yV)#177}JQX?KJQK}B950pB^Yd|(b^OU{edv5h0FWM_i*tz1wfu+5ol?){ z?`*I$UptZuy@2V8%pgTIpcPF7e|e%?^p?zGlJ1<4@V_A({C(Y2!ry4mRQ1!-Pk+!a zI9v05co(8t6l9!n(0nWP*Xhl~cURqS6pU3{v0O$Ejw>9U4}Iu(a}Wj5dYA$+P@R5v zY)Sn4txit1$sfYCF9NDGmF)6g|1r-&K2!HNpj*Q@v1dfp$ds|ywlN)>0h~hEsE<#b zu7BQrzFer{??jd~)P2*F5p06udIy1=H|NIFtPY+BNhrpC_BK3F+IWFH^Ym+BmvuCHHoI#jrHxoNED&A4if3uAx#Rh3C$FI35`rJ1jY4oRqU`A(6ou@i(bSPR40p&2B1G z_jvJrpeSHE_N>tL`DNFYbzEg-%Wm|eSegu&Mt!y-?dfxjw-{h;iZuf7a?_H`v$hNRyQ#f*y+Dr0kV^jcg>@zsIoX zthMwGD&OPxu^@RzRmUEj);h82Zu%ATx=b)QhxJVzleagPMaDkz!|5)wqjPp|M6P)8 z{4KVuE&0=|U%jTDh-mQ6TNL1V6=No$3zuO3TR%6Kx9OhuZnL<@XN{#GjQ1-39{I#) zEg?g0Xnv3&x7P7nNyp5#zj$?=Ik~Ci+H;}gS^IMCcHjHJNZly^Rxxqo>IU;{ljfBC zVW`heS%!O4sr*+eBm;> z0@|@${^ z{1I3)`F9KVjGYZ?PfBQ&#|a(u+~+n*S157ftbbkP99pgE!}Tyl%W|bmyK1EMsArL; z&AZpCBP=f}Zyh}nM!{TaDE+#ic-LPj{qD$fe%CL@1?Qx_0>qfbygy3xyU*Fmpgslp zH%Vvq)aHD1y0i9P>snW$bD-3%b9r`I{sytxW(ntc#N$jW{;oLR&~<_D>6)tkIlH!x z=STCN%)IWY<5R1Pd-{vHd*loB`a0fA)u4*BWbKZYY8?oJr8Kpmq?=oNCUo9j=~I5C zZQsJ}F4CgP_v?mhEOhj#S4L^ZOY_I`A5OgBQW&Rcl~>Nu+x&-$^sQ~^x!VKhX$1a( zcXtM~k$xwomz~btP=41E(-33TpLm8f`Ona`JBw-a%EBH)^Ra4AGb>)LYSyky+6;OP zQSKu@KRrzfcJ7tF^$XhNs}1fex;gac`N(uT=cmPx-(QZ3Uq8D4d+XW+ zj_q8GQq!i7%lyHBuU*lL2>+W8uP%kiRKb@&nFt-b_@rHDu+;um^2ORZ*;0)sgR*xz zgZZRB4{WXOErTN*e>{2v>;2ykHkT9+CrS>B<9~~s`B!QEf2U&p*Y^K9@Ns@|>5}q0 z>;FA+=3eo?Mb6~Q9%ue{Z|L8W&i)_3-^z;rGyJWgs`mdubb@U{Mj z$eBFOSZLXW9)wZ%$58`j?%|M`iB`6Hh`=FAoBYeL>e87@^9TvZXNepU=!l3;!gYfa zXR4o?IOtZ?T;m z8^g4nTS)EH6B2L>5`PgpY~SKivLABg(jlUJ#%O?aR+7uo>G=h5vCsB%t`glnCIMFS zUzMQHp(<~?VxRH2PG(0x?-w-fOZ?(V$+;$e(#)wxv6k()f4*H1r`%)7tk?ScE|6_aNZ%m*2))KaRN{eb4CiAs%I)nyvHN_>t!6 zrPS6v-+JMNb~ms-d?#jJ0*u+E0aD0fGn~jI;{ix`ge8Gl2>?0(-5dbq>e;)f3H&;s z9>5u4%uxW|Aen$b1$ag~<5pTU*y&|}Ls6rQRAE~v9!Ccwy39`KG7>P(V;RJW>>RdA z%BnuRt!@RiVj#-o@J6K(0d+U`8gHOgPyIw=oxbApn3& zl5~s31|)KL#nYq?09A$(L6T4_T zfC_q}+oP$QZBZoTEBxUtHXsE68X>&9m7M|rWpM>iaLHs)$*e_D0dj7FGCB%K`%g{Q zY3&R>(08DhS9jdsy{vs5FyWIZkaHgI1kynFaf&m~W^xo0@5B^34!^?e&_>Y+o6N%u z%|?*Gh@#U`%#K|$V};ZNNC%2!5YPAqXnQVH=2M?$Jc>3KM*;Cf!0-bEk_&VUN!{-2 zP6Oi%Jc@Cw`y^me@qmDILhZy-0iZbUGWFO&Q@|IgCI&UfrU-!eLl_v4MoEWv%CENQ zOd1IQI*mkU02&o{Xv|orgF|eY1P+-P{GnhW9MDMsgyBIY0HENx9i3k8e)hH!Adqp4 zc4m5J3TdLF;~Z)~UB(xH)2JQr(=3<_eqfeS#Aw*|9l+SPu4#{aSel63AwWS8Wdpv& zexSFt*TGPrt)ry2wTUx2_D&|z&$5uJ)Mvwm`MzhhnZ7#<)rW~VhY7}T=Qb3DOr+Be zLt$_L5J+)~@5Og$0Blbw!qLK%pN3~0RXg?eEG>EZ10+`^v9WmPRPZ!&S zgHvt$_fD~fp{f%1@3E;FYi=#SJ`a~e$DD~$;@p07`$Bdh*?|j*Wlki0^Y3dc94iAe zZ-OTWWYV6HLdeMWnsd=FWq1oB8@hU|{3m!fEw>G47rCbkp{IyNydqG}xShN|Km@Q^Oqa z|Ma+^Zl>*I#wmjTK|^9hG&g+Gs-Cg|)W`z%SMy?0SKMMjPW}86y9wp(mFzalR=8p4Su%VABO{5P8NIrr#2YegLJo90|t)5cH-YourlfiJ|vS^6)GM#|BC6ITYbJ1Q} z_p%U)@#yz039<;u)Ajk2#^k-gP`RdNOvwnfUdAP2C7Zpzx>g=gDTn0ZrUoE=M zWi@DP$0Gjr%=O4H0RWRJXymVZkWp?00)VpT)lQt+QAhfk{GAP~V85dWJ{4z0OJcGBTWJ z6zCmAIEET?T(9Ba$*M#^V;1X&p7YG_+067+0o)4d>r2IN31XiNy_M4)&slbA`eX_ccDc8%fzSJJrg%iZk|=Pw8}%kEDvcqs z%QfTqK5ZWCrLr>t`4i6;AmX?Hz|olIeMf>534Loa_Gx3$;4sjeyf4kvCsijC5A5(v zQ5+rMz$|&9iV1*|JP{9=?ch@nYDW=6+S(#BtA3(@D4;VUvGhH_VB&!sV%6nfUQXqW z*vD(nBvb-DjufVrrUUn3@s=5>vIe_YBuJPyDB6AF5_KES{V(& z((DGNd&2SSHTa#TJ$-Cw0TsJ#IR~?xVw*LEqz!yv7>~CyP;=%e;o)!^phelT2JI{v zPGdLPY1621Kt>_icW)hAAZMmsM8mpp*r&jv}cIz>Yu-JUtTy2xO!qkcNW@tDngRcNb;2+J8gv-?%_c&8FXrFb4Ha zbLb`h8S3?bXgCu`6QBYqVe*JN9uOE0=&eyWJS`<`?Db_LLnnRWYPek+YA}$zJK9w3 zQ!k7s?E667hafQ7Bt*kec#>>QBlQ%Yg0Do%Q)1wh?xyCIEf`-}OG1^j$q&`sP~pvWBlu%yZwB?AtO7toT-K6=BwJfeL1; zh+F)*P~HZ+eU=#O;Y2@jTOe(^reGy!43hx45{a-JcT4OLt zSut}BjOvxuisG^QF0Vr=@){EMc5_rw=npr#g$ku!TUx8~4*Dv#l*0zrVzqQ%F>vs& zt71bf8U9wOagUZSr$EIXo=!D%V(C8jOvb@u4$9LC+vgTkW4(hApRbU%NbvZ3SWW0< zP@L}Ro;tZD>3ag(=cPgv4c(m;mGAw$&9QK&(({}S45lJpsIwiP!xKAsPT&Y+KOsVG zfMeYp3XQJ)+W-2JzG<_pmNB#+fj}Ui#Fie9eVNn$GPmD1;b#2F&|=Y67L)5ICd~Sy zPEJ@&>Tthn_^2KkrG^LjLkdXTfe|18z<`6_-imJHRXE z5Q!@Kia`1p5@vv zBrd(#UfBM6Q^y{upMsRrDm^JPa3Ya8&#?wt`Vl6SuP7?%6AzeYpqTF0QB0AC2XGJu zbS7>j*W%M$BAt8=-ktBbMMC78rp81&uphG=zciM+?BR|e{Rcb%r@4Qp^2t)@*S#d6_Us86g=!1*uE4qYTv{8@2qtkO(+Db1v zUqY;2#+%K&tSj`}ZWHb-7e4Bd|LJ0n0#jJb-}{VbbRhX4V0T~r4Qcq=0^kSDcsN%tsYIiJR6fSw)3sWe%)vSMqv<3m0?|n#=A(T>xJyoq9+)J(*dJjtyM&-`#-o> zL;R~}t{2DEoYt3Zdo8`wIPDNTUsj=l zS|i0en!;dfqiB5QUo|r(%ga)3RI-h3vb_w|4ty}1-Tj*MMr`%zWTm-yhW4!s?sT>? zVfmM{yC2#$qht>J*D0N&Us1z4%3QbD^cjn3tE#ODMoKPK6(%=@2@N}4DVw2V{kcYw z@cP!Uol*SGM3zHMZfI^)=eM8?SmrejEc>aNr>|06GZ9M4M!UurbD@AVA%OzZzTxhX ztqOGQ5}d6qM9l|R_LL3HC)3Kodo`6$`bNoHDD)L2LXNzXg~iniUQVuu!6cCJuQ~)& zlTI3Zl9p5H;t+?5Qul>_tF%%#6EOAk$?D;H?ef#s*#vKW$wA_dFn7O+1-q1sH703C=gW8Qe*i}b^O@H>5^HeqMIlY~CxdeQ zy**MCI78j&$YIzjLdOkFZFmzrjFfV7j>~?)C=pE?XnqN{keks^Lz;OXF{H((f_*}C z&~g+7jLJMONuMgzwf3yXdUGttGadAg@UZ5H)v<_k3`wX#5=+EWma;38f+YioL-Kcq z6Zb`Y3Tnz?`VJo^w!al4y%DXm5$_HZYnr^t@%qyF3@6`D>!aUACXzxbuHQ=@Y z)ny?wC;_6Fd-Bxj13@PRP7 z5o8>PY5H$53z#ov-h}Y*h*p%f(X1$d7$G;dH$k4S>e#c!XN~~<@oM-B4O>nH8lP^p zy>D3@e^auU%Mon`4M(NUgM)6|yM`#nbZ%TJdp@IoNUUGL^InU7A;RhO=ZSacHvzQ~ zR95X-5e#?o)>W3~*QS-SPB<&U+;T=CsdMoX*;ku~G(0twq3HXH1bI3OBy~(nBBy~% z(xlWl=yX5kr{^G6*%;c%VX6w|bfZBZvyZV=J-urq{n~+h;G~V%Fvbfg&Z)=?Gp5~d zm1iR~9L^xZ`%VQxxji&2$2O?R{qw+wnf11{!N}q zBWXm=E)=5aOkh-gGN-=y+tk`U%|?BcNrUJz9jd(gFKZ4c7RIjAEiFZ+(Wj%|CnWbL znzui^Zdo?RP$12|EgiQPL&!n;lm24H-0y?09a^fLlY0l+c}X4^i(1bpY1DLotqeSA z5nT=D+rG;&9ZngtWf&t~*d(L5u5*c}Kh%PYb@#Y^bx;S-qF`YTOU{m5vCBun2o8W_u|bz+@A%9;qG2PGXGQ z&y^JxNpTUyoGQ~i8wk`sFsa*c-8xeutHl64&e-cOi+}di#r)Nmb23=Vwtxt~XUnie zQ)OW+`!HpQ++X)~Ij!lc!#`1WsqO4q`&^gFqe4Ybg8iu-ZL2T&FNSt7pE5XAR$KWy z+#Q7=`~y7@6+!*d3sucF=gua55;yBumukJiR9sB-jABPdO_~Sa4&_DItxABgbr-H0 zYE(24Rde@^7%2=~qm9plUUkGwY2bvjO9a*rTXkCxM2w5iSO}lY5M-KlGmXwHigmd_ z@Z+(wMSXMtYH(!a+p&qFa{iqN{gY!B@JuMSXboHRKmm2%91b=bsw1om zixSQ<3n<SOQqhrd|nGx zgM&P6wtEgyAsj{}{6)P1O;$g;ycA|~?oIO%1h)Np<|VdxChamznA%CQ{lEGc(ReZu z=je+)l!=4=eEc3hS|AZ132guem=19V*zK_!)_Y53C!Sn-oRp}KQ#Q&Q_2mqV7KcKl z+Bg;SQ=7Jj*$SQ^eCrt`XDQkK?E*my6@5;%G93m{;^g3YsA&?+(5n7w_>4D}&>?hR z24aHXxDhk3V@x?^s)m_ylHr6qdFjUrXd#)k(lJhKrI0!)8K3ThLT72^j zh!`-8Z8;gwh#(+SwQ3;a@F?mEa}3PDnQIr{&NiIz=``?2t%~L%53b$d==$!=Yiogl z6;bzUG}S3IOE3YrLqzH|sLYMFN`E~I+J^3d*z;+N+CsBgRSb?<6}?NMV&6Z8P}gl8 z>~mQ9XTgS*LElU?F_03y>(b@jEKy_96J2y_r|7}DFEvd3+B?pJUQEJU=x&_{#E1*n zCN?g*EsF6xVp%#q?K&pls`6cW$X|iZB%p;8L-uwEv+8M_Ud?SA!{LGtGnMiekq@1|Cc|G{1BU;EZ z{uzG>YkY|p;tSLZG4k+Ts^?V=AaE6#()`nyzmw$=CttH{}7?kQP`^wct-xoz%k~BGpyqZA4Su?^9?*>2-90-7mN!Laq>-YpM^cKGhVpR3> zQRClenRl?PN!S?$ge(u(SK|pa9$Z5%7y53tafooL59xfMM@cgXT|SLl0c1ay_O!i8 z6sl33apmgik8;r+W4I4vXW;#f6%EX<Z9e8^SDFPr)@mmPhsineWOGpdh2eoBLab~!dZ67iG)gV2(c-a0mFlwa zeK!X=sr)AmjZV@P*rMGXN6@3!PYaGPQqFFCRG4o6!lwsDn{LH9kn7-k1~3g@eD!04 z<-9-bGd4tgiEmPd^hz?~`2_D>8n(!s+s8x*l)YEGWkB9cjB7rRy@T0uCqvn5NdC8F zBCdwBOX?p>X#8-=zri3{YhhMmRGJnRy_f{M_mVdD>y(Df^G@!MY0_Oyi5OQ^lRIy@ z^!iO(RpWKBqT?o0j@<4s`I!>?k6YWaA1oYXzl%A8AU7yQ%Rw-hw6WD}6Q8Er7fmQ3 z5HAD*Whowe>Hpy9UHq9|9LN9P`{ZbZHgeBpbB$bbDUp_$Tdw6Av6L`!E4OIdJBFch zJ#xvd+;ST=mx#UHLaKvd8nfe42g4#WHrwm_`27Bk=kxJ=df_3~hXexWv>TZv=v%u3 zoZd3X27n|EARzz$U`XJ1FCyvmkIr1kj-ROg=Xv{T;>Xu;G+QqvH|>vnVYfLkEq(FY z$6+O}*FVE9Xo){KK#+IIRo@2eA)?pfrA@X^Vu?$+xM|!I+)RfTLY{CfFV$JN*wD_p zAOn{il#KPg^B8aEQ0KmWC3BNNkB9|ck0!`+vMt_e-yb_hnC$PmxG0%oJ86A!z6Y&P zhKFlx(<+A8|5$HtV#)F6dD1i}1oG8!y{z=P4>Fa^w9+7cO3^=$;)5Qe|4ehym(2+z z0@yB`z~^TI@b2qd)vq^&%S4%-M4u?s`2@~Hto?SM4Ub**6^k*@+=v49flYva0&r}- z94r&`90Ep`6y*!Q^ZvBa>&oiw?H2TP5IfmN!6zoeO1I9$G5{x!hP*JB-r^FjzXPc0w`dY zIaPBDA$lW!3>pf*aXKz>ByKP@%@;*xJ+%JS>_zDXA(0r;t+;J4!R%te0*X=#(6IpL zUU9J&8An`ko)yc1Oeqo?Mm@$7v|5H7u|Nm-Z3&N-H2Xbv3>lNui8p*@*8@QhskORX ztl%GA>0$6aae^(gu0RU^^m-Z0{7;={n{h#z7pqU#w{7;KTIp{C({k+n*w9Z;53@bQ zbWRUGZqbz1J9iJyf3@1njYt598cdcznIZ&(zrTDX*GO^loKZ$Y9}UOn18SL*@wDZu z)?d=El+Rw8N0`X+98%1-Ui9?AQOk_k6TnKxQknO**Un%d{EV}iL$ypL5n}~m9z|O8 z^?6S)I?&H&K`Sub>7Q9i`-|q^RQA9a91u54oVi*mbLwE@lKwf4ai?Me-QQcli`}>w zvE8-Mws5I(2~6Ja<8>VHw{xZ$?CyE;F>V+$~0~(5i2l97F zcloIim?55Dearykpv82fp9iFTe3lizFiH31^$M*S-zimq2pESbNr2AAE)1~tXN^z& z8IT&c>)l$SylobKoXQOsQ}dGdo1+dzQJDvoG2t7}O<<-xlT(9Uc*fm(RJd6dVJ#Z^4t-%`_FWu zcUU}~(0b7*Ys#4hloQrBZLlg(_?&un94LlbMQJRu92w6E|4~yvpk(Z|W?em~AxjbBQ~ovxdj#TfgUSvd=yMpQL-HHY61k9_ulM50`UI*MZ<{+Cr#P$wp$P% zmIKA=yZ+Dp@^~s)?4wJJ&wYam=k(bY`VV+MT*U%%NTV|%C;7tF56lyL5|>JvK0YkS5+KlRqUHSWqiLu_8+OZ*T)eMM%R?qXGNk!61Ju z^_ze{#=!9BDoYP)UljPm`?9kevT)yv0zODxF?@@(QKbc0YQx~;ZExQv95V!0O8_Ca z&2s$I?Q3ZgPd8#VH%|3i^_>*lFS(f;DVcf(YJ90V?>~4&Lv@9(W3o&D&2QbO`H72$ z6LRKJnU&A)GIH{3L>eY98g^L_VbgVGOJpGIGe#T_3j#%Vv8avcistRxY*a(uCb;-L zSKO}ZyFU)q7!5sZxa&;E=o_tq`YYV{aQZ$uV->1`9ic zH?Ke}=fen5bbY*}c_WVzsTp%LC2>hA8qr{wHr(=WkezK{q3h<|u!3W%mzRxN~e>eDF8RE|KH$SVA4`rVkXTBai`d2?m_5B zTid>19C+Z21&8b|{4`TZXc&iH%bAuPx&D&l!($%0Iw#fB@*kM zjkK_9(Ulkb$(k0N&+&0Gv!`b3Aw~vTdk^Zqz)r$gLVBU_YBp`@*QC?B#!36nawB~A z&dLrRzn>4E#+&Hw7k;hNr}nI;HOy4DAB^~-FB|j4i zGV`8t-!oS0A2+Joo9)mf`wde~-&K8a2!QgL<;8Op-vr6U(9c<{oD6`BG@Fl7#V=Q_ zc>f90wi0eRp`9=!2M+*R4@08yt!f=@li9al1!erW3a{sc8h1&HWw+U7*c`-=Bc89d@1T0FpXN9 z2ZdfN9D{-fl|JfaDtw`=MlXP*^FZD~X5dSFcPk6%lL$(#PGH6?jm{L=Y!oz---YJ)UAbd zyG#cDxi%l=^eju~p}U}ZufOukGT0#LoOJQmWP}>su%ZkBGOl%iT+h&DU?}%!b-D8; ze=c=|gPoa6WC|}z1lI+5yrg4t@wI8@g`Cb)ML+IoTyAt%83oS@eVoG3(f9jG6Yk_} z6@NjR@Y~16F~X6D!RxVx@496`=B&6ujK4RaJe#f+n*J>>^J14ku&tCm9Nc@-)>iA% z3KX9kquY$KeRsN>N!exa+FcdSBCS^=u#W7v=Q}k@lTzYc6rG;uwGiNnE}y zEj<9IvD-L&&mFl?cR$55`j?L8Wpi3raZ55abSB8Oem>gfVQ3b_W8&w>#SjIeqJ^{z zYrKs}uO%T{CI(7kpPQ(%w&wcW>q7VzR|+hye6n5rioalu2y*;G-2S~yZ}Y=F+;{P8 zAlo%B`=m9ZH(y&VO5qk-d4r~|qm2hyZ-y5Q z01l8}dO@H%7<%i1wTKZyQysDCHB->FA*j9kTqkhF>&2xB2y3vZb|6w^ClGr~t z**d~snFq+EmwsMFlt1_F6C-N6j_bF^+|QQygeY0sIBUSJ1v#higv57}IRZT#_@KLL z(zx!pOmx(zIDI{^79YdFJ$66#nYZb#&V!1oL5dCUn2Y^m!v|jWp*XGVCtV7nQbLpQ zJ?ik4s~05tf7^J8$J;haIxiP##tlNA=hh71C)Ry$MwhgM$V86=Q^3QEr({xA*xP&wV*`<)oY z0sJ;*be0sT83vC-C}dEg$21$$Ws< zU9={o4N6ox`HCB~G`@I~HTrvg>noj}>y_l|lTt`R-m;A{d50-gEt{L}yN z3%PfLhyONo!=t?{U8Xti-XTpzn^hDvko0fTd?*q*HmPnhNq<>nrvOo*G86hgCbQqS z8~Av%R8fRPh?>hr39^Bv^BP?XjY%XuH>a7`6vNA>-uQ_L#~q$%Eo4 z!@kMCe**yUC*xnBF1-{(g2A-H+P7X=JI#Ua3XT18wOkcko$k0FFhPiVjA=p(`yYTq zz_TV=jw`o>zl&F+>p}~rLoHDp8c;Wznm`5>TvqQbEXoAVkG~8B%{?m-)v(aI})6Xta zkP)(XEghrv7USZ)NgUovv!3616Sa*COTP*#()Cp7JLMMw)Tk<1wHPud9-kZ*qVnDb z!6K4kBS6OQtrmK?o&`o@Gfg{k&{cohgQ<5nOsnzhw_^=ZsF$d1accNN?#5Ru@w#GX zkuWg%aP8)?O^UEA{SE~O9XxCE_@c)|6R4U)H&NSrV6w7uj(~vmAELO?cTzclklbUW zH=o1iQ~7IJJpL0LA2%du0t5gT;PF_s96*oMJDK)>l4pOG0d5okzN%~_0&5%G)7u7; z#e6PDx#U6Cr{phqgTYUD6tE66-vx^D3a>{M<+iXUOd>UIl5{5w_0uWVi|_M|&aWer zi=tDVt5^P+l=%mKeQsgf2jSdRuPL zY@S)mno!|NPRoL`2$e(5zIA>2%mn{=J#l{eOBTnUFB1{2l?Nq-g)nM}GzQiKw|jm_ zop50IwpBK1RKVdBuJV4=T@N(gK6z&v!}-__q?#q`sL(=jdZw0Gzp=vWf5rnWL9ZIS zwU6=nNIQI5{N@v5B`aPkMIe{qCDr`f0VA+n(d9G#c>z!E7cjW_34O3JZ_Irw`GM91 zIzJI@qB5EIAVrPVmH;vrFnP3&Uf#~%H&|VQ;}qAqKI0~_G3-O_98-aLO4Bs1x3%}e zh;_9Bz+fC*z_ET2n1bHihA7!>jAPu#nGp9UIbE#SqxElI4Zh6XS*gAQ`%_}3BsnK( zx4p%i&hF7RW?lSY92X0)uoTB|ne^VGf9BnVt7X&SpzHBs^brnk498e)E3KNIG_j2} zMb2-A0m8+DnIGtw=r1vFXeL%Vnco`<>=nQxA#m}{-bq+ zrOLz!xjq4a5e%VHnr2VJLWjF1gAkfZzG%K~qX-K)M}6FqftSYb9=xeba0cHSN6&G_0Ifv+69?fb z@$^SY#pp;-U=Wj zXe_kV-PaXZK&1|*%1R&J=}&V<=phnRtm_YhG8nUbREuE7125m2mg3d(cY$eNujulY zwW&Ed9BVz5yNbJMiAbGys(vbQrG77>)fT*NPd!6L@p=8dF2yM41)22H)%)FM(`wIh z$0cUm6-HkM2u92vU&HL2(}^A&l|JaHy`2Srhuh|H`mIj5lD44e)}JrIlxhh%&ke!% z`ar+1qGn%6H3Zn{rDL$*8pXS_>90b!okBc!#U0m_Q|tpO7|vcwH6!_FTb`@+fvxc3 zhphdQ+s+1nKWH*g0{L28h!+szw$!6GH#tBERJs!q5HeLYwsCTn+{bE7A4Y;hug+Gn z4ze*C2Vb&_4WHH;wLG{bhL$A4MPX^WfX#u8JYcN3Tk~Lr)of6 z8-k~Yw^}AA_}bcc{5U*OX$Um!cJdjdn6h_&3j^S9GhTMVbwZJz#z{NF4XKos$Pj z1t;J%uJpw~CJ*=S?MmG)kRX#yH+uY9K2*EcZfn`ZG!)$Jd-Ijw*g_7kd)XM?UMDRK zrhvvgfsLVp;h=5Cro6(%U_|N}Dbi$mMS5CwjO+?L`-WJn7SaAOCB@ z46h~D>tuV7x&k{7wNU*04bJ$HlQZn&l$YncpF^q9uc6B7%fQaR1&5sf;BKssy=a#0 z3+yf4h(f4?E)zb5-2>Sq{gURS)7)^mxZD!AZy3*Q^#esC6g01V;$W& z!(9g2E^-C;uGL&b2`PYQo}zm8g3JOaZ}D=(X(v;{_ct!Rl#0AB{n&cLH^Q(~_z~9R>sOj(TwXB$ zpuBMT^mq@mN03V}ZVj{Tp*nQYoM!LZMU9-~Va!VC;&a!^OYE`F&6&W3MjclfBNFmRx|_8^bV?d4;c z6o2up^Y<5UYuCg03ELJm6_zKvwufA|=bkq5P+asuNtI!$$UlwHdrt20k^rwdQvV{0 zPt55$AdRJZrCO!s?7;!LrHPv0*gGU8JiBV}{#@+)EPRjNFhEoY(Z|QCICW{Z_SG~X zx1B;WLNxXeuE$~IRovPYFv2gZB(ZSAXcivkO^(SlqGVKaC4ngZ9S0z433XI&NoT?NHl#s6)psL;p(sgtr!&vYT6;`TzxHW$I;E#~ zx8cjFm{O%1XU00^Y-S+M2%VSwB>#O1LboqP{D)R4W;+>UmQKK@5v=m>#_aS0r1p>N zmRH$x6+`pGt+HSvi*){Fr2AwsG3DnAO;N*WE^XdJ z+^~~eAG`JImJAqcRVk}b?{rbY=7f0CiW-XBxY;k|dVQrYjU?wW)gph*_FPid=bI+< zy9vHSPMUak@^LfNf2Fn?sTP8yt^t9NZ%xDb^+Kn(=jN`uL^IA;U;5GAt|Vtw@*lCa zGvRG{O6RKm|4>c!oKV%#61Dp#2a`WASXV#~S{n$!-wNt~p(CY)&daX-??Ys{W<{)d z&Ca1=#jEGE!?!{24Q>7@Og*xG+v&&+7f|;byAnFyUaAS!Kq2_|vxsUE5`4H(}*M(TzZIeJ*^45OXB$n z4c}NIYz@M$%{=hM!(e^HeV$(wu|HL$(fz##2J(+p!N`VK`(aMZ=92aJv_L<5X|PUA4y)M+enA_o2w!1?;aBH(1vS2 zYOvFswTMy%K$CNU#mfT+EMVg>cGeJYb5ir4Lc@2)Nr36CYplueMSFrLw4Tb@_(P4c z_TLJt|AVhqz}&YiU{JocUVU4&)XNpmC|WCaA+rH2)t7&j^C8mt<+qwt=vQmrdKDF9 z5xWf3ji)PKKO`g%jLm+ho=RidXx!SvsNA z51{r$;OvgJcF3k+MWMt0K;<;%xp!E4zX6$u1E{2Juj4M=u7(u~o^$Jwm}V&ig1_>D zJe_ptc;f*Sf5lgCxcc~hw}C`4df3=l3fM3tE7c`hkJ0`v7MSp-jHS;$eL& z%J|cm^iQQdVyatf@^X|b{XHi?Byr>~ja&Qz4muM>=ZBnyGvB>R36o-!E0a$O*{vwe zTj3{b`}v2KoR}Nc5F?%JGLm^h0Gz{%VeIpm-!D?VD2_$&tv8n#U%s4M?=l)VVVWGx zVF`4BqLoAE6Q@3G@?`pZ_)ipC_*4X+b=0xn>dy!prgdK{;tz=|2iPbVP#FBWiZ>$> zY?}D#KGR5p>kBt9L^A1pXi@7K(z{Y@6HAaLwilHPZldd|Itlq4rv)j5rBFDY|TI$W^xmdYMp`_b(*iJXjI z5m&(-y{_W|%7iu#d}%Z=JGvnf0y@cGat3WOQw1 zWkVdt0Qx_ocfStD8m4nC+=oprF0@g%BeK3I0;Bun?GCcn^haL{Dbz!{`LBGhdh^9T zB}?s8Ay^Q)a6Rj!x%}dq$_D&;hmhO0Wo@YcE;2A*Va;*-P>>>9Ga0XE1xme=FZZST zopRvXuZ!iryr$NdF@d70S(uBm@p^lD>=K$o_GISm*cx%o%pX#jl7IaQXV>@O4_3+6lqQ5ILLerq4W2ty4i4?Sk z-}1JWzQ%$wabCn56tg9r(i`V;_?v&qz z7vvkj-tAt1I=XUJ&H>LuC@fl>`wj0>S7=MYb;Z(7@v{N(lmjM!;`RDb-{qa$w3eR? zJ2szBN}y|Dnrdi%vJcP2f7C(u#rEPj;cVKCfX*=4AKk^X#^SfHj#CHH7vkPU?WCMC z<@JiDojiHJkKxx(=JNtd0~TptRb5`8TjpUOzYgw;s|Wa8c!Z*6$O$$}PX2@_zXdsf zvg~}EvKpY}g7T_==)}Gy9>f*i9g9+LGw*QeVRQPHIJSJ!qXSArVH-WDg4cMLY{xCshI z9zE6EfBj3BPP^@Z@8F-6N_Le0ZE69L78L&*=vBH6BD}qVk<@EIvC&tccM<154=Rp5 z%gt_cc85TYvZv!*hwMUZt|n>c_MSBW_FII(mmum>osX`B{KqOCQ-DA=v+YiD&Q!IMDMgGnK&wfV``cXHHoaoP|nh zZ~tFK*rm*~#)ZONqAhI;dO~e3NE0{OS*(6wO}_s9yxL7EQooIVXwUSMq4q8T0BlK} zf~YX!8h@$)4D!rFx-Pf`*22mw#sbbQx6@A_{=2d$G1k++Nv&t@kk>N&1pCk3VEQx9 z9*%OpSR4$AG$NDhN21q|`in4iAQq&c4e zT>^g}t&>3gcyaE^EA6X5mQQvRXIIFL?b+Gw*qHpOoJi*Y$C`FhoetFQ$t6y59d%R{ zAL?mPw6=NFqf3YN|4be7gpoox`1JN>W8S)R6vhHK&3SvSN%nN!)g z7Ho!0ql{KiLst0MoL$AvR>n=SN(EuO%m4mKwW{KRe@}4y?WD9}8ge#!YB%i?zSrod z0ghH#V!4yqqET+CWFVliBP?X25jCPdmlFN4OHuw>?YTc)3Q%tpBY+6pWLO*lZ%uux zT)~HL$Sez4TfLSfY4oSd42o4jRb1q!#;NIl&D!CBVXc~muwMc)O3r zBCD6j!CB#_P9rmtakX7&6Be1OdY?2P?6dBaFPfr|JnFE-;t~a)&w>f{91PE&hyldq zd@}vMw7yGry)$)TL$OPed7alQP-D_fU3;sTN@=$h$FFw$_<&5-o|)M*tnnP~mzNCN z`N;HtQp~E`GMIwU0*&o8m2*9|hDWEdjH0#&r z^O ze7R$W`cChU9$f$O3k5mVNy4B^N?yY-ILOKAX{nQ$R;wA6b#JmQYeMubO~M{CXPGSX zQ4xO5rCod6Hta>Oc3|35yscS6ytL|4Sz8((S9L(L{cmWRVsL`1>v#_^te3$HoD5pi zcsO7MzFp>gT`eJaA*k3lGF4*cD%H!%4aardsBzg@i%S;x2u8QVTQf+0HK-K(i&X^X zwSpdC;iFi_Dj`i>?ctHVGg)M(#I}2NmCJ@BK8&UKHSGa z_K`N|1#xTtT6=P91(gj5;8ZJdKHI;BGD$rZIop2(Ii)>}F;|>*X=k&-QbA){-W+UK zzU)jc1Ba~|j2bfg2hS7@LSEYLZwU~giQoCMIY1`miN+iwT}qV7mGAN9;XqFZb>Tgh z2B-!25$^wyFAhSNH~I!KF|b$p$*z-TnwAeYmW84J4C|ccd$D-V5N~z=^v#X6mA<4^ zinFJ;@}y~S9ADG!Osl(U=hBvjpkg}72_ZJP49d|oj~eCv!U0)Pn}X&(KkHB53@L{H zDs|>YkQ2SO*S5{0795(yJ7fl9FhLE&HcNexd}7vn>9~#`|HL==Zivq6cMY5Vaw$%Y zs7rOy)=q^$bb=m(t7`tGb5Zx4G2uyPeG@Ny054uirS_}PRSy;oogm<0n>TIO(u5&m zPTyi0!>K%eYg?djT3z52UExmU!ucoPS6=#DS}+lkcM-uuQy}1BSchim1IbJknG7s7 zYDMj@0k?rdF>r#Kiux6W7U;fS)V@Zzg_?$#wpD$orlb|k(;?{eMD&$-@=f8aK9fOj z4h7>|st=NNY<=y0{@ZIvwf!T*wN!M;sIJYNi=r8ifT6BVwifJ6No|(OylfHZ19T3} zW2Op8aW<}bD?1e}qV^Eo6yN$%D+J(if7geVa(k?;{c*s$BG5HzKP|GQhab#)A(14@Uzo7fiaHDop7gbbeB%{QWjrfySJ|4Su1 za)(-i9RX$p23O;Y>xW%8LSr7?ht zSw4j{`=LBXx6ch+c`O_~S^jicxW(h=in+pmUmC-u+-65GnVw)i4I?x+Baz++u45K{ z5`JyoWg@vPZ62Y4_zD_wvSZH*NWYM=Gg=UE>{IwCzb&vouiV{bl91_ponU8bCl1OP zjXqqFU%T9BCcSR=qx9J64Nn?*~h)BE~_R6j+Dd*y@IGj&;$4;K_}~CMTsa!&D|zWt4)9=a1(E7?((JF84I17CJFd_OrPs(tAdBxw)0nx=!#yOM__c`}W-M36_t_q9tK0E_eHJ{70jT*t`{3(4Xah_()gvJ2fS`cHCZk#3f*N;*q)(#Q5#3Vc@fZ?wBa?p|;A6 zjXXY8n+%K|Mc&Yqugr{#FR$9@AxYkyOv}fDub@XzH3yr7*H+X~D@*x@VSBd!+FH1# zKg<)kfc=Jg{>6eSvU%<_`K(iqsGah{wx-~lp+53s*98`PvaE+zefm?=xs}IgnJfO^ zQp^lXWinQW`kG_J*q<_fbjxhdS%3mV!h++*6LuHA04nLs*-%emwY&!{3Z>E}BIfq2$h1>c_6Dh<$uGDz{1I9$5m{`yvIPSWjSvuJW z@V%oj9d(j#U6b$8>(9r3>=NNw;pGD0d^R8>XNV7s5&N)p)${>LD7-xs@ox|={Rj#i zyNuceMug7lwUuX(4ho`19mifvnx`lM&xr+rB`#6e@B*0b$5#k<0EG4X%Vz4Wkiuj6 zQvDGN>mFxv(g9vU3~chP;cwUxMcwPhkku=eOF=V9x)`_RKk!!|WSK_B`6(n(MFZpE!Rak9z;~1oSx=uk?@+{q*GHYsBT*8wd3x zNyJXwb@<`v3%|l=Oz?{FrA+<5Pxguznyk@vl45bUv9o(WQ2|NJ&X=D22aS|r{r zIzvi6y&1pgAL#Be`u)NNrGDH}b&#~*aQXK2k!t>s8gYVRE{kp=b4CPB!-+4nj^GKFZRurkBdshksFY4{&68*McI$Ccq?)EM4%v@1Y4~Em$)<1|1?u{v7{Sbw47#EN zKKSLx2t0*|uM~p{bZJ|m#oS*n59f1!FU)N!y^REu6zWoiUeh?hK@%ii@?PG(`!D+Y zGj2ma|3k33vIeR@w*nvjwuKWCd#(S~F;G;@Sr$fpm5~?=1wU~y(YggLh!PU;Z3F*5 z0@HjLJ2zq8HT0t!-&gJ%Y`1pv&#JGgBXy;&11)f`KDg`Jz4gTM+;@n6`JUlC*+oK{ z$-LeYF6V6EjBirZ_=v2SxigddqDb2|16vNT8MOdztc*euPxE8&6?Q65!g8vOcG-Le zE8NJ(=yHB^W$Lxh+E<#dat`_oeqJ}igYLdA4GDX0Zp=^Oy!*R;1Ze}_7ptxVqhHD6 z&r$oBlgC|uP*7_b4bA`w;A?HX{LpM>M^EHaGX;Y6Ld)K2dO-{RhxzpE0OBV5KXrxr~p;0YFx_gMMGravFax>HRzBgKE$u!I*S@bskp9 zL?|{O;x&}gUc!=BJ7ns^asvsOK1LcufPY?fTo??0UbO0o3tOAdgYd3GOu75SnyJW2 zYcHj!p2HBY2B_}ab$PmPh`-cu=C#mnuYMYJuUn=u;qbOnpVd9NO1x<(H^6vC2*#_KRplN<*y&GNEDm5|BYg_psb&%@kmO@P;D+=hpDimZw zbdbx!`k}=wRZOOn!mn_MVwbM~7-A@Bjy!;@rZlM@VR%n2_Kmlt0=Xb(6Up^-r<0H{H9M?An&r8$R(j`egj8!@aDr&F)KI z-J4(Gp8e9K7AVR8M}sOuf=vUx{?jblAz>MKeCc&#WzVDuF)GM+psgBol)!w`VNj3a zAxDA9Ugw8>I;U&Jw0+_yy{DoAQzR^Ci3l;UAqrr!fxfGZvv%Emo06bvQ7D({vO$8y zpCtOdD8SlKShICSh}+L$S1Y|FeHW3|&L>RKz7{85qzH-p?a*&YCRWR&_nq(<@g96{ za&yYx_8~4X@Pzt>b8~~Q5g^NxZgXZ?4clUPJAXXXIJ=f92yLE0FZuO|v{gg+!uIl~ z3-A;PfeqJUc&>Eq!nSDxCme61XwBF=`TFvIJmU+hoQ%q9FDNV^4O_Yt!ez+qJ;PlW z_;LJ?30^kSdQvg8pj6D`3n4ebPudrD{a)*JHUjq|MkvQS{9&i=mA}SnrQgAf?oo&Z ze-~Qe{JG2{m0gID=)k1|qR!MGDt*UK%H%Kw!1E0_xj9Q&-+lbX&hNiDG-inSxtJ};p?~`j*L~0bvv);@iZxR6@{go26oc~qzyRk z@$G(B#Wb&c@ta9$4$*YeGi6rQ*mFdG4CbvEzwuLh_`-HB%e}+w?o>3x3J*VnH~PN6 z7*2L|{ow>;(LyNb!OwPPJQ}$Z`?|i4dnX!@biTPMEz9b5@8`zEXB#^{S z^n}K-imiR{uH$;=8}n0X>Uwrvv9l!%v{`5pEZ12WjIJL=!#T(smv8G)hcfB~!#RI7 zZCg!SWo1rYH!sdp2!1+sVM~`I07_~5v5vPCy^|FAJjhPL!)x(QiJ_{y9)n2|E`Njr ze67jMNZZn0N7nPDe1X|Ldy|;!5y6l|>PI z2A>XBL&aSikpCll8u(@*SXgxi1&ZXQgAF$T(s?8Eg+#uX9^Z?b6EFew!u~eW!QY^a zy$LKARSuSb5}%a)b^n@s?Mb%Y#J#tZ&W#VPn>xCfMeMvDn##4(`(pKz*9dW+C4=r+ zH9m})?OT$v>Asa41cSl#zBuGjacatCo6?E?V9osa72Q4k@K979Em$Kk;qX##toF@h zo7nW|&&FHnnId>i8+f?<2eyDMAamnN&Wx@q2w-p-nPsX#PsW1m)wz)}?3APUT)~Fz zgtR@RbB<`0j-5Z0(1YAWyLf`03k5;(;D$GCU&wIYwVLj$u5?eeD1P*KMq!PB_aP7n zdt-h)J{rr8udX()wJLQO#S!*26Bu5NlETg(8azet$)f5Ar^QG^IdwxMyd$$jT)g9| zd@ePTiS5V+(csOxPI<3#pS!PRyemItd_FNy|F7FI;#%NpiB%zy)buf?=9ecpmDq+> zzw$?7TxTu>B3T#Qt-Sq$BgV}1SFKY=yjb^zNUD#mXG;o8-IDS@%Pmmyoi&Ost$r>{ zcJ;IT*{Nq%0x21UspVxlh+IYw9AtF3Hd>q*$J<#i3twZ3ye#}C(8wDcsrP9hq}(aa zLlHusZ{Fr55ho8yG7mk7$C)j)5KT^5;hgV+QLMJ+KhrBg1{9a;Ce-jJxDQbQgHN*b zb@4VB)UTo2?@E~yk3R+fYrA5OC?V$X$ts7Twlbxs`9m>L?GW9WN=D~LL!j!IFcex( zKjTdSZvH+{1X)xOp7NXDeSOk(UdBiY!_-i?b)q+yQpp8AN9 z(`)ZS<|qKLr^CrN<}}+MO!5LIcB>ZbE%VjOF`Xc5R{*=C&lI8m&8I17jO2e1o^iZU8jLY2) z{T#+BOwlR-6Hn2mJ9}$xL2pDsjOx#m-WLEz(ql}QiL8n*i$1Gu%L_1lyoKJUlXr{K z5@dP4eOc+WQL3v0c6Z2dSy;*#ALOC0blupz9|qIBt_}d3WMU9`k8bcjtPePny4C4d zKRzrn>EiPGrN))Hu7j{{7sJxW(CjvcmlIST8dySDnox#4JWXX3VqcS~$F$j<9_n+@ z<4f3*+^5!_JeiUcR@jY`xY4Cv={*K%=dZ#CY+32PTE{tnU*5cuMoHdI8o@b(^IN^O z6~%{yCd;R}0A~lLbteLT#;>Ml6&d*jZ`6HLs-w{6MxvA}hdp4JxPHsF@}Pe=bgS|8 zVo-uttjSYuRiP#GM@!?99WT6it-`?`~jde3mydqRn`!K$AwS@Rv>6UVB7lq%m)L=J%BZRqe z{32d*gNBRMm$ORap4rynB-y-RQ(6wBoMhX@EzyQgdwZg+_9<445M?_Q|5SAtOQ3f9 z(SxoFaY??jvFt21Gy8aKA~Zf`4!$$mVIlf19d_2H(da_|M?lbhG=DbMwqKypo%0cn zwiHf*xjp|6adfZzAV4|mN#yV8aCXPBW6WfogKuA}VD{3n=G$dH*6-|3Xz%TR_NCtJ6!gB;yYUJ_Z7??@ZHd`PE~@SA#nLVP2hY@Wx&yM6er*d+ zPj(=*?%&b~f)9>RZuk*hbE_G`jl+rCsv{AqJ5uNvJPa;}ea(4)dUR({e}mLut@B|X z8Kp{XG&+unZy$RHK^26i*?+CRL)a?}K}o((34Vsh^*SZ&mfgEUHFf}y*H&OKn-Uc( znwZv}?vY$3?sb2bUO20^XeDeg{H_*G$v*RXu==YoHp`)|x30qWcLgC3rpQ* z1=WC=PS9Dym(E+?41|f{4=07XOHRs;g}Y7&benUTh*7Te_sF~ynN-we`N2xOO02S^ zSawIfG;{ARJe-w450YRp+6d!K`{gyg*y-P9m z=RbrD_~<-pXqp&Q?`t6R-4)y1IyVP(MdX$`V-6nMULSf{5l}da^wU9WW%{2}ZhjTo zelc?Jq&1xwYZjdE(33QX!8Vce&O64YQV{KJrGs({VkGAL!+VEKdy&0Q!j(H!p0vi& z-3TF<27sov$=V$X;{K>3hjol}57(8K>tt3fUagkdX6|$`*2Jv;V-yi1{*sUeaw%AI z6%{$Ea+$frpY}zAW1$#{fyNHVE>UUWh6|}5^Q;|&$0Z~R9xa+Y8=4?PSjcTi z1}6SxhhRhlu#)A-Je58}*Ki1TDEM#j9pWUe%8OlIQXM|sx3Mc@9%}ciYgcWA^2j2+ zq&GDoNyFX-hnWVmH>p&4niyX`9O7}D?5H2i7Hy*#wC51V-xEIHgH~nQiG0z zm(q|S{tNUxjvMr-YA}XCGNZEQom6M7ATw%B3TWVPQAeRMe45iJDlP*6hya*<9)DEQW6N41ji3KL2}2&U>VmGs_X% z=xDb2@n`~I18bF0D$FAti6~HQU+8OeJjI)IFBcVt{%hZOXZ1Cy>VD3kA=IRy2_| z#;=4&J$X1i7FwDoB0*7yPf&L8dkPkcej zS#zCtC<3n4-~3j~v+T1M9|l)S3uRiWc>mOCeP4ZV39+yKTeP4nE-Lk>4**Ka=IviDw!Ru5%bh#oL};Bs`sovfhM_lPJIFb(HqV(>f0 zUFZq`01T&q|3D!L@w7Z~)d?T1ymUYYy6$n7B%;WBLR&Cq zTD$qMl+cd?V5iwSWr)^n83h}nbCHN+ht$-<6W zUnfu)i6?+edrP|_NtOS~T9x)#ax_1|V0GDaEm}JwW}32z?YknGz7*6>*gSE)f*qn% zCbke@veOmt&nrg4sLMUt;E;&Jtypu7^TP{yo+v*%m%i#RiQTFZcD@X@_zzF@@x@1mjeTA$u&lX|8M$9MU;z^Jr| zp6))dcRKqa%H@8KyWzWr3HOv~pCTO;)kbPZYw^cOTGzHXrQcg6+r4#jyB;M|_)|M! zPEip&)`1Pn2Z9gzbBaETrGW0KFN#+E{F@d!q4kvUAvEaI0U$+yc9$yJa(b1geFPXH zwgS|z`$=UF^T6Ie3FuQ`Ngl}7GPx{hAIiiN$8$8dtp#4lHqfV3Taf#oinqYE2S=L3 zlaCxK&bDoTi;CArZC!E3pN${{cJG|zov5K;GK-5Z;v1jhWhN;u;+2TlAw?x; zP%wx&sertf&+`h>FS&+4bY{B@QHG0|tLWXZw0hA1<9Gi?joV1dm>tMn?Hil;F&5|Z z_!l>F=_DB3gS{FTL720*((&+Z5_Zz(<)yuDc-j4HQLLW

#ska26m`)@3=F-6;H%cZIiH<%e@q1pv z{hF*2lDv_Iro+J8Hha;FyNTYkt#YFJ}cm z5h*wFy`GKp1i2}vyg@qg>6fE!2Au18F<_~2G!pxWv?zKk*c1c$1O<%~xCtG3WITh0p;*effIwO5`@ zFn7B`Tp>x9>C)(oE_q2aXg~rXBKwcvq8{oOGyYzJi#kD8ZVz(@iZq6xpM{DvL!{FX z29=pCdA?p{4>AbxX3BDrBKNId8YcznzNOC-61?7V(!BVF&g!{jY|W*K@|!qa zu)M;DTN2~F2pbmU9J1yW845sKo_NPyI$lrT>#VK3YrUHty7r`sZ`>2s;#KV4<9H)h zA3Y&+KS~}A7h}F8cUdiC)JBC)j-Da&BP63Qj-eC=>qqLrSr+2ax^{tAqMj`a z@f#{EspSVId=VKe{BUmX{|i$0*Fp|JrxXUA2$WdWU|KV5C}xgUrgos7 zrxS*+vxeblUD6IU@ea;_%32BwDH4Hk@#}Ei7Ag9I4mJxEc9UZg84`ZLtd=ox^I(%yMes&4ctEu}3V){*brlb`TxO##R|4ETLsA zkHoly_^aw3C^f)!HMXJNfvv(wPVRq5k^lAio9h|G#se*Mt?X{oC98 z-{w9Q6;%EWbpG#hpa1Uoe{-Mz$gBTwpZ~TwS)Be^u75r%DqR21MY^V@cOQ;$bpLEggu9^n6p7d^N2w^-JP($e}-jd1I0%6?s& z$HM52S5JRA3S+n#{*biYKD=w*Vr|hv&7wW0{XsU^3=2IPQ2Hcpc;#zRQBj`P>w;)2 zA;HJ;55Wo`6Z+z^4^xNYZBbg9Yq<-8f=Fj-E9dhr*_3Y=J})gP6Z zT;8?S&j~CMq1*Hgp1zm)3q6*{^(FJ=hIzcj3L-we_1C>RPLBJMQHP(WVHj1vzM^CK zpdD8$9(f(^LHCuiSHpvEv>lwL(Euq%t^KyYy$tKf_TKCmLe4xL%A@B@^00iSTbpb1 zT~ViA+^)`HUvb&}g2tQ3x*w;eg_d?Pwe>8yKTqBpyjx?qwJLP^=ZkSRp_itONB>Gm z1(~CNESV&vr`9lNUAapSe_hRt_E%wCfAcK+0>`--o9O&~?sqpjm8HjRQIm$%I^u{Q zS6M8l?!!IUV)?$8iQKO&sY@gKwK2Pw2MNZCGTW{4m>^1TylACMuGvaGwZCyc_>C+{ zmToWr9q;wL>U_q&Vxzk6;K|C{pzF+gH}RgUe+RszYi+%LjkLIXhZ2e_+m;B2?w|NDo(OK+lA2~%Y>W!xBR`N zkA$}>o;B;hE@$s?4%}kjU4n>*lC2(p|FvCIA1D0nrvXpmZ1sc=g{k&m)ql|Hogc@s z`KCz;-iJ>;mcPTU75zpwFxK$gY34%jycs4SB4&_&MA0J<@br0Fw*o{0<>3%Ss_=l*|*8%4{NPh*m>o3lKX{A{YR!12X%Bq>q#tyT< zZn(V|PGHN2@gy}qj#@czl&04Xg1;Nw{eE-5rQaSk=xcoB8u*>X%K4m6j#6>XPirHw zhyx$(AJ^rPg>m=Kzf1b_xm{bddys04D_ii@+IgKGmTbC+nih!m)3P0=LoOCk9)k%Da$@(A}6__+&*P0jouLS0wGod>#5Sfyt5<#r6 z<;XYHaRcujSuBKAz?O44rZa)6>_^J8H|T^tx=@=d;rp?uf}gY`m-IU0ahgU($1vwhNh(V9!*? zDW|@j^I{-SJN++)tJa-MY0f+^u8pC4rka3XIe_b<4edRJ?OioV8v(y&8E;(oi1ofg zx0Q6uBzKy1isxC04E*NKTj>t}d}EdrMA~rFu3T7Ume*HShbQRRqzUb!d%4fXsVPMl z?26d49&J%aj#V-gdowtz|%OiiM+Wf>A4D%Py-G3`y z+I996Yp#?s~`1&uuCm0?KMS@D;T9_qtJ443|NlsM*uH z8YzBrw|nzTak%HtjF5s-DZ0}p7Ij)9ci%l>DP|m)QF~nDP@0)FGJ;uuRXt5?tY9bT zj&*=S7Uq+BE=0Jxnh*XM zN&DD+9U=$ag!I5CZ-3_7G)vTdpP9cD{YEzWFYDiE*)Dy84J#XSl3?~Wo9bsseXJ;_ zy7ye?1F^q!BE*FeLc9uEwNa=ee0)Z{3=S^^2JLF#Ym`u&?`@)*M&?KS~@%i+n4 z%uRn5=7~aOJICFSeoS9SUd|t9^c$kt91pmkC+>0{XcygQ6n(w{b_IK5CtTdemZfrE zT<4svT)evdYQ9(ad~90QWmUOP!IgLE!ZSTeF?uljcRwFB7o9(hxIEZ>H}`Py!#{kW z>vI0X|E^H_hxGnm_`v_+aBFJ*fBk{~ErM%l{a0}N|D6x4{;z!CwTs}tnb3b!EB}Ko zyc_=5Ls;I}knTK4^WrP(ITXFH)Ale-?U2*?=d=@p=cQVv^;7yTW~>`QKke6ki)WhdoupEW=!N5}-i6^GZ}ya&mt$q#&?&h4u$3Ep>bo~vb%MWH3VT8{OIv=) zjcE=roRfmSt2D=qb7amnCsO0%lyYyViX>i#rG+W1%*Wss;BfH?3})pwf`&#Sk;-t< z^nKXK@FOp`Sxn+ead>I?uFX|Ob*sIdC3f zXHyp2U^7N-DbWc>bBb~x?j7!tm%qr*#q?0+BQ@Gv^_1gjWEasqoy%o8efO@^;RalScyf`I9ZSSMYJZcqW zHeK8V9Vm6MjXJKg-J98XNi7Cs8bz1TP73)Q2Q;kDo?%g8_frSiJR6I^g9VmN82`S- z-upvRnQDs5;c1M}u-73Vo7nbG+W{(sK%{({1TN8uld~#SU=L`;z=m8}ajqw6qA_aD zBv2rS5+(SCXl!kz;fPFP(#JKOq^p?aB_vvBW-1J{BBd9b)E~(8X)J&mNyd~+eFKNdw8K@fCDe0kzB81Bqn+Ru6E|D!v?)Ny`JJ+B z;x5i4#yB(TjcKClAysvcP5m;OhpvjMLP|ve07X&f<#7Ov7)!zu!KP2(Hypra)W1*@ zo-g3V9# z1^`Ss&cXmqUI-AkwOf-ZfQGA~fN>mcGlmDzN~OWuDA?#jAQMv`o+t4hPcwt2`vF01 zG9Y4?smDa3h64_ZI?JMlODAr}Jd-upL#6D)pp$Re`@tT&ay`R*#R(>*E^9;6Ct!%S z{~}te_n-;TjPd;?0>D)^XQ_!KRyYJs9Z&I`?QxM z90>$jdIPJ5gd;8?3YoZI98BQauPw?F-)Q2htHVb9jSg|V9iG=s+4g#bA>uWG}co2c5(-ngz5 zRW4kA$=LG^%+`E->vn6GPASY;9UO*R({AWDGj=bz3_R%W-CV0WIf|s6>6~V8jrKND zPNl~88bkrr)-l}Sos~`)QE1`TEyJmg7rw zpIdmnmGP&(Oj%X0>jM@y_VJffFNli9X>ywiPx#beA4<^dLo@ny`ff^+X`OeLUB*m) zp9blQZXH097SX&c7c1YRqO-fM^SZr8OyXt#RzP>a*`8uq%@4`hi2xATTfqn@e)hGK<$osHLZXaRrAtOqkk zDX;6#`fwmuZ9X8GcF!0g$aP4|_KI}cHp0;uX&o~TI4r>Sj=0GtLaQgdHB9BUni-JQ zV#dqqhuuv>7mspk?2jYI`14Q5`1KF@=_BiVWuY5|n`9U2;#tsp9012%k*8q=fj0VN zRMXMPSLonPS7OsuH&rsK`cyUO?vl!k9vF^K~K zkMU+T(UpZT=B-UFvNHPVZE_x0ncmDMSY|6$~aR>+h<6 z?aIb%Np6h2h(vY5)89S{oKQ+*N5CZz`pD)kMn3_@Z${KEEa8rOG|c{rm6=Hk_q|8=j)b0SpS)GQ;;B1x+1g;L zD7_H2b@o*AV=Oo0Y{a35*xhpyMOYvssE{-a^ z#^3@ywUVr>X{Paj)??0Vv4meB?9kp~J6%Y$(+l>x76d?~5lDcB2t5JBx+dZ=I0PpE z%$zk1kZ>buI6y^FSpj$izJXOk0FJ?CE5MN|P~?B$R+?4}Ar$-=J24^o0Z`|_OFi1$ zefI5P#652|m)3N!>6>!pHAMTNmBR*JrwUy@?;|j!GDru%XU>JAQ5w;Ag;DPy7*dvv zW9oUm1gI-hBO2-bl0ko;;nf}t#+hL*Kj&>AH_c-xKD(`%164%x^gh&oo}~EG(jY(p z{u9RNJb~%yH+a+3W;)07nVgwcU`Ds6`I5c$UkM4XnkM29a2_)zwbfuQol=+}Hv+C1 z305tk4brJFd90aj^R-@$d!Dg{E$b&KJ=_Qx7z}kLpHY`4|6s-8B1)+NE(35~xo_6e zQVh)k={R#U|E%Se{j!u@wuiS!@?=kI62>EV>7QthlUGX5xt_l}uf3V%1=WMmXLxIV z?`84L8fp2Psss^kA+&YY2Uj5qC4Jaa7aQ8n(q5Z98BxpIgs_?U0|MwjFsp_$_rwJ~ z-z<#}wY5Y>nyK|zXXTP%yxyudI3i{H8*M=ZFUBhZ(_nH7`c~oOY)7)T9O}wnlqdhz zta2d(+VuLwUdzgdLx!JPbEqDfAVTu01!TGB{T?Ifm~x2Svl>@5y70|N($r})I&`I& zN;djNqX1mb>7%y99|XQ`Y31>q&VZw`#XTBdAc`De)7A|Fyt|Wx9QY-&MK*c^AUE6C zSx`0$ZB5aSXn1?dn^%pWV7^6v z(~ui_@68L-V85S_S`DtFPOaxfYb0eLbo!Rywv5|OJ`dQ1uOP?Z%6Kz{&OIkt%a8(8 zR!GYX&pX9H^D+g!j)yZ+RyQD}rT&PjrY76P2A*?mUcsFf$7`4Yx)_GH-RFed#RL8D zYDf8qkg6A(RD(OLb3Z=afufPOVv=-^2g;;R9S~wp^F_9P^~V*%aGl&=Jh~znT}Vjv z0lDh8`k9m$$4RV4**h^vDGi4Lgd*N={kNHx@YzD*^4W=Asw_^T;dKu2yHW2&dli05r3!eP_;m9!%$?Tv-aJF zKCdQYY9 zZpMVzjcr|n!D!;|u&5g1o*ZaXD0r30tS@q@i_08ugm$PI;@8oUVUT3 zBUqEGS=_C?cwVOpI*8^|t@?1hKQGgH*AP{j2@W^KXz^3CVn5?p>1Un&@_aPPsi>VB z-uIG=zY)D}x?V6pdAGa0TJmLF8Gx$p3M|&=Ykb;S!H7aahNcc(JZ9<+^t;Jfkt>an9 z)Fp1aH1)Gw_=vsv`(p`t;PD>m&M2O8zdkkCwhQ6maf+}!<-_^la!ldS*oeZ)kfy?q z^xNQ+IS$44Jq+jD0qm$7AZSwUQm=XD4})lpk#nJE(V%{44(oDHst<485K=2#pq8GF zq8;IAwNzD?gns*o5N;)loEh~Ax46-BzkEwsIgWl@($(+)1=?8e`%`S-qyFbl`4rCcv%B_8jUjB=W*>>CNxNdHB&2yZB5 z77-wO%!8Q_F0Af8$3W%t)L>ksWg@~Mg*kbp>~jn>+0Q3GyCvJ(s#9YzVrd8l4Pg*o zyu88~#Orl^DY->lrQ&Y! z+;K1dE=Z?oZ`;srqN1K2d)D*?1`yf?MH~jqkj927P|`tA}wq%sJDJm{Afo$7cr#!Rj}?|P2)ci z@9$E>zpR&{;l10TU^!iQ*xyE=qA2#cLQ?ZvO&c*;*NTa%Vf)#}!HI02e2Xe;Gxiva z5AD%YOxs7G|9 zvzbZ|s2v@>`dqIE#@-8EtLmv;@577P21kFly{yclPy&A6cvQ;fv}@vPl6PrtbNDj* z@>Q~BePY_QQL=L1r$3(BL>^;V!scOdBuuJ?PkBf=IPv_Ak=(4OeP06K$Vy-EE4>2u z*S2yw#t*L^{VXJYDDgt(@NsS?()}hSA*o35Y2D-dD?DjqhwK$DHi`k z#1{gV@@(A{9W-3aDpwtbrCt++%glsa<~WeMY{)RI*-i(h;@BRkx^R3Jk67bxSHwFz zRMeVZ8hi;gB`G@I{rcdv(b56!dR~`x8>{MyvZ&)f{e3hy>Y+ z3x7~R^qJ+cRu)2=9wL!1YYN?dMpTp7hJB0JF?Cj5P}SPb)9Z9FLwrl|_1b%nn$zB1 z4i|P(tUfB@Y zD8c`D=FDoLTP1c(v8aE5;QKsh!mLpJJH>sjW1q^>AH|f0(?>PKJ8w(8k?m-6 z0YyZLUP}9cSs&$o&6}OM!*0m^Sh#b>lVF#G7LekEazrA7a(p{eA5keooKx`b06+wv zdJGjsqF$_Kl^UJ3fbNkE6_C{BCg3%EC(@ z(7|3rXtD8xXY8RU&S{NTLL)T5Uv^xM6~;mIZ8?z{9!#k{CSVWSEBw3HZN;ioDnBB5 zO-==(wUhy=PK>!Gcjvosyfs$1*bG-eaV`d=_At`H!M1h?G{u@h#e065MlQz>zU1hI zPPBfoO!BaI)a!oKAVllNl0>{<+_!oyyR8*Q1$uQ!9U5vy<%^M~Hv|VK8udy#Zj5F7 z2Mka^M`OgAZ=tJ7RsQMqQ8LT>Cqq}yIfP#qFU0s!wrV%?nx$Zf6_C5A-9?^0Ep%bmt~ z_EUa74Oo_Fbt*RffCkfPL_6y>6mSd#MEl?ptjFewEXp4q=h=tu01ECHla#?>9`I1I zXDC%V(g>)yr<`7A8cw>ojoK-t5o}BFo7wkwkvGpzLf$(C;6(k8xSTS!R7d)SLvrd~ zn%?0vUoZ{PrR4;;fbkF7G&$!uhW#Okt9lSI$LFjR&1u+1Yl~%ZTJH{}R5(X}psnbH zR_0j~=ADj1J@#*k%(1l?o!0rM+uT2q!PiW<%GD;G7&Cr&bf%J+Y0rFOMj}Sj+IfA% zI;-|-~cCO9&Uwx9Vb z^q`U*QKmZTjH?g{sl;O-l|wgSCFLxc--bY6gzs6r zC~P~L2_b6Wi#GR(ofDGr-Kc?a2V9pnt3q-Wp_%(C*-b^b=y+KyO`<{%ACJ}=QLIJS zD+~GV3Wz=WOXVt2Mn!&m{e`BkPAszsjJ>fXgbs3R5Se7foSTyO(x^SNA#FMmw;Rj5 z2uaF-(;?Xl#AT5TiS$kd>vp*4jj z_wa~Pnfm9i)V=hB@wX0WoqZN05KvD{aTESXild7&ExYqLX`@wHrEh`suFj-g;V#*~ z{NvM2M=2(V4_e)(dC`@!jzf`pS%qmNFbEpskc)Ko8F3X~?r`pA1DdIQ<<$I5if^p9 z&-QtSSjB5aUZVR(M14Oj2>=qc6+k$NFt!A%!lt(ye5^~F-(8$LHWL$=%VFns4$B~+adUVAX zS?0Co9G&un;{`9SX?5~uCr58?sl?#$bzdS-EAix}LxDSZyH9aG!c-k_pD2p5orS-K zYV`)kEEJm5PPkezfR-iVnc(-A-xjqGCMcT#o_tV~RawI>`?$F5LDBq+Uk0w`TeR{} z%Tj||+aTza-z=gr&L!jNIpJ|xZw0jB0-WcS6|4fh`Ta1 z7OIqK+>gU}Wn~I0e7NX?O_tkssYvvBVDWybjT$@uU7$`6%`=1uk;%bybt!)_f-EoH z>=u)#XAmC{JP@d4M~K9_3r`^6+z5DxsTAL^>!msoG#>+d2y&>DHSnB6{g{V_gx^>#aVLAXwzmrF9ob8r8l{ z{zK&}m7umPU`?$$40*jA4Gu?NI~LN%LG&h!b}OoeZta;Jfh|cPRxn4+59*EeWpWB7 z9^*zMOdsdV1ER?`q)?h&xU@U;HMO=b`9plnSC&P33(Mr%X~N|@!d*x`bpj1HUx_mZ zSO=ylPi86TYqPg`AHCN+v_h&%Mvj3|t8Z;nS1CCtzsF1Pam$;KGF}EPwDPn@(8lS5 zEt!ir_vB%Zonm64%l+=!1KtX`DVko%vtp=(OINj0vYunbhl4#GoGA9zZvH{sra4Kc zsd7N!ZZGVDOl;=2AJ4Ag<%T~;$c8d#U-Nc}aOPVg?*IzJkz4aGifnL-v8~nMYvX2} z*M`bu*PV44`{9jai8_s2n2m!;KAbaRV?(fCEunM~f_ZZZjjAwDa@1LL*)|*^V9nNC zLI9PF-x(9S-Q{!bQBQl@0J=9~X=hI7dU!;8g`+x)GPkK{X#z9_vc<0SNl#?#`ndfu zSO<~B?C7`APRGZ7EE)`Ru)(H#97BE<2RCh3ioBW;My>u$(3kjo7dP-%p-DVRQAlJM z0Nzg1y`7Bg4Glf*f+dAPFyR-;eq6mwGe2W?>aJ9ieW6i$Vi^h}H@Z`APr?>y+1O+> zt*vm)&WxwRfzgGEhHJ*wdJE&ig!3Bn-ofiz%bDkVaMjcRyNO6dzX%6! zrT$->Rrd8qp2K@#co1vq9e1>+ley26wQeq25wGl(kKmb}^JSKH3W8Hb!C3G;)Pj=2 zo3ACQMwd9W96BEmP3E&u>nm={t&dYHC$+JS0{!i32p%}cpTv{eHH@ML=GGT& zbF;aSn~7yaFb>qfDh}jp0^A3cXZWlWb()~Q20nS*Eux3!RBe>d zwP>rBW}ffz&c&`uFE43F&a}x@BjB=9stT}z6zABU<60L#E@t+$=5mj&h1kB}}Q|W_Q6mQ{FDhvT5fZmSpIFpt(W z-$*Z>gIRlv5HZOm#gU^7d5DWIjvVYU_o?L<%Iv zQ%d0Sl0x2+Z?Mg5W4?$?N`c)~wcKB1KMx(M^GvgDQb{&$B2|jKXp<)|;>1== zL;KqWk@IY@BE;=fxQPdgrKfaEl_)uxC6sO6r)0Q^ZscFj*!vHrcWZ7Ep>JzIgV$zGc_DcrQ)2d7 z@s_sS$Q`g@jKcxihs%enlV6^}f;H1PV@^*sjN%L5yyaCNy-0j)!XZ-Q^G=k{<#*Yc zqStY>=+y6>wLL1`Ka1(lWbDu^5JIkdn%9JNtCsJox6cvsp>4?7-wM(WIj6FQR+{CB3-NYkISCrQwW2LQACO zE{Sbj--Mx;%*&atleP_2Ozr)vTwyHnnBFCaT$%2gOnAcqT+UixGVrr;S&Rmw;`M<_ zv|4698o`*q@{p8O;Y_i^xH8PbvRVohx_a%31f@LRJ#~b8tkXl?<6SlMmLqacCksue zYVK|priuBgT3Fgt8`N9PjSVKz7x6qdI`v73a)PQB~XSkJD{hXF+LqGo*AyoE?+4v5yNM`OWeY^7(+ zl_+yj`Z$XGF6c_cgA9$4^W+}27Kb(QGM2M%GM-}D+YYgH>?Y}-DhsQT&|~T$6@aXb z?mOjFjYDvfyA0uTPh_CIns7Gtf(S*FcT#Jbg@agWLYLG*<|fI4U<{U;hyxD@_H}F^ zW~k!M@0e*7GX_V0P8j#|-^#byn>AEJiGTtk6FL_au$W}egOAG0X)4R7*Mp*Y`a+>g zeT3t$NptR6b*>8In*G}zK?Smy1$KzG=ycoGZefJ0HnwxKXS#&S)M|E7eZ1oD0ztUR z<-&gstT6DxzNe_lY&hsj!qN!D5^Vs}I6to6EIJUt1%q)NQi9f;s4bH`^o)g{da+wb z*(|1Z^n3OVvWz?d}8{GP^Xyo z1&8FHDm`C%405#^T^03R-Nb`BmJodqq}vtE8ovnoYG;RdMOe{O?5Qr>6)eWV!7MQ% z$@~LaZ2dfh2d-jNd!!mQ)(JBe#?KnnjHGoKWeY$*=0DJoOIBRufjqrrU+t~@*;IJ? zRm0vkB(U~0V4~H+tdasU%Q@bdN|Xr?s39M;7>26se5g&NprmdLkv_^Y4|8NbsFKr9AwL9u8OV$@n78#Sv!`Y0^%nZ%Pqe?KVwXUk9nS@5lJ%591)lKlQz#!jHW? zo)5q`8JzWlE&Q#fSdZ9yuLM{6Q7U3-Y#Xl(U97A>NL<`!?_S z?Q3qOrJ~_*?ajNFdtDXhz6{|QFqquZT-eYVK?0v0si@6dc!h>RoL8oU$xZ8BO}=v- z!XGXs)aS&c3{O&rMj(zSRpUgSmo>gp$~=0N|I4TPyQ^BZd;TrFgG1|D7{-H--goS2 z0#8d}NF+U^tY+ziDjgBg=(4Z7a1ZH|S8ZqZu|RG97vrH`U(nD>VS@@$==?v`_UlQ;0xNKf~nHl5^N^@+ItuHhZ^rhqfRE4pH_A zLjLN?hqvE9NwL7;epy6z1QtHnrlPPT7DsKb9AQ1zx2SG<+L2RjS3kCbig%x;rVF`# zMg$boi1lH|==VAcO02y7R$_g_Z)(?s2PzrTYu04ALZIV|Zb&1mNatQ(&qC8`_?`fV zS5F~BNH4oKKVjB54%0G$sV{vGNE%FGi*{Asc30t|0p-(fBG+K_xOKmrv8Da_2bBZ# z?3PO*u31j*Z@G|BX&&Qg6RsRuKMvWxTOoyAGOk0ANW+wP%;MbRq|Q|OS4!!4(LW9D zzk6Rwb*>C=IL`5ei;O2qhM-4JOL&Iuj0&hksYB>iDc%%{v{~*Fav?Ayk;uGk-vxlB zGpjYQlT0Tp?1^S(b)^@uzCte3>8ZIZ{PO6yaS8m4*~N$@Fb{^vSH_vynhvrOj{;Gj z{=9{$@(bs-XI0+Uw3RER7}}-ESN^^iK<4O<2%jNmj=u9h1!!wEf5jaPf$wTxVM(^xj*>mzs%MNHEqY{MH{i5ezIrosn z4I_-+ZzL}jUJ~9NP*xc{=+2I&w~8hD)P-M2Sd#CgLoN4!FwU zqC3+%H%}im!KMO-?Y*PyOcFQU;vDXp{dC{MDn#c}>#SO1;Jq*oo=#>hvuy0QC3kPR z#O{^v8tNWT(t7dx4{xEFZxzgnJ<_RsO*_~*EYwcl|2~|p=J zbfvTEw{66pQI}XA=C6)BmjfCzRWE?|75*&NDulrnwtKTuGw_M@mfXf2o<*j)pbR4j z=FBI?p)NB)EXY7_PUIw3fQNP8a;XhHPIDu%KQ4vxwV*i<<8=ZRabLJ`iuA% zifW}xaCjMS049AUC-TIuxmemeOeX_+v%fW!PE}}jGOvazT-Y``=_9H~jX~#u(dTX;N^ZKTQQ;z*W1c8>ghcYF{w9mZL zc4ZI6Zx`AUsv-i8-2=6kK5}l)`R|g*y?-6NP>(hUMx7=CfJ0U7%=cL&1d7MRYb8Ef ze}q|OA`{ndF7$BqZBR{D3K{wsiv1juYN#?Z9gBb}ztjtWi(57}-9GI27j>KD_gKei zhBD=~HxH28^H!E`IQm54B3K#@bqg@!KqQ6FyfEUZurj_POXp#9TX%HT5S}*JjOf#e z`{av9z~R1qbfT1XEOrRA_Do;w3{i%Qeuyuu?~e$b>DDHh(Zdg9F5}?ejscEx_h2IT zp?q?h`g-JU{1;^v%-I!ugy+jmPxY;+){8ncBfr1cS)}U1dYl5UQ1TK zPxy6mxc6=Mel)x5UFQ(IJ7WCs#SUvfN-nmuW*{mn*}w!bW~kQkcbQtGUcQEwyBkdH zs+Y5?eZM`7D@T#*tyxWp(-m1H4^eKqk9IRaECIAMoxMzMhy%eXH`NCWO>TGYTzDis_80-16;J3l&OFueBNKq*`Rjd&ON97O zIH2Y9LLd+ZvLc5Lk8%6WTm*@TAuJ65(xyh!4W-!3B58g5(-n!Ku= zqqrDujasG9Y-(y z-qqME!TtB}o_1iNN6(h)@c6|$R}Qr(`{f0jNulLE7jS%-BRkz?rr@lQdlQxOr|aQY z21ZDF{{vdjt<2S}usjpN-+#Hh=%#O~N=I$p<3twsa~`g{(b~bOvB4qc_(kbqWSuRA z2+rEf*n6X}BjTyDD3r)O-jl-2LW>k>f``Odpo_Rk3Xwqgv~fygUHM37xn(}hg!uvs z+Jk}IiTBH&zDFy5z04ETn!@UF9XZ@!F2wd#)ams5(Uk2vRhuqwwbA?jwBMW@y79Fp zvh6~K@JRsYS6G(fS4KKy)G3{+@=>S1*W=WcAP0sy3F`Ojf^mpx;nQ?tg2N0bx!~`lmFOhIMbyCEG_mVyd|zSO6X9Qciuf@h3@}J znlE^#diDGwR_>{o6n6YfazprVe43e=_ZTB{W{e|N2SQPzPC7rk;; z6)ik~W`!RWvZ|MzqpccPg}BN0JdMsdR+SRIa<28gN~eav<(6maJK^}OG=l&dW7iDd zU1Gp|2Tgm3%I{7!&7qaoJ0cRpNufb54=?E0^%{Q7oSOv{ z?-ecW^Yx{Zpcm09Grlcpsn057I}A)B1ASIiO_pfiOw>c~HG3Slk3t8WONgNeT*lpk z#*YUIB4eGlrH!{=2kxxEkKaGU&Z!)57`uW~SNX(ICEsHbg<}-w53!Gsr;EwkG~?4n zYz69PCfH=aHgiJxn1P25A{2z4XIpec)k=ZaNQG?MT9WgD z5(WxXX=XG=@*($jd^T=Sw2L$gGuU=Kfm!$F8yg)_TQhZ%PUG#=%?Wx_VCxJA>9P0e*T9!ty(CG}8ko)Qitp%^SImqi1SK3be zaC~CV^J-x136cK%eCC+$`{IaFcPxztZz-s1^OH%I1CuVi+L3r@0!@9jG8x;3PTv?{m)?Uu0sDzHi; zU6$v9jbXdYhjZTvOVom%@h^90yN1VX^y2lxsX!c;YYftV3-DtBz zK#Wj8-ER63_Ch?laYGhu4C_wrj-<`N;nFg*R4^KVSRV}_&8Ay|8889Npv%0SXd*~8 zPLPBkOU^fqRviXFJ#kUf>meF9?>dUud)OvkxR{uUtlPn0F!>OHG>Z*ZY}HBkQU!y;Ld^Q$`-e6Pgeyy!zz=8a_=G0GKRTSiX6FV=vIpe&s2 zJ`2Xym+`}~Dlc%~?O`&J4#RuiKC9d515%1Rh*LB5pf{`1%*S^YOalt&O?x1h+@4i9 z=bq`Zp@k9$G@dW;7!KkpyzR`!A`*!V!X%zsM9s7Ycu==qAaIpo^q+nC;5sNUiwuXXg?XDjE`ws3^V-gtRP*lyZn@>!NsFKW1s`@jDq!S*10*G}VhHz~Kv zDbnH`U!}(J^vG1n*-r>B=9p;C^*OmSHPJ?g5<8;aN!Xx8#k0;G6_0j;s|B;mVIn$o z&TOcjK2xu(#fs58ZxefYo$I-Cn@}Y_QDpbYgx1%R%Qs=LV4>t8;qzxqqWF339pLT& z#<_81!$!;`jeg(iop}ekJI_cwIzfYcNR7MaXNMP8F%AYxHHmWk^x@{-Vcl+A%0R?J z9ZwEo8~_w3KutVl_B*~C>{;j+P)08$)vy07iZXonwYNY^IIjbFllW=3(JaF5okXW2 zv0s1@Jekr8we12l0O@UVsmg{&L}D{tX{sbUpsdg2+2M(a#|D?azA`MnaNVrKfCdH5 zy)R!P@ZhYv0R%{U7AW3e$v9GnX~oXN1Ob*deWl;ty;1G6)0b z&+2eJ314iDMqwp2ZkcF03}WC3%sQw2&dO3cLSF7mG^9V)V_~r4pr?t769S`woojlk zUK(ye0I1L7t=H+RIiF^=*X^b01|Pe4JCFvDTO8Qe|0l8tLbeI%68CSA`r!2utWFa@qK#7t`$I2M8zgM4viIB+ijQpbkd0|Jx*`Y+$TZ2t4qt#A*6-+(2zRty!+q6A%)Ui&t_@bBbz8gtkxYtLdn}#Y4O1%A5-GOuCSr&O-`OkvwC<1U5B`bc$7S#^I9oOo7o0gix)8qIDtBhhp29P1*vtp*~4 zG22&3GYA0QM`05Idj7I?w=Go76{h7V$xqt^SkrJymN!FxjPD~<)JRKQ^?z9>W*gJYs z|4|+nUI4N*&)|O?oh58$HUpQ16X<&Mp5%}%5%sslnY>zgW{glfLO2eWSPGPIF#&*#Z(cVce5dVDuR1sN{cu&G(7bM3hH>a@<&6&1 zcg`s4VnrA;>Nv0|u8aff(soYHt&m1y!Ws0Yx?oQ)ik5XE;7x6Dyw9v}MFHT{zI*?! z6AnV`Zq_4ZaX)K0aNi#tc8O!fdtf<^#J^(zZhlf*)<&IJz zr<1bU&LfD&s^o7n4p-xia8rgj>POD)coAdY5J(+IC3ipJ4II2X`Ya4K)a(*e_1*_2 z=(Ej?JFBOP18s*V$updQ92INR>pzxdA^uWS9**0^Dk{;+UzRImyKG{j6aH+M1*1~@ zey`=rK4c(6^ftc6_iCR$HUI8js4|xbkC2MffP2c~msn*}Ok~Gjj-iHzFqmM@x$v?` z{&-G>1N^3Z{n7S*E-o9>Ni5bY(=YUNETlKch?XSQ9hhi%sH%S`o6T@-ys8F{M4e>tY6n3?N-jUDa*v z#<_FpzZ>#yG-e4NQjKM9bvz%}4SN6&I`b$)Pv1x3Lk2QZe}nsCN|C)llj7m4{hjSO zhd&*=^Y~cL&vn=*WNnOkZolB5Z~y(n-(ShJ5B4m!zAEiX;al*SZ6jOOvnnc3ipBEp z$9#Y-()C3wSxB&CW|$c!Dd=41qRVI)mlEa-eZF0R(+$TTs^Q`mLfnnR%-))XRKbD} zWQ!(K=sf2Tn6&w}$A^E2%zt^JWprYj8HtR3)H{BajX6nvm5ntW?&sGte0E5I7o!m| za7gv(P@OHGUJs_nE#^hf&qR@U-=RZ~IFpVt*+z=Xvb@rP!}Y({s@fks{rL^-DrT|# zN3Cs!0Sv|`J6Q)4l4Xwe?Grj+cG#Si9UsfOI##8*6y0@N@|Y-w_E@Q)+U(VR(-}S_ ztXIb#&UYV1?znQF?~ieBxG?{*-SqkuLkHI7>-x-1$a6^s7OGbo5RB`T)n=Mq&hB)P|D1#hM<={{SdyvKaU(A2+O=d|zD=3BTQ)1sK4^Oai5kasC! z=DIo{j``-ECi8~nOPdyk45AK47kBVU+kQJ{dW1Qj8FA%4JBi71J3Du*an2^Jl(hDa9=I@w4mt+=7em5A(d`gDAzdiE*VG^PL zcInW+^MhCTFB6QERYX-4E{NKSvdLYwzwhkrC#rbyFXj)MoVoJ@AOHJ~&JRR?`SSaC z`~5mFF&9<5_!pQ*&g8PF(!WqYawa;WO24o?=Av>YilR!tYGE!aXJIa?B>z{Qau)m7 z@7K;;lugcJ-$3!#2RVyn{j4l>L=`Xo#SM_N*thu? z8E79O@PGUI@7MO1m%oytsG`DOHT~}sj1>N=+5bW?`o|qJ_wlp$a~72sW!o?RZ#2;_ z!@mhe3i~iAb5TWwzkb0#2u2D@|9VKOit_(3{s(;O{|qqtW&a-mM$d0ddgol?3~QJ} zUkWZ0=WmnU+3q!Uk2@}Pri;VU;`W!@QrFL$%2y5JmZf+yr#j_xddj75R}VbTy7*wy zT~Uzp85hur}{a< zy?i4X3;gACW|x))iez0Zf|X$gm0zSEqC`A8O4zc`XPZY<>SnR0Q#ou?o#GaOk z`&n$HpG^#GPw_o=jAi@vcVSxU3D*AK8y)Rk+uEbok&9n6ssvdER{PGj3PlgpEY+1A z`gkIE?3_mMjmFoU7WvrB4~#jcY%3{6+abydd?~|UnFA+a^gGYx>Qh~bW>*5sKAq=@ zq#xO~wz*Szu>a;=R^=xtxRZKPunUn9&(o&QiBTWoKCQExc-AAs(pU6I_af3${Ng&Y`!gF>E&?fT4i~wjg2;lJ76VnQj1Gsx;Bs&!NcXa zIj+=~&lB5C{JdPHdXOJ(jMJQ3y3QK+|=5b;uP`92JSkf6Z`PMJmNQmRBhuEs;%eKzLK{(Zv_^FI++&q^t`lFPr1vIjsp8 z&cBqwCfvAVIi#9a_v-n#mp`tZz`2^|FqOO*ko%|=Xz#xcN&WfTvTK;bziU4Co1Xv3 zHTm@d|IHTpKa$0Mng7QZ^B31d!BYM=9TwdO^109Z`-{n0Ihij!?iT%nYm$RFvit8U z^iQhUe}ikH_&=JE{~g!l!bL?qH;R!eh;oX-`Dl=y65A)-ytZ7 z%IW&t^|^0x&)(5_A6^pR?&xfA-#%EB?Qfde1r-I={}gMoU(|jx{4cbMwWz$Pf~f8P z#DB>WgNefpn-yPKoRV~^>o2^R#iDd7MN!7(%1cG-BXRLAUCI12ntRQXFhQ1{F-`+E z^Y1npX%}!m{C_yNoyxngzQL@DaZ1>f?-LNrmsAhQQ_TRr*XE0sO zkxi`(2&7qJ{u&S3*PfocXZ_0b)A!e{2CTIe843CdcfSY}cc>nD{4wFdj@k*1tw0pR zi$glJ=Vg+HayRkEfefZrxEy9&wkEY*+td>iAG>Xq`Jp6~d%Wk|F+PJMS*Il;)RcJZ z8s}L0>SvT~nK23b;f~;NI6}Afdz9d+tCX`&0%8j8osXej-#-oHnUlKcsq={h0d2|_ ze{wmE5e4iytanGOSxgZdyv*IA?~`{aP~=Gy0A(G!=oke6vbgM0AfUyAO%9R~F>#Ut z7>I9RXHK!`h*CIRj#vSfUfoFmB1iL#fcE}e6c5~zx~}97YzX2*2myUASDbf zf(0l*qGHj2+KdGda4PnzsGpt%fI#|@PJ`axWS~b!&{zT;5oBf|0RXr}Y97UT;+g}e z8AAeShyglU*4im=n{f?b3&)CxN-W-na7NQfKPWhq5920{!N3s#e%A;1w|)cUFY=Vi zDcMRQFq>>9PFt=5iXC5Vs+y~#Cu)`CAYsd?5}=>KxMu->O@}L=$Kha}U^kklJg~gJ zu|6b;u+Bc1coSANBUhGO7C)QC;nNL3ZanH6VjndD!2J1Z9(64;A=lEz@}^~OUi)=& z!K_G5n>UumqS@a3( zpqMw4i>_N4{QRd6hAUG_<1d2Tl<}rIz1GYzOhP3ATP)1mOYq)7P0{b4#fO<(Go25E2J%=4N4<9b z2c}G&LHTSq`3StG{Xx|>Hl|4BDftNI$JWN8KczVF$I42$G43Ut_DqrT5deC&Lq%`r zhLsYr;Z0~>D33uEK^rakSJ?MlaWdm`TG4ycj+~A*yqBz6tHu=~xr*F+5!>uAK3!{; zA#8IoAP+g+n_zSM_`RYRvF*&y?UuM>B)0XJ##ef#3U${RQH06msV=>s7B4ns0i*mi zP%?LIhT^V;jXR}tZV52OEVZ=b%uMReBk-h|m+$4*+9oDm&b(?#ATXePDM9?qM$feab|7zR5OK-u^3AVyLA@zkw2Ts1V; zje=r{Am6?P4Y<5P0!nUAm4;>jEQ+BEbb%ZJ1@-d*u;H*dm*e2{=X~04<0~6i`3|hqv2jFCO|K znv@ea8_n%yQm+H?KhYiAxp)`-K89QacsJNZLyaFB#Ldv>@<=;?)Hth?8`Qkp%AlbD zHV}{)$5y zLLEml3cTM}$HApV2jwG`9GE!oJc{HKbsaKY0!gQFjOhUOZCWTx5T}p^7x~f z{IN`rCR`tQNb|l0-vduGTmSn;dQIcE0iLYl?$26Pb zO;qZn&$`J!w{o8d=X8_LonUX{IJz~v-znA8nh7&_)Yfc-`MtTD@OKKEx=ucRrixeR z-}yK@GToXtzP-s_)SmM6`IQ*)fY|n-3vRjep~dt$B0MZuwZTP==uT#1)&jd#is!za z+iEE-b@C|%R-Tv1VX}H6*I(oYkuEpkJ{_&2>D@{%29%;T+?=mn1yq#{B3c^&)WSZD zCfbBv16vA!?nj^!paygsv=mAp>C(1F=(UJJ;?CX$0u@MtJzqfB???gE`WOIec)bxI zrV3rpWYm|>tp}2NX8-{J0-%NhpgTCh*aZv@3IKH(J77rR8*Z=O8oipwKr?&*eF}%7 zE|9TJWIS%Net8E6R%$?v?>cc&zq_P*HY`CV_>kyK6<%uy{b8Z^quN zqfuy72qMVwART73-oD@GC(+;N-L~Sn{Up|#Tl5A5LN8G} z;$?3~>JJRu!90WyL~R&~Z#F6^%!{SLwE15uyBTcEnIh-w@FvRm>nelp`Gf8y(b)kq zS}Rvo?`;j*YbpyW3vd+rco>J8zW?lJ93lyZ6sVGvTC48)Zd5sER|$Q)kl|S z@$CdeNFqGjk1oq7Z;dFg;;-YiOPyk>Emt)D1*~&JB9R7!fM2(=--a-5dqZOH0^ZWp zB+AHcZjveZMUv9fO?h_fER4&U??1Y3L9F7;VinkQS8E@{~y zDpgDr3nEu@j|{Ulqe1=M8p0Y0jjFy$Uhs;Ho#^C#pUdb;x!P8X@QZCnqtP^5Ta+V} z#STZt&Bb-?1Zv1*%*0=6=^e=9Oy$onT5!!9=%L&6b}9+EwnZw9cKiZ0WNS)VKHfiTV#VME*#5|8n~gba=96qi(>R9l8k8U&?w)1 zZmkrld(NZn(rQxPR|J?fq_mH0Mfj~nTt?JQXIy&0T^N{bTijDMezMxVDFV$Qf+lh;dOLS;C<}fxk&LMnWt~z2VL9Ce<)U0$h zkSn7Ap?(qo2m-4F><;LR#AEDLJz1r-eoAs*ttQk7uuqq^Gb;;Elw@j0>Uw$Ot?~Ae zsU1k9kv~R0OAKF~Tau+(U*G5+>3_GeI%=uZS5Q8?-8Q_pGk`}J4mVUpdMogLHW1DH zMO@#X`*7935c?gLM96FR02}bZgSSc0yS@Xd@83>XRLYfb;!gGHf4U~7t{m4D;oDvA z77%Tn{rmTP8(n7ki0YW@Z7@D(?XQu7vnhgNe6b~PqnGBG{Vmm$g7Diq5526O)_vI8 zk?#1pBHH^{l8x$K8tNzDgEfmz=$eq7km3O?DCv*-<{Ym>%h5P|r+H{^;;AILQOO^!`B|6Zne^o z++WSzd6Ie>&01-1LBY*{vYn~&t9d24JEiU|4)AkVdO2>C$tD%S3lZf}c4b%$rdIe) zKPwtQx31p`NrY}c*6dd-Jg4uccP&*iphT%QV2+#5M8&M+m3)N6+$RRWHybSvT)dbR zb*huskKbQbVvl>Zu|AX@^mug7vGvyC^KMZ$KiCad!=&Mluz6REs4FJPz#1Z@Y=pQf zJ(Ud0AGANH9XaTtIBj3*p7%J!A7g)TL{oV%kh9HA{sp%V{`#P=e=DWQ4navI66k5y z0zMpCJ}RI4LNLu4hg=;O%5a`MJDm!TZFkCLfbg>s(sS2lsoMF@`1_}4zj{rSUM4y5 z#aV5StX%wXu4ZZ4NNC$eZW~etae+RSVa*II1Q@vQQwQ4%P!ZUIs`M}tgJ3;HSOGwC z2Wj5LIxyZVHGmr!b z)Fmp)I{HxwMs@z(1q~Ji?;~}Gmov))%J>Artvb;*H)R?$hwWuu_QIL}h)yW8?h5{CA9i z?geD7+G=at{=A@H#hu&Pt${aIoi*orrFyEjV%~Y?d*-=JpSrI&+Eec zgbz%C71~kC{JK*77X=i5X6xPU5fGn?Yhs;yo3*53Vqv1(bJ~xv^?`{~8Nw^UeYuqe zwqie*20YjFX~kQwAf_jdKo}eMlH5Zl{fyBBiYzad461NDp4c!^VxA&Gc4EOtU@EI$ z5Zhn<=u=yc9iKT_?r~}&Nm4yEaO$iVX*(tmtale^yr~)D-k}l&aOO9+M8c>UBDe{V zBF8Z7bf1fMhrR7%ozB`ebY?PQUZlPE=a|bmZE!XEZmx(ycPM_l!fY9!X;6dgorq16 zc3CfrR+2qSn|q0CDIiQU9e?Mh+~(dd!l)QkCjfxd|Bh;v7G-E2i4-Vcm5tC|MA;x1 z$}$$$g>m!-UjhIS7N98gC_D<F5)>4%Y%okH!6<0T*-_VsTa?k(k(+|%4Mr${T}10pr%OA+uvj1jqUXB7 zN;vmX71RhC4W6l@K=Pu1KZfOaAWjQ#!jjb6KDXqos*LpC$<5A{7^p|Q09Mv!6p=SFy=Ih zf@5riTvK2)5P=bvE``%U02F}6?uvo|GVV$aNv!G+W(TrJ1?Tg#Ic}07}zcS`K zhkW?lnESMRgjlU{TCCH>E3AvINZZ4!@t%-+nCChG#6^`lLFK{d6HMG@_XAV-yYs(@ z4!S;$T#H~<<`W&fgRzl|w|~q8J5=4~x)$}A6?Tj>rj{$xrTrXWkO5c_p)!_86Qj7L zozms9sc&!dN@CnAODCz6-T4H=@U&P(ZcN^7mb^J+xSjJPa#mcZqD5wkTGG`oRBJjE zP-k;d;pdQEt2IbYL{8xgy;l%*q&?D#OnBq!>M*DPElW%DUxg86++eH;R20pwjuP;p z)wxnB4;#IEy3Ngy)1W`@VJK8jx4auzof1Y{t(5bm?dZ)WH=pWsA8yU*sNm(1R$L+( zD)Wib@I_;aen-NkO&q@D5-AP=NldHvSSo#D@(4F#H*42AbM%4GT~Z7Fa^* zJ|q&#;?5vX(+moN7)FvEKctd#dzA%lKb1an;wyJ`}8<9`e&WU&5mQ=U(j-BI<}(VYoT7)$^LzuyPKQw!o6uMD0SKEt9WL1Gx3t^}4rD)PUmo1d~Y(E630> zUq4gDubHc+(y3$Sv!=0Kc}q)kGuV3TT8mR63@QArxBRZ+LF&g-M~;xRFPKE%o__77 ziNO00dgK()JaUrTsl(toH#Q811N3kLg&{@*OIU{7E=nX}5X3?3Y#fl>?%eg99UC+r z(5wNV1p>k{5fHvT28F(~C@^xfx}Ad&NWb6@Kz=Gf?bxDGZ@*@eAnWJ%P|aZsG$0c; zr=;uloI;<8eE29D5CdS)t(ajHm1+s$gh>E+T>xN>2mmDwP5k&RE-(~5KED^e)Noh6 zX?*^t64Q7iwS+u?p!g&eT@7i~4DrenbI{YCiN(DD#>5$)0Ede^ zKHdLQ>gcFqnoOTHlUuha!WBQoV0^#U9enX9pq*U{z6XwF9~uw zdNmxP){Fe}8%3FEfBJ(riu=P+@M&NMp)Pdu8Xo}X5|6i~yrM!D$BgzTlna+Vu>e50 zT`fRo06z+d%HR}{8i|2y|j!{h!5|Jsn)Pgw$%02Mw32t?wh zM15D^HOOy0pJdkv5vc%xzcQHPw}^fTHtg}OFZcK)=kkR8gKr~QQ5uPoQ6pfga|G`!?aq< z7+x~P!e=T~cwU0dS6V+YIj04qt3whYKed2*5wMqnGVXaM*>CD3vv*#=;6#?R%M}|p z%*T#UMWb6IrHb5Zk%qxXYWxS%AHeNY83=cP!#2_4v)BNMLZfDJ$<0DI0KhC@d}as4b*_2A^-;g0*)B7BLXIYCop56 zv-n&4g-BP6MIdoOg|j>i+^!?U*x9&SV$Sd7;Z)XM8apO1@qHk*@@#lxH?Rkkz2poA zjqyOnvI_e!P?t*2IfW&*K%ks5gIGr|T)ypm3Ty|Q$OVZIfM#jyV7rOB^TR32X2|7o zc)2t7gE~2IS1L$6k-=H}Xn(}U_uC)L|88gb?+_mUwOD8W|5XYpi7G1oCDr+VpcML7 zbh3XJ>+D~5?0=&a`a4#NwJ4jS;$N~TMa6wxkoiBALW=vksD0^yl8TDb|Bwp(GWahk z5`Jay9~B8{H&?tTdrmNX{v`j&Y>PQ&Xw}YfEiIW%(7<%5C*@qPo98*v>LsP z82VuydYig?dVRE6fIl?&*(isGnZ!%RIiJK&ahemn2Ynd5C(CX^4Cr&U;Rx{>!v~yB zctClThCZmn+Rd)h{XPlJvpqTc@}Bb3ksF;c|x-Sok4B+>J0yKUh+QP;kE91|0v%mYT0#R)0Ne`wdt1p;QWaQP3sIMPb~z| z=Yer=XxHn9s@8Hofag%C)0H3Aa&y0zohBj7rrJz=Tn2XF3kUJV#y z-QdPuibp~4R-eX81E%u^Uv9@%hsn#GyW8qgC-P=%!sT)o=M~M+_U~W9+x^m(!pp7o zBtAyho;3Ruw-9x$~$y)j{I<|34=H)JYc=s{*utrTq(TgyLdyj12jaAyD z9Q|l(Fd?rex3*Spa`*Ow#IHUkO~W6=!f&!iFrCO>^V&Mb_4VUx{|hkLJ2Uz_xpx#& zejK_6w7(o#NX3NQxf-0%i20x}{V7W+{)OyRfq28IXtB#rU+pw@i=4Wxe`Y&uywWe{ z_hh?7@H!~%T)|%2#U+(ZgwVW-_m{b;yrydl+;4Eg7H#=BX3o9jqrGl;o@)%*$v2L7 zA`Cr(f~B-8sMA9L{p&yjbKYZd_ajTb-$u zq0HN7Px^2_twGOS939sR(7fEkTXF4k9aHi70SED|^_NRt_n|lbRb4?M*|2MY+TXOp z+R4s#n-+Ruu<91YkCrs?3jaa$tryd!!i|z0j~_ZBjnybmxzt1dbXLXFk8-y-d>tUY zkZ^taUd>=@h7!=Q-tc+uSy$u2sj95p8^%hf#(xiZSB+oDFt!RuSf5NBZ}Kdwwd)!@ zUnQ@@4ttS_Dn0QsS@19|Rag28rGEYCRe5@5E@NY~tNRc?k`?19?T;nZx&qm+>pQuYG@?J&a$;p*qTx;|cbQgXCEVbvLw?<(d#Gic_cneC`Y3$u?cUYu>bQc`)9rur;X}N^>MFR!qMlg zgz$3H)lGw2TMDH=EzLtLx;(ZrjgLJNAt}^lyf$Nb+SiyX+?D3_%9Rff|6SIhq`vO% z(FbZ>&Bzg_wl7mQynSyw4~9n8SH#;LhhG_nyBJ%49`ejDwiNe{3CE+cF&2jWQ@GYUu>3144gRIO=3)kb7mPA9$1S%{_6*!R8 z>pqG`UsmRwoW0_OIL^u))xG_xT|U@o=1=>aFZL_8&*v>%H1Ybex@S)gjOBd16Q}LN zUYC=hw9|O|xLyAQ=HL^zXxRsUn8W!d6sG=^NY9G5?D;Ot$?LE9?s>xXBNoz}Uo)hN zBr~!EkLo(jq_f|5#~7vKrP|=>-qTs^E*l?>v33{s_7YfC(gI$E$QW^rct-ImdR(F% zMZIcCS-s2jx!lOGqtw#x*#=< zOS+eMqqSA75pQZLsJUnqBAnysnxK8my(+fp)EAQ^k-Oo4D$BfdO|Lz8akjXDIU~Xv zHK|DNI%2a`G5*Aq{yF#h!tdAax0Rgn&RG9E>G5OvG6jaX|F*R;OCf`)>jTjsh|B%@ z=5d2R68xI@Mc)NlZDtH|yXbo}m2bqJ#uygLK0Lh<{fa)F66^V(b$;1hKift|jamCd z@kY&j}m{jEu`C%VnIl^_{B2( zO)q2Y;wjX~w1atW`Dw)sa)`|l|-{!h>g{( zce7f)fnADN9ABGZap9EwvPACNKVL6@?R1>lY;XEu5FfH5df3U#{|vGJh{PB?Qp5Wp z=5dL5#!Sk2>#xffmkZB{TD_EuH@_FKS6Rn@-~m1IJP?iITY2VRU0|DX&}MgG*$tmO z>tI`jw4SC8pUKuM9+scW`tB|{laMoNZXNw6pRY@6{x8FIeHd&G`8W zcUwq&hr4!TJ#ve$lN4+$E#F4D)SvQ|zyCDfo%H+p4|m?CeE3qwbk^(om8W}8r^PSo zKIxeLtzOnjtRI!z_G!@faJq)dREhMOu}?{7&64c!gL2c?ZUM>YIA{25mP%+^Ge^@6 z+EF=+XTwZI{LD6Yr|OPV#b4+3R1Wd23w5q-95D8N7h#P48hxw(%Ep~TU4wE&X(xX3 z!PHStJ3-LqXX?dIin1M%$o`LcceqM0b<1hKv_-T&oS zYoEFC@|ytgc5{>MrF#{R)%pW?g)rQ7bouw;-KEsfawE1x>9m19%;}=&H+rugspAKR z1EZ(6_Ndpl0uK1Zla&>mk{|T54CYuI0ub4$smJcUZiK z;l>k6Ogze8dMB(7EgBSi#F4N3K}ko!z7i}|6pCAnxxJM>ve+8y-$Ry6`HAsI4Y+jw z4$C{FI|v(koOsP&g8vXRT}FrYvBw4TN1P>o08x2o$mr%JqmdH%TVXa6_=C=`xKy{= z8duUymf}1&FqwqTDsIzzGbY3((Sen zDhuO}j^?*#NjV)iSqLok`Td0Uqt^$;Za)rv`dj|#30A|g2Z912Z4I^wcZ&h9f}|On zW5;5C*V-JP50#A{J8ToEpN}M%xZ$qoMVEWqeY`q*_w?xIfsLnp(qpIY z6xyjoW#87rMe)hhKlHGB!&6)sQXX5^AgZUd6`>E%Uxo#aXe3o zhg&=3qvT;PF7;ZI&1+|F+?wM5<1ORPfkw_d<`Rm^1?Zosr&9&TCC?o7 zprgcJbFSjYV+qgyZ29=-4Y3e<`=9)SE|0v9 z>skn`q|7xPA9YXn8tmOJEb#Zof2udw(J>MiR9dvEjk0i|y;`j~^+T-4>p}7>uR388E7)U80+o9q8oNM@i+NNNhO)B&oSantG#jEgVKs|Wo~a< zPk^+<1@=3C8dLARKKe(v#OxlrtD@wT10UwwVW7M2aLmNL*=u5}@bobj2RTg{!%Jpu zZ8K+I&{ZJwW=W-9my+U!6w}fy?9R8eugVIZ64Vgmu+%04 zCsO7;mWhm32&IS?2}x95#?3E?YvNfn!V`>Jm9o2~H#!eBh!J#o{6z2dZ7H|J(J+x3 zTut@{(ZgNU7j6XIQ)dd_F`ctn<4S5LgxWp(mShvv-tMHBSJ5Z&E#V8DC2`PQ)8fVH zR2%-Rns+Gv-zpyr#w0(PFIu|#+O2zyP)z#+{_K^&;_IsmYB%oWQmQJNqE2Spqge_g zz6TDDGUKgNZs2-~9$`2G3JxDW^`2f3thIBgS8_@1fY8k^TNkz)3_~UfKkOiqN!nY} z!M1c?>?LjWmDtMcky~wB!-{r?$0SziJq1s${njNQS~#j#m~G`1WHOxOdTsfwOnK9A z%$*zG=Vd8utgf>^CVvlSoz{4o!HYh?`ddu8q}#ul>?`hjwCqn9m6iW7i~QRSWG`gaxjr?bm{L)WhKpX=IHRnGsvplerDR902|Td{uC z{=U~=u24pzGJlEU{k^;&i2f?;KM}Skf6(@2@6^567~i4qt&kbl+0&?_WuJ*zK*{ks z&uDpNIFAP<^y~>@7Vh+{V_NUJT&YQ!6fLLO60GovW4ulKYk=_yme*O~RNOveuJ zvi@*9C@XnS>7qC1*#EpBkGLBt_{sj$#pjtM*zq0LHwms%N(r3t(Lu*7Gnj+}@=taa zi0s{9M(Rh=3V0$7U@+JZ2koBqdlT;)9nbKI06G?HW8Jfe2Qip4(jFBB%Du_PyO})icB4nv~tmJ2qEwJCBibM^o#~IC~RZ zB^Dysbx+@)LWiecrC0J{>jP!F=PIMuL$d z6vpiOjgKjK^;S){-^*>yivVONlf%WnN@LuFP0?+`N zfu01Xv>`pg)U=C&Q7Ax!5KB=1y_PW-5mHD;xMMd7_xxxGjdsYOA`w6%el76hxav$o zAO(;z+2Upp;kL~aqJMT%@he2Wa8P{nb=qRV2Lx!KBhfUPaW^0mTU?wB1OWO$!q1>Y z>eMg|G*wj)p?%%8o59`@BG~DjnL$%W?mdFFH!PrciQ?ZQ-<^#CV1|wEgWF&_EB_-Y zCbzkXq-YH&UB2jFHn0Pho?_z&?y%cDfb?hlVV zup5u4U3@@%`;6|12ZWs|Ev;O0&<$`DECB!#WGm1~hTivlr;P%r_Et-E1_&qC$41e+rY(w3$z5V&daJk9nN*jh-U`}rjw9Cc4cTEK-%>I4G;k6 zc29uaCKAFS|xYlGB|mQKJep`(4mK(-$&Wxxx#84Vs8$)h5Z$r(rQrFdPDQouB$>`C__?{-kca9Yj;k$gH)3(vlu^nw=nP{x z75IXU9P4*y&Msj+8jEnn#6&cS6x#FJI80GpBVJv+OZIYwc$-gwdsQX|lPCfhbm_FG znp%99s_AyZ4_Jitew4P`pg{{7(nF%#<(c1y?D3i%5^-j4Othwc<3YA>@n+#W&r7HB>?@m5q*6! z+MLGtxwoo%#n=BYmfpji?Zu7ze@>5T)Jp78D^^>SYLrq{5wl{iTB+6A>)1-ZC5TP6 zYE+HdN>uHYBPgmP1kos|(Uzv66hS1P=Q_{t_dnd%eO>o;zuvERY!l}FpW~8GnquMD zocB{{Gxs;&{SWRgXDfz91fCCfv?9@OK^3d8Gey_$-(P$6;Li-04;)bPpo~Y3XY?j9 zpo*?#-E!Ao^1jyx&Qt>##9%-J_&tXM%K%^lo^CVBds7m+NWdXDg3vph{5um;?K9iXd8j(l43(>5^n*J?BI(^phkiE~`n4r2jvYYy?U#BftV9=sZ6OxARqfgOP zI;?efgt@1>bthJ4H3KNt1K2}o_V92e%Ztj8*qiu%4uEDbh8T=pfaRQ|&aV7U-dbSN z;xragPZ&!88$hG80AS)|oqY^r11GAnqlhbs+;Zo3fNh)ydJrPzyk~X?aF7Dh7`X$U z2LHuz0E_{E9%79B8uYxGcjc1X7Y*v_L-ZbX{D69(ZostjVf_YPJ(BY`#-D1Vrezuc zJitCp0(ums8G8~(xekdL#raAGH~@bfM(Sw;fKI_g+NQ)o7n5BH8~}$00N@F*nH}2( zk*gl7>~6-lKZmSgxDRuuYuHFfQ)EIeE@J@wE0W7wO7+()3>9fh-Pz8#!$LO>2ZJsnV8bI6BxAD4Zyaa5MqnGgXd^X+{ z_b~5Bp_%1y^xvb-*v#v%pP3etH1ZmWM*q%&5ZO-)W;C*IJp45e{v)3A z#q&D%J)7XLH|M9}x6{4&IRkdNQ!m1yP{Uv@kh`70q|JpRyRU&~)AnxN%l=`Rm+v#y zVVNh-5ia-d^)og3r8_>;3L~NNskRrc@w_!PhUiRzvDo~AN!|vzI^S!m88={Ocyd<% z1|c*u3Vl%plnbe58^2yid}>0be2Iy>IbHgTBGn=MpLgR@-4hWIc>jpOwwRGQG(`#L zqh(v_I~;CFtxu`&D-I>pVc9YO_lEP@A6QIhWq{-zfdbo;M2d`iBV5D?_GnG1Z0uL) z>NW8r)rd9eVPL`d&S3SS=-V5@N5FA#_MH_tbNvKR)M>qSyNJ8?ruo{J;oo(`@+tK! zP{zKAK@OxDbqCr!x%*aKdM7UhI8511mTAQu@aqn&5j~ke-Q$ws5Ef{_4JCE3m%ls| z2E-4dKHnhk-KI zVZy=cqh3`d2r>UNTk5MZ0jh~C!AUO+!e5?w5MzF5jRP904oh_+=|J1F?%9a2BOIPb zO|v%~RkyPo--u!*y8hfu?RaY;Go?E#&Gfx^l*D;pefPj_B4Omr1u~b6r%n)Ov?b6AyIqg=>v@KN&b2#v!i0^)+egK3@m$sI{*=P8^-rz-mkeb&Z?n z#jenk@q@9WYpM#D^82^)2esrAYV?p5aPhj%N?fJ^ET7I6OWoQo8kNsP4G%cJ zx|iM#jTl*CplJ~~+|F(LTFxy!k z^6jbW^vl<(TlL{~hzD**z-WEP*J5Mj+RTglB*PXi z!3zqcZotTyO^k8(M9$lOw%($|^n||#$hg)h3;ib#%OB;)ew@{4yk6*&=0VZeA34NZ zybz%67X-srm<*bvaQo z$h}gA{9743xK99t(Mf0^^eM2&&WaB&*HhIuGgBZd+Bn(sWgZKp=dilNx3b4ufBJk{0Yw5J@X*9JF6JNj}XQJ}gVA ztA;>o`ij7W95vdU`W?dVRd7T_ z5(ZpP)pAT#Fdu?5f4Ix~7NoR<6vc_%>y){M5eVqcTR+|HT z(jOP-gjDmTa*;k~-2I%Ya#7Y7|CQEU5%AKJ4sH)X#yuaK^EJ!--w(K!Mj4NaY8*@& zn}byciS@5%DtyT4bpvS^#ste&u$z`CKS>!OHVIDs=hg_xQ@x^us%f7F{BMw|o3VI9N_ zYgU51<(dTnhEj-@- z_Qj5ulhz3oWdQ!<`nsoiSOPSGo{*emnp z$3|-g<2N9r;RjnTflUZsSsHoXb*FJ7*Pv=-`EQ?9#b(swPD%i^=nV)8Z~9{Vwel$J z)UH*1-KUS+lbG5=S+i6Uo$3#3rWqa(0#bes+)E$#MT!y5%b$zR}Yea}{uin;d`Z27j#y(TyHg>m{U^$koQ#>^jD0)Q9<{)u6R{1`- z#X)$oad6SSIje5W_^J~I;W~~mIaLDprh~CqY__f)1j4kGg9wd;@a-Y=CXP^BVN-sC zPXbOoSr5^Bw!pCVDugWSoGfzc@KB>$RE?Y4k3TD4QTzh6^1TnL8Hdd}{e><)GnU9c z+Pz?KX!qx}_`}6A>fNA=riT6qO{!XuY}xv>Lx{lHi+m8SlW)zBky;7Ifm~kPh83Xs zJNNmE%bE&pdSI7j9v2|Q=U)_Ef_%@^t=g2gTlrRdwqRX)SdaoqzHkdZbAPMc6m9rQ zEKs7$O0BtlL5|x=hS>>xkx`v3`Dpo3=Y#wLZ!LATy1zGam1S_S1h{s^)*nC6GVvb) zYbP#+FLa?FK1%Ao;1=&MniXO1HYnzXj%KmwdZ!&9APyzg0@#ly35%`j>$J&-KOCmu+U6pK~(7uFN(o9zJRAn%q89xEJ!+{1WGU&bmc4{ zVXQ#brOH2xV}-rIWRz0h&J8)U3JflZH$FN$1uv2gELs8B|3SNqdA**kqQGV8)tb7Y zuV!T|2|?A(o_w!7iGFWDqtQfxE$xOq-)Vjy3xkZXc%K@5QNYy4an^?pldA@p%>3ke z2Kk_K2?Qg^ly#BXSb!9oc_kzXlnuzRDZoxx*onk%Kt1X~vI<%ImhsFh%;GFWdQ=9F zcLWkb>EKZpQBMAb0sK#dBr)I8P-7sm2TdMjNCc&S0{Weu1Rt7!HQ<`sq8~<1e`F`) z=0RftJ40EU{)ld#C+N2FG2hzEuD^dmuPAn=Az?e;+&y4~5INT+n->sw+Xx5*;syYN z&9{tUyx!!X?Bl=AHlcN)g(c^2+7}Rl)i)-T${k1H|DA+M8~h6HV7c>d5ruy`QrC#L zOJ26;Ud0k_=F8tU+U0yF5v%sbW%K=g-+N+6*r!+zb5OT2MCeluCm%RHy|Njbm>Dc? z$Y~W$ax3s8Tj>pU2a8_0%s1=iM=9)|eVm4yc5f2+iUX1L@ub3PU78^K4Z5r2u-S3z=!0RELUb1u> zyY0+hHaYyRz@F^h|6UC1ikM>jYOkp3y&WpT+=>YtV5Z0eRJz-+Srd10!J`_UyWoG` z>!-QG)n+tRGGbeJ2F#;N=gZ1wSNf-~mx{1V2ZAQczLXTL@AxoxhZsqLAHJ<^-z^iD ztB|+B_`7Qg_>QD0hj9-5U2PEl;h*!yQpvv{@qqu~Z`!gV`S!O`jVmv7eNdF2JXX@DAMLBgY%=@ zKm$Oxf+pvh7lP+x3^T8#i4rPi%QrT^CAEFA>fCMJXw2>ZY-HrEdmiy(6!Rjf7d?B-@|GR8dpR3Z5K}a z3;$2$NsuQi@ypd7;7bG9u{~|M>jm3FJZF-t(FVV58yyg?4cE2S7{>)2yv}4**&c^#I?%a2~V&`O;FB;1vdeVDz|{ z_&?gbF+)2zrhM6~d7*9{A*xa8a;z7O00DdsSifU;9MK%h8=h}YJ?qPwbM@^V7NEp8 zigN8o3C`hk*-?4i>)~{Kb>fFJPe5t*#6XPkD`Si+%#G?{r9#ico$krwPMscm?nzn8Was$G-{~u52yuqc_+lX7Ch5R!vsn-?%%(*)1^93heQ(184xhXVYs*x%&I}L~exZl#`c8sfyf2^nsej zkWV5{XQudf+j_>>8^>?DhFc_*+W#rEH?jB6*-(}WigAe1ChJ}F(;davwQe;<4VHvwzbPkw*?{H&sl zVdweZSbP3uyC9+OGCMLEZ~B!+usz|Q%!%>R*q|_`ZUPg90_JzYrMRvPYWDe6e5}{C zf~EfDl^hJ&_7znMdLv8BvM3DEbs(us7&2DA^2C)IZBc^WO#4fdb zR<;WhYzPpHR%Eh)gIU^7(Yl@jGy@P?hx%hYuQQ0Y-|%_DcdVLPDac>{%-7KeKp(nz z)9AEz{DI>-5Z1lS7>4cNx}c6V>A|DANXO0fYl1?P=B?EbO%?Z)vwBKE^G;tFPG+Ux zrz8i{bx)<_?4McF(59B_YF1O=1$pbF-E~76q-k882MX7K7{BV>X<+a=pv-aD2MYViP+y|rT>8n!w z4YXp4&B-YA_3bIxTd6fg@G0z}uBIGWTc)wT2a-NR|A&dYiqzD*`rPcAzzggYr>Fde zN$B;w(wzAU`I{dVAmGdyy!PGN=&XmiZ{=@(anC|T=NP-{7u9g)#^-YD`2KUXgupW+ z`{{wArKp@er90IMx(1y~;kdZ$7m$i{qH~C@AJ;UC*f8B!^g0*jZ;iNleA|T?^@bB9 zAmD@`nRRTg=7j5i`UWTwtJz&^XZHX9dH$dIK_U8Gn)h^=9Rvaq$ZG}dDu_QkR6+p< zMC>jaDCQ~yJXS3JI*0d)U_ER(Dwv?Q_Y&k^MG_159I%^t*|H9Zv5Wi!h`$7yGjq7~ z_M>yWX`AJWca!2zB-VMVRQ$^^R%y$JwHaCHk?&0FCjbK?gW9O(k|=lM@-bvo(p9@J zzf$Be$d98lNMre&QhTe(R2qIrRGLBW)&}lmqk*=&yxtKN%m$G@u2z?HOgtpb5L8T{ zV4>iZvVDS#(OAc;^BwP+q%7XvwbT@Iycj^D`@OY$;NfA~Q$>g5MlI{0W^JmvHW)Eo*c_-w+ zD3@V3iGL>Z(gmYqDe6Q1{T<*#|_o@g<8r%->eq!P%$IpM5@# z#;8S$en5TxuBHzf8obiO;{LtXP8I>b+AW+wl8na83Q1P#lz=vibRxD?L=?K5>DLNr zH4E`EE>wf8+rV!dr+Z+Sh%a0fm2i@6tf#_fU!s?eit$p4a6(XYlq9Vva?jTUj8cEG zd6^Nb?rX5)wvhwlX~4zokb}lhVZ)swRLQSDf4&q|ojley8~!fc?Q=n+b&DL=?waV( zQ62N^7I2A}kDubdmR|mhN9pdxfr^Je*bPI>4oR+}YOHLs-p`WU8!sNmT<4mwWkfBc z+TkEO1!*ype~kMFy^;TRHn)B;*}VBRW(lHcH{s=MH?Wa;XD_ry`6W+opD{)JV$gtb z#KR{?Igbje7;UF^hd-MBYN-LOEbt9uoXo_SP|rdFi;7;X;!hWKZ0(rf2B;Y z-*eCAs-XIqaX>y=XUp3lqby0YhFdZ&`TqFYa3@5{=vaV9{p&~sI^NPrr~)IZ){YFl z@!d`Sj1){~{9(qV$FSfofF z+~LI9Y6pLm8JNOxQG6NF2$kIrmYr2%t}N*GRFRY*ThSw!Efg<p=}+{XF^pbk=~c z@rE9EK<$g&@91-b7Bh>=q4SMj25Pscr~*f`Ff`1s-V%OYt|YP+)OzX4DAy^Y#f7yL zYk2Ll-yX*M1_xq_$I&qZ5?jD9&$u^v{a18Bf>Ch*v zSU~RQ>dh;d=vT4vvuHr+>p<9YLjHwhu43={AjCa*+}fqz^RJ#R8nyQu_oC|nw{;e! z3LONfuC1#`1gzAaq;s)OZIXf5XzI#g=fpPt)gAa_W$Z67OeUbQzSU&sH!CR%mq>FG z=#4&(X>lx0ndPeHd?0gh=dtuqh)+BX0A{z6fkOsR{J%#8Kc4gh!=*dUhQlgtV|~%1 zY&e%bZg#+Yi7~#HTeUa&1p7S5SO?E=zDJG*@BtbgJ#K6@`l-#%yp~7gWTTj270C;_ z{-E}!hpQJF$r#iP3OUaf2)@A=UO@`%evUxI`;xV?la^fAT_;^=fW#X9ZJAaI#tye~ zC%PA9wwJv7`>~iIW`^VM5NLR+4Q^-P;Ksp1P+N(Efjrs~%9TzB1@T;j-^$tB{3V=b zle$sK%@MVUJ{Z~=0J=^lwJ8k^BWzWiM}s4 zqyv7Z)=R?W-Jevgr*m6vdNL0|`3(NUr#LE#J-x&+kD6CC76c0@ZA%zMPAu_{IhI8F z)PK&9S=;%N%Ze&_9fxg)o5+Dr`lC~5z)7B)x$Z*jOlE3lNojPF9VcJ=)jVB!EnV%%)mLq1Q&+KX(U}NJU03;urdk!57ye@ z0>afTq0bseA4tAm!2kwAMRra#cHbPiMJBC-f48@==%EW@mLI{n&S-O=!5@X$2UIKm z)4SE6+=tpm_a5iRAqk-Z4H2mgyr5j?WahEhA4Khe5-o1AH#gFOnpKo;ZRdkgQv`CeGLRbg#%xEfl~E6OM=S-McS8P8Juz$o*|21Q3`c8*55P-O!9_%m3F*gV0Y_R z;`I|DVuj+Q%#p}5au3y>f-Jl&FNFrakPqA|u>wEJfE7XN%lJoRhx6cV!k(KuZ)7xrl``Z-!{v##D56y-&% z>ao^y#e40VquDje2d#fz2U|$%9Zcr8SZhLGWb4-c@TH~F&pqAWF9@n=#f1*lw|-09 z{`el9FYvBvvNpyG!~2m$c}~=?XVQ6%1L_g?LxET}HC@>C z9dp&)r7K+!gcFEb+uwmCo+3gL=I#nPg0Q7$3^_}N^2dP(J-E`deoCqLrFp}15)URW z7)7w2$ybs7Ys87yc02j(L)Mgdsm#rawB=I>5T7IP`x;{;iKR%XvzKj!u|gNTl8bhO zPHzxD&eihjp#+`B2S!)*2NAzI;aW!4uji6qI%x`6KwRdY74J~hzIO#aY)O~95#evx z7hm^Ab=>#M#Djat+3~hbld^}@t%FOPjaM-|azY)N{*LyuToP>^LaS@~-p_X2KHcx` zE~#kBx?Sk`>bfp&W>KVcYM@k^l1jPYKXp41u_$OST@nE3Zt>bu*MdAI z@BR&PQOV*HxL>k%ixOR`_IAKh*?8%N&6w4c@x|voX%P$-?QmF~tIy+B%r)KLzoQ4T z0dLdI$+ybvKRHK<E=A&;b8&C8wSg%^6X++|9OBpfPqNqWq< zvQhm2;GctuxjL<{AM6Pn?v8mG>h+@lMoc`Hbj_>!edi$K!MXBBKKVqaQEaIg7@Uq& zV~~H`*T1U7QIJl!Zz_w*cHC3XqVRH>DO4B#j1ZSf_6zUUX&Ed3G@u>S_4KW20&Tws z7{hv`S^FcDbSuZq78v0Tt&4K2V1j`dod>$CWA@Li9)YpIKsGN100Z-Ip91{zHERDYgnM2 zuotq|B4IAz-B5EPh?l%ihMXNV0HP=cv-$4heCGezzCh0FFNu%#h8(3|Z= zT64GSptA^9+Xw0!&W1mHENboN1e`!UQeqzoDY6ck4L?;5XuDp5_ZqX!tM;W-l|UBX z#o#=@pjPSW71ixe<16xODlZ0wPk7m6#lZLU6pvz_k*m^}YqACIN{iUyuO3qa+zHcp zGwR+x!|Ai{v;OJa?7!mbjf*w^O^|*LZDz@#{|Z^0>z)Y6`y=5QX?Z;mGDl>Ea+6R(%Y8Mq*1&I#W$* zL-F%95o+~m^_VG}qoRLaOW_MJe&CPJ>d-Tf z;_t5!FCO(zUO9-r;JbXMSx+$IlLobQ04mH8)thV4u>&ETMwAHd@vy`P5+mfJlvB<5A(cdzH)$(zMKh8D{fxqBK&>VSGj;oD9x- zV_7XxWB_E671#D02|{B#l2buJG|Gg%!3nw@4plPt`t&!(NVxpwAlI{>g6ZjC{5qO= zl-PMG&ALg?f#{zU1SnN9COhP7PT}dMm>#?P3Efk=0xACbpiWk(#9oVXIH@3JXDpP( zQ}J1~z05!2;1q374SJ}7ST=$B)@oL1Bnj<4kJC`&b|F82E}NS+S0 zRR~N~gY<3KM3=D2c> zqkqwK6>}&ffTu%UEY2#8_aZq38IQ9;h(tioqGq=4F9E%V>2?qun}y7FB5_Z_8nyZi`v7#kQxt ztT!wN#eBXK$^8W)<5?<9E>N}hx~s2yH}s;Wx)2Yzb9z$q%RB<%{t(@@{5*~k&;V6N z1~jyym3|z)9;!VxSrG4BRTj9Q7;fEp-ui|p=kS%@CK9KBT|3QoYg@_Zqd zz+>w890a&mnD`ZiI@bljh~rX)iL)RBcd|=U+G}XR5Z1N@IE(ChuF(1VALz35>UDVv zuN)R0MOl6r@+iXX9BZEe25uA$=oDoIEMgSe)qmd!oiE&^Kp-mL1O3GX3)&m5*(E%59=IIw9M-gDcp=(? z;sI&R>MkuWw(sg})ss1CVRlJi3#*ECvQ?Lio^(Uby!BM-A!`cbk{57i=g*0Bj~WfQ zCIgj5RV0f!MaVr2{gy1<=|(nPmp7nHCFglC+~U&XN(OLhAu{V`PF52VYRI3eU$DT7 zP?sljE(etSel#aL)uXDK4K36qb-i0%27ty^SD#Mao3aGX@|HtmZL>#H&H0a^iVqZ1 z700ItLN-lC1^;(<#?>r}DGkNL}=5G1moYPUuyQ@Xpy^c<9({*wQU; zmUS8Y-@`HIDU`-Ijcbk(k%xv`9X@%8bjD&yDQ9<;QN}8%M_!=3R*AckW2X-aRaG%_ zlD2REWcPZ74K=CEJMCVvv=idhFuMH*)%-v~%+s^`mEw(TFCTv+wKv*FZ7*PIoR|== zCln636j1(?Q(yPf__BOOggs&|vzC;-i&xAbr(BkqUDNuG7Et{1g!}V^yD8i9iouh~ z`6*Aggz7c7C{euH;}Y~laW5ilO?{(58+W{lor~u>SqnO%7R0tGEZPIocWh-gsySqj z+VK;6t>{ebzt8Qzeq2qEzSZ-e0-!Lw1QF#XAN^!kEmh}_;n;Bt^4Z}^t-kA_ju51Gq&(%7RIWnPjXH!HlWqI#sSbhMQ%Lo1fYegQ|DY`SF4JU z3v575=Mv~5Jx!VWV7Jz|a-tBN86Y4KASjyZ0P8tk5D{h+9vSmH7YQ5!K)hAc&Rgi+ zu5s}@9~@-oJrtK`@1*i_Du@89u=jro4z?PS@IZlsnNu|W_!1%}wew)l0VOMAvN6`Kb|lL ze#}4O6n3J5UT z*2xI7PPebm>Jt1GFnr-Ozq=Gx3ql;!6o-c+)FPL z8*1D>-ud-Sj!zmKMFP1(M8)L+Ln>~21MN`_o{k9Kw4w-tEjCn2U$v#hy zkgWxeYWe4xV_mEBP1|IyGbkoGK${Xk8B(V$c+vLBsNF?4R3T0am$dVfnrGk4q&?oM z@^51}GSIQ;l`@t~;WkvZ;!9Hc$>*Wi^mk|uV0a;wIn=}ChycLjrZio*y-GhUtQr15AR6^;S5r>!@ z&r4#I*5Tb=S>Ls@To_48-xM4ohRK_8bJfb&V$9<`Ezhdsamzq!p3zPl<>ft}BO-j*v&165G@c@iTkZSpfe3+M^E54~YRCED zA4QSN_PyQiW~BBP$YTy;*)r}FugB!QqO7PLF!pV2lqi4F7rP+NR134+O}PF5?{ags zC?bJq(SIst^6Hvovn=)oeND2p7t2DQ&I^70R&b^2{Wpj1WfXZ$e~~(laZBSV_?WX| zB=rm%vlQPv-dMaIEJz#*JKTycm%M0?;GMHGBkib9{ z>pQy01DS;eg~OzIfAfyFsgjk$t81wi7xf43&2t5tvydv?rr6yD;uixv|npPtVovsmMYrP%V;6GGPrB3zhDOUL3zq)2;g zX5qaZ-Yb=k`^TXow4S8#2+?>^i$%joK|2{z_(G!^qC8#-3NiP0Fc6I(oUcCj0I6#w zLnb3RpFYucxm5^T-LG6=_56C){9fhG^uLu+LYU{UI+<9}I(Jmv(yQO-pX5R<)1N1J zm2B%D2!Z8B9b0|i@V&lDmv6KU9-VjijK>%ro5d%{qZ3fyPydaUIOp&VyRJBVfW3b~ z{MlRziDv`@y*e?bo9hS~`*`?Pkn8zBTHIW(9|9}(D`IkjuXQp=3%}TXpG(HfN~LTs z-tR3CQXVFe7YMv@dPTna=eAl3XH$)%I)i37zMBz1gJsY;j-534wj4&j$QI21iN7>BXH5I*9QCv{dQs3OQAWuhUpv z3c>Fjhpiew_W9QVsE{mC-{C^9T?9xD4P0yw9fSKi3h%WC;fTeBE7-Z9F%xLtK%9ew z+Qg@njSa7oN8GlrT%CKL5*}PLGGcp?&I=!=KY=Q?BUFvDiKCdx3Esag!7&F`?*!q# z%8zqe;7}<+DG95xqO`RS(1m{D+QF{g<#!5W{w9x$zot&UKt4V=?1HQz(-CI2GK2oo z>%vL|pA_AH_f~9~<~rUp>>~$~$^U-tQLWW1E?ox|vB)(i1c^xPf$XDtXBB7AcPpXJ zxn~d9>&_Ooz+Q)M?P>K@$CHP#v zW;LK`Kgjdhh8RgR7=+|1iE336#;ooYONzS3SuEHucn<&3Rkg|_;1tTDB>eJH-Ak}R zTOO-8%zJAp2gQF2l+6toOw0poCz}Y%Tz+!bK*t7o?P^W@6q8yoZC2MudSu1su`>MopMQ2L%$bP3b$VjOM_9E3z@G*yGx)30R=bW zBlKvL)ci36%a z@!(iyKPxY5CldFZK0a77asw%)T6!2_)HuE9pi^1wR`OfvVW`0u;}lA*E+3Q-m;bOw zHELdq?skc|2EEl~?Ly)G``!15S085%Fs2s7CjJ#FhAFs0(E^%cvR& z1ey1>wZh-nC=Hk9jzor*I8rwy1Z9W(BVxGeAcW%rDpfZUbIZ>3A5Hbb9IO4Joi}ki zFI|;QWK&_22_?55m6;f0vlcS>4mY1U;V%pef6a^kq7_rCgiC}P5x9FJ^l++o?*_Ey2;EAI3UMWP_vi&Obt%HEnn*v-7E zu~_q+ehAO7Vu9<$M*rv(`30NJM%6!gJ9$lAKw3vzSbyuF=dt#j!i`bKQb^IsUZ zG1F@rtMY)7T;J|m-=oN^&o16@zx&ChG zC6_^y?iaY^CD!N5tYXt^4xtenJsL`?+QREg?6;Ju-YXTLd~53=ea1dhX}+fRwHSU0 zj$fJW{2clS?ya!w=NEahVar$==p=!rEZ=cl$-F}FijWz(2K}WGSfj=X&Ri+IBZg1~ zdCRkl8qBMCKZ{P6MWgB0+Tm~0-_7b8f9_1Q+&UvckgxKUzmdXE&j| zk7sXxJhOK>{B!8|KG(VPNUBM8W@o4dTLvjSO6>gfS;r(|q3Fco=L&#?Wrr)u&uQ2~ z^v+N2uJS-%+5fNaxgbxr#!r`EV^Qv4i3CJ-24>zPm#Q|h8sb0MqbH`3_BQFv#Td{! z-f*qlMT-S^927?fLY4i3@o@oF1WnLop5a9GRKurGF~j?Bs-37?RJs-#V2bmBC{L~Dt zl(S8V{EfvHBAVD8auDgVM4A<@>SJk}#(<+F2j9*qHuftONLaRq*rdV0(J?>Z&s;&$ z19i)@0WmVsit2zz=XVhR?esWy(sr>mUy+;c47YgFVm`i@Oko)4?YLh7*s~dL3CR-j zrJ-8(8B04c1AJQ~NuGQgFA(8raF`&HvC~F-rR*r#ZY1)2qq6L&+>k5Zuf`IWR1i$u za=afkC_BMC(hjI@(B}mfjpg7t!(4S5#B&Y57dTqMVi0Ay-N zuHlfK0wYCqb?Hr`QR(ILonX9&E*bgCnMuYyjA4`I+sNH&&LNDvyK^c-Fj#Sg`f(Yp z0ot67EGp!OB+w6MLyKB|A-vVTv33Bid6d#x{4?PsXNt$+!2PxNS86{8a7ZKpzR9lv zrtRa!eeOyvQ(0|Z>4}qoy24hG(Cau#m_#Sf?K~n zi5d5`rEN50mXHSgKY!e4v3_6p3uV`-STuFDnss%ZJ$0- zYGz)mP;m?xs+T;k6KmgPO{1`xTg&z5GX`c!&OHq=602seBoM+BSSU-PJ(~#p{gLKe z=bc{W8e$sl4YixOFRVgl4YX=JqWH&O7ntaLS`szTIRe5~6krSN9u)@10#?LM9ytz@ zWp3Vg^s$Ks9O{d^Lf|XnDh@X$4II>jD%FrMcqNMIqU+CAFX7pBPK&~;W$9cPvzV&6 z-f+}TS9|AGFW3%78oAwncGATbnG5G^s=4^X<6`Er?fnqUtTi!Y!3efe#PsQ$4C>#d zGS}X(+BYMEKTHIqp!-_^=(QB4qr=)1Us{t?1$pJpEr8_>6|)pP4=&^I`v3xxe(>RF zaaal(9kWtNS6am<0e1+4ChEq z>TH@aZnR=mrAW*_xmnREV@Q*9SS<8^Q;f4(-z)u z&r9hzh{=IX!~5(|p3gFNwpF%CPHt7id=X)ObUKm1AJbh%jKk(6&a&wzuYGA23zS|P z_MFG#d2X(W6Ne!u=2_!f&cT}k(NphTMZkrX39b$w%ZTlnD$)*%3n>l~oNK8Yb&}v7 zVb_?7PQ`vSbUK&glf`qX-r|!S2)`yw>T>E;-kL95XW}CgKZj=jLu)NOi<6J5wuC!L zL(8HvH{k_5`S^&~le&A4y9OG%K$;&$G`&R#Uc6X}uD8KdYhz}Cs+k|2F;7raOjG)S zh(UPbM<8o=Ps@c7DPAc&%DyqtCbK=CX@c>RTzkPP>Ol)7^gsD~ z-_DY1kTa8MF;m)hYxXx3zMG=@-aU$f^Y4-GxD|6z*6y4zD6V)dP|U_^a-jU~>t^1F*T%qZ73Sux7Iw5tY8P%Mg~x0i|`7!+AGWIzJ>oGI-DAZu2j-+$OU%hUjl1#80bYU z+n4s7uHP(#M}L|n_(WAI$vw21zf!0jwlg1#Wb}zOy?zt)sv-n)VV>WJ1>BFMJouUl zy1@ra@!6VyF_?9smE>P)E~lRiwOdQ01D?KX=uLKK)W0Y}D$H{|xQ2S8b+XGmS~*%H z5x05!^i`)eTHY#MBVVSiYCi#fvDL|s6P9rnn@9)9un}XsSx2g z;i_;o+Dj)N00u2uzCj^40zw`nmcr?@{q6#tfM?r!+8ky6Eq*~_`Vif2lS%`RfXtFR zp9g#+gL>v+(T;kU_c!=9DtK#8JZg^Lq!@YPj#hzYkK<=aOt(6$gsZi^9M>uWF#AnWfHaql0*el2)YD4|PGnUl@ zxaFLo)40Xgatiqmvp1Opps|gyMAINXu>_ex^=0**i9yArS&Q0HzIR{of%rBVx2NNN zZ2T(> zb^q7>{GWBNd#&f)Zzbn>9OpWd7e`*?`&m&3@k7h~++K-Xs=!5Qd6`W|vKaW?~?V@MT5coGQzuDkB_Eb%mvOr-sF>$w+p*=&)ascW-PP~`)YH= z1X5eTJHj_WiCC{NQGU~^H*~ki=(!BtGIhVK%3Yf{T=YlaHxPn#kO_2GPK;xOG1{Qg zPZJzH-t%~ViX)P}8o@SHo}VpI?hOhxlmBqO^<=F@WN5*B6A|CUjIQ$O?L*DAkHJc5 z%G%M@(2zb2Ev!;_eQeY4_XQIOSMsPgBTs<@@hra9fvXD>E4vDBKt-( zH5ts`m)n{&Guq2LDA`kH-Y9#=$X_t2WFv#C(#(9e@jc%+1b^WpJ;oFZFoQo^Z4$gQ zr!(YHI@it(4g8`Hs%tJmjx_zp@OhZch}hqkHF-~X%gt!<))Mhd5E^g*(?>S&>rJNZ z2$~5d2W=F!j4HGY)PYcdd>H*Ip%MXz9Ip<%v~hXZ?e=^ zDP9l9aUz`O=Gs`L60lvANC)1-Y44&wo3e_rG5%Z@Ye**(*fs^xkPCxSv2ATtahQa; z8Fl=u3eOE8bVJ4OnIof;eP`P4v@;xlBV9?~fUoStR zSH>=+;K)NW78aAWrDtD0K3}EyxFS8Z>m)0FQBG6>3!}uJ)Wnvti#O93qFQ;s+p^l-*T>?>^bNOG&?B(csZ_$%NCSza+Si`9GpkQ3 zf+{9}n5{&WuB5$_oO;E|uZXznmfpy)($|9_5r2CJf7>G;?CK1H9^QP*+jglW7*De0 z&sIGiB)VmLR+&J=QzJ2Y_Svcgr&7eNGt1OVixeF|3mVIKp0c-abZKF`g8DSc%&de4Oh&HyOd_B;N zFSH6oZ>9EL?CD9gH*ITLAOiqGtTHP5DFI?iy{A%4>kYYg=C`Kqd&Wf^$(vQFbR!wQ3t-dJLCBffMUg*TB|yR|-+aMV;L1_YD2-#lueq zUeq2mZQZ<{!+~e9$_rjFm35N6 z4i1lGve|=Fbz65^bAi<;dX<{h%*RPb=O3k_sY=a#J1B{JOkJg-7%)NvSgD2jy3yx! ztu4gzY6zMM9zEpsaLYV^#a^+2hS6UeN8^k>(MY(cCn_ShzDt zbLduHR(~O>+YKO{na8+AbNRFP&+U4N{lK+5n+62&Q6Fj$kfAKr zZVixm1QGgq2}kOgk8=8P16s1#lST#}~azav&;X}e|$MD$Q~YcqH> z9$%Bs9fY#t3Pv*$qOU>C>Vpv$85j8Q@E{yzBrYy4z`*NAImSRG*{XbnUtbgh<{rHJ z8vL1!gFI4Vu`H?o13Q4MYB>bc*snJIlIVg!?DAI;FsI~Pz_qE~0CIGe?dK{!PNT-% zn!K;?v~hYZg9PS7W;-Vpp(Oim*637EBuEd3r`(zTp5=FAMT`N{s*W}2ss{61Cf+(# zXXL^}kEz@e)3Qadx`7%V3L1GfC0@^1>o4OfF@2XLE_OQ+#bqI;WtScB$=0%+FX&cL zv>ap3bSGGDqXN^8L?Wvi1d!5S`0FATU`RSog0i$-_;qcY25U;!+X`O){8C#m!}Kn5 z1@2X3pvpuScgDqLFc1c*`^s*E6RS;9vlc9#N8 zU;V5%9FxAp81Uh?yllfuzlw|dbWF@rfW3pet

&qA&h+P72F*K)}O2zERj@x2~xZ z#DHZ`S7_&EkdZap*-*R8n=n(s&%CesDCF;LqA4I{d%0!q}1%wi2s1?UE+hKUl_+G|iM8_MB%7VqI@;g%&hESQK7{RR!omX7JB|I`ez zNU=;X6nQ~{POpQNuX6De#aPu5eif~GqJh8f&zam$gy&rw_o?HS-0V~;RngRAP^y{g zSW}KDt|bPdY>Ek(;067e*cec+#AHV{2vSX6ew%-o$-a&iV}EWq=$}}D6>BSu(gxh~ zj>(=q?($-)a`rOs?Juq;#^77!kdsEz$E*T$sn-~N!NCs=N0}Fb| zcRHI5`+7^}7^MtY55QsK5*%Fzutx;j5U&TBsP*S=T@WQbkI!Kvp#1cW`5A0~7BlN! zvV7k}qG?dxwN9L4cLP_5z84yyZ+aD6=H38YF+tWh7>c{wq02ViP-PI;EIwKodb?7F zeD>D6`!kp~ok#^(b?0787TeQLGsK^z77cTG?DCKSrx29RDtJ)V(Ujb*|2&;X>=8U` zyUn#curVif*;fyVEMrjCiH1OZucHYReFEc9`ST9LuG?~rCeV_VFM&N*s}i+L9==?% zn(B0LvSZ{HKdxNd!IiG`f^z;Uf;PHDTd5s|IANPZl`L>byNg13QSn^DX-yLkU3~AW ztMv-Mi+H#mLag6EZW;oTdCSflMi_JhbaP-|u>mxj?Pbv3>VEuLym&~MQNG_7NewT6 zOxNWK1@BGDGG&DaegVfU0ZaF48Z{dorRgFw4F!0-C%tY&&DY^)p;`;7cHTh0tHOye zcX37r!QpBfv%kIF=!DcD1N9`PCamo&gZ|`IX>av%)(^c1wrO7b}i2dvqn$eDp8v2iDrNvD)LKec`e&v+?O~49B^%p z1PkrG!mYlD-fxLT`(ur~1D`+V?~4QWKE8M@E{VGoYDjvm;>chK5DYH{sIIOJF(cq! zmLi@FT>IE=sFE(RAFRCj@vx)(?w%+H3?}cE={)y0^Ews}-WMz1JeveF@JE8R&LiL8 z+C5x31MDa1q@~Z?4v<fFj?ZfUe zk8HAn1l{M^g+zkqwAJvFYkJ@LC1zQ;lvIn0svWGjk@`!Vb4*JgO~eqimm@b-Arcn% z?qn-k4|y+T!l85Cnq6-AK|u3R?t>^&pZ|DM=ZySn|M8@}TWcVd5{ggEx9&r^H@nq@ zpDF%W-j3c}2+Cd2blt+jiJqUYTei-Q-&69tuZa$*bS37lN>JB;U=9-8p*5|#yEjGe z4QDTnq!UlbU991nBddCCwA&o7RT`BVkVwxvT0+ksFYVM8*^xG8&C0E&cNwnx2L*-$ zX5wgrU}EZRzPsXJfJiH^O`%tXhT3y}T(ojREQEJGeW(uNl>ugVmV{pG3$XCy@^Qi* zc~noohGH^jU=Qea`Ij3#T8$j~O0_+2{K0H~DmgJBDrRbS$M9W9x$2CMMISl;^_ocx8!&b0Y6u?`3t&N*S;5qNL zI^~HNx*bmMqz?dqBl(P&(fP#GMTvR1cVv9oC56MH_FRB&_*wo}`nR%6^19PAQWUK= zaR7q9Vno*kCi`6qc5}DFm7;ZrKsj$@^>4y~qpn9%OWy#3anX>Ooo$%zcS9wunTKx5 znqY+d;gQ4}=th+^AQL1JC0^3!&B$Zq>d)>9L-8UV!`s|dEm5*PCGh|-E9UC+z$L0H z>(D*u6N_Y+X3W$xkNjy*?S@)DU}^aZiDpcI2hZNEpEAax+OW3Z(}llf-VEMVki8Zo za`trdW)8dYIW;nv(fj@OfdtI>)J@=u{F8GB`Ve-3OP_|l@(z*6$tA@)-L0#}XPMFk z;A$}4?ua2X+Czx_j=EWCrzG3G%ZSV0iZ(Xbr!P0?Z+v8AhCq}BFJ1sof0AUm+MR0a z@>9BmL|kH-+%42&a4J*wXzxBel{Ab&SXfXu{ik7^ zmon~VGx@u@M|_>qh%(o2^BfEY{|WlnpZ`;wvD$y~mH*F}lB$~Mf6+iT-cf#G(W1&X zek(tAqHGFwe)q#;qI~@R$r?5a4~rK4oy}}%C#rly_|?>&nDkViT?qHGE-)^~&aeEvD4X{h%-KNVF`WtD%r{oi9s z%K!BIe_=}h?Z*CROzGbnf2Ujj8&mq{u*xd`xm1teAJ^|Um6d;A;lH2M6|eud80`NB zVJR2|hD7^Ci7FU{ct`ue{CvWF{X`Wk{KD=<2Z;Vt;D3+7e(Jm&wrs+csPPqk=jM1O zJ1q5s)|MLYkjWKIlIve_mWnU zWEc{aPv$im2th+{-{^Q~yo;4}nzOsM_bIF#ZQhch>88*N&nlqPBca06bHjVFN&|~m zUPMPPdCL3ClIB%g=YpvTb@98O)Qf+#&J!abF_hQi+AOf<%RkVI!#BKwF8QG5?#&P2 zD(_(5C(#~s4c1JLkH6+AN-N6ik+mb5CENq2iT<$RR; z`^)EyM{$?kh)&fD~CGH=6hQeKZe`h@Q8*2tEyno5^ST%Y&*do|;?$T9VG(MagD|zs4naQ421$xT&$>1RypR~5& z^Cus2?l$SqrbGj>&5gprY|qTr%@!4DZ=&PZwX#(<_47FSl~bdV&7SPM3d)fdkJwvQ z@|O9wajwYHU&x}UIR3;xdq(c#m#7AtXH9BMxp+fFolvHemD*n~khd`P(!`rzRWSEC zhg>|S1&Vn^wG$=Tw&v`!BkyoD%CD1Woy)Z7@os2mcDl7^F7G|ZQ9KW`$lkrF%M7FZ4vNfgUw2pg zR3vEE9}b_)vR%|EUomxfm8WZLwSqC9Kv^I}S4nwNuiUQBZ*ApGYc#<1vu@Tq)&_-~ zcN)uj@VM;@|ErNO>N%=niGsiAv$BaTn@^dgGM}Q^hCj9?g}8E-zrXc^_KRuMx2Q;x zlGt>s;%*E7Rm)e3IF+7{@1LyBMBuD?A1w&HPk8dlD<`DDhec)hWm?LOn}wkj_q$FJ z>JK5qM_&YFW5* zQ#r)zXuUtOc{$KxN-S6gmm#ElrMoSutgi4r>KD81%Y*b@Z^XSLvHZ!#xXhk>>jt~$ z32eyAoLrl!sSM`^aZ1P;YsNGIMrV}#jAnPUFFj3~yky8w@$?tQ33UbRC>B?}suMEw zMtX6JM`$(hl}9&Eu98Yr-;K|jpEw2vOkT0pF`}QB`KYG67wPoD#@NR=E4(rs7%z6; zH6|Y?O8Y1=xK^u1Y$ya_Zn5}A++=*`qv0v8STP`wIJy|G^(=Y*EkWM)==EDUsk$$J zUdbUJ&b1iJ2wFa+IxEwnQ?AAeWXP(WFg_>H^R4fKqvU5cECk>G<*8LgH9XcYlzlY) zq9UKSh`(N>y5F_y*4ICuYVQuqu8GB^)Q`8-c(i`vv#o8kE_IiUNhL(%!q8d{cl@8i zwz!}Hx#wH5 z9>?bS`Tg4S%M(PK9~reQ!s5LTZr!-;FnWqn3W|}(zMeG??7uQO8@KUNs&MUTo#i+z zw8u4ER$pi;t3Ivdxzac153u|7KOWrCo^A0@*@SH=ayf?h+gd)s?kXre&8gMO+qv~U zspjg)$S>cHORIlq&9U#UUqvdpbV=rNA6%RW*nxR!R0y$XRDLe9V-=|UX3-+HW)K_aKXs#4=cY3xtXj?=Y{yQ!`Baoe0e*5 zR==8VxaT%3ssJt!nm8{s?#ArgyzIiC7PuYr{#b_luZG9WJt>8d7R@xy99r>(}9yfevkB&Uj~vpoVeA;o@V=k9k+69JUv#`X7&ZEui4BsX3i}C z`Fy*7BFR3DV{(jH!=*w%{44F@X7uze7DZ`b;QVFn#G$cCFAq#rHI`j%G2RM?W4^Q2t7}XP|2k%u@T@*-3WhcJkeG zFG|HMon6sY4zr7+%tBSdic#&kce=Kn1uPTZ&j_g8+r~cE2)Nejs(x=u+VVBxx`8^dbu3Zq`>!GUmA=C z727)uQ9g^V6@u2OQ`5Y2n4eh)u|Ka!DPM{JYJA>Q412|ENlge1-BQ!mFG>;$3a56W zH(2hEGG{}XRfR8d`uVZ7YUFlKJJhB`1HaA+$Jc~?ulGW zw59d)g^7bdwschFxT}&j#|_if3I3ydgO+IBnk_JUhG}5V4&7A~l$&*ybgUnbGBqrf1Cpt{Oe`5~uUh zcJHa_Wo}NCR#@?6qZe&I@xh^?Z|T=yl^W@d;lFHDc{u#u90i&J4-N%T6; z@Upu6+ona|Lgp{QV5aWngP+6S9UxL}?r0s>eaRqD4x3^>!zeUm{+Z-M`~C6$&_WMJaNo$jfXx=f>* zCZW)z;H$XX!Z6bv{K($D&^;%alDAtcdS&KlQZSx;a*KPhbHq{47A9Zm&aEgjCUw(JH{^+tmb3w+Hq|RsV zd29afRJA2DzclkwP?UQ4Rw=AT2CLzR#zpLtj{zF*xRyT5Hp4Tddt&CiY{yLjxtzVw zw5QHbhJP-=H$w)|WZgd)|Mjoy_ACF>Z-@V)K>xeV^6%;O_pJJVwpsqyJbphq%FjEL zjoIWMn?=b{@n8D?yUkMf-)$D#ir@#|Eu@^h0UV+zs6?+15*bFBku?QnV{Je zoCAHM14NZHZYcl%V6!M)SN~n-pW^?YHp}l`{|B3;j3vKdG}Z|gF?<>M-Cfb$H`drU z!a&kM`GVh1N!u!Vtb{)-4F*}S+|$46oxHc-sUh^?Q6&fC_#qe!=Jb#7$hohhKQd|z z28$%=#?GEDrMwaeVl?6Qut@lul3jPldo#uh2e9a2sJ{eCSdU-DwflC zLT>UpEtlxAg#~#sA*QU`fp80$9s^_;4xAw1KzA-Mm;NpiY$ zdN;7_(eC*cPTX;>N-^dIev8%L;s5|R08Rj)7vDmerE%lU6XC#}tUU!fy_-Bs4O_Hx z^V+3_(>3P?IDT6n)HVPB;JYV801lk(<;N}C=d1%FhvvX)B0!-J0B{2j063smFA={7 zpCxci0BdnfdxVR?vB;gwHv>NJK&#_#uz;TYTlsJX054k1FZldO z*%c~|p3+XH;D@NBbiyXvuU;bXQ_{`Fn?g{Co8K;VdIdT4M^@)`;5 zb+81)l2!p=z1w_;-V0wFG+-l=TZl>YqF71RYL?usQX=xQv=x`nR)v_F61|M@F8#sKu=1ji4fdU(m#7$&CH)99$p}Zd4QLorZfGlym2DGTX(IUTAXM zPU&FM4=a&x*QWEg^O^Ga#gJza+RcF-^{cDLw5X8oUuBo3PFl|1V(I9W3ZAWVpsIp8 z7k&n|&{%ibvsf(N+jFGt_6>-x2LC;}buj>-4J`3$0vZZe#J_$&hrqf+KPdLrjt_lk zXrp~*Qlu7o*PAVo;gfntVM`jh)U)3g@GffJ#_%U5nepMX!mjz9ZkhF(jcWA%TBpxe z&dtBhH0}&rz2mxJR23swi8mInkH3P6~l2 zDUE#@h43MlT+nWIVHw8Bg;57!{g-FK(!10PY%50eRea-vDan8V+nb-jgj6i(! z@sJ2#lcAkfNfMvw0H`~Vz@1(Cbn*-u51b5Afjv(EPTZkq47FLrom`I(qd5b#q!-W6 zdIPe7;LS8Nk+w;ISVtt>P6zM+9d}l>^%y?41JF1~^1H`#tfEv3ns@+9z-JBs4Zz&8 zo+lwS&s;PItWSuL7vYb4dXD&L;Gcd8 zd|ophz}o_>QM-Q!VeXQLTxh`N4LC4>1;LEE=P${7Q`zag-@M3p+8~q`jkOL&Az-is z@+GQJA{+oH@6rJpjy|Wnn5jnDKUf*K@TinN0G!=TIavyho#?_^%phQsIC++%Zm&b^ zkOFR}g+kmtsnYe_d#ew1HykeL^)i2;OHKIlmIka3dgyGc&LA@uAU7{2w*$pgDhVKy z$y7XfiTgFoqBpsu>Sc$p~P58Cw*BT0+I5o%@gqZ`3(#{?X&oEJVg1A zdSln358zwAjNxIKyJC6#VxyV76V^XJfO$k1pQL_{m}D$4JXBV^m^`(e za~Gd?Q#mho>t4&73rU)PD+EBizb9z$`Er3^+R8S;nqND+ghSzIWM+YHV&$Fwz=jk2 z)RY<#{lh&ePY*$C28v;dfO*n->n@F07xr1}v?6GSNZlpH0VMkE?REz$o<`i?sxgp& z9QHN%(Aoj?9{SWz5C#_sKGuFG3|xaBavXxeLe0Q$J*j_g6*07C#UeS%2bg%c^K3nB?{Jb-sVc9{g}YQrf*MT1Ei zgns-jg4UOuC;C6cNjMU!YInRhCW+j|uP-ltGS`m}fH@Jc`t#y$u?SZJGK=L&#bcG0 zFw2bC7G&4an?l|?UApVHt3ebkQ}^yWoTWTz#C0``1{OOkJLK>pSGeIq#44xzzN`M5 z59g%Tgmx+(C^|k zO=Ebm^CtkF;W5FRbJLprAttHOwjB5-R~8eV+CUXN`L%7^Ss38pur_?HT@f6E0sLD zDSQl^flkNlWH!Yn1SHzPFOGNq6Qw*83&e9`c+SoL^?|P?>36D*XS&rFxbl?{k)8duBE`m&ZjA_^SRn)A}F^@tV$&MIm7u4IL#|Y*K z*pvR4T(2C-Du+3%;2Ki#loJimG$khd;B4Rwn(-x5ocI%FZbLLdDYKq~+W783REn0v z=Ff{bkF?$1hQ|E}5p6iuXE~isR*PkKEDUJlh?A)N>{W0Dpd38B95kvCCdc@=TCJy^ z=_--rjqV=QB08wG5Tbbeg=_sH-QYf`Nh(WBQtewHo;0Tvx4T}G65T7}){&A+=|~0| zgqD&>9T>N4)oY@|AfV?_P%(_HnU&A#Rdfz!m>U7n^{Q{J3zOblw05&va`nzozdg+P z@-OE;tS%p~ux9YB;Xs==7Y;T!2G21j2j>(L7sTX-UpIl9KMM^$O4S5&^@-){A^7#m znNx0vaLgp?I+U~N42if4K>j$dxXvYd?=RTGy5o7L{1`)xHqjX*5-|&#X#cx)dBZtf zUU|&+Z;59ehf=&fFN)-Z3VE>;i21sVD<))J}g3XT?z%pWtZsJTUOnb#pOX ziZksN(mv(h5T|O*iJ)1?<^+V>0VJ$n$6?egXCq2oULyw%Y-fZ>r6?Y<*D_48pWqWe zr3>p=7OB$HwOFbbtW)5W;6+MVM1gIXNrVHR@47zk!3Y_SO*6idTfDq6aI6tZq_#{r z^>VPYm|dG}ce_3$Na*4%_4?83IupDU6Y2Jp&tjzRHf1;O)^Ns^^(HGOUVk1@d_ZDm z8@d&B-rD7a0K%cf#IYqpsOJMBTzf2TT7pTc4-b1(6D7ZT^vp@5Z-E zI*j%*mDdX&g`KH#ijA=FmVJ$iAp5<+ATSqI(t_jUhix=suWlUAU6+!50pQxE&yiaP zEYp!SLACW2D#7<&y2h<<3?x}3{h;*Ysj+%-X`s1`#hRBgJVP6`2S7)dvvR!&gVln* zUyAkFb1y2qVFMzjDo{ZQ_1Jm(4foTF~s&hZ_? zuxONt27(iQTnR02z?ygftJ^Bpt%LDmyLvT&P2wOiU}%VV47}2B)D4WMkY>BDw0jE9 zaiQh3sYUFOSsmM8 z=dowNT)77XllaIZ2}3=v_}9+T8@N$21F0|(M>nR$vMg=q=7xry0jrIfd0L_Hc%kBs zda2Ve2w9}uwX|%VU>96;ICdVtaq#iW58hIJbAhF%8ergWzsF!^ec2{`!|uV=Q&yXf zQLFbL3)RU|3Z3q@J=t%qTb9-BQd1kmt*2-;6Icflmg)C@9LrfI0CK87)u6AMcGhUs z?9^J+1g?ovJEal*ZROpcHM}Rr?9-T%z0ZRT>fU)SFF8keGcsE&%6bCbkzi#OX50By z&A3gZP+`0PkBY)2)!C%pV%_z(kV_ZRSko{M2hW?rTL)Av8HDzUt1Nq;@Bj!Yo`eZ% z2xgr(Px!XRKchxDM*pG^hJ^_Vm`fX1dp zUsOR&G?A(NB9oY{VNBl+XUI;WGipHs01w_ z{@3Qh?2k?PzAlC5HzkEEnZsFtq@lEVvSs)Wj-XW(x41r!5J-)>nZE21DjYe&R8^kV z-SzlqH_{{o#xLd#!coGtm@yk4Kd{Wmnam)@(|uHEQfEaZdAF9N)I{|EV<-JL8%lq3H$epM6?Ox7wNOSb7<>OjrWx ze1XB222>O1xJb{vifgg^UopnMc|DwOaS{Pn*asQQd7OngJZHQH5lu@Cs47N%kLLUw zK`$&8bRF3>%m|w7;QZAN{q}+qJ%oT6R_fpHSmcG=cNnjZNjD+b%G=zPan!#cdS_=P zrLz^F)CR*=4;-y6aY^_ZQ$eP}yW$LyrFSuym=IhE0Kg4`Pwd}?LVRAe7v6QPZPa^Z z$9Ja&(bip#5$h^od^|O%hbY9-LhT93vY&+19=wR_7Z=$tda&_S?XIs4VsAs*?s9=W zyf!)9X*<{xYXn>OP%C+C`=K2`?2bqze}y6%GBcL+WP)UUESrgKkA5Mi|E$o2n#ExIhj61JrQ^7(;yueO1&xdD=Cr6S?*|Twf~}pYkIY~YX--Rf z`97V=W064ZA#}_avp#zqwcShlU43@~c~?OFcE%s)Sbqe?qPFvxB2FuBvne|3u{ov0 zlI!10SgPV?tpVZalBC%^$pu%j>sPoSjLGJkg@osN!~j*6xtxX89A75WT(9}f>N(os z&U`Q7kz4*gomKrY7tod*qA!mr_)76)cy8ew^aRW^>y)2Z;VdH zgC7^nBmqm0_FifcpfFC+nY5-anY#6@B+o)lL>NO;Jt%{lL_r>h$?TP8LF*el& zo?M~Etxb|C5tAA71#zZ{IzUJNda@sTsXo-D6l$tF8-`Ea^-g6UWU=6c$$U2_0`?bx ztXwd+r1v@2XYs8kRIHoVNB1`ALa+G`Gw^Oa8IUcF_`sS8S_dBbbk9!n^~J%_DyN=4 z45}Y&ECePxeQ^7O=elpr#qEaMo~{L?PqWHogYJ9hQ2SLBYEs}20^@5+?pE!Z+Tr#B z(G)zr7LqX3ob0#3%*C3G!{Y@Ll_HmG^v>-zyuG5W1JEh#O|6+PAFY(#^zLFiKVRTP z3NyKlIbJ>Yj=s?0iq;g zo;JR=e$i?lGXmlllWnaAN`$Q*>++WS+j0&0Z@>n24mtM9xAMVYZqdlb$Dn%%$Sy%w zJSo&kOhhVoGUQf4xJPO_DyQ)KB=ND_&SXZP7RxbIIja~Ldm6Lqwb~1K zj2&W`T3ZJK0ySzm)?0^!f@7Dw6%nvF{2h4p*ih`8}RCa0w1vJ!f$HkR37&ZjIOBVzpp$}aTQdr5<0$v(%D)+cq59+hk$MT4< zSc0C`Ni!R8A6L6t&UCZyHJqxe#tsb{N!r|b#(i@y2tU66IZR93(2u1_YSr|WG(_O5 z@uE5@<@%>}MsAQmE1$1Y0Kct?R(njg0eU8_GN+x=z-GtdV2LUGT#*;}qMeN5lWN%x z-oJ;I&>Wgc(f>P0|0$Da^#i}_*RBY<*+zWaRSbKb!5}ZQQp*{MV{cKb-c@3|2=?b)}Nxm2t zEcI*%lH#=d-jvyIzyBC8s!15KoY?>1%ijE1_wSo|&7F}+Zy!o|{LMhr>!8ewEy-rN z#>3lowBU|tGO4DHUwHagf1uE>N_r-y zFo8#O)>Ow$mHDKXpq}hhmUV4as|yQ)K}%I@Np&CIk45sPDD~Zzo*J8t*@t|z<(8D^ zBv6x(M&5b-9Ok%R!B7gU7R(sST&StGyb`pK$QT2QHsIU_>+b&AeD+!_np0KoyyZi1 zq$<4M{j9X-psIDv=fin^YZ1D^z1Gv2cyII|G0xYv`sug!9XxHD->tfJmPvuN59Ah2 zFnJE9Qix<)J0o9M5wt6{JMM~qWc#n)?(mpCiVe+dW6&fy1658YlLr+MiQc{THF})G zpsB&OFV}NN4b@LTW0=pY2;y>(j9W|mNv&4vA z%RsTL2-6f0=F1C7( zre8mp*MM=Z%w&c!SQ6q|gv%`z{h?xvU|dLrm~a{<8fg6@)ZKi!m#xZJ# zDn3TA_JXDa7N0;wMig@zeD}9bEQ@1sKf6`Z9_Eh*z+hp5OTn>5Y|VlR^k8k!XdCD% zmv2BJObnBjELLl=iHwl-0@gqkS;JbVa@_S5@Qj9zrghckGEfMk;Y`Q$RmK!C=-j|^ zGx?^x(ZIy){O>>6A(jwqT0|N!#(5tr64bUK*|$9&05ZuG085*UHb|Jw`2M**BTGL` zpJk(uJwS-g-4s3MO9Vyk(tnQi)BS5vBbkA6SMo%?ZGf=9cLxmuQ`ZT%znHsOeUYJe z@4jvD@+9Qr;1Ou~z7E7>*DY^TR=~6RixOWutKa;Ug$c_qP`9!JOiwrNR~#*3FqdO< z1Ab|AveV)j#gn+JPSq4frw>(~cQX*s;Q5%GH#+nyu_Y-g_if(sk0Cs8s&UJvmUH55 ziD=L8%g|qXlg7lFsa*>a-aVni*)j}JtP};lp55$?wjvV&BH+){QC{fVX{iNEH-+Zi zqHGSQ*BdjXDW*`naW`ilXkDm{?BQmJZ2~{~;hzj%yqpp1sS@Y0ov2V~wXKVXIMpU(&0VmTr=g@uO<7KyR51RS-^$-wg;jZ8E&rNj^^lHl) z`Go4OOR;LI)jBt-s*c?8xXRSwxZ?asDMcC6g-%}9za|ZPR%+CT#5Qj~(Rv{I z4BIuM2vg5|XcKF6{eGY3m9{4JA0Men+?G42MO4|?K14I|Y)`IU?)no>Z-Mvx3rHj~ z<0QtnO3%zy8jz=Mlv?bFlLM3KrfL-GncJ zxjQSf^c=OZ7UTx>#_?Hxk-vk{w=@r-?ALiS$SSO?9)@)*=+QOV+oDrzg8svDvP8=t z@z|?GSKOG2M^d~>t5&`V8#?HC9$o0|krGiBZOmL*&Q|gp>yB|FVsFPV_8S1?n7G=T z$e)%VB+0A28+UwUyN^ctRh$h@r2&~&)R)M5;5opqzc`HZv&V*59FDR^f17xlwKoU) zIp3i?5f49tun6~{-pzC$3)Ia+^%_ zafy3HrBP3%Y+o}Qq7yG-$q5*ed{2w|jmsed>Bf4F=y(gOhymsnc;ye7VO0Ibg8o{q zadRYF#fcA;70bI_ROc27g z78mbO$f0~eA4GJ*O7iR&yDEnW;I5FO)ou3Ay+d(zuC3Os4CuL~nqc8X3i<;&K)$sHUN0nE|e!ZH&@;WasS`K+%+*hDTF#>rz ztrTXWwD|e!aA5Cys+T8BtaaCQ4R^w?SDSh$H^N*By_a9$R3P47SuZI_?aj5Ow&XoC z_O{q(Za3(s{0eR^h>=^8vd^lI))KgBT1g<`pk-4m4L-THBr_*9sITcGS#FYQ6 zMYJzwRG12fYM6&q#sGyr7K$ksc2{Sgc!koB(RlEYxE4!Lw-*tlQF7@QdeTSrXTc-U zsq=c<;xC5w!il}JYqNnnB}DrL?$Ti7&6JD?gDA zY-nI6=oCEg6p2kqXjp0(e};95iiCZY|5!t(bv=st+v)gKr`XAWi0#mo6N!YBVjU*h zvEENw>pB@vo%(ifb0+MK#^mkS3?=lT5@GK-jMx#@rne6_(7GJakDfgPs4?*)2#nwl zE-x1XOQNLnoiUREV#o8%VKEu%pnqaKf`(tpG}WC`G$jQNEXVFaK(Z zGK2I$H%J5EwfpIVUxtqs2^0-mJ!!KKH=k&L?tE*p*pBxgB~k6df`&O?GjjSSGM2^W zi(33WK+R>qI$TYtH(<%YdYw?bZCURDjfq5Gi(CcgcLM;>{^F6}MoAE7XzI3*6iX;j ze~Euk!*&1dbpkMG17v$)tc2G{uWFvljSL36!%x}+18%6hQ9;nTeQTMei8)2&%!^1a z;w;eKRlWe_X3=7qtnvC57`jY-WdTjm|0oY$;B0&n_2m3b>EVD+xPzt5O)OI_*X@FA zRfSvg8i=;ay}Xn!kUmf2CGKufn7|EGt10@p#KSfll{PSNaHpxa(6>FBdG4Y<=UqsE z-)An)N`I8WCuPfL1rk$QC66HytJnS??(RIOiLG4}{`n^GXg;daR4z0f{200 zB$I-oAjAkL0U0-wOnHR>5oA_C1{q{V2r82xWD`I@Q6m9@AVdb0DFl%aNJ!Q#_c^D| zx%Zy>PThaM=dV@O{nYAO{dCu=)wOJr2*Ug5evZd>pCv)-?SWQRxtYy=&W zVlGto?%<&LKr&d~ga-0lmJU})6Et6(Ew~%5TAnPSeFt17~aYeJ% zT~_#A+N4RE#`iY0h(G^yNQ4j8GE|7u7iHJDTwz-$sZ}2hNa1Dv{tC}Ye##$@_vSEJ zvA8i7m4O((~woOVN*SqsD z?bwxC!x0h5%b-p$m)N2rhLX)}15ZcuvUOdre)KvspFabs)oL*d{X&CthOE$wR z`I{W;XQNP5b)Ws<`)jllk00O5sHe3}W`}AZ5yP95dvUi8Z%1n9A~05vewcu zTh+(V6Vmt~MJHgBYC817$vhJ+anmcid2r_sRZT+tS4!9+Q+s?GFEajnjGp=N2EoP# z$H=&ZX7a5dJhWNXF5uJNwSz)GJw`Q9iW+!7lM!JwMU!~{G^F5##`|0MeW-c9iA}de z@92ciK3gzPznfT`78aG}$!>UE_Oc3g$$M&8!g0hwxcu~9`4%P1>u1{TdKQ%;NEIMOK z2?NtBYj#`CUkZ|iIvbMW&6et_Gc5deWH26NIxUv!(C&jt^BBNQyM*(20BNeRHt3%p z;ukL{8Nq*$;YJw=r!cTC&}nsiO&E{gNYQ=zHSdS7J>J6ZXOwUyC%i;NWf;g$mP_BH z+T3sI*BHXgW%?ggJvMs&taUR8rDKaE-Hnr=KK_V6 z*e!g3a=s@8_;wE-z@R4ul* z76m!pok~{ynqnN^WR5`XSzB2zOuQ23VH^t?f1`a#Z0EDDlSyA(ya%OT+1mBMr6a+K zLYalgQ~tR6S#r1)svNnhtqLu`2)Sz?$Nb?~W)=4J-S>O548hJTT`{iiO2Lkcg-sZ3 z=h*3LA6rscec0*oEhy%s7{s=T64o}>P<~MAE%FItp!OI%_tXb47NGQY0BCA8f zaO`a)ULH&S&>F>kgD!ay;H!;g_)F|r=kkodVD(-KoKaj1W5=3^ z`(1rg+%=M=Z`z{HHRl-cIk**j?4qLVkO7!5DQOrKYnKdyI0a z4k341h8$BU7gr+@l!GsKLEL%;Eq&Hqd^rYl=hs+$BWz*40c*pAzzpxY5NryA z!5|2cu?sb{Q`*oqGvyZ&>BhZr++fM)mWyZH&drE-?Rf5-nBuZDSORvAu_~+S6{q#v zF`s}a{$-MEboWMJnlU#~E!z5}dF2$-6M(9sFVm7S1igdMxr4%`{sC)Ez>QlMC1QL5 zumM7b)m)Oa5UAAQpCpmWtMgCZKDS;?ah|s9+IOMxI@XlIcIP@HrqSaP{V0Pg6-%y; zNTogJ{gd3{Zyva*N@Q(8q`h35O-74gjd<)&UZs2DEhV`F0>mmPMz;W_6t$q=AX0Qs z+OW9?GW0xqlI$AmubXeCmduL_zp4~O(R~_L@uWal?KzCyXo*ITXNd&|lVJe+^^@2B ziix37XQQ%XeJ~ZXgXVs`sweWddzU=1y#i!=c`WUXq((rrfaQfsk?em$ifbW`Qo04u z!C4=zg!8wL=e(7kGwR9tL({RtUy${>a8eb2Naq;XT! zm{ei9n8}5lo!;xtiONo&K`$`w8rGjngkf~sM5OP{u9Ol?1F+;^>{9wBm@9U*`{9M} zHLt%>Khv$SkMCgVTG3F&aO%(Owd!wt6!ucwRx@@zFT#AUsG$ps7go1+*!;t2lYx3)WZRB`?BR1|Fmu83GSkaB z!C&+3oOVBUt=T^RMRfQ4#!R-D`hcX|=@G9@ix`+CY!A}Nmlq@+|t5IT(GsVdJ=9qp88w4 zS(Bw|X7KO|Rm1aZ{g>T{OWJdGN%3{o({*+3e_U`jQ&Zh?g#|jkMLA?0dR&3q|0FnG z^~ds&fy88N(>;W|SI?EAhlf?^Rh_hXyL~CKPi_=wVl?M65eYsTljxbQr^nyUe_o0< z*)-XnqybSu4Au5Q5Pop1_aP6)9W#DTRI+*ih=Ir8+0@Iw3zOYOZ8l)t2ZOjwV)N#ACy;=}Q6(s)Ci5?aA zUI%8bWw&eWOi!xiTpFO+N7?{h7Oa!kQm*#u!0N>GUNOZqs_u`7Rq6h=!KdVX zJeIw<&>V9`XZ=YrFKO&1K>sp|=734m+EjFxYvNUE1*1Qe7ucx3{JF`h|BYm)t(Msd z61{#nrJEa=%!R8h;iy8@GqXm>`+`0u4K9(D19lx^6vB-}i|*VXUiUZOklh2p69u6% ze$5fl>X%~qhAR^~7-O^dEtwWB=#i@3Yas$*Ycz9bIPJB%D0%x7)r~;7KbaJ#qxeAX zh1!o>s=UiTysuvFLmWeR+unzpC+~lx)yco7@@W4dM?A{L*+$Lkd(?9u!!*%qp3l;e zDz|6P7Mpoxep5M~r)u|v!2Ut0lDwKz(I*wGsi!7{|J5{2Ig3z!sUVT&G`KiZ^2%_? zl_bUP5eh&bzy0~yIReIQzQxX52q7PsW!b_IP_3#|w$<*zk!Dl8%<+`OOki7m09uxd zl)aI(PB4+Dx@=hm5$>#H?|jxy97-2LC_ciB@rW%gL6rM_RU11=npe*ML?vkYtBz;F zO=33;T)J>C@Py|;vT1p0^~ZHp+Dsl;n8+0s7BIa304W$6*g2=WC2ye<0rW|UFxaRL zuXk#eR?WqOoZvkVMI=Y=t6h#l;xus)K;Y|`zHFG@ir>qB=1-ZB_7 z_I_OJO5eQF`SG?pnLv3Qbn;nk+w@RsvS+d?w177?^J~KvOIM4lzu5fEl(uQN^`tv` ze1#z{K!2(R($=oB!j zQ+W+x=%#!JGj9S}NP*&I)m#jl=@ArqaRk@P2=0= zQLhBGLtSoL$7la=5D=3@s1s)@W)|eJ)#m5LO=7*8vTK#c4qcrMz5R_^%}b6viul&K zc!L2+YU4bq`BSW`Ix6Xf!E7flG8LPeye4TK7~6HYWPv-Kf7y-1Z#IgUx^EJ%=oqom zA1`3e!$ub9SkwH_UvocVstUsnH0yfDm@YX2hEpp{*sR}PrOMp2qM@~EPF5p9V4+MY z4OUxquiWIH+?8Mz)KOLGdx#zr{i_wKduu0LAm;_GMG*>Cg|EW)4l_TzT~H_&H($Ok z`yi*nUbQZ&*5E8pU=VXBL+JV^1=Jn0iVrB^e#|7q@v5K5nIHS@-iNiIR7G8V8i_}4 zL6B8ex6#fEuaKsUmFZ3SsGi>aa2KdlZ6fl=1XhpzO!dkXo0mb4ugVcJvC*jU-F&ve zU-I|khQ1k>8`v9Efk!4%moTO{9Lbm3Of}Q=z1xtK;M_sQZS(K&m=_5I!a1@CarmPj zV<00y#AB9sC3QgK>!#9V1di8`-Orxpot2|_5%Lx`E5{nl^%=hm1ITK+#j}lV#KdO# z(RQ$JraQEK$s}T=o`{#V({+8epkLE^P7M-$JQ8wFT)x9DV;m1o66{igp2;H@hB#Mt07g-_BWEN=j zl}lkxW@ES7wyDohg;#E0ti#p2Zrt%=_@9F2av)I5KEDOV8Tr(}!Ykcm+Yj(h_QX&k z(?+;i=(!z2`!NlX1HmItOln?rY&iL^)UoT~_Z|jRzbxKimc|k*02hK9x@^58b#`r%uO_95JBP3?8lKQzF>bWp)Sb)!+=}&Wcv= zmi3yBa*xVK{1qViXM$G9qBVzi*>~wVA62PQ@3QSG2>d3v9f9T#JY=R^6lj1YGIMdO zU)aq7+muA2wT?u%(bo%|$5*gbC6hUx4(r+1J{K*b0}oIJq>2%6RXn-x-NV5#&9(Yj zwjY*_orKBjSwx*sndb@I6KF^v!-6OTjNVN(l)Uj{0kVMQ8k6I;gZxe7kZ=9M8o(4X zHlb$N^#YibT!8=;nLmAmS5bZbws%3g-NURaQt2PdzgwLN8a4m((#|PF($XOb-$aQM z8bgE2KJlAgvBLY$lcYszGOl1t2XE#@klb+^WQ=4Bbko$PCFJN*_gsbgKL;QeLKe<3 z#rKcid;F*Uz4#GIJ5kVs5;RS8OnH#g(Wpa5dzC!-$=(OK5Uh)zGdIHLC<#miCOfS(SAiLH3bT{nvwzL!Yi+5}<^(ghelpoi5d+ zuj(UnihGJqrYD>lvT+j$TpqT4KE{mWkHqpC`bUCcXJ4FDds*?Pl<3t(*Rb&%P2&{N>Hfgj=mg zE(M4lewOBncLca8G%w~R{afeYt&Ib62CH!RKk??Dit8?IK(l0|#im{?yR8RS*@i_| zgY7^c$DrD(C;9HwbF5TmbdAFtDZFbM!4eR4a=36;p(cVWx8Bf%rA+4(^Om`x25!u_ zLhMpqo-ifwV1xT^VVga5>8`<<`{zO!?*^j-{cm(9<2t*QOd-bg`=7&DO+|6?D>S;J zdswy0ru1J$#!*x4LRNdz&QbVIEUOg^qEC{uQ=oUDq6 zO;1A9Z7;{?#7MWYtZ7z;s!{}89_9~GNbb@nsr^>+p=L&{Iw3RdDnV40;I+3l(uJ?h z1QYND5t;`mzFkhWp3Ce_5l$XN&*Hm~puL;|;vNmVOrfMXfrc2=qq?cFWPieg!UB0g z?<^vBC3InCut-(q#=UsKaAB3%6?C7r4}zf&n7>jak)`Aa>&FS7*t~jcW;d;aUQZvK z9SSijD!TQ?GXa~Oh+DcbcdLd%{>;r7}Io5@;O z-P`vlgCkILULyXh{b7edJzefO-%O65)Y zx(UJwnq{rLIOUsmi7U3_Z!<}=@Bazs+YO`}QVc_sZRnjRhS;=&|XUH5@M-r<6s~!nH4zM5=BoH zqT$IQGrpmRwQofXn*`>b4iq`HV<5b^>|h>M=jTj_(ov6eaEtdF&COlelAh-Bh`bf& zQKOe$vR9Mhg-!|`LM~i#<29t#z4>@!@}Oxc-@`+p+UykVP4Uf8)OSN&DHSWn_$a807L$Kbi+FP_22aRM_2QVc0D%nNcn4 z4q4~oEs1VfhY8fGj$@IEzmpjvoZvOBJYv^c-^-lN_^dkWL|vhbFwUrCs`xtuxnfeD z*I}H@G@T9)Uq#{z9TPGb>Rp#Ot@+5R#A;YCGUxU&4nBTW8(w-0uK*K-psclhEcuU4 zl-|5ggdky1x4JHUZ$p~^{9v<|{XncP)#X{+aqRjE{^LH>2`h|}tp>x^DoTi%w9CTFi z*xDqM6l0Ngjffn1#dv+|U^Bfb0dn#0el|XuDg-xgN6*}n zex`HRTPi)n-jG!;={V`zU1Dd-S*9g!hqJb3CWi*>nimT@jF0ri`f;)JO0HYi(un7} zwLra2rLh^a{tI?0X{6ch5pGOtYm>X5beU#%p#P%d!?6d2<@FGihsK>-+Q{$uW=B=~ zZ2$FQG0kGb%(QfP@2Okirj*M#TTN`AxeYY?#o;|<+?aTqm3nKP&rSF-sb`~Uo`{sl zPjcnj0xDy{BG3ng88eUkeI09uUeF-V2!z#f^Iki|O5;qyRyOL~lohm2K<=QffI?co zU@V>|!m0ShvhK}uyBbS$i>tA2x$X|O2QlEnP`h>%5cSObrMhfJc{GC8wRmi#t#^N) zTE4m1Nb*p6ggdVx&43%pZIfak#`y>M?P)}I>Kbop4R*=`t-?CP+8V?--N@OA;jeAi z8L^W%IWY$slV4Uy(8t%`OPvCZh8M zw~izHa9^79dm{%XMu&S%ESlVLomMq=R}}zUH2|a0oEU?sw0-jO36tRo(SSbPc5}&q zd6{tG)H0rj@@zB{yL4na7EJq4oXyv}W%cLjT@*cvhc7h3thbq>n{Y@Q zZ@FBrE=nQ2wWG1$JbAu`NBPz@*`AV|ENwW%*ps<{3&ud2lB5c=c8^x$nj59x6*jbY ziM?-WTUG=LpfKi5FooYCUbq--JWp)Zo>E7HW46mGa4O~d4FnQXM!Mtd@6>@aTK54v4 z{C*{aX}Y45bAq%aGI{B+78h>SyMA7LGOjg6s<0coq*AtT15;(Fij2R3_puf<4YT1A zZx)0@`$O}ltjy2#Kr*DVqr*h?HGck(<6$QIRF$6T)))rc-F%uEC!&jQy9QVH?J5r_ z*HQ6FNpM`Hw5yP@r9F~SrFewA*f<$FR9O3jUNXF65YZRD;8}VjcTr)xP4_&AY5pgj z)wMCWn808TpmYB0o6FuSfU1$3I99;KeOKBD?6uQh(jn2}B#~9qm6jLtQs%xKaU;9M z?Hc>mwF==Bb_>gfrf$6v-RB{l?D`~Bg<{i*B}@qh-Ch!*=tR4U*AMKfggth-wTG6f^d1L46vF?gb|A08SwTX781N+E1^ zGOHp4&U{4PDwOJl!E%Des?m1jAgWUh9KL!~GY2QF{oznU>8Or0mGEffjrrg`6MtKy z%$Jx|Nr+w#9`2p3ruw9((+m!Sbo}MsCiw!fGRdZg1lUP^4}~6{tom#^UDS@c^oKLm zJDtRbV)lh+HW$BBMz5@1Z7ILvAt}1RD&O415Xn=M()^64#aYw{5dR zS?m|)4ydwvpA&w|EQkIbuRWU$+Z4NnE7=89oU@B`;81r~7a3wa^KoyZi?mFa+wSGE zhQ&jV5?Yhvx_W3DKm8M5)}W@#=rSrfRg}%sBEJ&^X1W=% zue|jvY($%qBq6%RczMy2dTHoJ46n8Q#?qbBvSoXHE-Eu;!=`nn11)0fJ8`X6iV_l9 z-v7Y+9R4XJBs_Ksf=G>JVVSON@prYE!lVSEyu!CyJranhM! zC|O~>Smb1HuNvPGWzBF5pXuyp*eN(N*59?UZ*%P}v?QnL;&EUOfG#GRKg?QGx3`qC zUX<3-+>-RWKp!@0$iV93BAgh}H_6Ii7L7g#sps(lpM;xM9pQy@LQ8aW3mG~&I9#Xj zR(&#Be#9R^2BcozcJ&+}ipX3s(2U$FAo`Yw?&JTAdwI4ijuD(4UPMrsuA9UrCJ4y& z#Bcq^9AZb-u>Sgf?oM`s&?Ymrq+tL88BY`su*azF=O&!T84v;?15m%V{ai?jiw^{D zwg<#onJ#W!I*BBln>FD^g2souy`&bFdu#*IpBR2rr=QX?DMH8cp&{bPA8 zc*|f;x*4u^#}xy~fWEyG?0&(!^`8Pb0KR29{RID8@V#2g_I05DjcnM-5)TI8vCmUI zQAgv80D#?h9%o%$g&{`6xz}HBd^}G-x^2?kIcbw{(M|5wBZEwaUTMC`)DkUims|mf~2RBKo}Xxu4Z^I#_J*&rXGoh1UJ1Yr7s#6Vk2@Q zMqf&BWE8RBbtzcc7?w$Q@ud^uNCIU`hOSQHGh}DfzqY0X=WduydfM=IC1ShUKKZ&W zGZ+$MJ-oK(0=+n@Khib#R_&I`TzqNmGJzO2*QWtFCGy}XMfvEU_5~5?=?kYzU01DM zx#5V_={dsZ2*=~0oHdEN;&*Rf!iku1uPZHS%P`5mela^Drlx{!&b@wlUnY=2j(FUn zoz|J`On2;>sZ8fqw7t3w1HX<&)TrD_Zk;*K*(*efV^<#C+@tKj@o*|y){O}Q2t~>= ziQTjB&Pl*ihzu)jK(JNFHT0j7f`)&#m^@ZhcVK2mOH`nZxZhRqlc3P*S?JC4NA+u` z+vXLzTDOorS8?3j`0@KDj0|h@Xk6$>bVQ3#9NY0KvaPo_`%p())Lt5c@vv=;Rp+** zU~4`-jZdDfr)xVzw%LfASr)fFc2?TBG8bM|S*9{Wj+?vRIaNiuM7e&V#=Q+GNUuS- zIm$EYqnW@Nl{Ay5_T_2--5iPD+TRuzpPPPcw`igc_qDcrX1$Xui%bY?El@p`+SbUU zU*Oji?W>G+y~7K?PsBs;cJ9L>dQre(SD-}jd7r3&+=x; z@E>s^`jvq>%JaweDHyUl0&?YLxZ7Ivty&!8tm_`q>k|-+F}l|0@czCdrM{9=6I$@2 zI9a4Yn{&boWIBJeSp*`QU)<})pRC&MNt1|(2!#e1Z_%$T%;eD%r>5eGjKH>oGe*@U zuVsY*v#SxrHa@5>OFdU9|8ZRlQ^&!=2tiQ726%jf@e7GGIa z@$75csXLOacv2Iphs!`u{v#nOLFDyJ5mtG_pSz_}-YTLxcHUlCj9Fl$ikr%BU-i@}Llr~4 z(<<&NqW^!?Z1q+2PW~Gw`~R-lo;>+Cn)`ogw*O_s{(H^#@5JAu|68*?`EMw%-pPOC zfB%bSdlK>QH%b2#;y*Flzt8^O#9L-{P9Kq{NaYp3i%^ zm!Up~%jG|$u_Ew`QN{P0XG z1f`{&(MbJ#w$uJ!Z!O@lhprwH^~sg9>Xe#(>t^e?GZm&Ad43P(jp!4tQSG6T0qOgY zr%Doc=`SiqKiqiuP79SE&Y!9NfRvYtd-?uAOzwNTucG+@ug1^&&RYy|w||&>&x?nD zxrH;i-l1DYywJg44kGC3BBG72cn@?auKeOh)g2kTSutJNaJnnvlsWZz?Z;yErWb;f z>%TU|qy9Sjy}-ss&0763W2Wxz%le%o#(s6CVfsp(PQ*SNUNK>h)Fm>J( z&ZoWmWrWT}znq;Or0QUwG)i-3EGeOrVh1;Zo7T>dBP7o|cs&HMTDx=Wy^(rW4%Jej z5`B)@YBSAfQ+#6;$sCAV*jJJxH9p73jTvOc&q8Zdwu+NoPXEg{|4Iq2fqA2 zf_8tW|DT1az3@%%#_Qt zg&Ti9KbIAZTR8e~WkJI-Pyw{LB2Hj`1PsnW`%cK`u{G8ImF=63Iq}WOjI#df0>3OS z^QX5FMtFWa$HE+)A$=#C0l@UaH7QkCekhkGE}jy}0YQOkeFz$9!AaFxW5Mui!cW~~ z(Eq4K`2eNpy(O4qBDbpnAgk3hb;WhKjDf92YsmosV1Q3b`i`3!_paj?GPhUS(3PaA z?zRng`B+CL07O7w;pl)p^}EU2*-v6MG6C;P>aCw71dcJ9-a+KQa;PEjX%SVr=n+*k z8~gLX@k0OzOjhoQ5e9rv8~nl<+I` zLWuzG(}@diEObL8d+W8|%ND!tc9&gDG#2-6ti$ipF`gNk57GZgs#;Ai?TG*$Csz2` zJOCy;0AP|_!PVHYE2A6yPF8BehAC@>|8@^-d4#k=@dIEE9vm&!-H}BBycnzTa4#IL zlkVyPwtE_9&M`X^{prjIu4r6+Uq(!Y2EB{VKakXQbsLQ@+=d%*iAi@=5=!PftYh2& z_zG5VbP(4_2Rt{x-wpr~GYx0fz?IZz!nFbXtsbFncM0sT=(|7+gj=fF?lo=Ag z(IQb42etseF5&+EK78(;gTRlPoBh_d= z0Kn}s;QgMh5$R~KBO?R0*3LB}4=HoD;U@iwjqJ~f%JQ-3GCH4hj>HC8s=rg%G&I=7 zp+|my6KB!+L~t~&D{i?9bOEp(6G7hsE}gUWkpL{=*r|>6F=0XN(IkfuqGsCn3io_9 zTdXf}#1{_=;^4`aa>dl%1dIUil>sSf7(Gsm~A_eX%CnFZEL`SpcAM!As1I0UUe5IXYwa1L9S3 zlRu8c+p@)>Pmb`qOI$T(#Wy^`E{*~`01j~HKqDCEfV_{&d=e8B@B*1UT-7BokXN#@ zn^-uQ4XU}Ix9=(u%?B+Yw%Tv{@rOlMV%+cH)ai;zDW~L`qbUK$5T_(>o@uo5lALqV z`eTTD#qG(U_MGf}jil2GyCDXJF);f%)fzCUJinWA9}au^vSVKAMwvef6{6nPxL@yD zL9t-)lQcX8pYJt)Qjc|ZjcO-+tZ&?2`Ab{Kbagy@u<568LnBQhbk~Jz1o}*Vv_Y`iL7Kvc-0t zQtbo}AgFd{Gz9}r3w(HG{Y7n0*?@ER%`Q)!rQ;`#Pra}#P`P*ax5x8Ve zN!sI}zf{Pokq_caOW#>VpBc)+s=Cjk`3h|#0pI#xc~0iUwAo>K(@T?n)iq{ve^s;_ zVFYn!k~!pU$JYiLMv6U7L(>`yfzXK?nRb*UcOmn1?h5~-K43WEGka36;g_<2ySs2hTdAznUOOHV> zBB=Jq6`)kJ53oHaQ8(s~W*qy{9KO=t@s;@}#<*3yA+XvI?s`+CLo@5Iy8fnjBRNAB zcJIP{{KE^rV3#J4Rga6}AP5~kAd!Bueon{4jdas_QA|Fq-TMi1?Y?o2Vm^P&gG=JA z<-TGAvkqI+l`_|_oQSi#6LyC>fFXQvM)U+S=d_}sgPoz*2kQ++d2rW7g9s2vVi6l; zlmm&IR=74cn#drHHw1P9UKiFK!LHbF*y>vG{;)dAzZ&O}8k=vN;gzfseAFo;Cy z76gk5)>hx-rOwS0e1ane4UyH#MR|aGy?^C0;Fka})X_LcDi@=);Nm8u>gde5PBeX! zizeAcFaesTu#)p_{dTw<;d0B16I5Fjs&KEZHg4+(|M-!cd43bCotw51TX{RA>8|QG z?MUF8=SQ@pq^t7|I@ht>@5?Na`fI)Ju_+ z2UT&7!{}qn=X;(_gzN+hZLAXzR5Pj>wS~HIVw2MiSZ$=|I8{ia)V_P?2>%wC%U8Cs zGX?BeB44dD4KWtz{OOM{(xmsIkMYBW01s)T^55DmDk5ln^mofD7=FxM!k5(NSO$ZQ zHCR|IX{d(zc*TS%?^byC=%R3hB&m!Ccaeh|-BAJ%I_PHY%2&%cAVTT6DHEv!n(if_({uwJ7Eu(huOW`Y7jsqj% zIKcp(Q7xDqUic`Mf9u#48r_a5zbj*_?chL1cekVsZ~(1*o<+rN2;BDc27rs^VB!kw zH&|N|fU?3TUBHcACGAdcZP7oo8UF5fHaOG%0q5ABo@s>Gn9F|jE-r_D|8}cfutE!xuWqWz9u8OQv#?;LnO{1TWW8vZap<#>!FF-98Nlp^}HnqxC zYf8{AO9;;FG!~uih3Ms7;)As5;*=*7%V_tuoX1UWn0_hzHc-oWar?OPh9?~z%}%97X1qQSxxKL#@2`11e8fMi zGyDEiD+5h&UQ|6+8!XBII{1E*OGBeUWBoXZFT+ReT}dYiUmS~Tptf9hj-#R3fW^bn z_+U4j1JGa+fX3zf1FrI5Osvkd?)ybwuwYEzD&}{SRsfaj&?^M|s+LVc{we|QXlUFo z3pe(hay=pQq69{0C(zH%~&?f8kthU60@D(nC7q>&miwgQb@zMLDRZFMOT#1+JzTdlr8A_Mx zEk#{IMTwQo`ud+1CZpG zKdUU{1~u?us3QY_R|)9V{MLdJvZ(I49zov+``zOOp(kyZZ#yF|wSam4f!K1-rVEZO z(go59NW9#4$y8gFo`=WiGuB2?5f2+ZhHjQ&u<5ly(S4#+Xx9CRSI z#VtSDOw2Ct05V<)4T1(2^uS`QGFj5xarfG30F02G~j(N}xfm;_Y(E=dC3-;0qr zu3fZaH^=Y@|kw}wu}QBjs|c`wSZ0ckpTBzNG5&!`stX;&*rrOmF;0saaSrv zY*oS~L6-rE8++C;P3#x!lYvjs;Q&%B)p+igsSTUT0=UJqbo=>~aq;7O{LMrjqXy?l zY0=ze5{O#Dtz6xh)v&3c9u~8W<#0GmHX6)-s(Bmp;W>C?$HvPdDSxBibkg_Eb04oH zK;#~0i*;|7aMN&{UFWDvM+cij^J4u~!=X0_?dCtF7UClHT6lk?f|c(~cNY&L%@sYLz_bH24W_?- zH`SrzopyN>=`1}LfSrV+Cj~2?D!mKU=ak4Sk*d9>+w~|mS}I@Kj;+dTtisKcw(V6@ z%rkzMST5ku-?*9*!LCjqV5e4l%?d6|&pgj^XVcqO>fH@i5I7LR zPE_TIjjBK{8uweB-{LXB0v&KNHqSiggA4|Z2*RoW2&99LM34wT2jDB1u~*i!_jj+b zaR4wtH2`cL0Bd{_$J%#6qQ5^N0dOBElGn&L-6l@s9C$kX@_(N~!Qscw$~wzB%LROvWlTw4kM`O=G9>P zfsKQK`g)YQ%;(?2P}fg~-iD45X5bX;bQQgWYj4gyTD~)b9kuydmZ{*~6F)2NJ-D=% zNoW}}YFnv}G}HRx*@r?URcD>aDN0zCj3f{+2su**f@P(DEg)06$F;!f_w);)b^cw@ zvn3_C`DuldkI9xd3#y@M(H=VdIV zE~W+7@KK~4<@v}BeM;!lLp<1a#zL3`F=J4-6_Q>SFAFvh42#QM13OkvcO)!0KE}3M z>DE7W1_lq*2ZOiIZLhwPhd!?(fK0=$u0e!laxh^dCqrd>5M-#BQInpk^jG_u?p6>N zVm$d*uU_0R$Qszu=ufou_ca|n;iJckmjw%=)T~eYer{(B(hv1-?LU)Nv-4;&1HiW! z7Uw=rW@s1!zQq^9#|X7DD4DQ(zsBAaY>5BRs`fPnVB=KTKGA`}(i2y8(^rBMRqpu1 zXtDt8rn$8!t6hhkQ@J#UaZ-EQWDu;Zydyu)N8Q#l;loY8sZv73z5j9Vy6q9X#U2s8 zXIdE`^JvCE#&Ge(MX*rt<*uYN!*WCLa+|N7TE@;E@l`D_C~Y}Epc2?SuuvSin==ox zx{DL%7pyJ$7SsNgI}*nGO#y)afZtTYubtRUU3YWM$Qt#s)p(}0oAPb2(PdEL*{X8i zRkIU2GRhf)1sPc}pZQ<3GB#@VE=>+jqhcQY1XTXphOl0obPyLI&X5;N*_aXFsPHU#WO=V(8jnoySk* zK`p2gswj2o!KJ}jR0x8p|NKjck$Q~f&i?bClwk7>a1IPQY@KcXDpvZmc~R)vc(0j$ z^9dM?kF>XeDGTN9W1GW{itUCtZ3Fddzv{%O7Zo3BhquXD_tCZ&o@q8c%{8X;&(ujh z9D4HqFiYdcRh;@c-DhD)mF`AFD&;`}z6C3EqH)`z)>p$V7=2p9Z+5IJ1bAXyBX6&1Z>p}{-e{`~E~&%MuD_d4sGd!PH-`>OU4&Cv`9 zHWbKO`q$m;EO~f6=7i6n-*0Dw^Yuao`bn+65%4%>I>Iwi) zW(#zIFT{bt;TRZoCJ=66@iJ$aYnJwQkbjrrWMP8UQ)tyv;!ip*z>Um$aD$N$mkrP?XMc7A33RsH`~>8Q7gzb$n5Gs1qnYdmSZbx;0384B!tcq#?3)%je^ALl_pk|MI2czji?!c+8*w3EI zs(1Wi$IN3CP6ME9j4$MhvezowoG0h-OA1GV)JMqSeO-Z5H#^#0kYLWUFxYjU_XEmL zc;C7vu1}ksl!Pd)UB)W(zv`}toPqdV4EP-FDLys=^AokpNCFQbBlucNow=0RMD2se zoMsSh!8|;KZ|~y!-~1wNK#nBn{qOW)n7BMB!;dHMOR0Xq$ZhSM5=q%_xv9qU($}hX zv@1;2Cbbo;BGRsYyaF=xy4MfJXMOZ}f3~1O*+>uV$6cTxi>kQ#=x;&i2WKb6BE7Y< ztEJ3-gWipUq-`H$fO2ZtSN{2^p2Pu>MLO$9;=a#5^O8PFuezB2?KbbEs0v1t!>1Va z^%hAmDCapW+-NoL*Y_L|kWFA#SrPAxpkJ3zYjUOo6)2ygyv2+wN}K{H6x8IbslZ3> z=Wa-dOx0Ofs@+#9NWTuKOYg?zb4D8f*q@cqOHxY*b^GXOIyuWFr>4r1z1U`mv5t$62J5 ziSS24>)`hf-yXFfZ;U>DW;)fRT4bVg&K|YCXrzW3dLU|A<1Ih6_e&8(*35k61Fo^k zi$&r_M6XNF$@El-S8Vw9a$?WupQ{um_r&r~}?mHcyA;^+~ zL><)3+dyW(LzqdGFuGXgl%!12BQ>N+r9c1u6KCroIzAwLt6hmrN_9k%NRsSV)G09U zTGErNu2%J2Pj4YL-((iQGlB$v${k2T>K(KCSZplgaW4Io+3hvHRHYU!q_XA^%=AVQ zSbC~ddJ2>dwUWmi&u^2nm#hA=ssfQnsxANv3zQo{WcI1Wi|A>cN1t+Aj@WKnv)3aVSX#LNCYMcn8fhrpLdAVaP;P+big z{?yf|!{)KYvM6G-@~G^=?D3-k?H4rdUY;ML=3T%~WWgG7EFA=o~G zJRaSDXtseHJOD5@O(Y)pq3dCRr;H#rB_?=OZDtb+lDdFG75(w2s6Zh45QyyiNbw+; z1Nf!?71;YcKUkp*_>3wFk6J^artDD%UD?_X^gm13p-`x7h&GBXi$Z0~{^`9yWl!~? zA*&Ffv0(72MI&9Y^uO);pN@Jz9e44tp}D@9KPA`-b(oVYz0?tA~GUluvBPYK@j$AY2Be&m$FMBr-8JG}v3S z%-=m0P;vWcyI3br7ku2NHUhb}=U3RNE6xJyQICCtVPJlUq5vdyRo4h?AvFt@w-Lfr z=Xq5_Aj%%QL1TO(lYX(kR03g&;CCf<@FFvC(^db0yx*HFKcrb^iKJSNtk~-hFCHL0 zMPLuWXB(3yHl|`%&&k5>U(Nb;V%{+C*H2_k>~e_6OwM7v>XT?QShN`|(ip{v6B{xP zsJZ^OXzWnZpfpcaLZB>ZV@f5<-+g@QhRK|X{lW%Bw)&?6>JVlN{=Hdb^4Z;V>YOQ9 z4TT!eZ2(V&ryMFDM4lBeDnE5A^RR7JqY7{KsN0Bidf-S<>alX!mby9TXPByY{k}u= zN(d!7=_Yc2z?viVoMgj^mxCKbulFi9D!(_nT2*3-$m*p<1J>7rs|&cuvC#>s760*# z{(lTsv;r|nx^~an2 z-!t}~lScmz{2!zd^gq1d8qhynk;DH?8bSXEz5iUM0llpD|Di_z4)`yjM*p7Re$-LI z#*^m7VCJmhE8eq}+Kb6sWI@J`uwES_GH#V%WAOMyb_M618}*kO$i4-FoW^P4g6$pg znl0#w2P;p1>s^@O7^5{h+&wdP@+sZnA!5Lmz1mV0`F58 z3$G5$z2x~%Jt&cjK7x@AL?pld9hlgCqe5X19`B+;H-#ivrT_|)XNW~SE3a7=7DX!F z)i2w%FAXd`{WgAPGy>Qz-08sH-iCGNKLQoV_-jQTJ;X)Nc0KLUc|Y($SL&Ybkjd5! z!-`!n?RIvnfKT!_&!MNN34Srp>R`dQ?_|O{QKWPwf3B~sx2&)~@SS=V4wCly<(uN) ztXtB3Cw!spMx*SMLgC@=qh3;_OQ$D?_aw(_&GjP&_X>+AvftQMo_}`A;fonZOw6qP zlcR0}XqCmyvnEe{RUVo{_BONzh@0kV=|=Q(X%`zO&ee4{zurn~2* zA_Dw1{}?YRZ^_L{t=wv%`ur9T$ttaK_%iY8?FF?jnhIYuv#fDB+GO1eskju-guq%57S0zf)Om@U0 zr%Z8QQa^heh+w~G^eADc$lmvYuc$)6DqF;_oDaTr+ZOQ8^y=&MkY~5|$941f;Cy+KC<+N}z(?#jW!C zF%|y)Rz$z_c_yqf*kgJA0TsD9%7z(e$z zLQoHf(5K=N<@;LSi8(UZvcfgtQ&MKMUKK*?D{R-@uqWqZ15|u<&MWdP9>~pHw8>NF zu@B-}e){vD2W{aw&qB|LJbwb`$ZQL|q?u=^ScFLMjqm_b9K%|wos<_lRRnoc@4~47kMl5 zg!`N`Sk&c80C$^xn1B|T;v4Y^s`zz`JX|04%O$O}pUfTaIGt0KbhdQwQW9+1RIfJ! zr>U7`6Wj#pi@V)ax%hbRQ%(5u9NZ?49-|4CI1 z`v>wn@UM%1IettDOiLF!t61WZ8Q^%&V`!9*vV6?xR`W>tSaBTxj(?Z8hHA&)(zj#~ zf5C?4SKq)Ohqu!AZAN1H!d^;>y`O9`l6WI?Roy%!^uew5-LTCgcVdAjbYu|s`RSbc z8*f}d1^YZ^(ht1_OVO||btsnff6)YK)T}!7vxDgIL_(uRBQa9BBP57eEC6K*Y`&@`HxIKCI8cG;*P5SkQ%VH;mzeW zZ?!dwT}^#*VOQ%PM*&Lh*YABES>mu+^o+Xu#2bBN*tbEJuzDq%r_uq{B@REmXUpMq zHeFfba^;gO?P|Xn?$wj(p{1F^oxCyljlVqjjc@in=_*^l$yx4n{JY9BmxIZXmLuvo zxq;{tnb-d*@GrN&gQh%H#bsPJSue)K-2B5t5H`sU5;{{FIa$ThqO-s5_lJm|=!g{& zvqvv31W1~>z-6mT{GYabQ-5*4u3s%-S_;Ho>A&C|B=j5=6Uj3rd*r*Z{jI{684`T{ zOts)O;VdXJ)(EABj=$=**D-)Usf#JOqQQ61fZuGEuhg^pJ`Y$d@Lh3FaIdA_@Mz6@ zna6^m6}R~XbHk;r@~?)*6rcUN(&?jd(a7Yqo{C>n#^&Z(TXsxAQd+s1)o$XgB$Ts5 zljH{$yNbn4GgQw*KeFRiA%+#dJAvXh8N4hhPYx_R>*&~s$4jhzsxZkqHsT;MMek73 zEP@yD1*-}{Vr0$1y(SxXk*OkCoe9|UmeHPwqBA<3dslxEx+Fs)?0jd%pQ||(5zPg& z*C)F^s~_)gW7(#zNfl>$bD0i_asCK)A9D{3?V*O^#f>x4oLlzK0DjQ5f84(57u&B5 zcP5&h_IY~LaKi)@4jSH)LmC@d=rv|!TKj6P~=J)u&h{Mto=exzU&*lEZbSUs2IQacj+QJtU6Zk^)lQ% z^7FY_aPGws+nCq8n+r`eBTRfNw`~2&B=?l8MCkF%PXcuGkD>mX0YjzE<}BH=fQWr@ zNJG2)4U$8eKD?ZiZ=FN&^Ew$+EPdhcCk-o0bja}HL2%JPRb!R&@;mLDq-dpv=TM{j z`kHt(#@x8TCEt;B9;CXl=!?RQXu|6e3;R!Cg2bCNmr}w+M~m|2Etbg1_r6o*@-8+V zi^$XC()=X@$nwGYTe~fG)Su0m+U^zvaX7^LS!vB^A6a0@|Ee?fk#@%r{9URC{?a?s zN=r_2G5VxADd7Z6cyz>A;nU>Bq&G;Av8dXRl=ZNj8`Na1nqxy}>j5xq7gf60CQ$0B~1 zx6$nM;6V)+_g}C$N?n9#eR8gD;t|LFSN|g2HtoxOa>L4XA&7#oel9;8*Mszhq%9v{pDXdQTd-#?9e}0 z`~MF2{<~)Uua$!TLB;FqOaJG#>SLP!3*3wTpWxnSD*vgi`rl>q|G4-61>Ae-{|xv3 zueNHa+W#BetA1JS67>H__x@LG)!ZYNR^yIPvC|`l_W2VUJOLKX<4Oh%yw^n#0DwJe zJ1y!9tHrmsDB#D^d34rHyB_>WuK$s z$aFFT(2yenfFqF%4BY_$s?TA0-wSF2u+w*Ox##0Da9_TS;mvXZh`o#v@*gGhAAXa~ zzyVm#V0sUeg`ksv^XM^=Jli`b$?Vj=)3XT%UNkaonGIO<%*F#f0Lujz!v@&BZWMsX z0H(bb7<2#&)Ou5a6b&Yo!9cJ9!#OgG={-gU<`b8DQtiIx7j*&$0Iz|ilPvw>}ZOa=fZz&byl`A28X@Mhy&i4=ec z>|hds+c<#1*fjtEb~lR-unGK#}1>lKZ(rw1)WP9r?kjil-`rt9 zz{PmYL-wNz4z8s-WsS`gSff51olJ1GdU5%QTC#x@!3oE>g%p(@;NvW#JBxZ+S~T~U zloWpe*EBJ<+jnMOn|`*H5;f)!=M+#YBh`f+R+*d3Z#)}2R0x>W>Hz@S_F?YZn@%vu zv40)2*0r_SaYBk-e-f3wJ=<7l=l6gE*rO2#Irf$TCQT`+1dmdCXZ73q26a8n!M-T= zyB3S_bI0Qq-`~=##2tR~Sv7NS91Xx7J?mC{f3Fn$JkDC5!FyhjtxW)cQRU%U&tG@z zKV^T?veqIVik^~fjH2QIfXR-IS0I6lW&VMQCsgj}Y49SfWC(@K9+jrd9yXOhI1CjL z+9KL8Jh#lL04`z30L#_|){;0wDre(=%=9E0iCYurR#eeaN0#Ai_D;S8X%C2_nkRMx z2S6AA9ICS(z9if31}bjk+OU}miR|YoicMjB^qJy~KJ5C{`~5HXB`zk~7(Dg@W&sv) z)0qs=f$u3f6u{76LW&W?Bm+{jT@N%5)d36QIR7@9)h6Ca{r5xi2XLqFvYBygoL7T) z4B1=h9xy(_J?mEvEW}dL!(l|i9snG24HjwxWFSs8W8k*PMYjPK0$?%P_gHhpw!QWqtHG*Z07IiPnYiKXWq=LzSlgk} zl|6x+Br=W+q{X}7aMT{7DJMRMYj?Xbtbqb4G6n~Kn7ghf*f*=y+E5^&hJ+0W&S-q8 zd?zW^4&czUOd^f7)mMh@4EE2n%DU)Q7VU`f#_Wp{r#_9Nvq zj=7J&hDV>u>9M6W!s{yW8Kxzu=NkWdj-M2hk{#^0j7R)?IgNkiMl1@Tvdb`} zr6HK8%&7`3ZlB_SW75#a>){^#C8p@#{4Djy=00InT&7>rzh}NEb^WsR_b;JOI|5Mj zrTl25l-IM@TW!oxGgx>9?v9+gA4#a4m{JX{6l5Qsy>cSx!geF&GpG3R-n;TO`wwyU zm>cquQjFUD?`4RBa8JEhTbwt2&JJ+j((*~N7HDoPYXQitw!-bJ`g`9=KfO0~iV>8& zqTq>b61K?|rmNCpNe19bDpI`C&z)CNsC#NmZUDQt&jf8n3R2)X9j4!3tg1W%$Zp|N zpIw6_MO|DhI_55Yha<3o4rmoYk{ib2*y%`OJM+__XvDN_arKf2qSgu`>IVU3Z<^8` zP9fxl&UUI?D}nQ*g}1C|&nouz^ity#45D{H)9~p5jBe#8{`xj1Clb;Lg zt-rAJNwbztI5AC_xYyv$+f$Ylq=mR1g7ErWpSDBZ+30S^rsehs*R7-|u+I>r4nj+5 zUW0VE;zhM#d~`)|)M+ANy{sfxuiG8_`?UAo8Ib5(hwOIh8vRDQW>_PKRbu0I%hXj~ zykQhiR~Vy~O(`$6R`xQOKuf_2vUv2emCP+Ry_twWyRoQ^XTKZZO{Jj84=p+N#k`$zv z6323x9$Bcpc^N}1c#4T5vua-^MYG|+Q@6ERz94f-YPw{u5!j|OUm_) z1ls;H4IXy-BHv^kW?j3+$P=(775^Jdk%9` zc>!Z|v8s)m#&fFphxcgYqjq6Y6e=x9@oSOMaLmPY&}Eb=>bBay_~aAuAB+kkg~unppo@kGxD^n=Z%j1KI#wBM8KTR#5wvKWqlEO-xnwSI zms7&_a1A+*LYDw`yJIgyqzk$eCG^v?C5^rL**`j|0Fy&V%ELPzP3>UidE@*SuC-cD z+-nC~7HGo``yvd!)JN3Qsl1je=Tz6SUH6W>fh4Iq;@bk2S|51kL30x`q+6e|H47$A z$Gdn&QQhtKE_Ch^9imsD;yqPTN6%e=xvY(`!kW zS76P||J0zY{V)M7qaDma5=Iuva*Oksp4IWZ?Wq%_HOFY1QAoA|=RzR71E)0APyt9y zOY5CpJ2m4c2S^jVn{cUuo_UnRE_ULct4Wnc8w>)j^f8nYFZ1LisB)O_H8F-?yhL00 ziC!blO^@^%BzVc$eM|+3!Mv=-oXpDowUpSO^!sRwpE|-5axD(_b&W+%MO0-Wdg7unX-!eqGo6 zm!T1xF+W!^>qT25ny>eGb@pJEM*3$IShd$W@~2NH95eqeO-j5V%-`F498pUEDB;Xu zbZIaRW_A18{A1*)o0!@+e{=ZMzB<+EsQoxmFqAPJDpD&msjJ!j42tP19NJ^wY`8ZPM3MA?mUa_{^Kl@)!zaZgeP^7Z!9;c1bs$z+Jb z5G-=W>@d&8s%@mjEeLA#y3oJWQ&7Ql1a&j5#?*p0O)+so;~wt~bsG%lwIQqDsma@e z?zUX4>P0H=Ah|Hbo@*>0N_hBHyj0wv>)H}OG*ZP4Do3b?&n~zcuz>;I$z9$TSA5o2 z(x~FX6~l_#fhyjdrMtMqYjxn@>5beOh)N5u3e~!s!u&aHIY_~GpO*mLZ(-J3dwgUYNOspQIs+Q_SzcGDqRb^wko;-U~oe_zcok8v#0qk1x_eRtlPAa((kQ*g78{tgC5 zDE#@#{>KE_8|T7x`RE-U4juTjVQvk(y$y6#j$$q#WtTBQ3K(GSYTNhTFlK^|wf5{u z91pNp9+;SD1TYqZU{Jj@d+v)QT;wlRd6qjq$W0g&9~A|x_Vp(8LG{uceulmv#@vKnB4*+BD&Zb3Xz?^hDZJUQ+5D!8URqY0p(oRR2k{9 zr3wEbr_sWpvD_Tf(tx{r6$d`LwybjcgzMD|akp>zA~X;kA?phX z6@RE!zUgKiy*t1n9C;>oIuNdBiShoD@vgV_f=;iSt;FAE@Us%w&sgz=LG=!)mP2=U zGbZpcy{g;4Mj2e^f?k_x7*I%@Nw1W8Sn+hWo??bbor@0yjx-f2+`Dq7@eN4dmA-!( z`Rc^9od0xOV*a`_tEUP8aGt>;E~U;UJJ%!fUaHbknhWpmQp3zcZ>F?q!EZ>tx9wwJ z=-F;(GqB?e{Y@>*orZ9!@oXx!yAAKSfaz^S`~U)aJAFb}5$a^b-ga1o5LDxnb~?!P zm3oO>d<@25ZB@1UHV%D&C1qe%1_rb&j0vw_-Aq8RKPn~SSR@uRp}}9y#Lv#KAdRbX zM-wNMcGEP}a3|r=JQ5Bs*^Oa2dS2dT+NKJ$7F)>_I;1AIS_j9=l_e`aXTZ9jC81}uI)n|tk1DzZ-DyCGla1pY0hGXP}>#WqcSyH?qr!)23EmV3@QPdG%LptHJMobTl0%awskz&{hfy97-A^=#XS|iwS3?*>e zwHAA*h|1(C@bxW7uKbi@NQekMeLGv?gt2!>G$rYBZzWzj%~9V}9}n$o?yC1td$g08 zC768W4f0I$$63>qFdUu9wh#soq%i6Zw-9lf#V74!nVLth>8x<_1g1}7lEAfZ^Ge!f z%6Pjx6c*Cv+r)VVd^FPRO2OmZ!STD;p>70?4oH>}Rt`7P61I;tg1D;0AwhSbNx;JF z6%c|4G4DC$z&xFhT2@Kfgh6*es7!Mzo7zd;7hz!6SZvxX6yHvD-YdG={aI8>YKOE} z8Xtec83}{ILV&Zy+lFj5d)oZ~@Y0R~=*Pd1ON#iE6C!F2&RDy5QoIHM>;qN~4~2-S z8*dfpjj|-i2PAMj&0NLc;iSqz5dNae=o*gJI_OogH__$)>u2NxslbidlC6QXEl*~P zxLLnYPYxVO$dtFd@bIp{1(oK-LD_aNQoi`9I{@TlZbC(GTr+||bh(FHTYHHcyz(6r z7)%>M6a8nkVRjoFjvs&ZCi-GrbV;2xHG>I3)*ie^RO5Sh@r`|)Qb z9;zk3bYizmQEACn&4)7}I|hiDUpAGPja}(H& z279|VO-$rYXv-YqhgS}#SXMiWKh}6r=YqdeYF;tpz}P;sfjji$#6LVA)y8np*kT*t z3KA!p>d(pdDiYlYOqeuK;M0}d57J0hAt?Ge!y1(?IW7NkD^pgrrDF8LVam3)?6=$A z35rMxpd+#F!SeTO17GMHU_hP@-JF(aP9L9uZ0(GR|FqQ$1e{nq% zL9`3U|OedcMaW}Q&Q3iLC*dh#t8Pd^uFf*a4q{Or$8#mU2v(% zjf|81b{NL^6!SJH$^NcFv9Z^wy=24Cg4WR(s`aa#{b!Z<)P&8EqGlIhA)YSMvjfVH z_dKyT3(>yE6LRVK5Mgzt{KXZT+KNPu!1srpVX?j8z({I|Iv$0}Uh7UY)NK0^pNfRR z%mRxN7VvECR5Mr{E+EBs?g-`vZ`o~V0>MI34J$u>R`rq%BnjMsT*)QOAb_K`Ab*`g zhpy^t?@!pCxOrJwfLgL=6|z!W2VY{D;~=}l%EQC+A>nesM`K{di@DQ&c)_51^hbWl z(%|uA^?63jZ#zqY&$A|`5^(8-G;#`cytg_5*HAtYQ{!X$J+UHDrIHk_+9A>dtjOV< z!}OshFCp(VemEFlRv`m2vS^mY1Gikml(RCLzOwzA5syJx&(4oFS1K9ls?#`}EYeV^ zscQBBP!da^7l-uN>1`()*+Bt*X#;Z5+yGQ--r4+EaQvXS4A{mtp~ zF^QimW&Tz&jIma8P`BjqaiL?*l^R%w?iQ9*>U%4{L}2b*Tn6U!HnNL0itGKqA{`eD zt0GQYWyQ$X=sIEYh!iVoQ+sH}$&j$K4uz39(>gCs-+2|@0072)+iVeM=!xj9s^-F=ASj(h_au9IeRn$$r&TnoRRq7FZCqukJN0_+lfUaxdeXRWa=kpmVf3+UF8!oAMz!ka zF6+-fRoq-(OSG{Lw}9UZN3re#$!FKYtTD$vnLDw5^eXcgv~^VRSS@Xx@q`lO0?oDd zd(a2up78czGO$m1xko)%Q+{78?H7XNvsZTG^Pl-;Vj5k5Bb+?{(@?F{#g3Iaz`Z^? z9dg4Ogi7Xi;c0z@#@K%Z$XG1>M+I#udQ=84Xxk>6H7-+D=4*bx-a+!Z#`Cd}4*Lm# z{4-a!*MgsSw)fUM+&(7Nd&n(ks6XF@uhjrGlO&F%3Vu&*6Ylh?NMK>3zF9JN*KhAJ z$>OUJ8E6t`K63fG8?Z3S@488*Su1)yV#SQb{T*ibV_(o{028+gAVOj&w034AE79AK ze5WfYC{`^mdJ8aI`noM#Ks~bDqK%QGyk@TVB9)Xh1%fza&9T5j7@-hY0&sm;=A<{* za1!{eaPw85HmLKJ$|G8&Jf*kQd9;TxZ=OoE<*V=Xv&fzlBhOaf?qe?_^SX|}Gg(p?Kmu(68m%JhsPM-b#-E~@$e`djAfoXrAA@8tY->w695 zWz&V_sbC?#r7aXWBpaCC!YRwjAjPGTtEkbjC1mJbft@xvzxa`SCc9zVmIF_8^ZeT0 z&crH1KJkr@G&Bmci~>yE24W$7?KbF)wKuiq zp#v#pKc>0VN*jWjLJ&0s+z>+4+-qssw%#%r-r%1ELE21SMXC+7&2eofj(bL$Y}5#v z3>h}ws&~A=r)C7D+M8o`N2_+1p1Z`^zZ^A!d|cEBZS+wif%KP%W=G$rmstoyEo-$@ z>#;{C(y;7?`{LgWHW7?1FetAqFIp>jf49O{W5Ubii?!?_K2l*4IvE-m5r)tt`ey^+ zZQ>j?s&Lb9aaL1bAnKkIC8ry1(_wPQs_!lcN)hr4>E@yVK2h!0N7fpu~5uFzFK?(}o-orspb7O{2CZO>XuIit7b z1|jEk^;2riZ$q%ku+IQ$sk(_ohjpdpgxic6O!k5`12p4=3CJ!MuE{ zCTCxuaMjeuliW8;tuks>JQ*Zy41!r~8-cstpp)$eK}$tGu6m;}iI?k=1S+uGvFxVt zSBr9#dMgKyYD|my!%OJrpz8IXZUN=_hzOIkuxo>>B?%2Jff}@ab`bOT( z$|){W)0*jv6?HuvrA#X~MEe(1_&KLZPw$^z01Hs~;%5g5lBgannV5LDId*TQEvEnHpvGH z(Sgrj3_<{RFDmZ?ES1xXqDJb%NhoI5r~vZpSe5cZZ5Oh%a$NH`!k$4`!82>7I4cgM zQ#T5b#0ZF5-}P;vhE3S*%H@L83&udP1c*l}vs7;Q>uN!uf@{jmB3x+-nvY?;reW%1FhjFvd_iN}i=M}NT&Y<9T> z;WH0d3Ze0L2z5P**Prd?vM+y41lG10evrD2qB2jm6Y0xB6rDT=mbf^J1rRA}yWKg= zo(xKv003Yv=0r&E_I#NP4ptax!nNaoTiXUl-ow9Enk}ZLkAhM}X<BrZiOv3?MFfa+by{FVLzVU?^4Fbu3!y29E4a zl}u^;dFQm>?_W005?MVdKu2N}X{p}0bV>>!1!F0+G;d;`iuj4WOSD@%F(iO5<1ypT z__aQW!2)@gNvk8Vn#K2ih^XE6gnQkL1i)*X+Qemie&7yBD=d7pt!1|? zp87pa;Az5;8%v9^{1aF{QcS2YdR{vUQ8Cxtnj@&{9labma<;E>)rlE0xgPH=MQ5)M zvmlCZ!`A0tihqC(KLF{UeTnZdqf&Z9bhvGp{*#axhkM;RCmKQnPU{V?0_2fp_CkE{_G_y?KzZhamX(z4TLd?A zj#b(i;*L)XFZSNs!ZL|Ju?%=6!H^Ub@?r9_e5`bV!Zs#&$77?7@T1rW!h4!;mbCYj z#AbhbUsXcbF~DPiJ)xT(HWu{G8tJDQ!pTOmT-YP9gkDW~ew1B&duyqtE~pO8D)L*i#jx6}8y`mmpNI>d zoW6;&_?ndg#ryHMn|&ki5eN8=;i4oN$nWQi4NrBC!FVe!BgG(RQ+>&ut*+5YgaH9I zyKhLI*Utah=h%%w!|~zku&u4m#uF05jWh`ZOVlmo_|2GCFvTCX+bEj~Ddt`;MY@Ce z$t83Ar8U``nt1(9Xzi)va%zv#Qghi+N}`4nwP9{CL83uvqnO%uFb(gc1#_t>iGqcW zwmfY$G-4#8Z~am?l4Bt%=QbZNOni;Zca`;c^y=(xzR$xH(~tV)IDqNl-3NIT(o@pp z^D3OjnG3zHkWPx`p_1ir>{;sq!`*!Z@zVZUZMp`@d9=L}-GNT@3<^rtx zank|bn~NnKwReNAgj&*Ad>p)6<>k0Cv7!ealkZ28xzgmkcNu%sSLb^6t9%YnhIt)A z`jJRv)Jf8EcLDOP9w}k#{E7I27@?VS(*4ke9kov7eptegV@~@-%zjDTc7e1Y$Zw|> zS!Too5}$pmhC)t;g37K3=D2N#fhAY?!sBADk%2*Xm$dbHR~hN7YUWOF5>OB*l#9_) zO<=7wU13e!SA&Ts+~gC1e>02UF~lef-UDGw&xh8`KG<0ND7md^3fU%k=|!40^#oHDy+b1bnj?ew!;Vc6xO1N>U=rsguG?bbnNmlCux&GbAq!*fqf|wn6pZ z&Ef&b^_d_qiwFbw+}yND_-|1ZyWt>O1dL7nHor@+0KUP{8 zefrf`Wcyx9?Drj%)d^9`I09_;MRIj@IQo(7r_h=0wkXNV3>r0ZPCTQit9QpO@6A@3 z&Ev$wn8`N|i8g|I!0=wLU{56E`Gsl^A6?lTS$=aNejYS z;nQ%WF+)$aol4@BYluIagI(Z*%6_nO&%ed`LD2rkwYAR%ToKT|2(wCRW+zHW?!iDe|wShphzLIw<>X1eQuZyd@V>mNzYs1~!hG zeu3awp@6!pD+&!%^b+g!-P#v(tDbioGYZ|Z{2p-Yab45DSPwf+*);EvK6UPVbiGl257-i$M)#XpMu)KhQO02pp~jxUW4 zD6zrqy+EPLGM4~AVd6BK^)u)hkKY4r#ORFWJr^>q=Ioh*cz<2PGBH(wmG*PkAG_jT z<#i+wh`pNgeBDOVpfs9!4dr|~Fh_S;IRUVXt&f4MT7&v(dF+zW?e43*f<^-I@v0_t z8WU{Tm&;TUiJ>)DMa4W@?!$exROf=0Va8AbtL#;33C|t0vsW8~251ZgoaQW>`a!qL zv2!k?!6T{51(Z0lH#>c_m5ASes6Qcb%q}=2rpvnT!gx2PsVY|C(nl<{?`%DV)lG$? z%R9Z}rbV{KyS#C8seQCQb%`qZmC?rx3e`xK+*0pqyiLCKsQOKb%fjy_Au(wj>&j&{ z7|e84*8BD}s=(h6%pX3$cMRdQRSq_8*GimBCRm&I`oUg55Q46kM{1;NW~VX+ts$Xb zlUpm~sFA(fQ%`rEsg>SAx%=IA=FRO=tXvYyFblpD8M3J4;L(tpC8aXlW03;3rr z$S=_?x<%sHN%oV+#HD*fH*b?plBxR-Rh@xVvjbGlFb2ioABYC^n3h|o4aaIr4i&z-%y!=$rf+l>f)ey_y`Vt?{4P|O(L3o$R8 zmDZBLU|qS^e$XO<+Vk@*4CHHH>!kAeSn3UwNi~zM(FPI&(#odSoigT6Uic^r#c6 ze9wvWsTD>>vVf-_zLLdnaCAw*Y6ZedMQ>c{*OHZ- zkAAM-L*(QKtr!wCeERo0mclKH%bR%*dy~8!)>4N_RMb}4QXL77l*afbf`1TrznEUVDJy&RpA$bv7Emr8`G&YV=XFOP+Z6!3Hd$gP2wPCCvypyW6nk*Dg7( zBm&l|&YBfktv5Mo(nCiYbMMv&vKMwg4tZUBt7spWJdfw@k05}2!OQXa`G-5cX&ja(nY0Xt5d zDB}o!N7t$}HJ`HE;(2PQE53f1TAmcAHgUdqBk?*FCQf;vve|)G`unrDrTodUhCgC` zD*bL{dKs`DJ~ZePWDdZC>>k(*lR~{e9q&!H9>5ew5^S-laco?$q%X<`q&aTYK36f% zejZ_*I-|gYD)|?bN=1;Ot!L$Q1sTTLzNB;Gn7 zjpy*vNp@ab52QY5Q%_w?s5`04soije@cp4e73ZN{Rn*DCmAg3*A)U~(zNZqCR=C3K4={v=Nn&V%#)KSfab*fv_D;nPrm(cZVSkxq5FlD{2>V?n-ET*siQ* zfyV{>O369Q<0qP4tQYOq)G>UCS-uPHpy-c{FeI0^~NEtm$TX)j^;i>&NV#!t~!}vqU z;)m)BtM7j#^EF)a?hq=@yA)Qfe17?74os@O?x47_p^{*CRQ9T?F=R)-lYk>J67!>G z^eHjeUv>*)=}VpM?c@Ja(m-k>5=tdv@7E=mrYr>;I|xB(!#@^qlto23u3C>XkM-EQ zz)ftElPxNTJiWc?R_kLVY+WNbhubgvQV*5EIyJ+u@FGpBF2)vc;}S?jpA$=c5`(gp z#dk6$1r;-MZQN55oOaWET{I0<*{bwX657Q=E&s_OxLP<5NbH;P^n-mETFc!GfUb{H z_n-qT4r5{EV+HRhx`xN1JmlHqmu1Zl-bzufb~=Ejqt{fMd%gA_N?^@t?$$9*3?PqP z)#$_Zgolz-D=Uc;*d;Hx6Ui`N zui$FPs+Dr1IeE88XQfW$$~|rywYITuoVY@VQtRG&!^~;_QMpZbO)iD!=Wj0?OemQ^ zx|vLZCq;kuPMho?xozbzx(2~VxilX;F|MLii z8tr@Mar{+$k_`Tn!`zFU?UVomrjCC@E$(v zEd)Vz{Oz5+OLJJdIKB5h3y)6L-VAy&2nuFyuzzO3v~&frIKqCQa@Pt!uv;-Ix;kfO z-Vd#wx^zS2VD8ctImrSXS2cX{9B(!7`IEwXbAc*COQIv;v1QaHuK9@$U84e*pw5#X zTUWyAdWOnSlF-=4739g2od;g~&k}Y6S;Od3iOYycF;S^?S?I0Sw4+2LPWGywkHD&C zNQ6D3^}y$1T`a;qJLu<)+Xc5wO$8i>T3mYL?To$*TiRrE137OG08X^D*GAiSh*)8yxMJwQo#Y`mAJBi}?#;uY?En7%tC9#YmMmFE z2wAeH5XP3RL}Z&}Cu>5sv#b-cMwVo$C}Jog+gw?)Rv3&WCR@c|kTJ}ddH)XAeSd!U zb$^b}{k?zpef<9Vo`0QxoUdcv$NOB4^L)Ra^LPL>1{+~)cNO^C%_&-}%Efv?bB}jk z)^NWPnBrF(4#|}}A=drL{JCX2@Oe*TI1%qPfCGdJJ3bw7WrIR(A}Q6;Tl? z{1pUquSTvRP4ib_KJP*j1`j-sbmy;L8e{> z4-e=+JaFClJ-R6QV)xXBek&AH6fhGMf;N~*2wW_soFMdva)+<6X?Fz8wefT-V79fN zn%l9wNAZXlC99m zu;X<@-O9iMMrNSrXtJxiriRK%s~1Ic3XO`6m5(cK@A*IVDvY^PDkNM-Bdiy{X*`M0 zmDg|}FQ>y;p05Yq`r|$w$4E;$$Cth{4W3)m0KKCT<7O^D4au?jlalGYImD zZgPnkBc8!I#g3>5IxdEl3@RG1W8a&7yzH6fpuRD77cc00BG1V2&tP#u$^2Ic3%(B{ zVy_~1R%X!MvL7$1XO~*q2AFZx#v{DcxZ1iIgXz=@vEf$`A#Np*D9Bx^#Fan2j5Cc1a(<#j2tJei(czcvDA{G6B$L`wB;M zl_bBQ^0|u{1Dh6A$Fd-KeV@xbdiCt9&U9g>3$?GbBFlfYR1Gt~LVgRwPg(Fe;T>or z9NoXddtP+1_)_p#^DEtWVKp9@$64Orr=QkgQ}jOiZy6#?QX58MW%+=4bS!6)&_nb} z>?Wt0kz+~%sq*@;e;qFtp=5;9INr*t>Hu6Hdk6EJ-)%XHi|lZ?fUziXyMx1R%AP!Bes@is zh#I)-{C?vq+EXy=hj)UJwK;EICj@O8RpVYlQVp{Ta*lYU$H)uQE%()8 z3}JfcKsIFynOlo&_FmtGCsmK2+gw{B;T;sBf5aTFdFSOyxaD>A6Ij+%LO5XO}1EP8HfDS<6QU- zfWz`s#Cq}Fc6|0_G`kAdUJw!|(}A&paA>MibZF^$*&+1ppcCjb47Wu`JmSX<1shF6 zi1zjMr$VZ_yh|V5L+_8S+J_c*1x(SmdYn|S$km~s@GMq)L8bVkVBgEoA%9>-10nX= z>UmqR9C%s4xpq}PwxarFk2S}`SJrcMv|{DkZ|#?1_4&M`qnJuB{VC4b+QfUXcm=T* ztGi*&*z)}8)YGZ)mnLUlXm5{`eVb61MlKBp@G`I+d(jx3_WHbQ!n98un03f{S$2wF zBSh|s=H(|&+X5|y2ANP~O%<9_&B&2|IwMj4bv;7Bubf{4Svr$&X(SIvwJw?iOC_7E zrxAnKto1p@4y$X06ppwwIa3FupTRiei%f&95V_P zF2lqc3O>VU6eO9uy8(#9={J+4|j!Ia@`<~8)MpU`k^3a>mUwKlJml*mg=kj6>8$xuAh3Td8z3?KA;TMh`gAZ9y19uFNRz2QZ zqFYVH;-}WdOI=iU;o7SlSOW7kM3iV@t_FH?;E>Q`2WvQ7e5cvV&-=CN$ODaxGYCY? z`4Ep-26&}-TBJA{RBSuEYBhY~%2Ni5QM{^U{Py=~5X0n)_d8Xrz3+N=CNG) z5kKh)JDL3S7H3sOnA|ub(>2`(*vDlWpmmV+cf1&Q%n2ens zh?ab8RMTqMI^KRwNNB^_dJ zbLF-&H1V>y&3Hbuz9Ij(`qkC5*tUJ+U+P0?TB^FgE}S>6N-@&q=+(ZJ*Dr+dQtRKev}ifsk^{sn6_`2{w&Rem>IzxzVGbWPKRiSqJF zw&JEYEy22PMl|bWygqa3cC#r8Z(7ND`=v?a-4_iePad)+_h?o2<`^j5md<>tyJY`; z=|frEx{&d8lA!WSMkWCX0dr@rM;iX2m1_Nja0`B6aU+)_UK-`Jn93QO89y>6K29^_ zBa6n|aUb{tkA`HZR7?y;@d}2?Y;wVebz1|pvg4UM?V|>nozMtLBCR zbqs>CCT;7NZCkD&bj=<-m(XQ~jY{jE5_@Z~5baWVtg;+)DLF9ayd}0~w!`}!yAVU+ zi7m++8amNMCrA=3CmU=@noirem^r2h69=E)<^G90qMsRmooPs*qDdqIiqIo+DOPs^ zj~#Mi;4(Lqpo^ zgM)QaDSa|iM-B@J(i^&&3;LY+OJ&B%ku>~LTUmH(K5_Y#nWPs-Qko>)jhc|w2HB2^txQLImiEJQPu7^u4j~9`wUb4c)g*vRI){|N*g9c#qO%oeYbimQ-77{ zc4CX(ly>5reh?)G&KObbqlt99+vJs&2z!%K*S4n?7akhjh8@k5c-cH`-{MQ! z7*qOAHDxg6#-9~0x^BiByD;%RIFjbVcRpzalydh?dC&T=r;xf3YgXne9iBc(B@?!x zIHV=Xr(I&l;)q#=^3{v+rRsJO4%qEe!~`JVCHz<-$bSr7ErZ6BRx*r7y|lL*r$Vv; zv?E|F?@%4T@nQlZqq)sLFvaX@jA`^xg#zsC)P|9>_CXVF_vh^vvo;P7CMG{ErY=J};|h1PCA*FzW&Ns&-S`jJ~Lyxly@9k z&se4pL^BCqT`b#=Z2nXzNlECmJfQr@u$wlM-rQI z>79mKl9i2k5{VkWMr)^UpgwSDF&0%YDQ2F-htagoYJ-V@`coDKC%*3B-pbkgH)B9_ zJGB|)8X+8eYlm6+Jg0mmS5+spt4pv6c%sSLnp)=Srkz7O>eCcEvW?!}a>q!QTZcGL zpn^tK)qy}w)SbewU1v^ZpOg}4D4BiLiJ9_`Wy6yi@ZKYOSr!63xnu!Gm10tTP9?zX zcY<;{v0)cI{SB>?fN+v7qm^A*6Emir8jHkFv_%lS&lb(d5y&@7gU&2&XP zwiyF~H7ccsPI&~`$2@xwFW|Mxp@>1z+UFcKSNX0p`!pgO8(MhcJDE#$S#--eP^g>+ zZ+EHCUOT4;)Wf+)(8};$yG;Uo0l{7o6 z@A3_6*979foVVb}$~l2s!w`=X>*{LIx8CW)V4MoEa33c)TnCTDfIZjBx6PmKwmpAd zk^q&jS*fh7Tg)82RixA$svnO)_(6EI#j99L>jw=#-5vBh*3FP&9@0I`wSh%*NA%(p z1X`i-Trdk4?T0;N_ytax26n(agcxB*Ke2B2Uj6*w`hK^N*130%MVw07o>eKzR}cyO z9WEsuqIq6YdKxGcEg2?p<-?6G4?R--X;aa~_~^(~(~#e%C+#QAv*EXW1@)BS={rst zuO8jfNECOMjAf_0nc|25-~a^37&={qIu7voj*h{C;>s@{74E|JvMRtP{Tj2hUzS+9 z+{0O&qF5cyp|s8YJ{Q6MFHUC3Z?#<=jr8E>{yp~tfOKrX!=2AR^~FgPSZ==~Txr4z z!ED_yc0;6&-}mvbtK6;l(a+p4ejo0wQN<`jd;QG;&7y@bqoZ7-79;WUb_;Z?x8+w? zE3W?aKN$ePUe?%87k%cHvL`rtXB#&$T8l;mN-UNXU+R*N0uEy#4nYgnwQVvVxwQ`@ zqHO`;01TM84;Z^L4<9dG3tlS=q~f*<0RU9y7&RdLg?Ta*8?8;<_$q>;jDXq~O?fz* z%6A%)+=#ze@PBPTZ_xtQrqcoa8vl6l)}%OLz$w77k=JTmf#rw(74Tf1)ws)F{7v<- zKx~w~kk-aKyRJW9zHs-uCHl1-V>flP)lmEgBISotxqw%;r~>UXGDXHM=}a(3;Dgw7 z6bhB?F46<`)NGbM+>FoOHYi=ZWBkGYEX$sd$K^`aw0793_`2wc`cS#9aJc4pmxr!3 zznVi`|DR+)_JvoL6i+zYS}!#1jw{zHX^4Mt#_s_F{W^OE2F5&Ka_y~J?HPhkNJNu z=TBW!N%h}Ad;bg0-@iLR|C#gmw;B5{IDh|eFCG|0RSuAgR-#I(2UNfR%=!C=CQ(iC z{NFHte?v6>pN*n_)&Dc*?~RRL3ic8QUAPyrqXnN=Tx&l)`6*zTzu_iQeiGjC;Ia4^ z%KWQ}R5zFd8&U$(L%pMG4G$+PY%(*%=u0~FeG~2$H zK*{*Yp3aJBFe@JzFFQ}6EDF{@#gxlQp}_s=Z_#ilc(-4{6F&N zu*p9m-2UQGczb-gS6170X}w+3yMg%NJ>{wQQQnepje;TUQtQzmJ)0z1^cL|G*63?M zdW(!~O4KSONadYU-}o4Y6uzs4D$&1*+P+p)`^OaA&3KwiHOSww-zjJc*ig1=tG1pW zI#;NhXm9)DC-dST4f4UZ-@1L?+1S~43Gnl?%n4*Zc$H`t|Dh-8Jh{vC`>jCi9MG|@ zD@bj$_APtx-Y%eLcua$0pqla3uXwh&@_{ATU`T;{o1`?~^BuE8m~cin-Dz#{jk>kY zd|ICWJuH(+HG=F>bar(5<+4rG+UXb}sm&Ee$=itt?Cn3#_U+ur=OO=bfk8C@o3vH7 z?o91fw&P*ZIIqK4)v?q?I-)}U7?oDoefPpn$$Y2#HDZC{XrLtVSXlk*c)`%8%$Il1 z{vmLOOb~c@f8_nXfL+UPjib19kNP?QnVXs3RMw8`6&3K6jPn;2wYtX1>XR(e>#w%q zF^rTmTx|P(NKYD_dhyGW_z!+Q_k$4Uh@p+lJT&#Yz`d034fUN zk0YHih5v$3q6FYaIE|9lnyO+Wfigrb_i6N(m?{`gk|`kPMq ze?lly|Bw4kU*E*q+R!B&;qDsXcHm*Q^>z#K68+Em(f>7}NbS7h|1bK{e2E{XS2Jam z>{DZ(OXRw7|HUUdpA}fF`-Dh1P(BWcor7vg0Q5t>%aLH!CFu8C=VqGk?l0MPtO8ht zX7RMU4ZLKq7f3D`p+#(vQ)qNrCJuSwG?GFAR6LQI9{uYJ-GCQj0lO4nV#@~6)_ixC z*Y^$EXKF$tU(#oPL`N@(J-c=$2K4Mlx2uI3t-HN{9Z}Rqrj#+uG!skdGxRaAG`4lx z?Z$O=@kfibwJn@>TL#KR~JdzlSOvjX|SM=0Dz3q zexi^Txif@34fY`?;%?Ono=Bi<)KPIS0j}-3a3LO0+A$ZMv+G{k+xD#2)k_8?UFYC6PiZ^(E3lI0QW+%z;ew;NvHbb|KZvyLnWH zNLmEc`#_(4qz6|4=)mO`|1qP46%Hpk44{4o2i8sMTnlJ?Gl0YZa(-|cA4IL5XC*e$ z!H_$9Es+$$WiEza#-o?)I@vH3u<8VM+TuHj$nQ;!pav)X=@gn~0|C&b3P@}L^!9x| zh&Wc=0-ypl05E7ki$DWH+1VTjpbJcqYcvTm@B?6*YP*fW;l#8-^L8_P1qH08h$;|i z=`motA(5AYfkbGw6_3+t%LFHN8X%Rc#R;efz9Jt0 z(RBd0AV&lnRh9q;kW>;LfCX|z(U)mw!^{W_5tOn6=N(T|8Fe&S045CA3K8$_-c7+# z0ia)cA_5|3MR4Hft=^M75j|}X=1nRGb-NXr4zY-uq97zB-C&t6-Jpsk(J$s9LX5`a zk-3`EwK$jv9@n3qPTbE^cmp9JapbH{&drvMWD$4WIU^V^=>YGPh2MYB*}>)#J5PS| zq<2n}NiGORTS7E>(8Y1%TO25myvi#A?nx@_qLVg|?0}T%_r2I=kbpwd=?!g**C;)h zH`%>Ej0`$6*Xv->54rFDQWCF$OO&N%q{3rwc*%TL`5KGVttcrRMzSiX_E^ns{zih^wkO+>?AV20D!de=*v}s##2%={41v(afbIQ9 zkyz_K4c#i|0B9;6zJHac)H^Vv_4-y5hj3?aO%*>|Y46S8ryDKe!B0_(LPyK5&BNgU z-|yw&5}bbqQPLgZ%Lk|SyHy)p^l&uVlFsZhS&aHM)Eu6Y?ruLX%fb$d*gxb8M%k(G z-~KYk(BTZXFUy>KEfgQNrrZn-nA{Q#ny|OVF1r^xzpen5az~p(ulkHAL2z znpMtJhE|bEQ5eIxeW~@w~PBvi5E?t z!bCufH|PLI0-%DzHsoK}vu3@(Tpri(TB>Yq;C)J?Jcowcwtp6LecY~i3*+mR0+N4m z{21h%fR7+;dlgF<|<3dI;?}?wAcAQ$@gju>uCfG=c@H zI`lC{mSrx9_p`k%%c{=eTug>K%@m-W7wV}v8hS5j#~(@oA{6IYTx0M8k;YC13lw}I zpdtZX=N8_Zw$b=1VeUg=itP)Gst{QFjxQun_~2`bp4QN1wiPz-Rr{SyObAd5mW9vwY3RpHx(Fai!xp|3}Uh@ZNjs&4#HYTY~> zE?(ck4gwmIGfWnHY#QkNk%~zt+q(nmoXg;BEKCTa9~Gq-Px@b3l;SEq7K=EUce)FKKtK?ZKy&ln!SrB2 zUmU4BdXYI&PKg&gf1`c$>^q$=e-gewDEfkn0FL!X34XV>moQvy8gBXRS)7+$jwr() z6dSU}9b@1V^;lrwQcg4d{lfBD`cD6^+Z&xyl?Dr0iDS1We2h*d6GejY zRtuK%L>lz;Bqqit&;9A6#r4awaq>@ms?@}(0d!uk&|+*G&Ri#|lZZqE=jJ)?A+8&> z&pL&lC6NFaR;NWp*R%k-0}Y}VQ;~WP*>~8%c2U>}09a%R1_#hoK%j3$X6P*MKgAG% zdIXsLkkTQ!rk)O30GUXGfN(?DDxN@`q6PKTwa~lUSMa25sz&{qLOVSN0u}qt-Lo8R zk5sATmYsa5#FHK61rA6X8*`nv=djG>T;?ipz5|=WRt9f%R?Mo@f&SxQ+dH9E;a&bd zUgfPCHv)k$O2OgqK=QD{0uZ$oQ|bKFMBc!F#gNT#hjFlXWZ;H*kY#S3_=Ur1pR#;q zhIJ(iAST&!@dHYkN_=MP0mwA5vf(KY&|##=kzM^oL@vR9%d}?QjB9R-~ResixE;D%JTPW zuBd$LQcxCbrOW^G`Qh>c?+RY1VmXpYWv;y7&WV199?{|bYYcjGZ=Nwm$*{sj;>Z;k-OCH>ykYZ%Z8;Us#O*}x=W|yb_!M=r-p14hZJR|PiJD*oah)_)zkvs zk3yc3Ts=K=M&)dF9pDJk)zayq0{TJ&0AGrtvI&=UzD?xdsTu$YXc6Q#upVc-JmNpa zwk?CLg(d(1zn($>P$2sBPyl+GhF)AC01{Nue?MVT$t|kuZ4ZTlbK|pYD)FmW;}xEO za3m@T;FhbaXw+>?I1!L=I|o90us^@&N;MOMk>}ec?4xbeA)8%oK-_B}Ks!yAW9{Ob zARRgIC7%gHF9x&_DuJ4kVlmRLr#j2~tJRhKkYmK4MYpQ3k#G^6*gz1B6q>14>+s2H z1Ro(w0ABib&lYUr$p8S1$XpD@!Bb(w{CKksIZDx7WyqKHsc6T^I3^?!fbQmL zhnD(nY>UI`o%c@tE-7A~p5?#>AE~ z%rd?I`?$U-1xMkm)R; zz4Ti3>2*+n>xvAj2w-TpBjkXESjkuKs`+{5G708;Z(5b>vGq6%K-1&YMZBjx3xc<< zKeK@iKZcba7TZYk_#MP^gZb!YtzsP01>NrD(h~$=yBzHcK_==yUS%^CgporrQ$3-@ zP)$1x61SIPAMAb-Fo@rF>|o53ELdJCklfiT>pQ`DnwS-?@^JRD>gH9aF)9ZA<1Pkt zm(P^x<01Qq?na-&OryxQNCJk4dt()_2|&I1x2IP_=NKPyDEs=IMyeE9584WZ7NDoS zU7SivWyTaR0DMWIKP$wG0MJ3fft}6$=u&nnXrZw0oe9Ce#N)1#3Ec}|{o~oD;5mHb z79$4GbO=bg$TUQxLG5eeXj@Agm=*&rg?08asX7o*q8z-k`hj3t{6K$8f7 z4oFBa5SMlwLr)!x1Tk`6ipe4{;)?7}I{=+f-N0cw1_fv?j7BETcwh2z7A)qx&|O-L z4v^HOIY4OAJ{}OhA<5G-lnGpK4(I?Ma~?qY#3YAv0ks`r&C8vNU>@zXv(c@Mw`)x8Xb#icH|R-!A??Y zRQ0mD?4g0Me#YD9HEs*ravtflaTm4T<6ww_pS}Fkja^fBdmdiLnScD*HHn5GCJD5# zaJvW(s9D144vf8y~6{lUcRSpcwOVS=Rd-ueZ$;rP{w;o^1@PZUc#aYkJoF~ zA?ZJV#tL%m-U<4_Wv=0?JDY!`!y{3j|4+o%9}8Py-W6dLH4oD(7H?;3e>}pZ_@E-p zyFAW1cV*lBTZ`3i)n=}DU5OYv7DHdp56BiWY01@J-t3857Ff_%F=UmD^S;g&5xgLO zgjLc&glt7TtD>SJLV{HJMR&etF>)vmnTd9sK3Hcykx~vTj#G;hi#U8H=;*Fp=$7CH$ zwVX3Y?;K5@Xpq0!*Y>i#Q^@8CIow{Em(sv>V3P=?EGjl42=>X^y5D zJ`tcnyYoRSZ@Ey8Vwxw(cs53n(5JGNwHApw+pz#3m(u4k$yD)K1!0!bO&tA+?eAlo z$T>=`X0E1t+VPi}u0JOA?Upd~hNTA;89Fo_bS9?ymzNhrn?mo&I%1sgj#9j2(uQSq z*^I(FBfRs?fg|q+su;9YfMLtQa(^QQ0DuHftFMLA?_uPH=xYH1HTbQ ztwevP6gQ1n=8x^Z5P)X20cILsUT|-5a;d^oTOi7bHglI9tPu%oppoi>y7yih6~xX~ z7b#4t$C}Gy)*t}nYea&D_rt~jxn)h&5;yJOR4))6GsStK_q0Re`|-JwA)lv;1*|-b zF131a`l9v;*>Mb**(oY-X5?ZnJ;{MW(bhU0Akebrr@ZB*aWfu)xB}OKLqrFMwF?$= z@du_;1<_lmx1n)o|LyT_^e!zPaZd!c$C&Ci(n-OGizw}+S94EF%`>a>dp!krE#mc` zlx}NR_{Bb!J$S)Mjw&B1n-`o-D0d0gWI||5=porjoBc`}`Ha7B{A5k7;(a_Mjd4OR zvRC9V`J&JmG=`MJGT~8J;j8lSb~?Qgosa~2^?o<` zicdQtkko?}lUWRqgb8o5C$gk;0EoDlj}E7YUL&1*Le;wnfyc!nvzUG_`9;AXsa45# zh3$QP@_ai0s{6K`yEg=)6?d3#HEyXi0qWk7S*>WAFF}$~*!t*36TtQIrR+(T2JvFH zl-6pR0DuTT-T_|FtKO5a0jLzPU*)l0;Okw1q8s%_{JMTIJt=+Bhoy7MZp*Ayo+!-Q zxvP)_@O?pt$sOTz3~<;JaN<0~|F$Sdn3P#80*DcNicOcsJLVfP^poTR>RSYrvM04s z?5slvfH((X5-@0T8*%a0QM^chl+Jv6`=y%v85kjv*Am9Nm2HOs6aXRjU#Qk6L&AA> zmT{JBn?xkY3c&lO12p{-niNjL5`siCVhT$A?My9p3QTccK4V=$91;2=9LZ~;)yCxhVuDq zLak7nA@EHv(|x1rMYdqHd337brAzQPaq{_4{Y50$mm`7%GQd$m1hx0#qK7YWEyWbJ zXb935`6K4y>kjrn!In-J1R;^oB6FMe2wf{c)cco+_pL3qjbh(quq386P%~c#Ep{%G zor0j#1GHE>0QM^=;)jl?#r<;4;Be?Q!iqQ4D;z8pHKl8@tjgZK(BzZwnA5VoHHecQeAU7qg4u@ zg4>h(z&jMc@i7P~AtEw<873smou}YipYz=7<;zmnk>~?Y=Y9(BF1-nH7hbzfO+9~z?>P{>f8Ss~r3O_ZimSni zQ1;B_W>3*CU$3VRQRfey(pxG`#o9RD&E6)fLQ|*P@;X~KMQLs2_b4zR0^ozCA^abA zxRAT)ME*m6q>MLiNg|?}?)Er6`4QNJ0{FfwRlAB!0FUdlU#>>CI&U$w<-cQ3_O33^ zy~@-Ifvgu-H{vYo!Ale-(`d~v2++4=L@Fke91Zq^53@j!1SH8jdH+&4-IP5m?UNk$ zWL7$I|H&>IL#JPE7lSZuP^QZh5ln5KqY<4%%Bo)8;S~Xk98wY&Mfgl-b+)WNzlqVCQU zQ(gch?um#K(DQIGi@{O*@qMNWyxyCYEx)eFK54Qp_SxkR7z2gO0j493;s?aJl%TCv$TFT(Cnf06?OH@!!q- z;hzkiz*j#R8yh z8UX+@o-cZ<0u%s?wSph`6gCjh+i&8k0peZ=qjW%jo6z;xVC#VvuJ0DiB}kZrrqit_ zgT;Tqe+2sOhE+_#;sscxvY8M@=|oUXxFG*QPU$=!;?B7|(FbiM9X&oxC{#KCxIO$^ zP4Ti#Ay}6<%2i(52F9)jhs!Z}t}~~m-bp)yr?}kSF+d#*^&XewWdTA%58VLA`Pc&; zw{Mi8w-KFy&kElJpufZd@ixAgLpQO>%Tzt}L8d6pIC(0{Wll#@i`c;yS4ITWR1%;q zR*JVp??=$y+&YN?TXWC22x}GOWefpe$RaiXAn}mzMs9aFdV7wlqF{$g>2(_IbZF>; zAkdoN7U-i1E6}FpvG(bAzpS0)TNF}LN2TxQz|U_hylZuRJY}CwSQH4SH-i59OPQZ< zB_9Fm~!< zsH>7ZXN|xvI_sT!4gDiK&zqcL_(N^Evj;e^zoaLBFRqqEy?s;%n{7$+cZ9JsJ8 z)ULCx`eh_~rR-hpa2cS>Xh!0NfqXmAv)$yS2ZO}4KijSacCeS*?H5X*y%06pTXj$1 zKNHUhb?NU}EPq>NyO&id*~bfG>?L@aytUtiEj-#&v+?+aew|f=)IaxIqDTU~o_!yB z-8-LOzd7ZRb_=xTn*M}+wvoOI-lg&4B|jCTa2L?LB3s`cn+wg0UB=9c9g)&9smlUC zeH54HbrxXWI$vWj^z-f#=Hc`nKqG=|_k?^2uw94z>C*(d5Qv+H|M;t4ekUZ@-No;q z19;GBR8swiD&@ZqJ*cYv-yC|-5LHtBx75M^JoKRY?>fSN4n6#B#{PBa;jhAj^KcM) zP(8?>9E2VYA`bs4^q_iRUHt2GsVOV{N9y6Pg8y&*;{R9M_&1}?V_V?=?GucSyg&Qk zL$ladt!KN1M$86*xe|qyAz2bK7UDcf8fl#8ZJAEW%V%6ppW_W2CZFw|$)|0~DZF9j z8wvIZ{V|;%;Nh$??NGf*1^-|7K z)_0XYZU(QainJ=N#}{k2l~{h>iwX(~k9a@$!#tYOoLy+6Cm;Um=jVGgr?5PerILru zm<4_sjZ$*KSm~Z(k>fE-siNnqPTRdkQRJnNS;40YBAkFa;xDw>MWU^*;^16hH$ojOI;IG`VwYC^x&~;`78S-n2eho9BvOelyjm^b3nqzRX2W zul}4DlipO%nhvMhjYs;QAl;-zlB~>8=no5 zw+^4`ocA@#6fPMqc;+B5Iom&d2yS`Q^*QoU%1@!bcAYk*j`*ZV0b@V(BUYoruNx~Y zMhM%q-c7OX7U$dAORjA~f zFElNMoVKzn3|*=i8`*{5DO%o$M+-f=7opl;cG>Up%y96@{Jt8Q>$cA&P{)bcd9|lt zhqtz*7`#4VbD2UH;%6q}&cHR#dGab->F}i63Y_VC_=5BkUpDfG%EvHkMs$d@@S4S! zL${Ro*!YKQyy{PAr#IAmnzrHOl9xNX2KVJjD=1L&3rO3CxS!bCrPLkzgEcnadRb_q zUS)*S1^36Gu03(sNPzF|ITs_+C7bNy=L+P#Z(MnN|48wQCn+=h{$bJKXqm{e_dnzg zF_0(qjs7%>d$xY_yxEtzt~ep~CtqZ_PcFD+{ZVsHRQ0fmc&S-er%gaQw~JNx#mOZ< z?dd2npG#~!S62H|)MW!*Nmmh1r$=A$%;e`hw}0?kTzdI=-(p6FO;*4qf2BjE-0=ua z<=wXFuM|56$y?7pz7swap@Y8u$6Jg_-`2XNsrb7v!8=Ul zFJ!!&rB-5e%Jt8##SLz+Eo4xl-F0W47JM-MTAp*gE93W5dqrN~^PkRLrB`{1H(#}E zKg>V)&f=4-Oz&aWL&0aXc~3w5jULvV63G;5GEsf|{93?#)=$2B0ZXQJh|S54Q<;b5 z5AzONCFR|($rG#;Zad7mHGC1x7B~oht-nD_F;3wdJr(vnHAfhFl~nJluC{c_cmF8t z$k!k9nk#aKEhjoGC6n9zuB0py6UF#`dW{}x4Hb-(B50GlHJ-WMe=6u0v{?JjO7h3G zzRxm#GW9ZP%?aCgqFL@<@=b6$zxuTDhKsD}pXY0=$@Cqzs4+E>NX0VG8))s4DN;Bu z5AETb;m@ZCo)2xax&)kU0(jl}Z?Z^SB5{6C)s;OYciySzl!*qtoEQEoK<DU%7j!IIekF(`JM5k7A{@+!E? zqk{XGR5y$jW?+9!yS*?G-fhGhg|e#52~c@|^4Y6`q|v%#*Hcbh@$t_a6$+ZTexpqEpH7cQgIt}&aSU;zL|MaKK@~-Pqwq1*8`2`*$Ehn*(aSySWn`=IPGIL-18C{>N zbX_`Sls|u!Qcpk=qPNWpKQ4RGXnmXvcYk(cdHM{08W}1*lrk0HFeSTpspuPUET4UT z`Onp|FLGTsbLzQ2ym1N`o?%v$CZDQ)1pa9ImCbO`%I*^S&6wpF^06XZtCp1tzaP92(B?afxec&xIBq3(K>a z%&;+@z%|?nmu+BtFv#szBgq#M-|~Is_7Y=Hh80b{(%PjfRO6b64dKv_VH;?LXdm!p zL?~%vUPa(0p4Y%?&hDiYe`F;$JI*M(Jw!z!K%YA@?UwI{E4dO)oUOW>$1*iEY#5PR zB_Y4Q9@|?%1`5Awy%5@a{#J1QDfmm|((^~3&Rx}kx@t3JmTK4dYZDO zsUct#vr3%vbIQN>@Wt}?=b2q)7ltedW!Sc5FPsP=`*r{Rp?BKYEW)9$h}ROviH8^u zmtNy&?rv#M{BHM0!}`wc+hL6Z4oB2xp5+~4PBn_@XJxwFa(s4l%&qiLl_VRw=4_3w zX==F7;wATYiBoM~hv!BmPw_J`5>J=aM+pXfkTERba%^&*h|&M_IEQBa;QYgKn>U6> zud2#x82vG({YfP5ihP;uBX`kGVTu-_p5n%x{7j_+_mL{@lBbk3T{T`?XXt-IP@1M- zBv(4hdyM=Ip2^&pe7MTwEW_i>&wbq;$G&sY4Nd&s#f%tCy~!(olg(1pXgUx~xIDRxcMus-+3a|8>xdt`ws0%#p=YVW zAKS~a&%eJ?y>sVT&Z5T@{OaO88JzV%%GrqHZ7;|YQrxrZ9SQxk@tVUdEcTr21#8uS zS@Dm2&p4icl_mT~lvhRhZ!fF=2<~3I_#cr$!`m()?*E<_R4{Y*_YCn8Rr;&^Uxpi1 zuPOea$8vy2ZqmqiKg0Z`| zr&oyR|32HOq@<#8?!UD!9{kq9x5>ZHmxHLH=s8iR|D>tRXE8Lrnkkkyn8Vu3lYdrO z^u1f5j2B$W!vpFre5Dv*(8xB0>25R)!qbzGgEy`hj~%o* zD6J4gn*qQU>`lS}5u``D;sM$y3=n_Ats5W!Fhu-NvMmYhKY18p^rb`8K)drdDQ2wT z7F-rj+mB#(Y1i3Epog8BobdfE@diR8D}6x^7g!qX{Z31E{(1I@lKoxnbXCRCGg1YO*|v%BhA^)cieI);Wm z_G+8Fs$-`J5_N~E;Ty9?hQF=#KX-+9oa6OupH*Nf74%K&LLegd`AuFvjidkqk`@z2 zeo1eWph@9&4;E$#fLs*kC<>+)Z~$_k03?i@k3!FV;F$K1{yIX3PF_>LSxkOX}KL zr3)0xM&qK1#3;Q-0JJSXjvfcP8t&9+j=UR9<&t{G06MJvnJ;gwSZO)WSO|tyevRW! z3~sxMI!674im7u3YZsLgcV#K$^=$In;wa^gT(9w~`4vkYqgDp#yHak|uZP?RCtS$6 z{)utsI`}H0ZO!(!$nd$PJm#!j-FN|C+)khr=4^y(vkRAC;FnVK1hU?ZIKx2w^IAHX zfc2Jf8LcB^+HvWXKjG`z0(;$=fP~ zLHXCXrN@qZ3>~4bD^_~1j@EOv&o$6cy2nhkSn^4iEOuC)22H zO)j$WYY<|SY~oL%6SjI$8IO7rv3h+A*Kg`>RWSbwG8kuCm#Sn9KGM2@r%ITLe*e$`kR5ED)7D=4vmzsSIaOr5y+k#PF5C3FfQY;8#^D&ulapGan z0my2y1AYGV_w_hkg44Igb+X*})}CfP71QuOTvD?lRQ;gUfDkf;=(em#+;BAEj&F>_ zhi>KLftTX>bSqXG(T`35T#wixKrdB**2N}uV3*N}Xx%yfxuqvn&h(vZ0Hy%grKCgq zM!Iwyx?w=HM1PUPbMjL`MQ9~a;uJAg8&rTc{GJz{zI3j_yG|n-%y%WGY;B2)As^G(-(a2 z`G-*0YMV%jUml3uOK#JNs9gJw0%SmJpF+}bNU*jaqcjtFvXUGN)z9MEs(3Knp#U7C z>wpT<-o+UI`t?Ci$=6*5`B-DmhSnx^7P}w8uC)DV5&*jj?JYzi1~j$NwDt|Q7jAGK zCMthQbXsa(nZ0{? zrd)GVu3;+4(NKiUT}I`~xhBd8DOWUm$1q3Eawe3>IW#xh+ZEEW4AaCSdYfy=Oq=cX zdwlJwi(xzo59BS8Q?VdA&_31>7-Q4k{0k~@bABdP) zK4~i`rK78)&t&ylsOL6nSt}s{K!PIx_AJT$a)6(pzPtvrW`${lE*rGKgF2(x>)%l% z?(*m;AV_D-?H>>tFQA8Qo*O2gQ*tyOpF2I2t6l~v7-f4-LONoE9u#WT%^5;!qaS6Lms z+*p>g+5jm1$P*Ag{jd4Fqvx*qO^s%eUhUw-B(0;GyA1$9V8k2+n%QpJxBlIB)xd%O z{5@LB?a>xL*!x~^Nay+G^dI%)Auiz4XP56Af^nEKc#PNy$WF{-D_6sMtd+M&huww1 z#u>5|$A!gUW7cjmXW=mlfqz}^fM^F@v)Uo8krSFJ_X614+`F9#dr>}zmXl_CapqXHRO zi)Ip3Tb{<@^DgzA68-11FK(ktGQl|L7s!64UreWA@5(F+ov+FRV!4shoudCdR6L{$ zOZu#0*J*xG&R4KdT+A<@IF#^P7#f7fKU-Z@{C`vTKI3g{HZR{;6kAR5mZS*Sqg=lm z!7xpkM`cg;sQybam0waX-^o{(ZhL`K;$4!}K!hT(or4QXkWTG(I7D;I@PCcYGm0k_ z21@S|A;zV<-+v!^CN>u0Zs%p6w1C9E4HW+Nck{Bx)qqTXl|1xE!&9SqGGTh{08bin zv^dj#h>lAZQmFnTg9XS#R=9H5bR+4}o9)sKwZTNjG@G-afiMusCIIgEe(iW*-&!FT zWy#@@QuEh$={_=wqvmIAoBM~oTb?k+TWu0d3d74qrj%So$iuN1qb10VJTW2}teOCe z#={P6`Joc5L%rS4V5!{+i{R%jI5Ejub?@O_ijV5FW#M&4m@;#3tby8-AJf)V@02Se z8B+%T>2Yy!2uW#St$lG& z{oj7TBdX4FaCjq&F)k6#-yeJ+iDgVgx`M3pl?NpU{L@LBn#%4wWMXm*pDAbuCLWZW zY4Fi_78*TZ3FJpbVI^{Yvgbc$5hys-mdDxC> zYIr@tvDZ^Tc7y?{pUqNwq2?B)!@Q)+?C1>CLLy0kmn4nyDq-12M?gf3grQAD`y7kiTjq5NM=I+Z2k>d0bGJa9`Asd^Rt)ht4g&mW%?chJ5} zwd!@suIvs!lR1_zSAH~h8kh{-G)=UoZheiOh-|6)OXL-5zsl&%`?{Z7(hkWg$&R&P zS;9FZ?TpnmHD(meCYr$TNuX}OJmI(Z#Kcjk_^!(HV|?v9C)`Ee_m%Tm36wk10#ksn zuqHs(wApTNac$F_Q+GS;$(t@+)@H#9Re2El{FvDN$ z>`is{3=@8eE&qBLxv1elWHv^HE$L{>E zG>{E6+SrdS)=Pbq8TO~3MD7R)Ag@Q8f@&1aAED8i6R*Rimxyw68R5VSd>;E8+FzYsncHwljnL_{yUh zuhd64JDm306E8PZ2KrLXzZU6?u});1~_Hm<}Mb4k+45yW4r2Q?adUaE2>?7gaPbdDqk8w(0S;-2vN!frEk6Iz8|?N&ai>^+wuUVoyyjdW zDB}X_nfp~wL#vsrtEwwGi>H8;NR=mv-CS}rpRnz5e2^v7^!W4Is=?3N1#?zL2Eb<& zDFe|TxrqRS+2{vQv9tsprMK_uf*LzEdObKz>0*d1A^T-1lM!Ry|L#UngX5vv{tIMc zh4OTmK52W>TNHYF5rp@n(_Ea+A^u4obyEV%Hi1%mLHcl2V%t4!2^D|~tmuOjU>2@_ zJs{||U(fsfQy&FuS_Fk|KJLihjfu-S|0sb8bv!t$#_FmkG%ffzk0}->#a=0*w^T^z zKJSg}_gHyqtYdy^3Y%Ng&V z@X|hfBR>Vn{*^GfOXFiKGx&u4ZK8_z5SW6$Q{F!`lXp_6i90`C*^b*P6|42bh<8T# zF!gj@L8}g`L5uE2hMH!GvES_I2|!RN=iPPJs<|Ss99D{50LET35*+&_trxu0|Gsqo zn!2i^(93B$^z2DO)g2<4J|I1k;0KUdYz6_d)s0R%cI)Zi9$@}@lRYBdgO}|tlLt>?u#XboI4ZS7Y zpGeM5IY?n;%k{G4H+$8n)bk8tgZtu#e^I|{c z>Lw+3Kgbufkm|Tc)409Xf?XjIWy{6*VExkj%Ri*TzA1rWSJXRt2(~%rCK%PNZGuh}uNXUpvTYzE9-{rBG`u^?AHz6r|EQfU@J_ivN zIQmmSL-NJAoJGBJ+T$&GLR6c1x;0kZRw4|E6nlT@c%)(L=$&mpS9cl9{m4OLaX9l`DRQE+=ux zi66~lZl~;ikW11yBH>aH&8P7WxD%&ux;kW^a>|8C-7VGpqbmt8>b`C=u!v)S)IVEu zH(il@%l>X^o32ov7qpnGa!oh}(;8yj1o=-9XIo<5gr)!KoJ++CrrA4wLh| z8agBF^l?CPS~#U@`5Q_#e>{^|LGDWwVUdyOVVg(BGLq0nEhi3dD7Cz75fzh+9dpg; zZ7#z&u3be4=J~arKlxT{1U9R3^RF~s{rzHh_a;^_bO@vmH(T_q{VgsiB>_Cxka#2@MixIZ&*2V09IY{!M)MRO+)1XO1w@ZWQ6 z4yl>kyEkoR0Y@+Ik!D94%UHR!dMXfzB_N;74P(WQcY8~uw0k06-R{^@CVmWnbo4L7 zbqTC{>Z*>+c_IZZ87+@GzUR}=;dG7yV~H^1a_uLq4YR>(_#d`=5V&Xf|DKv38`H^a9JrFzD$p2 zQG+nJKIHQJCA%cZ<<8~VPeMxM?PQ^$OOdtAoVWzn=$i2pJNl&$&dY6l;awn726(2H zoa~TnXA|Y&OBuDs`ZA$$WIl(R0f+VA!GsaiZY6aj-~{U? z;?*b6se)T2eeytbwz<7jkNSdjy}HziO$$qn`)!CM>8hOsue^ofH&UsQk3u}pwWJ*2@i%uTrN{1IWFka1 zUN3mNR)I2igj|<&bl+K(OHG8?*bN*JHMiVPiYQDf(|iD975?*^Ef=YI<-A+5)AAr6 zl%y^^Hiktr&Q?%>uU=*P?UiGH;44En5`0YTr9Kz- z2CE|HE!X%Lko#@NPHsutrRbyyeRSwthKiosXLYstq2UiJCytV1(^wW&>{gBudP-hFZcJKJCWq;{*~5R!I{ z=+iSFXqgd`f|EqO31!ybGxA|4r{d1c(3qw*rB1%y$It$9Xqt#wEqFuE-s{-{(uf*x zJs}%S@t*jTqqMx|mhaa?eub?UM*TdMBo^v%(7$%~a&i^9G8wm_4)(gcTpG>ybFv<{F84q`QwVS@@0XY21o zNuDMUm)Sq~O|DVj#Hj6YbA#dF#&&uBbh%x!o5+!n{$z5G7!VyY?K$3UmA6Md zaNmz$0Sp!p>Sc0r?6#0DY&qa*=$E$;bF6$Kzxvz5+3>UKwMpu$eCemL2UbnZZS&@4 z8$H6Zb3heggiS!)&N()4H4`h2 zniF+k|KKf^M)6`4)a8n->d7G-u@(Se?WgwTe&}B3%n7sZ8TI$~Zi;Hn5#H2bZfpwV z`|pkTT_}u33g}Al_q}`fdrwrwp#r>KgDN#xT;M5L;JCB|@v3rw_NTeea2?8CTV5+e z!4JZ`_-zgkl0;w->7Df>*P zmbDTQ8PyFtV5=J9BxZYZ)#IcM^tqVM{=8+#aU3>sbY;{Bu2p=uc;$EX5G^xwRUJ!B zVC`J~Bq8Qb;{YS{Uhbce#?E>$`^}7Z{VQ4D%yc`?J6I-dN;1d{CDe4`PJ|I>!yd`6eB<79zoIh;g~c{8_u*IKpo}te6J=MiYw_Y^ z-%D$jRhjht`oX&`h2B@*_81Ka$2Ne{U+3cV_dA$xA{`9CrX>nJaxd4mzdgcM#!R!! z+&^hK22~TbhCiBulv^LaRNA`;7I{s~kIGe}rD4#^3+;l9FJc$zTGve`_eSUi|J_6# zb+nQvFSI%dMzg3pb^XjsJ~dV<_DH81r{c+7P*ii!K>WEe6L@i_?Yf(R$?K%Q!L z1;#&-*=mX@mG5id;^3=FRp=$NKeAb?(-&I7)%C;Z>QCcj;+#zd`p)Otbc%_M}H-ifF8l)N;Qk6fy(T`wglq z2>v?nW``9}H#13`;b!@HGr*cFvFRGR#f`J7_D83^@x(ma9TIjE`gWN5`c!L>p73ct z0lJbOo%56bBKOuy4HP`8Oi0R9Fx`K)3@=l8#+B;;K?Zn+{<^-{u{&zGzhA{CJ_#tu`-}Xp2!hWbECMpzgPAqd6_a`J`KA zAR9zX%=ve3a@5ubtX@2@Q|OI}A6rL8eWkzPuXD8w7^SRi#3zrWz$?}uIOG~WxfyW= zmn8PNUr~{MZm8(#4!fo%J>v8GcK63qgjTt%XNfE_=>RPx1|5Pu8-pfItP=)a$vn>MaF{wi@@s^^uN$^m~Z+M`oL<)j_{i=nrF>7CnA zWBzxme$SU@)$eMaE_M{}d6?;UVm4#7iieH-}=ciBBmj{!HDG#Me%Wfpv0hp zkjUOjT=*QA0kYXpdkSh#R|LD9pH2We<7zbG=yYG3hy3E%#*K6NCk^9sUc0n7X87S~ zBZdLBj_<#JHnl(C6vW@D%W$%(Uk-r0ewR-T3B3LsdEGsA5M}N`91P`g<^y){c7Zaqvdby>%ksf8N#QJit8E!EuRMh@*gw^DdD6+ z9-Ahc{F$!#WnK>SNB3-*s_FM3Zmalg!CYJpbj3T|7U+-Uyb}(g7;bm%Mkr35k;C9Q zo90x9pd;1l&B+K0-~vBbs?9q4iTF)K|E1?r)T z>qyo*mbHlCv(}Mbz9SUFV#uT1vzDVd*mV{lkn>*s6Dsw>sIaa^+NH3*+ib!6)e$8r zQONzdwF=Dcv=LG43?}HUTcZ)wlC@G>UyTf%&tZACArq%gZMpq~(zftUe)<#&XVDx;dv>#TG+CO*|;P*BAdOmb25*JhFDT@W-7i(N^^O zN_-=y7AL+q4Z;EenNcN=D~{JusA$j5m1}H`(=pt=WxNQ z1;IYcsnYU`{U6QrWZZcw%XjboXrEBo8yu|-t(@Rs`piiTj-RRfPRNVsCR|cvDAM!& z*xUQS?nB47^}#TWt5?)9iTYi4tpNauu4)$9rv#5Z(0LR4PW&mwht||`dp2zIVgXP ztKJ334mSd*p!i27e@xlP>Q9WDM9OYha|nJ^?&6P4Ton)9d++&md7M(9SqVF`*(B3> z;Qo^u+14m2%{6L`BtDZiH&R~@W=?5aDF!Zn!zsUYFSuKMeRHe6G(bD}gZ4Het<_Oe zPn88c|3K-B|INcmLz+FT7mcg#(l%XdNQ5fcqe-g#f@AZ*ewnph0B3VQS;SDn-{Q3g z`c%B1N@o+V=DqX!N%$O6S{wUS#-s;wt_Z!-bAyzsatXSKQ_ynXQm|eZhuGb@d@pb1 z$R$sUB19m)$-r8_Klr@&aVwKo>CY^ZK`{CoWlqiYu3Ev@$JCDw2EVR6V(rW@e_bxe zr^VxM566Fc!>t!9`8a##@bk`i%Zq?V#+j;posUxsB6tkj2eWIZtctQzV)|BYE7a6i zFU}nh$Rg8*=3Lm&`Qe{yCCSzuls~O#kG)0+3{AjG<#p8h5>`yAyVTVHBo3BpY3dlZhlfzvejo>SsZ-+ zU$_o*rl9*&jYa6lO}I7+34LGPCm-kZ@shfed3USeJ395z-yX`)p-k4NW#3ke?6cqkqFWoP7w@N?5wl-kp4qbI!t!B;a=& zq)vu4+@ulK=xYym{gB|$O}<&9r0FAL2~{q}i8brz`Yu-sL;Drreb+0dC&|vb2nh5- zGyWWlnYFqhv8H!JS&R(%WDZmpVA!mh*UO zxLGbq6n}pZqTBXCcK4ntH!KNDAW=uQ={%9qf_v+H!3ZIizC1gr8tKix^YRs$aZEZ{ z|Y2!_Rq%E2ul(bSNM4FJpw6fT@uGVr>byYJa?&9neec-9EGeLMVnMEP9OuA;Y|kr4 z0rDSXD&V41_`&6Qlsw1zF2#F2apQu{GPOdymBnT-c^T-MmZW+1^gMt)Ay_-4>+ykO zo1S5gS%PJkoix^0sYZu24LE!tj2AN%(2jNV`-D7Mht8Mg4>FwC6={&bm>2T@j!| zl$#{yxcZ+rKl;O9mu&0~5ZYG4tseQH3#bR-uM4oudDbgPf^Ml%K~SGv2DEnoH58wF zB}uxyG1a7Ytl^o!JUONjE@pv9Szi5EW{cX~Fy8Kz zO&v2XKxh*Ohi$IB43&4jxxtLm+afV;6+6~Cyf8hg5{OnVxv{vp9*f79Z;w4SJGv9Q z8PsZkP7b10c74fmOXdXFJczaX1UHv4(C%x zAX2$VPUK@tfH=e7%vhciSF(bALSp)tO%LYgOr0%}RjkdUm3tLeQoD_fz^%dO9R@;6 zL)Gc6R{B?@o!}@CCa~}Hw)Zmd3l)>D&}efF!a3e2?d|SZG9WUWn~E|$uFmPHPhi81 z<(s~x@RZv?F)PB_cm6gtA|djNl1`8CfuCwGl^M_xDT!*mxe)s4UrD%Ms(R)g3qI4_ zUuQrY8>{Q8iHHVJa+_h8wx}kva$*{kB#i$Dbyg=Vv|Hk5?Db%8vlG{-Vh#-2SD6^r z?i$KC1(&Wlo;|QOxoUw#va-A(f^=K!CKD_`opf@>?}6~Q)|4fp`u9n|pETXcz(l25 zEGB{$%UX@pX*>_g&hEZOOLAt^01`;#&v_8l*UoVsgJfllx0|v$Kdj(N1#98)`eyT8 zF?z^#x!iaxk^wLntfLAyZd)|1Pnk9lMKsKR*&?xdS*lH3{=8*#V>UmNi}6EKMyAuk z>w2!7#sa{yH6SoeGzpOm!$!Y?nuXnL2)13OW9sAfiD**0_cW}fyy=&fh}rfNLd10u zx@b)h_6-6Wh2YP3&OKRQGUMrkp zqq+*28&4$;f`8e@=PgfZq1DA#Z4md;E&2VXKJZcqEYryFNOi$bwP{9(_i-11d;`4F zReJgh&Rdmm+n!)^sa}6ar)g0bl=kMx*;h`vJA6OC%x@yzVb_B^j{l_dmeU^jwiF=R z&XSe`o2Zt^0t`3ACs#hB zk_z5`-F(4glB;1l-s<63g#S@!4=bX%01>#uP9M+rgNt#911lV#JSZ^{-{xu3cQ;I4g98tGn(cG*&b0X9H%)p( zo9c-lOa-ivj9-6MiAxeI0$vuwJ1U;}mv8K9SyT^7CVz;>=N5)sYCA1x8C>D`Gf@5| zkHB6c2M>0!6x^b1d12t~3z=E7PXn+kJyxMRU@0x=BK7)> zuIlE}ncdr;|1DK3Kp*H6r{c-Wv)!dFPu@n>`uOBr2kSts2E;{dTzlOe2mV@k3uDm< z%+-xz`#gJy&VDq~(VqrNvrhfO2nxy&6P8RrVKeMt_Z$y{-jTfj0{XK3O}S&>T=pR{ zO7|HTee~^%#HQF9d&V!ma1%ethY4++et4<*c)_c4A6?*T^dVEnw~K%I3{Uw%-=2@f613OAzLlp3 zV!;+#Qk|3jywPr2 zxE#%6Q7LNcyg_&T?!EZ^Dc55$vQqq~hNGSoZW`HV>;dX;#3K!j&c^f!;D+kgSzA2u zbz(w63LA*0Z$frg{i$$(nl!fhv&zZ(Si_F0((LtqT}|EN@3LD}xl`WdDGD^~N6T$N zVHbr4xWQkbrF3h|4IV$uZQvqaNjN+elAIZ=c`1D{5W8&8;1JU#NIidyjixiUCvZzf zzb>Y2hs8%l%@0yy^C4h0~!B0u7*g44aN^Pr;w;ZoZ>5HE;T%BIv6Z| z@-wwZJ|S31HvL9t|D}qWp3xGyJGQCT*-wsO{ESOJ+SqE%LMt$qLn5ryc#&G&Io`Cv zJ?(F*L_R>PQoxtEJB)S_RVk^E7{>!E2G8*VFXxXjq~G!oALe?Gm_kc1Vn6y?xb!;> z!0|6N`*=}RC*34%QRQPQ2mOXFUPR~dh*kKO z{*iW44>pwlHs)o)yo~gCEALqOFVA>x|Aj+X;02fO5roAgGk4n72gq*XlhPKrx*69& zU1I61{If*B*E$f@yduT+EmOj_Gn{f?Ezhp2)l|DmC6}lxV~`u7XHC ziZK2>xLg$`e5_)Z72h9Dp^nV0almHkg?ZlN=4^@|QF`+)Vx70c&GIMjXWaq+i{YB~ zKJ`F#(n_{Z<>dhbFpKMR^ZCqYl3vnl6U8wPOH!I4%DSv`VDP>UT?p{GXGiPDT~oV2bB`$)u_#v#;%LBxZTk? za#hvM>A9Vg5A}U>ZS7ST4WIEYn4f9whB>aZl<$}D$oRa1y4WNc)pB{T9iiE% z#t;1FTk*#iY`kS#Wp?#*2YJ=#00RCy^;3j{;dixSDmD9j3=D+=&m#;rDj}W&$q9egHkmktwbE|fd!r{f&TCKY ze9E9Zf^u-b)jwh3!Oexkx{NXT?qQJb?_IOw0dc2Bn|(Y1yPd)oVDvP@0LH(+Q^OMH|uom6CCspn>%dco-zw?zGh!9MEUHVDmrn$@Ubom zcM0QnzESJJw4&q;mE%D@OiemUL+R8H?cPIf7g!0)H2={O2WwwV7H_iH;|vDtJ6=B( zBVs0El_bk15MNT7H_8+HoB5$N?f0o5Ed4m@SfI67EdJGK;{Mp%6K@W(2dm^6yek`L zG_-gNt^PzM=ZoKh1dA#1a!ncDnDeg*l*h`Zh^RfvT`Nl;|6bx7(vLNIV*(obUF{GC zmzd|eG%8cVDVai-f%;9%N6TKaGdHokeCASFOhkBHzOl@9dCKyw!cOKaKKMKcWaAk{ zAwu1FP0dd%I_Tcuv5H|ES52FsKyBtzdS)E^4E?ff_O%{|3t zXAXUb=ie$o)SgyxW}f>#Ca3;IJ;uRzEWX?*L!^`a+jpAF#g?brJVLVFm!6nqqIZIo zaht;%i=r?iDO=3Sr6#UwLOXTjOi|Nu5_xG3*$Iz%nIuzC6w7oK7!e)rTzPa;iX9)} zr$c-8$NrJa638&;)YH2$Cy|;$g=T%sKJC4R=D@l$u_(*t0V9lBvczG)U|gf7@{q`6 zb-`7RgZ_M9*Y+w4NAi1F)zzo#V@n4ib_euAhZA){k^ z{Z}tcl3v2CQux7NdXJThnmxXTCH*YcJFi~XIY$1bm` zV?(;>J{wT}s=xU;Zi4j}GslY}Eg$tHzo|i-&WsOQkEO%vOG8#;nwnq;IZJFUV}?Q; zdtIMB1(n1vL@$ibzX@j=6^-%m_$eFvLJc?4JNgH)a~7p%Kb$s+tJObz8r|pK#&+K6 zHFJ0jC1Y-rDZBTa0#hXuW;Mh=tSIk6lvHc#DFzB((6IT90z*&{*o60Z@tgoItU1dF6epKsI)952)Lyc zH+f0YmTTWLePN1!1v(p$s=`E`O9|T9%@)Z{pCwBWxIu}1;xHjN-%wq)K@&C|FbH;= zCz?RetRLnXE-23GKe=&9|}33zC;0<(o5X+)0=c zvk5o1fJh?lWxv`KQ0=_YZ3OH>+4AfcFJpZxeXDYdlMpkVOf(9b46-R1396*ZQQNIL z+24*OQNP~qUDlEh#pqjw1$B>7OHv9=H~R@SUC?qB5?xGG8V-rEE1^(3QYNFU9`i&` z)D)OXfF(RtdRvNZO=VQ$Gu-zU>=fb5X28TcjG(6^8K50f8hY1yFMo{{3^C=@kel_(ZQjXX%crb$z!BmYiqemd1pv(aO3gK{QSHu${k@%I9F*wtOxZmYnj zmVg`S`)i-8DzhWYv)YS7$-T#dgQ6>~FMT~CaV?_dMQ2Fv4S5HVR}IcC|C&u^+608`S>SV_JP`D5|`Wa1kM z9EOHUzU&-t(E;fvFPiINFMqh2Ve4MWn?c~W_{fMf670z{O^*27px9C9r8Q5SUP7>4 zZm@E7l%-0DkH|v)$Bd52NTi_gUBPv2X?faLkTn_?b6pKn>llL=Oxt9~uYHMUK4c$*3Y!;-?VQ|5@E=Eq+3Kf|w2wQuJd!OEnfPJ29%* zHLQEp1k83v&U4D4JcOx>PU##GVt#N%arAgIkNHeHuszPkvnF{su_u&B zo2#Xpxji*vF4OA^a(kd;IAiV2uPRr#N86SFxo}O7D^RKz{hXVrQN6QF zPko+|Cf(+gb=Q`QG9&+84_2Roz-@MxEWty!x|(5G)B0D@``72yc)JR|cKDOwE`LB5 zjgu;=knEvzc8U@MGQ7(2=s3jMTV~1*7_9qOsM*`m`AazoO>VtC3Hqzf>w_y)_$Ax1 zsnCzm(PNgOXfap!r&5Mq3R$*4Bdec$xT8^Rt6uxeGjyIn+zgLI*9ycW9=-nq9QB?Ke9CbBC8zgujYjZI;#b`d zak<(#-P%1Rf!o6lcO1m=I4}B@a{i6J&zTQ){u%seDQ!DcnVfbtzQFHRg%Sw0D#h6shuWa~qC=h?F;>44Peq-cshsfTe8>C!R~H@k%^>-XC~0UaJ8%X3p3;(K0w zcSpvq=9ZrPGRhPA%p?w74fc9Eahf;dDR-08`_&{p51)I!siS-?&le7YP2Mlh(z%N5 zURkh7IiH0(8tuLNJ&Zz!UO4|#52>P1SqQxxthTYrrhbYHY`-2KrnQgQn--zdPj6c> zLVCP+%w!A|*G@E|pALbp1?yXV3S;fJlxTSQUK%$QqA^!PQq1kCA0E@%lP3x9AVTUy zPH3pkvldE;LVKBBQ(c_es08}ZwU-yQ|KzonW(75XF2N?ut?E~!()_NqO1Jja-t|@6 z?0ax}23@@41T8qmdt@wzNeG><4PWP6jrc|wLAP~7V+5C3lArh@D zF6Ha`AwbRX;k2WHEXA%q(v(5a)#OzB-iH zHBYf9UpmBMgJC3@q2>kvx!-MECNfsq_C)qCLSu|`o0`&0Augz=YUdiYapM%3+jKE< zzb81FHE^u-8w5N0#<6pv$y5&9u%}cbeM)H*;86DH)WvVZvUM_snwb+zKqg!nDb*>o zxuGsIwUKwEmIF6J$P(-FrW+kWS?J1Xtwo|g{e>{|>|8w?>g4b#0l+R=9XXL2 zD72UsW{IsWt@n7>3aY&4h{jIt+g%2( zkVDx3;F&{K{{k$h)+tzvg!fJw`8P{bJ%3qW-84-<|CmOeOynlgBKx4YGlI!9JmN-~ zZjF+-rJ<5%&9q_=0Z44`7X}y1J3Seh5PGX5a{`-xG_?LGQIC>T1Sng9r$wHz1(Zj z9D~-;uhuRr51f~DifM12!TG&UwKFP`U@k8VzWtGU7}u|OY7m8Ms?ULbc=^%NW&Pw< zQl3rQVn6cbALE%*xq-LkI(&79L{dP|>uT(XD||J!^Wmm*Nb9!_2k`lJ6D;pwZ!$dJ z!Mhd=IU;*s`{s~0`E7fDNJGr&&34ZOVCS`I{-V&?GR?!2rhnKx4lBMTi3;)g8z73% zctHQmUEQuKjY75Ah`X?XH=zsE!{AKCa1}dS3-bQdgYGh;V3mGtK)?@D>W(mo1=1gz z=EiuQRoq^Mt+9L-lQ!e9KPJZ&{qbGD!mn?Jj$Qt2Y3Pcw#BvTuUjRTkG-otXNdYH% zQ1{AUCM2d}e%FA-z!2cjD~qZXz~?O4BOxgfz=73j#3uP6#5ax4@~hJMcTrfRxv7P1 zd;BwQk-Su{`&zBh1}S*$wuYw7jwMrhhfLnniv+_YlN=YPO8Dj6iq-=|1A1b8F+#t5 z0F*vE_WW&GQ>` zLI!4pdtUboja6#N+$QM3x<(#m0Jw z9q3U}sNJISvqQDd{RRA=0GzTIte@G1#D(X*%G*lZbXncpij9P9pOl zSF*ue_2)E=RKY7k)i10LXOJdBFDm!U^2=r!EWw0{iE; zmiu&cTWHoa7GP{`HKt0R)YORuw#g((G?sCV{Dbri?v{3L9i6k1ZTla9e61GGjkL%&NJr8rO*86Gh@%}wJ64$pq<7JG$9 zGXY!p=GdAYgX3E647Z?&ow#dWSgt6i1P|4{X_`uEDsg=fIyv&xx2oIgO8G~9E)~?{ zTxHp%1~j|p6ALSzEAgkziwAO7j&{`d`?JXNdW!5nbu+EZIxK`K*u|m=2%qe0k!E(7 zG=RxVe|TDnLGn^7OF-%)oxA%qjI=Kz`VOw%D;wbl)5n|HwH?|EqBf9irXiY6yV4`v z$O2Oz#nPv!RlH{4VpLUs@Ku%|F0IIBSC1;SjHDba>s0cuiNylGoe%mR5h`=@^|(b^ zw*Hn|NFJMFw&9gJHwlP|>bx;NtW7pk%+OzOV;4OwFBomEpXHWxcx45+X}K&uDsGd} zA9-o)eXputL6%PkUNz^H-V+|PKB&&5F^Fu)`-4f)c9;OtZQ@QLwj%aivnWib2EbQpvWbJACzK2=$^6% zxWS?F!tNj&pW+3TT)vu<3*9=3{(Ls?@Aw{_toDh#vYWXS_DrEdouREV;V z{Mi^EJ|W^@UpH!nY8Cdn(O7%01TY(MeiG6r9V5LVvsO$Po$qDd(nyt3Sp5ob5^oA& zD+p9$;SD>N7N^wp(8i>KOEO+VO+{C1n!02T<(Nq=Kl3}O=S#|c-W$M^N@NW7{9LyR z^eI?6RoPGPux@($ki5S{;8Xzu1ZeH>+wDZvjoQkoE_9n~mnjWLz2<7|L~|J$qRV|h zqFPWsBdr2$(hu)lA?9&)GjmxpNF4nxGAv@QZ)0)f*q3a_BqfESkN(i%#>cFQrlsi1 zmH_&1IZZE7LXAL=m_M;jL>{U0PX3RPfZG3$tv= zVmn0Xh@j^CO-&v*8anR!Sq-!D3J9&tSD>|I;&r33%_0fqyQRx;?rbNV$$XbD8KV|) z+J-VFmLjlnkM})i{(DwS11!kAHaN4jdHTc7ZM}naBv74S#y0UsnaXO%(%>YRnYq#W zPQD@Py@uTl0zh}@U@OoFp^V|!M)c#$%YALzC1VgABmX8gQ$B--5|eY-{)t$NuN^m; z3l9>GTk&|rl&Y|6>8W~aLetW=nTl=3xp=T4ZlA=4L@wTb%{EhZ%mc|SksnuN!=~8! z^0dL4K&_Bh;nN}ZaVwsiJ(5Y7E}!|d=LM0iaj(J>V^l1kO0Vlcb;AMetjVMIrP!_6 zT-@~sZI_>$$3Az?X5fArMWi8B)46NzSgB4+t`)u(6fyAq-Fp6YT)_7!^QsX4Lm?C~S-r%bm)FMSaX zu#5$`8@Fu?cHi;Cs?^xbYRmgqdLFyI>=hqfHbnOiMT{z#0W|0Hl=rKtp9>1(j~rWn zR@Bp&{D85;{j)7#jovko?(9RhD?Bc4cER}d!v*k@dlY1m zKD!$3qk0#*=|_P)Lpuxl;d_*K_^)wz(8cP|H3WQe(j}O|e>81z27L>U89*kem&(=PMWGkT{2zPv=oTW#X)2(7QyNqh&$ zjnwiWy@arLoya3Ln-8B|HIYC6EJ#c6{;O`Cv-(!*Fi`vAlRiseQraHYwSTX@m(QE` zGKlLc?_*HW+FtoKd+V4gZJ`^%6Cz`1v^nL-eXpkj7rt5-nmCUwUc@p#k14kqO6x5d zD7pm^Xom>PgM}o4nWg%Bbu>FaX3Yf?QG4@4c}oq8gw5S<`vs$rmDV><)KW3_gv0Aw zgFnw=Cfcnx$UcEfB|a9=r_z`J8hHPtm_OWg{S+PxPqBnJ=4XWO=WD_S0@A%4=L zuZXmMuU3KwbQ=ma1?*)LY@~>u`X(;1uTc$Eo8NlEGqoEOaxexSHLsP%XoMtUom}JG z$zt}j0UNR&)DV6yiLCVHR}!0`c5X;3ef~Bg51UBKQlMqymjY0h&Ek|i!|tJ3$0U#zM1}aOtIOc#o+fGxnAG$j(aS05 zE3HC&lHAq{YDd8^%}oiF>Ek3G5wtB`;425wqby^^+a;@z8kgAu$>dnXEPKjs70;0L zZ#BZ^)(gj7&e)4Ka zI-aE;gNY$geYJ7~)p%2Pg1AQE68Eh&U;{m?9bMG7q3sHzYhp@Rg}w1`(ff+T;AD!%A|thk5Wsv1dgK%88K61@DI~P$XG5VcGts zOm#Bpcxr9;VtV}--9+rO7l!Zdm+W})*z{-K)64jiZ^uhZZ=xzif5e)b?_5r;OY^y1 zq=FqP0Jy0fwhuTCem;+56{w&syeq1;nqZ5e;z)V`&w(w>$Bq7Q$1TcF#KhLUc8f+W zWf##S_rSSJOI8e~;lX(}0P*~y>rp8U>o;rd0n}RGQ(eqXylK6^T7- zd)Q05qc0bY&5hl0<)mbN&AjCIAnZf{i=L2gUe19B)k(5d=9SUM^nM~LMRL6#Xq`!U zC_ZSZdk0J64-fz8**q47tdhTTm$0!V@eaOoGQKc zxJQ2c!B!rd$Xz`X-&TA1(_Wqy*9p&7TmqOL0xENlF>zX#tF2H8g9TNZJ83^FH;IbB zvizhegJD7agpL#z(Otc<7|c5I4uRbK=AAJTSEt3nH*enbZfek`d5mkl%Z4F_phscf zBlEl9I zbccsK>_dZER!63_QJtycJATff0mdrZZ9Pe>-dw~n8Sybhy$By3o_QpRYwI_T2d{+y zN0XRz@G@W3Zfs(OUpiBLvY0`nMxH#*(b0E_{`mK1+#O3p6EG$=X)RhtCQ@7CUgdIr zE&7ly1A!Wc)R}ID^)GnK!vGhoe5+k7Gg-L7Q-}wTK#&u@Jhh-wujBMG(ua$q*u*S@ zr7M2i$VEPL3w8Ms*fm_-#+qK|9`)($d)4)B4#a*-LIl7DxgxleeEiD8$%^^u4>pybTI(%0FYn^P)US6 zJ~a^zX`xb>I1mUZq>d>D8bD|O+Nq0Fu!s3TE8BX0T8#Mw+LXr>sttn8;ufT7zV)YDr|yrP=x~kPiiM^ z%s4s?L4d9zHZKxwLSS0!zF6I(bSc~2?*#~uBO9|{!=)67S}&+l)DtRE?7hD>-&?9Yv*@^B@KujM_A}gtFh#zvli1r+enn$m*5wxxdIOJx36}cy#4%Cgm2Cq8-nMe)2$BoOiF5&&>S07y)+ z_b2iI6SoN<()JXM>5=&~I`(%z$!Z#LZP&^n4H53b_)m*R4c9v50+Xr0ZDrJ zbT|m711uZ}N?;fw0m@j{HVi1}6_57>0AfbME^ae_q&-2$Fm=#kp|oupaMq$KOSvSN zjMH4@0TBVvK$!yvz#0|6Uo(SmK7+t+&lOVY6v_e@3m||7V$i&~1)$X}QafTPH0n~r zMm1$KKO)2p1xlMm#x6_L0RWGBd9f4t&LF5_FkB@@XaHCnLTWvonC5r8T2WyIrCSSn zY7#p`x_2UvlHg@1)&j;bQ6=z9-Hw_P{OzxnplwgF6$yqI@NIPe88tKTb^bb0_|Yq-P_m}zHlN_ z6V9AXNnzf2ZQ-Qbb=|1Dt4-`fAH2lm4&{(;XGd6}Z8KpRO0Ic)aO z>Tb*%5fV~Wp~&`fktv@=PrI?ifp?XIvAcgT{+KB&M;hH~CH#J=b$gEIAd6M67@*}R z$M>`w7@9BxG)j%~llDK@y{VyiQd#iK0XBr^kV)wqXB|g8{o?b~G{A=_zb$vCL2gZS zm~yrvN?Z6^{6)k-HCsC;^4L$(3H#@=RS6#NvO9hlHr{<&qx6RD`;KZngnJHlNFSGz$klTsieJrlu&M3 zqQ4r<`5=6!_sK~+e!i8~afzVyBR8h%F=)R7@%L{v%f?ilu{62-;5_UEBGuYFI; zBb}vPP6@xh-rRLns7rg>@>o;XJC7CN_5(es8ed7SNYDKepQo}@O8<-$zP|59?SVnQ z?n80xPA(t!w=vCH$KHO4+)TP{mthw3GFhQZ@ki2(ZrPn40U7e8#MnyDtzWdp!C}aj zN+`EaRgW*@`sAgwZugyW_JuEoU>Be@IgBcGo%=j~Ucz2gUJs?`Ho1A#f_wPZHyLBK z-M`pblD-L!dPshcm|c_QuX$vwE;-Di@fTb5-K)~=VIow&eDSaEc%`GIukbJ(7hA&` zo|K(#xUk{2dCi&IN0fgcP+qm^3{tiWU8!kjVY;o7&D*giBy1@$=6&;Q+@&%%wS++F zpC4MTM%)Iy`mU}o89%5$=jui=0#XaY+-~bf;Ai--$lH;@RJ+ik^~3n~EWYSVXSg1O zBL|(@n!~T&2=;1nN^tz+YGSs$KZ5(-fVfV6fN|i8=A*5Vtg2!ezmWH{@uqhJVHe}h zZ*zUBjf25+DXePRRN6&(;-Q_js7%q6lk9VoH{&(F%_+5>q;$`HX-;cK7Y1K7T0NtE zd+n~-6VLB@vR;`hkpYuJIZf(?6RVvoYnDIOPMlJFF7%OGH?N7E-PP@N$0s*6j<#A0 zm25k-Xa-};{Y~T%qD-e+U)i^is0T2E^qIZ!RxeKt*vI*YYMSWff43y=@t5}Im5Rzg zO}2kPlm4UO{NI}Y>ts7UJEweB$?k84^Jf+R*>S$?pB?AT4#NNLh4$8^e@yiM4afO& z|JiX~{hadu0mpfDRmHRaaFV~^7VLjpd@o8C;&Mvj3I>5UL;VA8i~nt?|719S>a)eg zbV+5WhjDLCWO^L&G*9x#6#FSC#>@o(EU`fprVrG>q|oCehncwHa+bn+^? zcUaJYV9`XZI%_vbY!D*AmGYo!3r9smppppoptzvrG=;*fdx?gCP!m8yk$Vo$R0i|t zArDvVCU`{%9K#X;NT#G$beuM9B@&r#Xg4}~Ixh@#5vFj7bZQ{HSv8gR8&GKgy&VVu z4nX5{BBcS~h7>8l9tOkFilB86+rZrXs1%l81OsBzJHgo!5;_hy20H8rFcG3pHG?HG z0Jn%l0MP(|HgQ$p1kw%$ae&g|h;D!Y0Y_ZL?Y&$%Xa+O_3;={%sn|;-o0o_XoeYs6 zm`0BTBmjfW%<{cZZ;g-@m>`Oog$3~2WotlO!U0kw6W#`37(!D3OaM#(sxbiU1`;SF zDwE0pn;d&VVdCID)BnA^9u4S#WYY_QsWrezW&jEVa3op>aWB7L3?#w+fY}UyPb;8y z09b*+ECYZ-fzT6|0F6eQO?IV#A^^xC`Flg90%kYOhPe&)l0^VOXEzrb4&D2N6T>kc z?0jt^QMOQ99~I#M-Q$3O-l}fh4Wd?{b7Ygh<@hE#8JIWO>?A!}G#voBEPllVes40Jhl0QoSi+H(inNDL!wk5jS0Xl_mS#rJqyQ$Mta(FY_?2x; zow@{!!=&2z7p+X9?EJ$gi-HjSUk+&NBip&Y?8G4?x-i-vhrbB(eXQc){T6U?TH(&# zuY0zu|JF19BvRDzj2$Xxu{c}&Ydg17o$b`CesA65j4W;^{3fxtMboPHV>23VX`wGP z9KnIb5RJHl0PGcN4LqvdFV4OT`cW?B2mqyttleGUuh8!3+L3OGr+Hlu<|MDDaw$A+ zXWXLpiH(#MhZ%G#lqOEKywzhh^^8ZoOnnlYU(TvO*;+Avqe+ykWu?N||AkWlmvM%D zE`6@`XwuNF`z^K8WW{*B*P`85)9s!VTt3tNO;A##qV`)Gk(t$8?myR+sWq&NKaaQW zcVqQTHB5gFVr6mg`7c}tOPSr?7_y9RD$wH&z5o;Wrdi0lQp&Te1okw;Ir3skdnM;=1+3;c%=Fwmd;F zSEG+@UG1^L@)a$9;pBX7K^wK!Co|XRRP1+_r7_ZeC!EA2u=h? zf<%vUDuEJyC&~5<(>Zo;lA)Q{y0+Piizq_TR?C=&w0G(ey+kXOc2dFdA9Y3RYx{Ws zFic+SXJV;jl(+a)Rwd3oBV1aGtkUj%_U6l!6l**QhEghHpmu6G03=I!6xnn#1Alg` z)@p+E*3i(w*EBX~&d)cndNMzixtmRb=|#Kl;6krvB(6iLXF?|CrO5X19XDM9u8)Yr zQupd_imMh0xV|PIXLu#xuMa8J+)VCp_xF3Bhs9>UrNj2)0HhMYcJrHQ(hmtj2t3>+ zHfpU#aQz7p!HQ`J&IN*_rlQJR|5&{cs*l7c@mcr#@<$#2+{MrNfk}64pqga(;Q*jp zh~Bg`4L?_3aPxWP1c==RLqUB#tt38aoe3fnbsbJ}9#>pe z*aV<=_Vaxn{C!7F(y7UVWDHA!9!g(^v7f!hm7Jq@PfIO%eg%(ZZMS=qbnbFWN7(o zw*t-@ua_W3T}Nm^^VooC%J@?FqN&mU}O3r!o?i{qu*dE?2;4TUtoe98BI z-3`Gb@!KWQr`!(+MaaBUe@$LA&2!PHofhI@;rx2(ijf5J)?7zuOKcip6GSaMC)$nR z>+5cT`lHnRvZ6Y$pe`9LggjSQ9`cv;vAk=ucY#ECWjP zTh|9#HG`c`gvO|)J^6fpob8w?L{ zRD_5fvaz4KNa8P7T)IDJ>lOM!3^anvU#K`oW_yLoScC~gpw_xam)EjV5hFqmK5(d) zU}IiSxL;&tQ*82Wc*Fqc(obxKNaS!WBRcN<_6_2&lOL|xp}Dr-wF(y%SS!bB)!$!d zrEE}~JB>Ugg+xlJ4Zk&(J-N4PulKv;o#vFjfbqs$$hMTuSy(MupS3oe%Vb=REh}(S z?GJHQIZT&c!RxKrgGu9^AVXrZRS{%WSGXWe6I;o0L5-p+-Cc}V0NB0Nk>!UYEs2TI znH12=v+&}S_pw$O8WTFs+3a42d;g`+KIP81dQ?fc&&14jy}?H9azjZB+-ZC-msio| zeES|#x8#C=M7>u1hBmimhvZYRg{kKmM7WELp`ivzPQ+| zrN!vxn;ltyx?UXfc^bEm2Z&J!D;mQx6A40I*KkDa*xs(+&e{D$3b;K!IwQ8Ve%QnJ zOM$cL+fvystuTY&iLfxiG~+TN2>`s6%6B7n4wVy{#A&nU%X*ewxt>1IdN;$7Iu=$| z9+qvWkSwuJj7#6pZ?fN8$fqQiAAnNqiZjYHrgH0LSqbrpB0LsT*aA_)j$FAvA+zTH zHM;rQy3*iJ19qlqsyXl3wR&5`OSdQ5aU^-+=M3{WuGR*h%CwOWYzmAf*VYvwK@B36 zR#M{aU}(^Dn5U!|FrT;Rc#FxZ@G*~BZ`{+uPRL|5OGY~H#_HH_#DRWL6f@Z*!_(}FcLkubqy70IO5tBR0A>j+g}HHj6o(;&9R&j8S)qNw%Z`s&Wa}TMZ`U-uDumcCJf5o@;eh z*;W5(Xqb>ZMFmzzOh?-+GAs0S7hBCMjwjY#I}y~?oRqLsyn^|UE&=^I(ywI zk+a~wvxh4HbZ=$CFLN6>d@-R%{9F$NQ)hLZRVZ2l7|~WL6K2im#rYKD014~wpF?;W z@ub+pGz&~Av^E80ldQkBiRb)aA;F_^OAe0ak6_g&-xq^!?pIgTgWT zT&y`SVtcrL-Gi_k0Gnc&z$?wCBE_?^LcV1ELlEr5Gr_3!F}(yKH`ZI1*S5ENl%;x1 zGLmJ(a4V=L3SiDoOn|ZCc%A&IS02lFojip8;wrODZXC-%Q)Z{*BEpR(js}PIaOdN# zRPcZ6CQx1v@gn7O@C~C>xTT3k0?axp#fny!%o{bJ@j8I%0PCp8k0=0WF{TpBG{{;P zSHQ()%rGj|*-$A->>3ok4kBdK9O}A!6DlHtU1${m^tN1jtGWDr6xN1$COc}(Crk&8 zqgKH2q(u&(Eh9e>7~dXXjvB#{wi?D5yC^ief#Cmd|fw|O0C@H@(ZLZ5rvM)*=t{((zaNvgZ+~@pBxl=A3w#o7Sfi1?# zT`k#>U>?wcwF7gDFtsVgHJ)g)#jon*V$>xZbn`4k!xpDAqUJWh7ESNuGbkY20W#K@90p#q$dEsQ~P_hO&AIb-(cXbW)+X!7EY5_(79Tajy7Q`;8x4hKIb5tQxcj45+^j zSi#jbTMK?RV6%)(v+56URcx0+Z3->EKAKY>tb1y;#7ESNnFZ*3^$4lN2NVDzW&HEC zUh(GO9i7(!1L{}8oiC=Dpttr4&b6k=#1OokIC`QI0)PpR*=*HcsUV;Mj0M0}f%0VR z>jO;+NT{pJj_v@HErER@-xuvI{dVG9QK@@)Ih?M94+*pOT}I%xaxlmOnhj8h-hV1e*bXqaUC`A5aD{QB>p``>XSg6GL>^bLtz*(xkyiiX7tAghwHHpXtjQY@m4AZGnV4($z`ufa^jhkhDgwo4RDMvvFMnc4-lY( zM05#Y(06YN27FKtr$Lm+patcCcn$ypB;F=B2Mer>IfM;Z>_*m0ZcN$+R>p-LHF|6KzKkS z+R)I@(9sWq!m3F6uiySA(`Ca3wmd;53w(oEzE|?lr=~N8BR7{Htsw-;Cd=r=QC!_1 z4ow0(k$!YQL(|5YIH+mvPN$)vp#ewzVU8_@D}-jH7*Y%bfGlbuj{uTs4{M_g3SJ)) zPS)GEVlUVwDB0$@LA_c*hGUV%VJPsB;>z1q) z>6q>vdezfr@RDtSD-?slq_DplRuS^(YF>dA_?NHz2;U2h;UxqDA$-m)@%6hfeaQzk6om;`S-%(k~Rhw1I#o0~gohi#Y4iDzS^IMe)d4&>v% zZ7Lta7cQvvyB!Q}(H7y0&0Rg;cR)o_`=L+BWJ*#>l7&c!kk_l6P5-nXdUWf_O=5;f zg5@pzFl)lu>3uvv1hUZ^P>;Qzif4X|bBRrqUO=^Ty$doLH|oGPu!-tkLP!J-!jUbD z0FF__e6xu>?0dhh3!wWeVq(5(v7ac8XG?sy+KOCzk<$&2gPBT*{;4*LK<)P##=)o= z3ay>PXpS!_1@~&kN-MYvO$Xq~fYYweAk$h|Y2o?oL|c>C)>Sd=?#Y|tjiD4$yTACN z4uy%!N?|@D`R{jS;_2l9_TR@{0(YTxeZ!fe>Y(B1&>6<^Z$HpL9D7A-A_9QrYxN znBL3tv%c&CX1QU7th#*3^+j}I$v6Pp7|eaifOw9BkE(V{c{rQh3A?o1$z+5@SRQ41 zORbOS^P50n->)LUEk51OEtaySCa1f2;X&cBa#u40L>9(jQj)xr4wWT{RJf{|Baw2f zM-d2NLud``Se+@5V-Uaf6r=)KQLX*X?#wXGU1)FNzKSme%&VWyxeizx=)G`by(#<) zO@DIXcRFu*m*TMKWwEB>g`hKmzTYM-$r7;q(_Dxl zqs|_A)g6O^QEKKj=^R}^GP_~Q}pH-*3vF3b^*G60h6nL?0 znG5@;n8G~Ue#b?FrcYBMn33kx2JV`eda zjmBaf?SZ2sn~L0KN-`BDqPGpDdiXf|L8ye5mOw&=Jq)&lQ4}!%uQ7AQnDb(Q?(+)Y z=hs%$Vk)W{K!)BbcJMH9Hl&m{7xFQSQ9KO*R<%*zhfI*TgNf%7WO=wwj>)J65NO`p zH!EmvF*rM_P=pdOa$;2P8Jmo!_l8o|L*qbGJBX~I7g0rOs}2NMEI=poPbD|+UPyA; zcT+HQQD2%;9j|}PN-@DGj=M*h;>YajE=1Ax`gEAnoa>rwX;mi?Tg%398Dim~oZ{`Q zb3e|dIYe#}#Pb2swVBa}9YhRLJubx!bVR{E5#pu^8E%=u;YKr09Ls!WzUpI>b8G^;gTpWc>%ur17GgFN=wM~MoF)KPHpwdb3>8BY1gC@#cDq}# zro+Nt?qpr%M;aqHpIouq01``A>J~38p|s^wKI4112b3m?`N%5Y70*vg0v8j~ahuhz zSMnJ!#DJVLNK744SP=8*YVSVT#lZ-T;GhhM_S4W%<(OWUfIz1VX|!Hr7r(Uu(P)%5 zJ1Ptr&;ihEiVVm->6Sn@&0dixP6}!-8H39Mtyo*jif|OLTcZG|^hI?lD4OXdENbs< z8*GLSdL~aDJps$!b^(L( zH3Wi{FDcup?&nS0u%iJR;Y>g$pb4OwI{7BWmNJZLKHA{9z__^%0E}Z^(_%oxPD8_E z`eap``cZUg@)~*@ZNc39_yV|3%cx?KTU`e4l;EJ0@zAFJWY)-}|~oQmzj+7AcV+r`U)AVgPJZM>t>UP!^(_m54q2P1fh^6Y4%ScEH3WjW2Ih>c|9)q%yZq7Q zqS$}AJNTz(XEb?c?`s|=axcUD$CFvTgaYd<^7Ac;2rwrjdU?Fok~n?t0*dqGT$wN= ze(h!7A<5lk{WSn~?*%dK9=E5;ddR(dFp^Zf zx8}xa?qQ;3opSTpIRXX)z?^PWhu*L3lc``wUVaw>vyE`+-qhDDu{Po=Q>;ljgxW2& z6)D}VFd7hj7z6;AGq!zA^S;xyb9`!l^_%sRwq%oU-KP#apU^twJ~9-{lFAe9_z)xZ z>=0^Q#kI}YY;6ubvwom!z0zdoxG}$0OHeA9WpkM_-R{iTg`|1Lo-Vj|=L_F&JU^9q z2O!Ji>x3VaT8nBYe7(`TYm_L~J=(pJn0bv)+#}?U`KuQm$fTEk0ry)k=~Vl$Y=RX+ zWh7jsqd}mKnP=+UcGA@rZ!UprSL49YO5JGFMX*^0&DuHINR0VidlA!NDgRol6VjTS zVH(S7p9I}M2DqQgx0xjzLy}k}OPQ8IJz@Troj#hJrXO^>v#x$2?1-0_hTd43@(I63 ziGn{v9~-9Mt-r7xuYB{^dPR3r>HW%MNBvHDf9UM^)>bZnRCYLf$F%s;m)#QkI0PT- zv5TxpG75rjLlDU1y7N2q4Qi7q|a-E&uQX&=EVeD)*PJM{3!dWN@vUR@<$QB&e%$=gQ7&ccBxZI1sfCv7 z-IASMfBR(|_u~k&)uH~N_S1vZ;n$7=S984vgH~*cNTSc_kGmpBQDxEUx)Tv{UpE|b z83D4`Z&Md;FJYpY;o?gXBr+;mK zdJ@eL3`K=rv{_BhJS=!f=GSJk&9q_BLW4HNcI$vzbRw6+6^CVh0Y*X*^Weo^O||N| zx2JUY1kZ%lHdC(B@UWKDyPiUA&C4d{r@Jm4$c$WgYQd4EeEZ(lFJYHoxWnNs^l`3C z`NGSh?iW^BH}F+UId9qWPrd(QXx3TB`LU#v7+t)2#%uKJ3AJ@N_DuMwY0=}SLw9*M zf}?*l+?MSk{i&w$xrtKaE8dM{bwD@k%ry+Nc7#qPxZKvm_wFE9k1X2mdby{e5HESh3mF> zcIi3ZPgeEg#kWu?LZ?6T?|y49wP;HU)RaAteXjL`!!^6txC416e9liQ4qF6Tr(eWB zazEpLC14$YLd{G3iv0r5)POC|u}0IyN9V1y3Z5fk@vCdi)ACW@9%~W2cko7uE+^jQ z%nuG{-<1`BR1I$&{}p9SFwoBubDu*9WGJ;=y8KpPpY^S@N3lmfa{Oh@mg(r;d^F+M zK!)M%AX%y%ly4CoS%ckb5mB>zR{@fY$9&|;YdR7y#7ID@&N%zg=caH>*kJuFMfdaGuXu$Hj4a#w#gq|| zZ7pu>+g5eit2ZaoGW0nsC(+$D&(a-AMSE1RAAp-`g@BYgIUtg@a5d^C-w)7 zT<&GJ`u2V$UMoD_nvA$_&A?pi!v^+4!8&1 z?fFc7XkQpQB)g_q)O%V%;CF|-_1w+GuIbmtndXHVlMfSm%g;T%m6TA^#;cWH)XtT} zIq4RUP5;Dy_)D|038{7*ID&jrbQoaSxm+fbIMv$uy#0*h6I#*Cuz6pwvM^;NU)T^y`PHT-H@xzl+};hngpK-YGYk z7#o|GiqbfyB7Fj#d#n+Me&haHL+JOM^|*RIA-U8r^`^(y*4GyLTCOCqsUG8}alI?C z3rPg7i9ba#t0U`^*B4(_7V%mih;-Wg`vWfx~h zaMF#EZt254AL^9OH-B8rEMI7Edl2|=|Jze~vPoX8_c`<>goP<~h-PU^`QVh6(L*N- zzBEa4oJ-}g**6>{=6l}XBj&xw zk!Nh_qSpePJ~Uy~hc#0k1>SlYU3t^}~xS?Mjbh_htKNqBo7Uqi$Z4+mpe zj+Fd*S$d))Q1JcvC#@gFRg8xomU5_u@5?vio;M7vA75X&;jZ>zjP_wWsyMmEm-dtG zSZUCC-ftC?74HM9LmpJl=ltdQO7`SpWvoJx!11u%LzooN!_)HZ(1%Y}1*)ReBl`#2 zKX$XxZns~-9&BDes3Z?`g~U>WQzTq6F}Sst?9Y-Fq4p7Di0@ijy2@E70FmxPmb*gx z47pkBysP288kswEl;hC~>zM){Uw8a{iDyW`bp<;~`TVO|nLN^-S>|WHpAatIj&on; za`kgIHZ_XdknS$d>Eh85R5o)}2zh=^phSGcOC`bZQEP{zy5Y26(wv4sbG#>JXu~En ze)4`Nuct6JPhO9;_1yTydGhsRSFfO+ilhK}E zT_4pN)6{kDs|~McVEP^>#v8s5r!%(=_Ar*t{Y!! zKJ>@s_oP2l6uH2+;}b9Q>C(qkDWZhAaHvMmqf12kBBeFBs zgsl8WS0*d}-Qz6k_er(+%IYR<`y^Jx{ut6IGS?eI3f!0Jx8UTBdyG1CFlJ%;sLtGo zH(UT`ICyv{7XY0Pq5Ee1?}yP3hM9T?{p#!MeYg6h(nvLxGyYHRd*1rjj|vXmk2bj@ zF>_%(>Cwkx1Vdf+I!bd(u%@%ys=cesqF0PPe0eZ?-S(O3V}WfBiRV3A?q)33%f541 zgWK+Rq;k;4qbH|q-bIutf0c>65ir)_4z0!fk@u-4K5KivSTwlnuI=uwRO&r{F~sqL zOJpZmfr@(dyz`arjc3 zSXaOzP($|=TpZTnlNXy*y1@)OY(}TyZmaZKUb@=&K z;?IYhrj_AZX+JSRa;V`ObbIQma^W$^A5na=xbn(%Riy#X>P5l!y5&pTMx=+;H-6mZ zqJCGgF?vk+=s&h79V9!jpv%Y0SwlWipXY`(igL7gyFUB%^v7qH<(|!wtePBceI7sZ zdPmZ?&i)?E@a>rQc@TrXw(;9AA>rtaqOV0`{`%a{kN;Uc9AA62^Yu6Sc5zC#k0hQu zAlx}T*6+|cH?=GLx2yhKsVdRAr-nH8;BMvYku~HfZ#a2G?H=E)jj|#k)1!d|d){C7 zcckpNuBnK>IFQC(<@&hU%soZe3B(>e`~I2m=ew3H(I0ZTlcs68V$Xgz#ojLK zu99{$z;q{SA>KZ@-MxNf>F76y_sYt^%RR`(+?uGVhjDL*%-Zu7;}G{{iW)(m5p! zjsK|K-5cvaXm_7YDqr<9f7=tFeCT23)wGK_r_V~tPUXmOiDK!Lm_Q;9RJBq-#snh< zLep7kvt?PVgPH)qO9`lcr!5aNZj?tCnoip_jOqeP5Fj<9(aiDaM+yMG!vKo_(3$~_ zqQL;vX$q4;V^<&m^oVh~F&Ucaj*#i}*9A->fx6BXwv!9|B6I`U>oc{si3($G08Ap0 z<9Qw6Yi5IM9R#&L7XxrO*nNm9r%)dNuzrR2F%g8UZps4^laL;YTa3X9lP{t{Z(7kP zY=BK2NHiftqIV4=3DCR+L|AuAANbe=$6|k{JtETJXh*SfFydzrLj!$(auwpRv_S|0 zE02?ct8h4HF#zDI76lM7{Gt*i0oz!pos`3&KrN>wh&5~}Q~?~*s1e0A zAQT0TQ(?>dM^`(jV-u(-$N`Yt2pl1CAOMh|bkoO*9=w2wV*nWP>41pf%SR)C1(-kv zkx2wJmt+`n>^r-!0ixTi@lH^q+G7F$v1IkrB(D45=<95{ zACC5;roU-+Eh}J1Owa&gm`xGK+0Yv1&6NL#qj&LVy7B-2zn?2~0a@v&*LpfG7IbO0HM`3c>+mK0h$zqzrE{6(hhRoP(uix$ZJ^zR2 z?RmRBp7-bdxr|Wqk_U@`^7^TM%I2%WSDQkhQCuS4^54gh_@hn?_<0Nl!>a=R?Ga)2 zY`uuR5qG@r#BCk=JI`D^>;NWhDW(aBFl>F=f`$xB-am7AS7b$DiS9HZnt|nR9oGB) z-a4NW1e=Fx%KpB!!n7~VEeV#h0EJkDCQG<_8J_zO+hB_@j6G%l5di=&jI??&App?y z>>#jriaKu~!myru2ffGa;sIcp2=G~$e?_9#<_<~yBKe%y_FIcHi= zRk~G5oF5zc220h*L7n-y-8N=hWN<^`bkn)J7xlWt(Z|u1&%E1ZueEd1Zm51?7Gxbf z2HH=OklBtsjD_OVz2K0^Ncu&tkLXVAo5*GCG3ciss2x>d`!*dAQUErk@QQR38IpbN z;-`bQaw+*Ei$NE$4hl?k9ieKScSA9+&^E&2B&Z9xy6H|%v@DDV>Kx{n33ZhW3=m}u zwRzj!q@l+UGTsjSnFnx11Q#0?ai@|I)cWa3l=IIptdlvqbsQkCS&0N*7!sGh_n<_l zJbwM~60QUYv&G|wxAS3~R*df&(0JtLH zqr)~JaH22(0STDFYz{81?MY3(07L+V0*C-%Y6ueercDvc1H0=E{5_R*9R@={p;d0J zIVMZ_a@H_QG7fCOX%_)#(zLNNz%CLa2E1~CZ4t0{&jFx_H=z#?2&MP$`(wnAXDuVd zF;5-7g~LhA7L6|kniGltT>&@%7y-cBd%yyg-Vq=ERk^hlZH5^$*g_feSn}gh6w!a- zcLGlm=^TuqAOK-d>3=joZ!eV}MFIp0Q{VGa9oT2)DdK0{@?3xopfQ5^d0sbga8n3G zApjN&003@8cppoM5Y~(wUn%}JYw;U+6WK#yQD)rw7Q~k{Ij@K`-A7k0v-G&hxTEpF zX7><=zNsbVF$#lr=F;{~rq=bbfMh`gW}70S?EEs1py{T|EfplH_1Ux!E^-=g zRW=WXl=KUIg%r^tCNQGYu{{^Z;=&_hc?glO6! zjDo>nmW~!YfDeT8+041w8G1bwZtr@r*$}d_6^hz|$|2c5wFT+jk_!PNFLNSOZV+_jkqI8&+1{HKc3t>*!qBmTGXlQ%DebE7=*{?FN2O|;`PdD zw`k_e8%r-^qC@qM=2maKhWsNzvkD#T@aubCwM@LPMk_VeKLNW<8cx9g?0IL*GxdGU z*0I8224Xm)DTbkKF4DW_II~R`$o#7dPaT9%&{YEpyRLWd*YRh@-`?!mve=nd^7xoU zt7z0mq|r?X-whq$w5^Fuy2nesPWQT=sK$=3d3LLHAb)U!sJ6W5{pvj4eD*{XWwn7l zzo*LJO-?#pN7>y4zdkl04dk%7euQ@Vd36KHdw2Qyq7!_-0)J}NxMc>33y5=H6~3o; z!1oGoD2e>@lOioTU*~a;jJh`Omyv8u(mKRjp5H*?N52$^fg#xM{e?D(lV*}H_pB^* zZc>6NA^|Y*l`7ihGr0RnyKo0OdUDTmKaaEpbntbKwgLVdV%sMfi~H&!T8TdMr-YId zJI7Ml!jEeR=8{O_h&z#^Kl@MYa+PvyN*jxp2qiO?MDkVa7WcgClD-i%v#qqH|wjEAAhQ{+$X+GD5fygQMt{ss(tu z8;jLso2D=G+HU?V!Y2nt8VzJ=6K9W$DF#{;=5YV?MM& z*Xb-=_>JjIm#v9hC@`&Z%HLlC5F)bz5-9uAAwHNSnuv-h`rm+!M|G<3iD0{2)O;GM zNuafEiu-Pr1%jSSQftR=VlAahDdKa$_Syuq+JMU7JTs8rWh70KWdorZ$OB6V1|V)< zDJ#+ut}12u{<_K(246E9PY`UEFcAQQBHaFVT4#z|Gs56f@I?FCVm4x4mr8g|5}ILdFAqK-8NNUm&cT z#EzK0j?V;Hc9wcvMLGD+>)T?binXql1fUyO`!MHRB+6N0JZaQ%uEk99HgwC>O47$J zY|`;g!a!4GsN-1LZg^gx9PJ5C->_HRDQAmu<<@xq)|3Glyu06?W5FFMwBP;0{M+<1 z{>hMS?%NmHd((`%5HFi%oW+ta{)u=0`;6+{{1&#Js%wzPL=@#o%*n@Eo8i1o)|M5p zt9yfcJ^#P`m^i!JFFrBUh=7lNE)IqCF` zOE{Sq3Iw@Hi0qkAl*2R(AuFlmNq5fEY9<=*y{lQENbOXrz{h$ErW>N7C@${$4TiQc z-bbHhT)&{L5|soM&*s)7p(X6etJ+L55Tcph*vSz;FXPyS=m_0~;UT1?KzGuMVa5Kf;U`EaY(?IwEmK>3kmr<8(Kr>JDs)Lbk;j7VVb^agR9lu8) zL6x*Jo^R8r7qLZ>g_?7j7L#^xU&3k~*@P6TqSh_vj>E^Y`kB5{MX3oBfIcn)l~EnJAo;~ik$SPd6Uz`2 zsTL&xBAuREF=#1w8S6z6Y+oR`84)+*+{G-e>Vpqj0t)4-*;V!Ssba^5=UC2x2~KtE ze4KG>n`#fxzy3uA;d}L{+JvBcd?BjN!8YTLMgOtFW9!_B%S!?5g`9(V9HKC-GF2!# zE|>&<6UCK^H}9mTMkDtXB71d$2~S4dh5xLk?(g4%z0r~&)_13R%PH!5S0R&#n%KI2=x zye1gKS?&lAj@mkrFIsBeQ-f6Q>nve{G2d&A_TRcJT`9B_k3p>Q#8CH#$4|Z`Iu9Q^ z@Zv=?IJ#PrAa6%Kr%~Tzo|*R5_)jl1%D8?bVzlkb3vEO9(3WOMa65b&c|E2p$Y|FLExMlr;L(q10kH@begonq%s%H1U*hYyh zR&CnoHf@KR?0y*4g;^NbFK5Mv&Uh_E#82{pekx!o(3#`STN7T4?(42Rg=`?v`%$7G zEpbF^SFnj!At_FWOEF~s=cicbi#ZV&97fUvz*4Q=>y$k<(eE8MtE^$C&DHSB{7?PhMLeC;<|Vx<0r~L=@mxkr5}2GN&8esJFg4bq^1@R?!CG z4^mnVGyK>Iw|DwxwQ-joCvJN9w$@KyU({$a#$ED&IBcq^5~?*7Lhs26C8%I9I3P18 zdC|g1`roo%&0V&U$+pfk;{PWdwxWN$omUc{G`qcJRD!@PI_wTe#6K_=o5$rj!@aW^t|gl z=ceA0`D2vjqYRH(!tK!*_QGi?ji1|#lR*Dvl`de+dsGGc#&8lcr2_aAACGD#JugIE z)zmZCjM00cc-qcHdCjFylJZXRnCZyTmzX0Mo#!PIrUghzg|J6eVy8(5H)A0MW49kk{g)q&3$3m1J-$75v?SZUU+XV}2 z3OC#^#_T_E>hRjh6EYSYqA-Gv0h%ck_ukKY!QP+V|CY%rb^Uv9rLgkJkmdI)RUbeN zIkARxJ!<(_H?mffKxEywU1g_b2S+esgQTbWl1UmE(D|-+LT;bE{k7i~%_0E7HF;xb zvbxRS0Sw^ty21I|xymy4VaJ~qmPu%$+6JX?(=lG~Ufs_bUd%6S;flEQdMtLgab#I{ z59H9vmq1nmcti(jd4%4&?vcW%-d}Hbo~i@_0dg7_0D?*vFoGRsQwA*Mf1B`YzYMcC z+!~xt-je)cT2(e*lzhBe_K&9;uRT}4MDE?D%v7`gBpfb17C*&kz9Ywt5%Dp=aOuNu#{(o^&0`a!*R_9+II#wV zg;lT5CUTr!%_amRE~9~TsQ|Kj1h{7=V103iqX3=o>b+s>ioConmC+AiSg8)tVo~rq zi-!<##mx>gsk;DsA9LdmM}7ONf$sd|Xdc7AV}WRp>v`#YaZvoZLWcsZON*K?$pEHZk+>;ON-Jj}A#{!;Ht2`(H=Tt^8|1O5 zPtPVLwM-ZysQ*tJ>x zl>ipCzkWYi0Q9$IwhDokrV}71eD9^N<^$weLkro_oRde;$F&*2l~g`b>oSd9lvMNk z!DU#@*+D(qb`9-@lE^k0J@uhPK2Mm;S)+&narXl)2oE@NcOrIJWOp@6=X>0hc$Qd; zj1EEhjl2?HY#id<&`6COZ`VXhDi2l-H(n2GUGn@Ec?BFBt?UbwX!Um_r`p*F`0{LV zb5gU2h^Ep_!mhLFAzc_5dv*__3W)USw&1bE+p+$<>T=$COcjCRmy~lk6-n+q&4}ZPX zM1mkrv|rE{ChfZ(FDDXR%A+KLh#r1wk_lsx{jl$!f{u>&ikfcX1`KaPigIgJ1h za)Cg~a$AbRi9Pk2`X#9g9(ud&j;~0gMIB3Ac8C1lz31fVm`@ryd4B+?x7n^YJvA}a zCo?nMhkaF7u6~%CG=)*f!uJJ08u?mH&RparMfDtNd%e#pzd3623w*lEd zD!`W5R+uj1>}t*Jp7!-~%JUc7*T&K8rv_U$^Tc!4o(p6XfRunYUEbF`7LJwrj4qn5 z9=kdEAoIedq#P-iZKbed>d$(TcUMW@EPFgJMPFh<)uU6H@SxHLQFlHg3qaP&75WO_UnWKx}-n3jS3ZElf%Ab)@@a3_mk>Ci?mYYp%={IGzBrSH)HfelK?@6hYLo zPQQg$zVp*wuhQ-}^ll2dzn{|_{85X0cer5t$Oa$j-4Cbgd!EToDOVd^yu~2WYG zN+iA%C!X66!g+011N~-J#drH0SSXmsqt%}iwC?`E?k?eTacOi)hW>2&E*Excj@c%o zkn5qRY0TXFjDx`(!3NP|`xr{Y?@xW5+JpSLx|a}r>QNNT8ASOuRGg&u7;crL=W1H9 zQ_UHbBh;jvd2CRWJ$<}J*7%aeu+SfrrY8*C=0Fy8*V@mg4MEJ@(=6csQR^8QuKJSM zDxmsi@W8VCX3PBbRSgQ;>4EmIDyTGYh50}J zqfY0p25cWD@pq;}Q|%dF)>(LGIke&PpRhlxmIAx^Gc47%*mgAzz!+(sXt+?;tz7Pi z+2=(O$%Ud{hHs)V-II{MevM?$3yev5mE`0j!jZOXw)^UFKb_|HBBh0C8>A=7e7*s!M8is$b{hYo$o@4#(Sss@-9zw_CEU->EyQJ_ce@P#m8-Qyo#R!7SW_B zmRb~-oh;fFB}?*FKP5zj99brB0y_N;mAgIO7!iN{%?WXZ0N(3~5oxUkG>kC(LZz;M z9AMP;$vv|&#pqp9erb41uTFvQ(V}}UP=d5DM?^(ND=ksBizs150zXULKI<2-~~{HlcV}+;u4;6Vh466J`v)s1A6TB zwilLEKJSG0`1PlCp54|dpH?b3^!_seGc$t;27|TTZNOl#+31+j;jd-QFBqrNCAD29 zv;%iD{wR`+uhEw{Bd37%D44RS1KC01lh!#G&b@}#RmdD`tKoEqC%=ni45zk!(56(b zJ+W<4>`4Sf zjBW1V!RC6h!mgq6%|ZDQ;N7YHviegyIwH$<$J-=yw`^YuxktoG5bfuu)z32$f>LiW zSk29;j7m2P{fCuI+Tu`Irdk+OvKeQpxLPP&y4A%;K4k|AH~N|z!d0;#%P0OrX$?4( zbM;at7Fu-^hrl}Ok?Vf6w&sUq!U4;njF=5MA4)V=$5T z>}Oxv8=I7B)}+_~_!e%mnX z?Kt@5L2-`rn@h+;=sIlH&YLmvH}uotMaScYW>#=3=2rk))Qb!$YK4~iG(!IE7w2~HW#O4x`j~y zbj7lxBWgi|anwdW;bi?E#YkTRhePe#o0LSs=iGR+VC~<3nDw4m)_FE*2{WE7be3t?lzHOHJ5xN| zBW)xvqatLGcKI#*xqXZXakNEQS@%QPIfCwA$ijQdhH;@Q=uxVNpf=~im-q?Uz+wLc zo+Wp+hkO|hgv|A#+QxJ)gPr(jW4zl&xe=N;ZiVguyqroXl*HI(&O|DPBAT2Ba#xMB z{~)4rO!4=yde19~IcV%bG?0?a(^s_U6NN`4P9*oB?Sl{i2vU*#UZo+(yivqPBuz}X z$E;EM^Gbpf<}d`UINrq^9sLJYmMf2Mx>b%I4V`VhjtgkUp!=Ixs`?vGGW!vKaD z)`F#QdUTq}bvTFhZn61MM6*A@BP9Xr$pFIZp=tAt%ziEZnk#Tsy9HkOy=5Kmm=PhX z@tbaE^)<-Bw7#@9RE}Ni%Y^XV{oo7zqIz3y!Wq`a%QhhZ%x!rtaE*^Tb16L$iRN^6 zf3?5wkZ%@sgB6?VG=ps2b?b?`%FfFA7vQ5sh-QDi$X>gfr&^6g&dYMY?64YBZ94xf?h8ia zWS(tlBdN_cS@(4ZKs^@+K;!wW2ulBEE;5VnJtF2kO_&Qv6KsL9$dPoO=Qt8{Gi$ka z)@EuU0#P*`Ndib@@26RIZaJ)-(*Gu#I<$&vBm)a?5hbzMQM_rfXw?amx}TzrgZ*iA zqV-0QnF)E=ko9StGt=C2Dcvj3$#Vmm(c@u^l?GRHRuD}Vh$B;sYRc>bF!)L}JFg_} zOub$F8<46W%2;H_@h&1{)Vw?IFA}Z~2WZqbm`M`uWaUy-)kNuaC*l>_R|C56czhmo za3`a=4V6hqSrIHFhBKyfK`^AeR>qu0SY=`8lR>b~jiC3Jf3|et^L5zsFdzr$1^~dU zt@`Of-GD9Tb>+f3g6!UX&C@6GZRs)_(JvutV>jE!@1W8PHNz^>(*pnBM`_}Xz9KwnJ(Z97Nk1%t(X85AF9Hp6HK1=UAu-j)c>UaBhuqytBhFX4!W_&NE zwjZY*aA)W|9S-q4KrE}#a=M)du+i?G_g*>_>v+wj0&^C_W5=KRA3lAYHvUR8tSk$p z%M<3V-l2{}5evi8C8g3O39ADRj@)42cA)T=TiZoPQC@=+hZkklcRG#MY=IN4vYBJ;(iA3x6ut4FYheSLgh4t zJX-Nxo#7C#QXDVXe5-H+(li|)HARvt(^q^LsVttj*nO3x(;v7wVrSen%uaargYe)V z1{=PA&shtcTac~eCVcfmWk98N-xVyW7`=eg%h-HH=}6i&qU(rD&ewN!=c920lAu&z zJsnJQ&$vCBze5y7cmtBM7MBZC5hquM&NMr}?+8oeUr8zEUmaLOfFWPZl0yg2L(T-G=+~d$x!0T;7uyC{8 za1Q?9x19rI3TiJ2yOLUQ?`3iiw4ACqx~p$`2c=IVi#LztcqR4kI~U!JMq0vczIUScG;|Jyv+h(Wo%c>dAq_1Y^6j&Ptvq1FjnE@@TcLogIYiDu47^4=fpIR(1{g z@c>NW*Vk)*!dlGV7*dlR^^Kw*8@paEAMIt3qolZ5a{4!cjp8{mk>a8CZq>~&n-RS@%(7rB6zJzekba;HKnotVTYsX#= zqx7#{P@0-r9ueEm*@rQF=ftgH*{xl5E-!wcKJ9C6D*pZhq%+vs^donKG|i<tR>FTa$`zg1 z$0;re_2OH-!Pma}@c`xu`GOPZlD@M!Q|3{p#@8pyI-CALp9yh&!jF(jr3*;pRVFd3 z9ot7t2J(sg=)mM8pmLtgNwf7h9(Z+cJig(Hh`yUHz)3KcPc~F#K1mgh^DBK_M_}?hy5T{l#KDXcxIkbcEP2hP-AJl=w(ga z6qXLKN#U=qxi9r|NAtP+pH3Qa&oCTT9KsW16P^1J@is3V$9GPQ&OdLb&IN8;V^=*t z?9-)gQf{l`k*AZY0mj$c0Q_uWC~%7$9wnO!z5P|Oxmd-~LCH>ZF8mCT#+HutI3zLM zvNTYMbnLXe1arP~MGXOr&An7H(cw>@P?T_EFI5Bn7kLB2+Q_#wm_ZpjyT|GfIrPV1OQ$k z9j}jrPY<1##b_L%9aUbkxuvgfAm-V1sHqSsW?Mlb<!ff7BQn$xPf$w}4bltqd=K-c6&WpmfatuL(<{^~&|Q{M5GRAw;Sfz(2d3aq z(oGRyMk~1Yw^Y@)tmqp}AD4==we*wn3;m}}W}jL=5^`e&t6=euKl9}s7Hr$ilor^S z`EjlzM=Z8>;GDl~^I#-ulj|q@O8f(}&Dds*toV1RRw^J{DXif%7LSYbX^x&D{dNFI zyZTvE6l38?WS5vC_~|~+{}I2=>8o@8KMR1^Y*jIAYc&PyCHL4H5Blw2`kF!b`;zWL z`+lsrreKZLzxGb5DG>qAxT>0+E_v-~gj4O=L-!7GDSdKu2?OECO&l~`R{EB)TOz(G z=kAootrgU4Hk02HnBjBLC_6=%Mo1O<&D7N_J}QW7q4!dWU70$B|dmX`5zlL$x0s$!WB{`hOXN|98OD zAVyLl({1>Zd`RMBc}>h;>)q|^P#oYoIf;M)$5r} z0zgOy!%ciFNgiZZw|-A<)T@(l?+AZtb09jyhgR8yoXaVz>3?bUrK6-?6G+@iXf+^a>W49&jJ8W%bVlr0I!xcW*pwdT8)uB*PPLeH$E;DR4WJ_EnH!)x>U8N__V&% zNOICn!;z5jJoEF(l+|Yk^NM7fK`1M?cFhM0OZg#`5zTmoY_HbWF5qwOq?SJ1f2K2i zi}hX+pij$hLU-UaZ{3)5@zXh4rVgIs)qKXiXgpWDi|dy$zx(Bm>0#J=r#n8Myy1}X zd#c^&#n*0q8ip<}&VGAMZzaqLF#26sP=F#Wyy&grVFeWA^Fe6ck=ES!&fIR_h^9%< zJDW?P&>G9ndUY=Z>skw33=6>DE5x>-s4|nsWs{*5oMW~zSD^mzdV~AfMjhNlZ+vcZ zulUUxs$fME#%k2Efv+aBTloCZu19cheVwZ@TF*YoSh}%ZR!h6th=p~<#J!$?ue#6o zHB;-f#9W{U!x!vhgktA|#vcws>ng22X#~|Vkq!G7Dp`S2{!8__lxaZ1bv%5A3mi!R zL>4Lu`%b`m#kT^c6pd7WzU$q9J7sXTZ8wtL_nIyHZ9@3@ZxQ8sdW;wD-)&w)GRJ9V z23Tb$djUWwX5jBOx`cMw9M#Rzml(lF#C*?Nt7?oao`uxY5aD=qBA&&16^uEV`XD<) z{C;cX)Yy|glOJS0#zzEjjK{BUZv^7lJKI?pgn3}xe0mxMU|vZxOJe~5k21LqFi2v} zOZIyF$;_Tf&bw0IYZ5s4t^uS0fhR>1|@+tlDXunk95S-dY3M1FW|L+s-q=}3|wvFN8 zl-v=YF#K39{BS~DeJ||Iv!5P?Ivi;alcx5=HM6!m3Cq|n^jJ#Uhxop&aS3IzRu%n> zLXEU6*!JO1N1fC=vt(TcE2Tr}FHZ8B7P-))?6{&#rs59d{Ue5u&8n-<%wBwl;0gsm zilZc<_(wox{P^~0fAdLIR`AyXq5E3j+)_92;q8zONb@5kKPLox_$ywvSM5r`bW+|f ziLEu?IGLtKn(9b~HR!`uoWepfM%Z}*p|44K)qir)U)DUS*#gt2O1D0qO%lk89GHD{ z3Vjp9*?wor>S|p_ZAMwPDkEP4dOzf86G9T00=iCy7sn{t$R6_A z&FUzZ>F;bLvfF*$RLar;%nhp=-W-@BB!b8N!6-)%iGJ?w9O4qSzqYIKs!6Acadezuq5nV9>x zft}`_UbgY2uXqZ^noYQM4A>QplT^lYd!5js3KvHDhV{pX!U4u|jP4#AvZ z%C0A?5P^YBFAerfR}wEnmM$w@Hej%|^9Eer7?0(^bMeAA_iC6NnjQ$Uzc`~!RL?YZ& zz?E4d;qm2v>Ow7K3(g@kaaj1Ba(&P7+fwA>SiJ6slx0*gc~l3F4n}ukNh!w4g^k2= zyLX8L3JVV;j{0`PQ7TP~vpz{7{oCRW;UfNN(H{-QdaOR^vzQ2UfKSh8@0S#F!Vl7` znVZ$Z5zYBl9Au_ANs6ivDP4Q|sFNhhcWQvrlLpFSoWEHymj{JBReaZS|Vsc%llLK{%7MUMpWC$D@fg(`%i z8R9qE1nq%PBTwe(zQw2hRBiZrgDURLYubyLLvxZZ%Svgee{^pZx?Fo7gHgpn^uXsK zbdY5|f4IC@yLS1-1;XAgfAhpFK~5c}O=F>6`fbzG;2+bqoIO2HUajRhiG-seuBY!S znjH3~n@9v`zIIe_8L3UWb6GaryPvHv?G%8uI=|WO zt%CuA9lY)vpASIkzC`-y_6YmiACJ{lK8UBtCI`2=Kaf#CN-7=BdL=);Ze8j~l~HKl zilVwGt$|>$5H&BRG4;hfMc*U;$V3=(h&=9i?CA!y{3cdJ?`Z#G12qOKTT;<16igjj z{8}OV=>|da-cenu?EOy_k!@;9Eeeod#&70o(2U~eTgRjn4ZJ@-aZ)phdVcl_ZZdXS zH$rGU^f(Lsqq0vgR!wwmxA?ZCQvnh}m971-Tt0J2>8thBo(T&cDTeQud3VhZa*6%v zr;N3>LtGvyuyZu~9Cw^u&f5quY299}jT~SRPwvPlzvoC7|!RyLf1<7G5W~8*9Sk}x& zpT*`8z{Jmz6iO{{8uxaezodx~S4=M2pTLkHlb99S#o3`Lb?@s_0}r^ug~SfH)zWC! zR%bnqb04Bt4c1H}6XR8J;qTvL{Y;%x6THIu(og1G;<~q1bl!7z38S@_UcYz8(nrnl zlq2%xP1G6dwDa2YrZ)*_QtHgu#V-=SUMeU&jBlK=wp+uG)V=I!9QED5@Fud#Q9I6{ zUSi>V|0?8JZQqm5cFlx%r?uwp5i-YoPvvkB$o%mEXe7kchwkf{vFTI3cINqlFo6k} zC|!^Z7X#J~nW)2|pnFHLUHY?i#rR0Uc-FXnWxskj%J%^n3|_e~o+_rQ2%~_+D7c+= zn@`uxbvP%Sjj1;cPGdnQEn=rwSwsR@#=S#+Jj}(8$mOlh36l9D3{RvMVVgjXsPN~e z+K@O7tOQm&&qSWG#zSmIGBZPlu1{Azqx;RJ0nMd}WFh=E7Xfr=<)|tkEuqy&Y3ZVG zTwvNm7X=y5_b5}_rQR%s*6QmU&=jliEgfDppG%sce`NB}**1o-=jZbZ&)+#Hy@2`t z6wjzkm#64tJ}N$HmI0g9)WxqHv(x>xkO7Cm65Gc!6I@*kXS1*MPtLIL_%GASmuPy= zJ`T&&G?OtKdx*uZ2RN7XvV66=`pVI7+J_k&=KgVoJK6S<`h-C^2xTl~**J{&Jn)J+ zb0f*u)+;I*0k$)>>&$>m9Rtoz_4JyTn;8H4dtQx6!fXpm z!J17ZB~W@{E&`Np#)rj8@5hkzd&Qk*{-z(J#CL8kr6hzku9fZ(JgI~C*A?*i=IXB| zddsqB9>YPK#_#jtc3|+{OBIJz=fvGTK4Re{{5%Rvxd;0VOL&%u^IaT!tP~sBcd?I{5k@9obk|{1aON`r=L6m zRcDfLay@s9j9BO?rVtJCpRS=H%FT_XEq$J z?v&-G5dY(~W&Ft~>L7d1lp6p5&(F7<*#212Gc6dQ_hP57GL9o*-q(e# z&nZ=#oP$1QATbqftcq30D6b1Ij{faj*HA&X^FCjnIY|3)IK$-5BgIS3E1BLL@H^A< zYG(#ke4loDx}{nXTQrrNZP%txDQ@UG8e#(Caj>$6)Z$j0b2VB|69xHl_j>W7zP`o_ zX}Pl*Qa*mf7u)vIzyGwPFWyi@1)z5-V*xYGno4DvmlI*y-LInPo*`E0Iwaxp?2AGJ zsj3g`xC>E@Ei*H%?VpR1fE`)30AcjPS~Fcz$)ivmoiP1`-zk+U2Kr|7HbgVKzf^X6 zOcd6;qIcAjJkB&Zb?i2-TVyq_yfpf^NoPcK=m{rv#S+;DI^g^U+xEW0HR0<5{@Pb2@HTMl)kMNuk_VHI5B!ahm^~Re9jFk zXAu5Y!LaVeJUXIed9m4Ap9@_ynD76$$8Qp}U-p$UD1GjI9TjQ$I^gaZ-&N7K<~h0} zH9;j~60!j$;_>8T zguie9qA}=E=}><4fy^XJbrYu!m&B2ca%itWx%d~2QdN_Z1eB(c>?x&xTA}GOzcMvZ zXC|3jBgc3o30Jt~meoGYq zF<9~RyZW-MNvT{j+T>W`f>!w!=||(2ZoM-XA!CJM#5NgVdp_{W3N{ z^rQn{gIC3LAV+$Jo%c&aTSCcq=aqad$G8Q{C6t99-eCc%@kD@4bL%O{wW1GFISGbJncWQL`*K3OLpw-EoMLUos))Zxneu|9!VlwuzU>9~Sa|TPio*f+E2pA|D z3w?`HUM7VnX*>V?R*Lyv_}kz|6`uT1eWB|~xx=mB1}^<5Ih)~ z(P<)V5|yxgDvdP-7X+0RJAawPeRAou_w74%DaY=8iwhrZ3GJk3mQBd}xIiD;T);ti zv;o1ogV!1(scwGz2qVhrd&o3&ry$XFsmKd@9L@|GFs{cs)yck+%5*=dxAEM>@kpP^ zE6N0Abt$zgFePv_uUOnL9t(0j%n+nzbWj}!x)o;JGFMX7;(DKkP!a?{NO2Sf^OmuR zW6ksC&pH`AUkMnSk~io4S}IoGs%}f}rxY65x0H;elWTez;rUgbZy1w*E{g{ED+|lTiVoU>f(=5-*Mjh*;8sFJ!!k zmT2|k84LH}5Xctw0IaQfWs29@;(zVd#86pyL)CyawME~kyJvnP#ZO}d)b6ME!xc}^ z-2xUA6}_N1O|UWbHTQZp=t@yKTuL3R{HU+_fLa}n9GGrk9%qe!OCq4fZ@7^*me46vM0W=2e;Cb0c+Krt#zfF`+<4yL~D@1vA2fWHj| zrZ4H|$A7wojc#WzY)=}}a8?oV$EpUS%de`+*x&h7t!nATu>e?`Q7SXzNE^PvmtOL= zA^7_{i^GFi!4bt7dx!4u>(rwQ1XU5M3-`6Tcah48$p~P+FBR-+p%pQ@x;!$TaysiE zfB}R1yNPqTl-<6sHq?L6){I>E%ZKJ4q|7?_oQcayA*^*yX^az*HiF(}Z0g;(E@~@Me5QJiM-j5?u4B z{}QMmcTr(8to*g(Nxft@9ze+JuV)g&2;tfmw-bEuj>;x-zl;ee7|itU&UGr}C-td7HFEh`;Ap7+SCB1;mU zx)oWL7fcu?43$Zz`}Ijn+zAV_tRR0)Nyz zB4`vj)(jaCa{0qY)$2IGiy4h0sITu#~ z>g_5dD6DmH*5%40on6`12NYJdK$*(Fj(gOcc=l;Kva^0o7=SgHSIJx`j&1UeZLmHU zrsT`92yVL+T%3ET<(qbucQbb%;cmP@gN&m)vsdI9Tar3+5=>>f3a)i9tiw6I|z3Dg1d&4;v}V*&eKfdZOntuQR(lk=|=E7joGF5XhW2 zJTgTWq!qJpGr4?P`$W&sxqETKm;i$nn<(VgkyG#1vL6JtBE^;c|BC7RRaeea)=K#M zF-!aWL%q!y20uA`_u~7FJ6EXZyb2{N==b%Vq~X?FZz>vrV2N#aO8Ck)$-^T}*H>}F z?Gq!vo2-0XG$ZcX)s^1UI>%GCPLE!+EQOyho1*yjea|ECLjU@k{hrW31hXe4NbQ7s zLG6Q`^SIz@)PMFvV`(d@<}b>+Q=;&9h+a8yV< zWZ=M=JGyv?It*G@-t@OovgN;zo}WX%ob@?V7Yn`ic5ZIaYwEuQP5}v#S^FXv6N#xK z#60lMet#*+0Anj+jSh0at^#`8s(r+W@#;YXm+;S%w?lFt+e4J7oeC^N(NsklvH!*S zQaD6}dBEihS}61IacUJ+7D5g6D+outo#dnAyAu%m&EQ1iipI%W2Y?J@1XDySH>}G- zv{wwOf)VW{H^1knF0p|rIv=9!fHoBJf@h}LBw8rY6j=OY(d^K=j+w}EqSuBoIj=Oq zPM(_QhBJ0tJEBA;nf1&Dfb5$9QyR4m7S-Bhayob5`~F8(TNDy z^ibP)Flk2-dc98oY^Q=esVQ{92G{1}q7Oe5pOoGA}8(-S)->BFhm%23|L`BzWDsoZH8%jxv4 z0_vrqX8574`xeRqnKi$1`F|M-k8tYHD!NxU%E2pec?8%m%Q`-q_sK=G`do4VK#~vE z?63$@1D@;awP%j!X8GZuCVcml$mx<*tx4_But$?~MvfnUq@$(Lq=}<13w- ziI{bI(P z-%EaXZ>uO$EJ{h_oI`r0xX%seS?{ROoE#2K*E#w9T@t(V`|~4_8e*4`2I=`?1#WH+ z!n4B>U4;W2alYEmgWKFm<`lVXL)$13&Nq8s$wu|~u-3>E!$-o_re4+x>j}T;ta;k$ zV(9ylH(#uwH7o4eiHW`Ee#JFCJ9alESlOUCDom~}#jWNjhp2HQXS4>VVo6@9t_YrJ z35a-Inq*hj{AKroz2C8-lg2McwMWvIiiGm;22BA4s1fwdv_nhrQ%c!*ki*0G07I+? zrKHhlY*~(bPuK1PeierUgh!59SO&NlhnG!c+JSxRJ(qRx7C+C-V$FmSQw+zM{xZu2x0POc5=EX?4J2F2O$xj3S=6-|dj)n+k-h zpX8?!G25{+LetSuX{jR9#32n?_$ttmGx*+ZVVY1#DfE^wj-oK2WnVKg8jRc}9LO9g zekn^$M^WZXzdVUw`Eu2yl;$2aa#P4&dB(h+L}xR|V>#DHuj{}^IPE!O@=EXKly=BV z=1keyWSB@yFDeP$jY1+(4Vd8d>AJ15<4YEmv3Fy~s1w#lCT^_rk87`w>x{u=3GLN( zT^P(3MdsL-8>a&@O_^A%!o;Jn3{tSmNk!?1f@SOdSygXR^>w69af)^)&_Hup{}y4b zJTYx*cU>LrX!0yMMoaTy#5HH*Ms9x2x#E<8@1nR4)dh7cEH+5M27_W%2sY&ph0UCg zYKDz?+&VlIY91zSN$O1?@WG1+DaV?FEMzwYIQ+imUL;ddA=?M`jODq>JeplQkS>N< z`)KA{ayC+$jB4lYZJZ7`#o2mUE!Sit$yxo4VFUK*7uar`!evz~ZaOLuyY`B zek~Mo)@P5Tw$D*Q`bv7AafGvR^wQJ8CZnY>IM|kJcwJV?GN~_xPC62qjBRVAx7fn9 zPOXDNR(0KL`%)qZoCU0_ITtc;tjAQ5zE1r{{>`g1K1ZLT@(1e7MBT1x$u!uYdL$hr zXAt8wfr=ehK#ADC3|cV@vtT~6Z(lpraGZ-85 z`n60X1u=gXXGh#>epI}JF2K~i&XvQ-xsB&Il&*LAH%1k zsYhKfzS^`bBa6bY(QJ4I}3j`{FQo-6&sy5Z*){SFD zg!x0kP|tc%4k0$)&?zAnPnE9v z*o0nZP!D9UBEu@SuvmqxGAjV6l2J8f`JuNdJ_^car-Gd!t@=u%s|np{#<;-kZ=oTK z?IXxLa&>YQv(i!Cx$xH3o2>{s)OrchOpwtm|M`sV&^`7_l&QWzASJy z;o3hdzKtSEG-tcL5J_P4%60)jB#m7j`D%Y)?%m#{Dh#pHGrBW`!Pqtm(>gh`1>HQv zu0#OR_MWZmz1=-8h>?=dq}o+~n!KKsv|xujy~#TD!5}Dg%&8b6-xzaJZ^R5dy$?44 zct&WJ0})b7CUpZ63d@`rcmV+EhvCy9l*c9r00osAkY?W`o_vrBU<0YtG0S0DAbE`? zg`-LxGkyRP$cza#B%9`hr;{P4E9r!-OMo5HW9Pc{Ry|aY)oXx(gEXf~f>kjc5Q-=u zeha}4MPTr0ih~{04avduN1ykCMK!Ta0Y^wEDS!-B2MOqs$lZ}(%j@{Impg_@TDkSd zSX2I^pTQySM3X}T-mP%U(1yDy9co|yd|b-zc>$Gc@$-qUSkGIUQQHbmcOrwn{#mtp zZ_P_wf{=C2L5hJEsk!$=?BvDt8HIqbSG56q;-=A!{506fwT4Q>@Pw7ThVuRx*CD3; zQ*mfoVmw6vNcIiI=71Q5p5r&Lo3pa7+?Kfx9U-Q9zpno@EdxJ0|J57@X*rc?(+1-1 ze%h7JD_yCcrVZ559f-<*0a#Y~ zr+M)I-vP_=q6(^i6ORA)fMu0`IH3P$KlT4l!17;#JGiyK0Lwe9>m9)I4o><11z1-3 zr=haEoQmqd0G9s+j{V;Qmj6odpFwenmY!%KHC`yG6Eptmod5kUC(1_arLNebg_UGO z&MLJf2~*CpWOJAs=aK>96#H_Vw@Si3o0EBl)LC70 zPV~=rH00wc(WU(&FKuRO zTMTn_4;o68-g7-Y)~xHxVz25{P&H3nYIBeI)p7R4V-GvEkvC0w!Vh2NE__owk&B6I z*IY#;Y#$nDr|kVxR+|^~(ocXhw^8Nc*I1i^haDlQh3hUC-iq1G1o%W}9=UYuyXkEM zj_0?R=V}eAt+jw!*5i1>hxo1J7cL!$m^THkZ^KWt{+VXuGU3$qu)S`y#cHNi`O!d# z$dg#1{Kr0~37;(lJA>pV#v>_F$(J8xOo{W{MPJko{XS_$IbtdxHoAs~^O&sjpKey2 z3BF%b8bicMnLSWG@1Ii4#3o6^n$r%PY*CL{Ih=V37qiW9+91$exJuLXdgL#C3Ou2@ ze6e_T=7+am`JNmuBmM45$J4f|H(Bg=x8WPrb<4OOS0ksHYOUi`QS~ z?6h${`FY>CUSo;gxtO_-duKyxF6BH#G?)%xP{i&!Pr?n~A0HQ^#Tyd*w?fpfec^LV zrc%tmzpMNfqGAW$-6zCL>740%xKOQof7I2b!HSaTt^Y8-=ZwrgH>DAwD2@0>Kg&?kGr#!}N74Jr$5eEKcrRk zlcA4yY%Nb+@u_*QKK$vb?&GJ7Z|9VaI0kRuYHSZI`JGE{zW>J&s`D+0qD8&efs;xw z;f{{0_nU*R|7z~M<7HKA4Y=g~IGuYF_V199|AfTrR#8NQX#_7sHYDX3)*9$y5Y{!Uvd)Lj209vO4 zKt%x)fB|5|6>*;VVG-lD=HWwPJ<>u0e~3`=Gb&Hm7dc=XHF9U zWXcL=^`aSVFb0(h91sA%<4gxg1OfmA)NQarB0*2xb0P9}W*%6=0JreZkf1I^055Um z4Gfu0W|M#&hy|ng+l`ndG71Dk)njb%!zj1~uw`#U07u$+Wo70YO*2glK!~Do+5>918HBtWhZwkd=#Os15 zI_v~ueENr8ow?xpMd@S&2R!IblB)dCHkqAcTR0ppIPofo0|*oJsw^wP)(Do#z2 zdC^<;K5Ps=^=an{p_ES8!avoF7A(Suldt-~LLA9BF^mX_2*_fNiz4=jx$VPSEnw|{ zk@n_(jIg1AKn2_Rnh$%yVx7r_6GNGxy9sz`ZGYHZ8kq``wbjm092v6!ki{-N7v1u} zu@YD)aPBr4H}8$^CM37m@7jtd^`(kOFQO`C=eg#sE6q3xhCX62*j|$gzcxNrS3*ExAP9jJ}jVR)J zM~MLV4PI0tkFGG-j$y23OF9Oy(FMT1Uj$DEC?hIiHG{CBJiKMU0*(&0DQq9y&YP~I zKvb3;i4lV5Sq={AHH1NPTXs~YG)6EsxVa+*mvSgQ>G<@oXG~DHK>*aAYblU=)3#SE z!4fQoKh9(cW=QvD*=9XZ!Q9QB!ZX2-23-y~98Q>o zx|3!7A#HWqSp`*db@3kvfG>avv|J1^N*=yT2+OYf%SsM&&gE@GI>;1ApN%}j^SnM& z`dRp;DYvV3ZcI>o zzwlBZGM~Pxz+5ver1GvP81?&v4B|4aKZ|)=!&q=4@2f<4!&U zmpz{CUP>xm|3yA^*)2)%Q6}yX=dFD2$o)~HXk@p~gF;HL#x0jD%sa(PMXh(*-OB|q zCH22G%EPY&BB=eU@9)2vKWFAq$Z_XUR+N^oSpKXGKu#5+^?r7>WiGutzEp3}NGydi z&z6LnXb_VJwOnVu&RnNLT=Z5z0>AAH7J7!_x)hHg5lX9(=^F3km(zv=<}Hnf`B&!* zE~FWR3p_5sZ&`kwx|_@E=3Yu)b6lFwO`|rUA{cBGgAAaxDQRa8Q$@K**A~Oc<%)V2U@PXF!!v#0P8lvcu;AbAE#)dG%|>dv*&$|{OwZ>P6?t*5B8G5 zo(fC}C}se#c^Ltyi;7=2v8HZHWDf4MBkRE?`!>W+NSaK@d^;~XEmk^dtAha>tOf=V z6tQ>#J2cgxbTbZz%scg^h@zl7mFm}S zuQX!9JB~Z7h~N0zql?Bq{o8|5M+X1|a5+s2xfj4-0yq?7%f6>z=adZ?LaVvUvAnXt zBRosB$+-2>;42tR1Wzue%#rW_LPNwsj0hmqjw;O*6u?9ZST`&qeJ7uQjgO4G?_vrN z$v(RsUXV(%j{VC13!*|qq3Q|X*MtewO|`YSUJDmr+ov5`y=uppFsXR$bFJD$>kF^F z(vZE<5J<;0*Jyx=YlJ4dFD+NG*t%{;>li!UA@`-m{wTN-9MGYf95hw&i6RbAL%%g> z*K))6>~(~}2n>P;kJEWL95Gd!yY-SvejTzxeAOKN=H(`VTar&^7mw=ZX7*I6*sQqC zqdCqiop3mu2D>E%-3h%eRn~P$?V%^-=!ZlY_o~*Z;GXxMaG}U&1DS}gH8Lk=u(VSz zk%3^$um1-g8|Qb&^6~1O1_0Qsh|7W};M6UwbIF+Rd7OBb_Z)fl)XSpj=7_lM?sQM_ zH)hK^CKnpgou?)4F64-ox~{ybGdtZ3t1gqKCY@Sc(cz@?SjO(LPyPK8irmH8M z($$O1DIO*Cn5#t{Jg)_9`!E7HlUnt{P}3|Oc+hfQ%DvkGk$T;p61MM7yCY&Ijy!Y6 zgR$&@oXt2wfDf?6klXNJgW!lHo$n8k^!1)mw}M*yHt;780g$5aM`{S$1YR#lJN|BW z`qe+9p;|-*hB*9Sp|Ko*ksa4BItdEHfGko00MPgX9iV7{II_VcurW6-0tgLOT5jr% zL9c)`7n?m@E?_EnA2_n-JOGAH3GWKE@p%xC=T0~!g<-JYBAhOg9eHYnCQ2d?L>iy| z`bG}Wo2NFtFigyJ{kRF|>+9O<6TpMkIj@;R#FP6mHm=cV(*kAJ~fivYW z0W5a2E1Vb;%R7Xf#G+6m7FAYr6CIpLB+@|5Vs@xYxtp!DdM6f#I+rlny(XESCv517 zo0q;IJAb9)^dF7b&8wWUI27jGgG)@ihV=66h1ZX@vcpir+7taZ-errcd2S!ozf#*~ zJfJJjr(Ge1F_%am0nnu(Z2H~nE5P8Mrr&%w-D9QZbGaR_m)%8jCZ=EgO7T85G#EfE zVWN06-eN7J!=a`lt!zYr*aGL|{?Q4Dj$e~5?r_%j%OP?Ist&$hlhN>J}IMu6BF&A$c-h9!l z`;{4ejiSLGR{54TrAws))Qt0WHGztY$|hr5F_E0f!1Zn0^?Qlo;}=z|E!tlabPjE1 zpkzcYJ75aYB`ojJiwLkzu!hz&EeY5k2jCbUN4Q_*y=vNHbdIz zL}KXSP&S^iMFV8QM#byoT*DeFV8s9mf^7+?L^S%_moK7Qq!0od)4j8wW}npny}DG0 z2pHi=4l;AycG@n1iRV-gYiZD?hHw2o$i`4nJHIXFB&m^olR&^zFs!Q6jbj8T15dAJ zdNtebTf%rU-Loc`#c*NQ6dYpz2TfU?3u) zRtbI~LzI9%FH#3-bG1x72p-pwfx`j7&k-I3TnRC87;=9i@irF$st8}vZgNp_QAj<> z=y34U1dt+Rs;dEgDV==20Coa-%jA@FDj|&6bRvj<2(Dq)Dm6JR>rV0X12A@5)KJ4_ zwi_}WF5au(<@A+vaoej^&V$E==%~Wp=dlGa)EMnWFgb(Ng+)FhP-m* z<&pWIC~mk&q_OBwooV~pAV)8EMXcFxanxy1W63hoQrGnJ#0P6CySPP1NN&_CrOur) zgIpz<+U2alU)D`dxo!)SQ5zFyzn)B)Dy2AFu2B|sou4CYAm=t}ZkYCv>WSbmR*XNc z2{~1hpGnq`c_fO>)mIE^R^V1O9jaw#A3n_^5RC4G=ftFXW#ezMqkBq@yTqHBDyi+! zSI~~&QKH^p#vM<;n61WxLltl70susG;FiNr|NO*xH*xRTM)ZI)N0eNoi3Sxp)iYH{ zg&#bdEzU5wkU_)?=%PTE;&yJft87KMSZO&}@rIqUTtijAox0N&l!=P|vGGK=` znSqta*@XHZ0VKeB?#{e&5iH)uthdH}U}PkO1G*4cAK3sc7zV=(V91sL#UR%K{7(U9 zD;Om}tXNr+nE>Hlyj}pC$%b-kk3N3o0iu>C308OjHkJSY^{gA2KTlc$h|oftnCKQ^ zu24md0FeaXyAWW8@GDAJbtVL`Td_9I9}@yD$UI|@+wP<9{4ZMqgdxPrECK`AAE+xE zOo;z91AK10N!X~g5(z;M%Dy2lpDM`{dDY;Gb($6oc=Y5ZFBV(e4RAE#1Yo26*m7ob zOLTULv7d$x98MsO+kqm)=Gzh>n~)d;58C<^7Y`?PZvO*7pJp;$&%AsI@MM+}Tos@) zaTC*x-6qO)wcL_XNTmJ-fF^FXG*PaP%&JquN7(TWjT2d_I&g6mDE+cTLDXT_YS09> z{a)(?UVBdLjI(7V0U~xJt*Im&_#D4^mf69^k(Qb@^-7xMqHMI+$HZ-r`fIz6tlqjH zjXB@$^gZU`wG;KChj=Wbv@?D4lblQT-h0$&fBk6WAmEaCm#L3c#Br8(D$_6+lxUIu zCk}|sA=(~@L(Ox|UXLJeTlM^?7U@?qT6pGbPsW^4x#hYWD0P_}{h20?`h28ZA#)vrpDw{AMxSl~DVFG^uHl}d4 z3@U?dNod-yzkw$NmQw)RA7z7@Yef*g4QHRFvtG~p5daV^bDB7sk<$_@E1R92)+*CJ z$s}5C%$^M!@td3~X46RkOq2Xy`PYF>m9V1Nl-BZC*U#sZn#Yj77df$5Mi;01+l*ic z4hMZD4|G(Xv}JUCn3nC0k*YkUbfW<>P!xet+4HIMuwz0!g#xo70ytK@)7+sS!u(=5 z9Qn}vHJ^Eo)3z$fuG1A>MHGn?4a)K9I^8VH%Dq;p;jrmn zxAw%8V4xZ$0`V6CvSLu#pagklgOEjMqDx<0noSTf!N2L7vE~+ThS*-O8|sX*%<3L z&+c}4mg1S1*0CY`s~`bK1zWVQo6Qb9^AKx;5(6+vr{Z6PgVW_Tj8a zJEvTI{sR$q{>yNry34~r&)3fqd+s$j?ah$v=1x{!XskZCPctFrikcei>!#m3uS-sQ z#9suxIfK22)bEkj_A=l|Hs;~P#`g$`|4?`*?H`5I#}45{#tanc-1U2frB9{Y(AwVJ zjT6m=q*!sM6Si-lS@35{HhQ72WuzAJ%_Qc;JWAbJpKFv)Mq|zkDRZirXlmB{Dc;y4 z>i>Y^xAK`ZabE20T5$E!4ZSkhI6j&6aB$v(-Ol%HH!mj zwIe3s+0kO>Y3ub8J^AsqciLbs(vq*r-5WQX$ffM-I_uQ8>o$m$V^^wVhCj>2T{}m5 zn;igCaeFQq7%7V?S`qpV77Wsobq4f$BUkNSx-s8T zkk)uJEl+@yAguGLeeZL-ya`Dv0Q7Y#aS_3(HS8rMBS8_!Ix`Zv2dpx2MCvqgIr*0X znF@*~?V47}>@fD+OzJLOv;8!(I{-FvP^&F;&iZQFD!5Al0I(r8h82wm36Vs=2I?aH zJiyxYu2vpcMlb;&vBN(yzAijHj|O(fNn|>86FAo40%J0N9|P=tR6NxBMvv(#bDqBO zn9ZtoC6QK%8@gLnD@5%mp?PmKI~=Otfu)5YHNrYL1L;4g_a4h~W4KS%g4*?C(nusK z6+u{@jzn!rd9cf2#F9LbY9A{_!i3xLd*-miD)L#VH0>|t7PaTWKJG9i z4AsJqiBU^hNy^A~O!M zJNF8nUbP3A_mlQJhy#U^-)GY1jg+ISrH8~tOS}8ka&J6FRO#H}E;L0tKgu7mO4n9; z8=z$PJd?5TWHf)xx8{P|g<;kF3QW$gyU$8nRLtb)>6gyLd_FD3sZP1Ti%5D~6=`Nd zow`j1sm;%J9Wa+@=aJRxxFT2SnN1#*&3A#(CfuP3LgQ9Bs^^TWncke<k=l!QPhgHGG6edc?G&^`Hyt;I$_8FbxK4OBq``N3CaU2ECae#H}rtYgGrg|dm zfcQ#AK5^x%SewN0l%^$)lbq-gGw=Yc&aI3Yb9n@qtr=9cOH!gYAOvb;XyKA%#5c^r zDi=#Y0T3W-eU<+SNvj_MWIY`j1>SQ2ELW?Ezpy?Beb~Qm(i%WRbxc4O7Rnznz@#|w zbOQ_%u*3O2g`8ZXVVHmfr~rrGLIa~<7yu(H-;_>{n~7tj{Q+UZc8pxwO1XFla}w0u z9IYLl8|fH3cPi6SIs7-ha~KO(Utx zK1zs(CjnbDSww^FfO$<%1l>^3VCko{aH<@X6%-qa@4N|m9mO*a(T+Ap;6p8^^@zr6 z*4nU3db5I88*qo_jl!f++Xu!BzsbFgxw?e|>5rr}Ywhx+BMVK<&b_NRAvDt3=NGE> zzGQtU%-0P$pORmhX`&=VlHyFlEgtYhBD}A22 z#UEW*L;aPhy?g(YIP|oQlF77CXf8lwu_kiar+EZ;M8}eYc}8u+@J!^~hYU=(i=Nlxaxbc*i9Y zNCX~$T#``=t`Jkd)Mpk%hp%LooUH|z_9Z2eT&BZ|QCooj7XJJ?f0xooX=LrVy*U=U zEhqrt^OvP9*F=Ww_eOF)l56j>J}Hs?-7Tu* zJ1Bp6J8=C@|BHcE*Js?xpZYJ|aS@v0Rooks+bEX0=i6N7{TWkT=O@0|kv1`x_}VVK zv`dJfD=Lp};Y71e67h5U?GU|H&g2ES^0rM?+93nYo|R#=)${gwoA$fLU$sZ^#nxFf za?e;Vb=r%D(UP~g%c`;+(nb(C#m4r%nH8i?6WGc0Td!Zy&+25wtC}dq#R+%{_#K|o zq;ZIpv=pM*o5Xg>B?pety?jS+7zZ2{HJ6z%DK6TuKNY8Q98#Mb~+MzydVn>f;fKL zTuRtj*V&K3)2EXOG{92$W_`NIaBuhpdjyn*CUq$291~<+XZIR`RfDP0QVa&LaR4H0 zyFBp_skKoZ_TJ`8RLu-4+igz^4D-zft6PRvY;TN?v-Dh$>GhYzH zOZzcxd%t*=kL+i|&pQ{5Q`3l5!brN2HeSJ!D^g`yGc2%a~TZGHQW{d!n zT}gcHUS!Hww=G7TV?dOmj_X&fN|bEhX1mvM$2I^*aOCKJQlkZmDHIey0wJpRW4=)55C7Od1nld6G@}W zq%W9xnJ7B1VE#};lErLGU98v$do1XYEim=Tkvwt;Q7T{9}I5rzCZWQ+kH*b5y#kupW zU*4tKjKq~(!yzn4F%GO?hs_uGupZC1qGmlLM7miRR@sX~Q74Xd95`Yp8nKadc~u*k zI3UClMF}KK*V7^nSR5Xie-W?FGgZOk$@LD7n ztoQ$P-&ohwr>|Bg^VYmLr`>mNglzAFxpmI$@UGnrYh}`LGkf)!tuz>?0B#x(dva-T zL0{R7M7_CA{XrR_oTEOlJyY_#PfUCBr;K3xZB%@rxCBqN~1(X#)NB1!gf=9*kJ8Cjg>0GsUI0t;txP*fSgHZvb z2b0l~BBh<`hUzxxYgMN+F%AO41_(2O)Zz^sd%<(9JlTWa?`w%HMuKqk_2WD7VPf0I z!U%6KwjweFPi8pT`oOg5^WIneZ#2R*WREvA&=&55X%R($6k-d2;B7;p5%J2opCO$X zR&fSAi1(<&p!zxyhLJK#Q4ZAy+eeJ}f+{hgx90#$*t|wfcw4HCv&t&++%?X9V`i3!)vl{K<<+E^cMsIZYnv?9QGoo8D0^ynw9!Hb`g-=Ujpg{CL-sg@Z6vSm&){i?FK#Fc=%nO8v2~M}!Qs z_q`E|BQLnBU}jk;29vRU26-H!;n(V-1j@yWu?Y;YV5TL&=*-_*d!Gwlk#VOI;;2Nv z?GtEf0v8T|zIMch?AdYS?hooBirrYSea0r332xn%iCmW5Kex@VhX8RUnn4mAjJ|6$ z4a*ERS66820uiRMi`|UD-0uGqA_3O&_qOtF!-OY_y$Y5B&;9??GPEVCZxCV1WYVSFUPv1@G>*=9`WnLZrY7r35 z#*E35sThrBobS!#n9Cap98v;MJ=h+fU#m)1PT;WhISR(s(!-SBjT_H~mfmbe>Vpmj z39#ZTHM0ayuEw8030cKL1QLBCLR~9utD3eghIfs2yOG`-X z$oV2>jl~H-1YkWl-p!hT3tO%zF zY^;3_%#Q?uv73-A89b@A*}5W0E6mOt4V-|8+vlk`@{TY9{0w*uOhqQ~ST=&~V)z?L zZ0Fj-vbBucn?S#J29|(gpy*`Km(lFalFkn92GE){*aB3@!kmTyIZ4R-cF}1212aDJ zsM(F3T^9fi{6;ta>GO|I#;s}&R25&aYKV_3-g)*jU*LlQgbK8VOz5(o8`t{Bdr3_? zr;2Qn@L%1syG>U_$iT z5gSTxPKovG+pCZ`&=3j4=VZ6$dEh|KR~e=aX6J78VDixkggps z<-#qT;bT#H9Y7C!4*Ya!>ZWgiUUP8x#jLeMUL64Eoip%&P?x5fcfr~C`f`$3;v3@| zEyl8*x2_S!;L@UZqL3cp2!bK&eAxEn{C(fSyM#sUhOJGXxgW>`O4w`U3e09?!wS!4 z0w4mY(w`CAieO80AjZYWh@@bV{)@1>MW)yzc8-7nVBJ3@v$1`_=r&=g`#1dZAp*)4 zwVixiLGFxZM9E+Ws(4GhRR(rkRbY%yb&*%>*2!YbiWn}Q5H7~VkZm4SBq#nt;E2E~ zAuPCW_B2@UxX`aN!6tUbe=?mZoeI}XFO=D`DgGt!L z1pOKPVT7S@##pnb$?9|dKwv3Pv`7grBu#}L;1`&@m@o_>)c-`UJs=GsASMcY)h$>z zNo9xXLq8B_6v)^uCdb7Mc20Db)5!x{><3%G2L^k{`NzY5C!PAIAMyW84XmIhYAebk zd)408*~?E1vY zD{G=7swlT3aWxl}HBk^%l;5esTvYbDxu~Mt-#KNk@2vm(a~|32I{^y+ShN%H&qddF zuJDhn*RLChDyaP}v_?PH^QF8zHlDoeW{AbBsq9w&^@-jag{hs<>Iq_)AQTM^*BYHuR zIw;euz9RAA1d~~v@jVyZ8o%ZrOx)C0!3_&o$Z~iRtE5g(6#S{Os*VfidYO0niLospj>Ti!@WxCM=o_E*HtPi~ViW)Z5lgj&Z zVV3j$<4tCKzm9#p=_a9bByFSH`(cCS=hs=fc$j2g+8xUA zO&bpA;SVV8jHI1!$l=#IHxgf-e)=gzZd++ltq>FsA6&B zpp%!z1^RKctIX;28>fGqUFK%8vIMg?xR3qn(J$V7xp+e8TE>qU!p2dVFDY3rG2XxB z-bj2SOO*nViSoVA;a`1rwO~kp1a$D?yz+HQyXQMs%I&W+sfZhzMPjUSudsk>Cf_*f zz2IUdt>eqeA96unmm{nX_=aN9k1L)DtGs!=av{ku>jWMBGw}Y|!wng{vY1KgKwOl_ z1@FfT4zpcJz1q8<@%NYS%KY_Mv~<&5w9=GY%U=Fl;_a%SH-CJqJ!wo^4La&M<2x7x z{?L%B8n#0!MwwJgKE0c~i|^PVWwH9>dtS!L_RInc@xBR#2Wi;P?-o^VKFNqawg27e zxT`!Bmx{!j2QP%jegH{HAGl8vbdM?G$z_LA_Ry|9p7f50sYjdDKmpdDo(3pNFPOe^ zw6-+X`oYPBZdqIu(7e=iE9A2EbL0|zl(UlV>znfL>ohfWpex^>+moAD z&h_H365I7=45Gr{9;wj#TDDBmfG<&C=s~c8OV^C!@|E}QZ*p5X#w)tbWb{zG_^E3i z%KL6`yliN-9y8odit~TT<^SYn8_V8MKZ8P=y!}7T*_{FVkpM35)!oVF=}qT6T7t4Pdl%>ZgeKe zpzB)s0Vm&~(<{nK%s=fr+U7>T<+7Z>2%`@4ru76K@=ktUUJZ_+FLTfm>N!hX#Jk zq-$K}G1Fccw0qYcHtoLK<7 zty?@`Xma*`@YN-ncwfidY3<|O{qj*)UzVJ$8a^gBrx_{q^0TwB!Ep{mzQGUL{TJ92 z$?U`#h@$mZ# zea;VvBPiBuHLB_CnI^vna*o_t_xqL~&AdV%u@lL~dUI7; zHuRi1x0dQ2A2#zWuH@ol1s+PR)2#sK)N+09G|vwv#px8qv9m#lYb|Tx1&!xA+IXKy zZJ;F>7BkKADj$UoILX>YJoz;c@k)1eKC5U8n`&1v<*LoSWW*(P`DLkZh`e~Jbh&&+ z?cr|Zx1;XAwy!nlc`0YSA(~j44Q7A4M?(AP96R54EECP{bAFQ7eW3JQXXe)qV{t*G zqh!pHb;w3YoY-Iy_~?Obg-7hA&GWu}x~nhYZ{n*T*l2xde;c}X{z!?Wfq9|Q)#cpo zS4D&+#^8zIkCu(ji5hv{1B-8tOP+tOhVY$Le4aTR-^SX-UteWZELxgCKn&58{Mr#` zHPcK|r8F4*MkCV!hQ23WSch;w867D}(oI8NSzWU{I$DeFKI{J5foxK+OI7Z*%uU{x z<78_UBcJ<*xyxl176{hminA}3)AC1tX=GW+{bmT7pZREz)hm;^)MMCl>4@6eqiU1iqb`qg z@AAJ<{qiZ9wK{gXd4wVOk#!|_w9M#_ijphGEw1YeG;)}K&uUb=(Zi*L$cfw#x;Q23 zE;>Bmc*!$X*U;8o@{6gA^RKpf4h!=x5|Bl*2V(tdAlCe)au}Zg8_KfIQG;Jt8 zU}~D_Pv~6quPl`xX_LyX;Q02HI>4V*Hh3Z`QDq)O53(3_KgUnKxB}n#| zjVa8uObz+7SkCo|{nQsyyl3sn-sk!rDvSd%=ZDepa-W|ZrfJI`TPlf{7xDEgP#gXc)jKmT1p|2mTO zznDEx_>Y$De>8ibD5oSUtK;r>|EjaEF51%@?X}Z^%ZtkDqVJ)7uY21&I`2#v1h_jo z>-*XViSo!AJA1kAj4-Gv$tnI{89sQQ-yu4D=`L?UruZKNSB1C=Q;s_sUg-HAcp*(h8)afqkC@cXz8cUz=egOldD!};b>aJSyJvZvLe+9~h$Scp6c3vM4dw~ zqG2=e%q?y)7))HO;K`zHO>9D(V7Bwu)tC~u{ttJ8o+~6y@V3Jgb!MgGqK#wPdW)fzfx-B0^BCSwzO;HR*7w`$rPVJd9yQQmdvEk1dR%S`xg{cRIf%A#Vx6o`-80cn zR?K(W)!G3&tdg9v_5PmX9{8NhL4D`_(q|mtaD}LYXg=ePGx|f=2u|de#iz4yi4wVl z7b)Iju*2ReGCcPCkM_1rDRD+yocn~a!lpFa_-yKm#ySjJ3!XT%XWmO!$vaE8dXGS0(Ye8 zZb*H;CLJsUmn<-L@;Z~aM=N3E9rwzkCq}&4+^g64b>H#qrX4suJFCtO`&KGG`+U&$ z`ND3gPd;i_`&wuHN8A*nmTCM^3duYjSQD+;~qJ<3uSp#AdJbEH}x~YEMGZO!vQ}`$!~mv1eWEFS+tRU%U$+ldG(=_a|A+ zizm;eok+{{%^m!4VlYH83NG%h5UUvFT%w|Gbt(}#ejn6z z+&tHpt6Y_n@ythK_pf6)xjUr{IOtM3Z8Xk>B9Tbby@TSKLa>Ts7pjKpBp1}a#s54p zX0r!(pjzZah-~B{cIRd;?`W@RP^>^Zb%naD#Y>Hdy$QF)EA!?N zWLEH21ZNU9QjRx?_mk$2)K82_QfYx;2ptf5-<{yA9Twq~bQR4eQK^{cI^r97Vj?K| zG_SP*_OU+|KNn8`_a1R30(RV$kU?23^o!0LGz&SUW-kL_YGd_VOmZX$#_M-|H} z0bpqelLV;Zg=#5-n^(z=M1YMs`Z6gE01+|-Y5|6hfkeOtB(MPhz)Z3Eh)kqE3N$i> zbBA&+GN}35JU+mKiAsGv{WKU%+R|CUtZtey22k06ZA-^Px%AX70K(V=FbzquAvS>t zb&6O6;Pe)*ASTiu@2G?w_~59NbZT1^BG6%-$Q!qhquc?T6H7RiQ&WtmlG%;`&;mq8 zw*Ua!L*oGf8i2CNi>3oSw}3SpkS4%DI(utO<^M4D=KoN?{}=H0Q_|RHkbNC%vSo=V z8palbB1A}*4B5(-Z9bX7*!P48$<82Kws{+bRtzR%nJg6s6K{-+nb-a3dw=iW@9Ph^ zetcf%I_EskVc{pZ0N{9*2mrl*sY)vD5XbxjTLzq6S$%japOY}q#sB`bJ0Hu({R|hX zSdCRk0|3^A7`v@OCJp!a09YVqBg6*Jk2~@2$jB0H|!=^sT3#tj#tWIcCpH! zggc%>I5p*4acDM8YNzfp)#@d{J(#%6?;}QAMUg2syI>lVJ_Cmvvl_JCb^~R3$i)I# zo|ERDP*RBJDCV*bg0jQy#@rGQ+7oqyhkjw|nk?#Phox^R=(seV!p=$Ljf57+&f5z< zmz9>tOW#)h4YOEhQ`q-?;W6o5BWR(e+XcF)HO?@F*6(4lGWe#J@XLj{QS8soL59u& z0C1Yh>M8VJ^b*rgh0xqTlrdbid_vCit|V@dug-^Y`+oW?oU#9XJ>09PAAC!)(tisR!|u>r>3`Suk;!D%<^P*V zr%iYL8rJ`tGF&cHemAkM8tzphZ}$CQTlFpJLRSnZd;Epyup;iUoNPUL` z%x`w4cU1q;l5K|-Xc|ifQww;|Dg#E$sWj#jYhVXNIPZ1-u|%KMVa(BP7r~82lota3 z&AiB-jrcSjRf8XwjkDsj+dAsN<7$VA13@}aA4r&Kj)lx`wX~jt<5-TC{0+ES1M=k? z5EhF~%`v|xtj>A*90wfXmwN*t5dPk0*3Z5ZM{(pD0mqp%eMgZSgohXcck^CgS~>fb zftpsrQE>qQ0+IO8zZfrUHtaR2b)#RiSf8Ubr(@Df2P#)qAUBl9>647ogzt)&K%vm9 zXTiOCrK$f6{WEd)+x_m<@PZyMBs|YCGD3 zd)Y%>w)KPVe=1D$KX9jDQ%|jLY&6N-b-96o!!6Yk3npHsIH9fxPJ_X!x6ZZBNo1Rt z<~`Qp43Nv2I2U*g{KxYox5vZQe*KEz-B|VxE}6nl;vAI@bBP<<1Vg=mfvdV_}j;`e;!#@u2*jLJaHCC z$2M6&E=a)P@MtW(=}pUDjix_ubbggKJz{~U@4qW!DLke=zcFDQ(N~zK{ssC7CU{O+ zRFX}$@G>X;f=sox?AzDZ1=9QkDupbpYQTLm-VUw(1!6v_I+I4klyz`?#bg57p?wNr z3evvH{s^oLtDqsy|F|0sdMNdL5DS&&J`mW^br*&yJ@vAQ=2v2V$jZ3F2`3-RJaSryo658%hgbc+`yQcRDG|*;ef4 zCQ%w7B^;vG7h#QilA5&IzUhRH3l5K00GLwc@Op|fipcA-hVl|CB+*b~bF4103-sQ- z8!r%;^)I{K2C)%40M$eMu;GWl`9s1W_{O4kcH*{P-w97HWGH3l@t6lFYY-xR zU~aS*bHrla@5AF!Ae)RgdmZ(}KL$Msw1W$iQL)wuvU59`yZi9L=01uVg*7lo5!u|N zf?}hC!gcxf%v06B0eGh#H#EXwi4k9|hg@Q~A=uHDSL!aC|F@{q&T%@6fc$f_(aV05 zR6R$UBlc--SkxgazNoih2$ei%*@(6>Lt5WuA-jl-D_|l*v!n(S23eIefqrh6n=s*b zd*}M$Q-sBX{?aIXXq_mx)^ zQy21+bl6ifG*9?X=bb7Wb!%L>2k zwF!AvY#LMNU*FkqI*zk$z-NsOq)o zQez5uc3T-Q$(IF^KE`skN$nW*=SuVRcSds6G(J+#L3Ub-gA<8|BvL1%Jya-%!L^^r zSn)y6-%236<%&ANoyVKzccGDm=oCW8G1 zBC@N*|LSZftU$3`WgsZblZkS>Er>Z)#AtRg*)gs@Q{3R>TO3Iy1R=1#7BP|g7@V%T z!b5cCVfWd55$%t}tjc`AOk%Mea{n*P5OI2)>)Wm_ZuV)=J@>c>dmV&Lfp}T`2rN|M zmHRLrGjDgX%)3}hJ@ejO%JCiqB6>wybv$d-fV*%kc)TAzztJBrtbIROE=*2i>Vk3WTmnrLm_MXiv2!C*$QEhkp$Pqn|BlIChTP??Hg2n5QLZAQZ^3) zQmO|{)>z;2wQQOI^{O|$uylddM8qJ=$M>WhO{DpQ%`PQ8Sq*-VlhB`kl3RY5tN z%-+LAZ`fn*zIM2N_G-m_^rYXm%)=YcK*=RmwqI-PN|ce9Ngpu;m-aK=zB{nx;@y@V zNVany5{w4&Ci6`u+$?g#!P=Z+$cpLK;%b4puQ#<8b*8-g*I*O>JUZ&+mVa&bZ+_(L zO5*d)@e~a$=OnJI57;;R-kXQyfE^+AQoGox%ZJznoF|@Td~h8O_la?+SSBm+90^z* zrsOB*oWPQCE7g=~6a$Ys7^IMB%iRHV03X5tP{8bXCfh5fE8;lt=%j|yi!wY<{iWEf z67VC-Fp&OsmzT~&(di@rSX%Dga|eI}<~QRkZiQa@={4cji6`;39FNCPf`?4QEs}F9 ztXv9613Zk3N&&1D>VO0s=@M;ZqwiAy;Q2viwAaT-JOgE?D9&Jxgb94^LFH#NQNITU zmQdez5lj?m{Vs}!d4+%nV)FUA-*1vwOk_BP=jOnbLBI|G4!1q`DKt8raYznqs;^-6 z_ry4N_IWlcUf<0_F$eCcpbmrX+Dd$_W5z7KVHqzMx#DTS`|{a{h4O~0Hzx*eY}^w= z4rdV>1{Qs`WfzgH+XRZg&aQ}6I??QXpp9IHUUktHv*nu1GCfskz!@BL#~Y#99hP`& zxgLl=wO zx0egUY}2bUKIsT&a9Z7!mi<{bm%g3}F;&xVx7|HeaHq{EZPwp0>;3%j0c6tTCn%AZ zJ8KA>$VK3q_yBTxR$QE@%qA1oT-vn#8f5YG#?wp7fzW5R@){uQGajvk#jdbYp|u-9(24--W7D#kzTaLRe{C+MJS z8|(-%Q5a%-i_0w@Lp0O*XwVWB8=L<9k1-{l?mobvLwjTV4V@;f%5~vQ{1ubBc~3To z9q5U*)**Kpblj^uZNfZh7^#wgjTZpWwHNU2yvRwnE1yTt#DcQ5qTxpDOs&~hBI^|s z7%zW7Iw+^$h=-|lnu+&wm3VC_rqIkkF|NVuJMvODmy~rMCV+`n6JvIVs|N?al$aoW zH%$Pe8-)@t3+&S_*F?Kn;VFmIUN^gVA7tJ>a@G^@ppvFt<57U>V{hR3b<(OFjEWm@ zjwi6c?xq~W75>wZ%dj#&nCsg+v@YUH!MfR=w73;BcLF*)7k~u-pyNrs;Zm$uR7yPK zrWDBzMf;*P)oH#+A+TsIj-`Wg1)xNnv!Z`{$g80dD8 z*B3S8Tzjy@bOt*1oiVez3>JWAMzQi4G+=Wx;d$|>*Wu=G@{EYS8Wm`YMofl;ukY21 z;IeI5{SnUYD$k8hc1g|Oj#jF8!$()T4^K7jW9i!(jFv{yaz6^7;%K@WclsDThl7o@ z=qt|;%6abeP+aJTzuX4NC-`QgGDlR)ept}`wc1+BA(D(-(Y+W8$Q!fzYUxbia4BTJ zEFO5X4iv%epmN~R#^jo$hMJOq;_4i$-u5NecoOihb}+$}`UcMw#o5DlptkRnV_zEE ztVkq|_$SG>NG1>H%mpQ5;AWK&Q6Hl9G(e(uefZ|B%jF*y&?jq?u_X}-#FqXa`h)~H}}iQpG$%}K-%IVsf-x!=nw zrbJdM4#u}PGOH(v>Xxp=8R-Z*-fef4!BHzorXJUDGFPqbJPf?)d(OQuoLAXGNjwG9OS@+qOTqV2{=5q zA=2AR7OG{$!;XQQB|;$nW(6|GAWgJZlgH%y7p^99fAKIp;%)ilfR&uRa19uu8wOc>iPs^YIxmU)znbo(?fODo09g#5jg77RV2T5o4lDP zf3V+&75}ucn9+x@0%&(l#8>i1g}c}cg3PnL{p$@7kda{G_X-&wkSq-HyBeD{@f{6H zd~&_!X-$b2R4xXLtgi?kZ~R-ZWK(8pGI2f(NhfcTEAm}z7`-k!VqWakMu`ur#ngtN zkPnH41S6dxiO5uw&J^5lrfcWzm4c_TkdS~}A)hgh>tSw!Wy|Ah4W5i0Pq`U;&0JMS z3B?#2nK|p*2UkPG^&Z;`rShhTS3m0yP3-I0!FL@P1Ej}$I3mYJ3{#njdU|sUB8}f= zeRcJ_K#ZSGdsE^u;1Jgx$aB1FJWU0-gK)Tk2o{qDrEQ+LN7>~{EVEf)cr zz?&MkqHex@n|-O^&)avsvHK&cp5@Ov6!R4Cr{u_0;xOxRAFZXoNTfbYGJ&}J)H>0mkR4rmx+0B#>s z4u^6dvhjeldu(JOkZ)$8F16$1h2xi{TZ=`uy3l{!xbV4+W`e_dP}F3=knmy)Csxo2 z`wa40|32ZOjDH{$YrCa6_1wO)!N+e7dKn@P#E-roLoQ>?3IE4UW#`)*UIJSV@Ocoh zSYVC589J$lY1016F=V2qO68hs5`2*V(;E#kLC=7ET?sbLd?zCrJrXHe& zpY92GG}DPOLBLMJ+-CIgeb%LHx)=__?%nPF?YhM^^>k zB>_wQ=40BMuLn2Ds2coO_<`2=B?uw$Ccic((R5Dv*v(3Xhs&PGaV)Fbmi)pLaUP4! zx?z&mKJJ$_lY1d^-9$Fcb?L>+L)FCbec7DbudrG-(l8z#xdUfmiR`9wS4wLH+Mk^f zCR8>bX@%rRTI!mtx?6{?uLcJCo$wHNCC?G%4ESvSplp8h(p2M;UAAuIXnhGAPhQ0u z&A(hyqTsXkdET$2fB`B61#F|ww8+up)jvoNPbX;2$~zxUi;XT*I!Z;dJ>8fyp$uTj zB!zg=^flf4Cdg5Im4@n6WH|xM?Wl_^$4OEnfD=r59JxgFOLeL#{%F0fPcdD;%O=MD z((RFQ>>K!^GuA3CBnDEGoQT9gMKiMIv{aKqAJ&5=s-Zf(9MQi2lOhE#c&a=;x~ph_ z-B-jK?tQrb_1Y&k1ttC$4lJ8^YZu6cf7*3(=3fToMPsoU9cfRda%)g;AyfPiXQ1m*j%_$7J5N9r z&g6|x1VIq2igUc_X>pS66>m99f}xW5hf2#Mc2}HbWvvhVRb2H)oA5|B(2d06#0$z< zUZ97?Ac9P}=$TY=u(n5_%A~)}N@@PAUaId|v#|H(qlQWq+eZn>1N4RZxZaMT^8^Mn z!EN_0yQs`X8K3Qp%98VPHfb5jvK7@FkpKRgdd-pNQUND$S17QF)g*ouQwZc7(o7XS z!8pKIFj8W=V(Rpzg%%B4Q>n>oD)W>12rYB;lq#8b_KE(l&2fsxWTWW{MrxY5J8Xvs zB=`Nz&21F({Ly7Oga$9o(qWMH(o6qK->jh9y6_YpffQt(Nyu>Y^pW%-Q=m7^{U9}K z$06{jU3oLYbxM{AjqIT1H=-FKwm6(Pu+&J2?CSMNO`tNC*WGxYa$CtR;^SUkyu`WT z^Ik>V&2C_>(JBS>puW2QjnSsNn`g})-D)kmvD%FE$N@7Yy*xO0I)Lww0!YquPZaNu zY=8ma8Gh2tbM|#k|04CFhPT2z$!;uGCw*>-FhpKX0*09pcJ-H+atRu0pLU{2#7F~r zLg9|*5J26*;lIdZ(pKhH&s( z5)>U#h`_mj(6)h#oHo#lRu0)*OKNY59ZVf$eI)gb;Nb7de#u3`EpTB z(<-H=akLJhr5yUzUKTmQ=BWW{U;G>H08f4F_aUN#MPzjBLJe)j{4Fu=plqR^;4EEk zng91u_$%u}L}VfFxn;#xCqE2dOGbkv(!6Q};g2WX9dhg@#|rziuv;Lrt*bW69+kQN zsXhV)|M1&nVr_3=p{8!nd*+<>-(7=V?v0B7s5vFL(ZV75?3}?{M+m2=iOt6Np198w ztz)R{crE)Jgze7;D<{TZ>)kcQ)=yN#^`HoZSIRr@br_Rauyxn`(>Q@sKsJLa%A*OZ zUosbx?4ni=S1hsZ=)|F=1i|D@6i6x zRvmu+w&_(|Gu7b)>wNin0ptsLYS_oNU^X0;`@q~}ty)}s#P>iCbbY{M>BQ6PjJLm` zTPyw`H9Md*s&PqPfEfbpgq*@HI;RZ%GdI8;4l5W5Bj{x4^pI|3-hnMDGm?}Um04gI z5m_d@7`(LMetq*mFinZY+#9e(ja;3{mAH~bw=A0O3(rXQe)u$WG+8hd2^98b_t<8yv}V><7s zH0fEcJ^%>0T37Y235kh{rk2Efm^~y>mJ(_PKPL=$yldWh$8)rld8DIQvY~0Se!=&a z4B$~1>$@;F1N_;E1puHg@ZUdnDkTbab-Fq27lkYN7@gs=%-BjCU=74y>b$_1;`7bW zO$M1>5xFsm2I=cI1G98I3ShE^ff&-PPAC4jJNzipRwt!DMWZnypiG^=FJLBj=04hH zU|8T12e)E!f$Rg0oSV`)ny{RIS)@*F_oyWlIpEp*150lno8jKklQB%ONP|CIC)}$c zT+F^3nO?C2)5Jba5kzZlV!gl~K8x6^woxj4eotWEcg4VdU^xGXCKeLk$=3>NfatEu zRkL;;9U#-ftVnH1P2@CF2C3SF7nHpSHCR|GIga7(M(AjD=0C2>u745TT1=Vht&$!N ztn;dYOxF~1;Gr*v{=;Dife2wlWCbcS9vmVZqFTDi0U#HfjBwHJD#!)Mn2jR36@#!f z^L3L|J&wFxpWCa~yj0KolBk4ixHm-g z&E0S?=kw!)n0uFYOOw-~+h? zZg`j&coljJ=lKvZF*OL4g(=8Y!u3TV=e)*cO}S;ZW!Y~mIiwR2*JGwQXLVH*J2cT8 zwSjeJec-uUi_b3oxx63NR7y2_?C3Q= zqCQ-Xo(|k4)eAWV(*`?#xez;_eEak2woJkgpPMJMog`_dPp#GamSaqx2{QB^%nT1K zKHJP9Y+V69NFKwC?hAqHU|K&dd{_6{tOqoUqnGdBHk8Yi;uzL=k>UHP|K3AL z*F6Yi&;DcDy^k5o#TmmIXG+tnqDMS0i)27eG|oWZeNR6>eAPmQBP&q5gfsE<7+E;V zT|5S9zdCH-TttSz{=dHfINbIB z0R8{JBP9l5cPuE#R0P2vTx)ot(E*pRw5MZQRzD>S7m7Y^5YK;^d+$T zPk-~2y1zBZGe`CKX774C3_kWa zw8QGRyF$PVH;laB`?Ev?u`)4Ly;u6M-X;+X(|4D9!k_KEjnHeID=+2f7vni$4*(AM zfD`@tcxE7lMZ;cusRv68Dp9^3eZA9-3On3f+Vo^ZRYl_ZTw9W8A5*3&bUK62lXcP` z+d)&8l3F<71IV9N2FGScPsQ%I560BH?41OzdjkxvSDwI9ENa1XM`4du%Ga?{MPu>y z0o`t=Git#}x7RTi`BJ+!Zx~U#$&}7MS0LLHMQ!F|-O)1O`1z}QaG-ZBKf;sVMaV;c z?a!g@bn)4K?)HH4M0uWip30Io0M=Rp&_1@e?OZF}Y;Z7)q<2#?l~^tL!*_zIgL%w1 zz)2MY1$Z+02Ha2~zXyUBJi>h+kF@pu>N4c=tSJ>yar07Jz_YA^Iyt*fq!}HXf!#Cm zT~+l*B^@WZI>U++n(xwb+1~dakS1pwYDj$C@&dLK8)d^TI`3x!#QFmocf8(=VhF-D zFRqk>Tp>bPxR`*;plgcLjw2#6ekPW15tA!WC^Xj=Z7M&YS<;x&ihh(oT4MT89OQ~k zolCRPOiBsG>=%@sdnx3xg$-a?*`#U|S8(0Mn=nGiRbco;QXw6Cz zLKn75_U{YF-Z&uA5W2f7ys`PQH~aGsG~gi=ye18y*YWd+Czg|FX*x0N)!_Z6)zV}po__Hu=76qWFAqgkTj{m0qULkM5zMN&H@EC+xvC0_@C>*fMAcdeJTY*75 zfM-ExgIoFwWKqe-UV!E*b>Iy?K6s6(TRn^VL=Qp|vx1_fd)xwN8>SWP?jabxq z#`K5DkL%w`H}&QOeZ!190WJjnQAG82m{UN6CzT*85@BEo`zaJ-krTG zOVZ~NnM$z{HA~dA;p6*waxLp5!dCLABodrZy(sb&WXL9Q>xLC)?|8L%hCw9!nut;; z@mv-W1P|<`PV|nppznb@Bm&R#Sjk-G=#H$k$9jRV1;^M-5YY#l-iiRFJ7N&g*mVn2 z$n)}tfzS`n?;=1g1%goC`x*8*-{MMBS9JCxcz5OJeQv|@&IszjNb=v&dXQ=E+}g*% zl{NKD%ay=Lu*x$kA9>?U|Zd7kYzgYY)i=}Xigt9mg2ALBHy?CF1b7cq1cvWs&IcxR9< z(S0)ESLSBzDiTaw@pg20&H34rN@q?oPuOG*BrTYY3*l6E0#C)WSNMpQ{8?bGD8A*e zNo+nvPBMy&V3Te>Pub-;lgTFw`Tg~Oa&%+J@5>UW@>8vbh1$f(a-@z9i3HjMBi+@* zMIBYS8a2=d*Z3te#DAQ0sc!t00+OA;{bEHAlw8Wc*bAa5=58OE^MIqYOaqWFe?9r* zZO)}505+NPyAipl!~^;LAm648!d=SsdOvn0!3CH$WxCg;x*Mv5srW+pkZr9WC5Cge zKvPMMU*|J6Az%Uo;>7`nia~NKQ$;he`V`hnxTy&d5iAC&yq1xi(I+^aTsvLlW&c>? zub$)M)d7OTyYC22UggPknVIY``41YlqD=;GNm#YI8lu5ttJZUC_A-0bfFs3qWUns@Gdw8u8<5JPu2!hbgL z1l&*|v2J)~Q;|FUHz}{f|DyCJ%DC?l)}XdmeUK%6pvOD{Uwi4!%qBI$lc9r2?r(oP4wD4D)}oMRvQR)m=E`&^1>3JHby9BLH*gI550-Pas!PiH~VacCU-L<3Yrx z+o-hh@SGRD(W0!6(B=!Y>qL?-%)7+D09m+CyJP*s;x}u3wj80V+popARlKyd{`u>J zF+dKR?D5M%GD-{5;MfgqWpK-Lt!Sp=mKb*qfjcXg@2%~-26<(;QgVq98b*I*l_*P& zM>hO{zPMh&nBd*ruCVeJA^ommOx!by*uXch6xWDqeS$vy@q--P0hR1G5WV}mmo^~3 zfBDDbtOk8-Hpybyd9(u~sJtG@a8Bw1HD$CXQbLg;qm71{e)J)_A26RJ-mM&dy|tqspQL|nY|v0DOc zA0>4@1_@!Y*o@BqK$g>7pJ=IiLCim?N_0HG%`Jd1GRxIlH(PU6JgBV6HTvn5=?hzj zVJzxnbl}e=BRa?tq&Byo$8rvu zKfDK7vymaTU%FUwDF8lo)^Vc8M%m=9!_brZiHyJ5yFK^dqbkq7oR{O5HBY6&a+W6E zLAB0^A-DVsb%=ebdQ&-{WFDHxwchwZ^#&Qp_Ew8M_I_^PCQP3&0Rc~U)Fz_gl~ z%Qgghlpg99fgi^Go(d)M_-GEjo;>{yMO5@HtLyg+7%)*=xY(aPA%dw30c20j?=5Aq z!1^Me@bV!3kwr58gubw#dov+~wp+1Gu<7GE0Z7&;*1(c+C(!Vn!9#W5v2Mz`Y*lf1 zQr2UlpAvZW%a?e%9l)ecup6`Pgv(1ktZP#7ld09p9jljgubqsEx|9w?Ftrm}_)u6a z<#h`a=vv7@O$v444g&yAvbX-%k2PzAxlB2&&=^iBSiOE=dPt!KwlwlY9B~ey;s>8| zXl~I~mK?%&Fp}BK+mwzn2i-5jTP4By>p5!bV9nwg1+lWTlFi&Q;{^y%-(l4w_e;pl zNrop8Tll)h<$HruD*L@K>j+zQ5qpd&2ySk0IGGMI1zBHoMGF#iuYlm@E0sKOc!${g zeGvH7b;$=}8Y1vC_|z5c@j*+^1J%kkpEnk62CpYmXTDvAO!2p4HNTIC!{H|DXeby) z4r|KuS;o$on~UE2^Z{~ayudUw#+Pl{>#xVhpd>~;F*1C}!DdSI4Vyzsh2MTYd@R;_ zVj#E_`~3UerMED9UB~Y`I%0l_Y(vEB$o!7!AX6uMsnR0UF~aa386hB{zy!y6pRf-5 zb>pXLH(p*5K+61BkaskWKdf9%WLDE?eHnWQW;~LK+CkA6)-01LDe!hn5IgSQ)sy$4 zUaX?)Zn#G;)kv;;J;}|aP6tVv2_+o;*S46zt8v&i>BNG^g0fCppV5Iu6`<}GFv#D1 zn8`o^8y>F?QHR4FqQcj{G@}o`SzE_P#h%3Fy*_{HaUk6kOC)ztXeanT4#bHz=lJ>O zmM%e2{K;PIl>G4k!^Stc$|{?E>){U+FV_^YW+?<=Mqgh5wamSnYYPfB^azkDv7dD? zDkZHvind!8`KB__L*AWj!5@eL_!!>C5ZiPU+wwZiPBV6ARcrBNmj^EzDkB8~UVGJ& z#gNkp1_6_q;k$%df1Oz^>g`~N{O~#0LdS?A8YCji&#v5|3b};Q&&ZQMZfL7TCb8{+ zG9Q%QufV|J=7ttl1>|$wz0W`+*03|yGUFK;Ss59GocRlKmAS3e$(D(-$;gX(+FqJA z;Aq5In<~Vk>U*Vi7WP;jF>aa7vj}$dmEZN{*_Jw{Z=Gg(JDZf$dm9q?Vq)b#>wv5n z3ARq|1438r#gsVsQ3VFUjHLWz+#{i%uhNOTtZCYQgL1cOtnDS_eE5z%Veq-QC-6mT ziWH?;ij4?wrr-ki0wWh8{HD_&7&(Ty@Z0Q13qXl;2LK9iEB5$`d__j&N@ei76#C*F zX5c$n%DbFPRtW~yTL2y#>aPnDi9FgL>tNAPb6r(HSgjo$w-a%nV58O*yKyD0B6kGRfqt|X)$2(X%v`U`m8q%QxG0k`bVlYUo9Jt!uMexlQyUHDMJ|4G zg)3>>D0chn?0y+oF017bhUt9y@3XV=AoQg6W7&T;bSAydKav*<3?+U~!o|e651n`_ zo=kV9uP?a}B45>r`I6qneFgD+Joz~J(va8ojvSA1bkzF&)7M^6yQOp8gMepTUezN9 zE51jD{oOUEQNy&PH=!lR$fdBD#|BZ9>k+6s_yd5c=CN|Q^9`|FF#E_oBD=atdMt@s zFA&x1?i|0zYr@x>-%^=EYDAsTItDB9snM8R5p-l_N^`W{=AJt~J|@5o*Cd0&1I)(_ zK4Dg^(z7RXfVXOBW5?|8;1g$VgLTG4K;k((jzMH4`M=)HV{oalj*9lexcNg83W=3G zMn~>&^}?NVZ411Nf!!)&oF~fDHR><|Uve)2kDFukv4{hjxlM(e}H%E(BJSY%S|eYDBG zu7K}sN%& zBiRcV-NrZGI$aehHd%-E`iz=Pw91w}v9H!Lba)6$gt8NSuh!Q334yZm5wNp%9YinM z&6n^}Wi~b*O|)IRM0#X7>|Zx-r4vQg!QtF-inL&rNk4JLVzW)1u>j`j<+3%nF? zXj`CE+vy1eJuncqZTwxxIsszsP_g)qSAC|D)IG5eylX({z}6vfKxux1DWSqT-QDM& z;Q_0dMrqoU3X-xAQyuK_iYtIR#VZBMMw1Sv-Ttk7kT<_xcD&!-(n0(_%{41%C9^Ke zcB^%vyN(=IE6XcpdHur=n+IKoTjYXT!OaS=X_nn0_&U z2+~BHl{es)&27I_mJ02S+vbP1jwX89he0srK8*shQ#B8ZvR*amK-d3hrnY|xNQ~El(TXWn#J=Rn&{TzY0j>TFTOF28z5Oo zkqMiJiL$>hv&pN<`FL1bzBm0y4*=^25zgP@aSyFCKkhjShik$zlPZw_&36i8aY(Dp zy#|jY@U=OLRnTqbY%u>isjESTD~3V&ojiI1cU7VyoL=?>>{{}QxF7r;rgcv0&>ZTw z=aqi;+9eAS_z3P_*u@*IcPwf9w}!I=BU;vgxu-^~y`+yDkKE5a9lF?=Ft`@$v!sNg z;Ft+K2>{@X1Asw(Ynat_++Jr2Gw@Ucp!D`-1E<(cE`W81D`rE1+r$kRUa`#Dv%>+v z!KvpdM0(4G#l@s;YcOTJ%92*gS%J|x?+>#G&kde%AT`#Q{=%{D39pvbtj&1oTPsWV zTu|EivqAe(_-mEwq2x!ezXS$)%;^JSuQ+RvSC4S_bm zkuPjM{#(_d`l^%a=5mKkGflEaz(x`Kq{Lhxpsuu!9i&HBoYoa8*lQ`F`t&{3Coa(Y zMod3X%%9jD1rPTSMC_Q$1yNxUkx`aD;TE3ROh7#1i`Qs_2~*B9GGzH7ofl~7q~X{s zfPPBzgeoG>qbP<=46|zPJ>ar=Gyt=@xkx$z9H{`Rt!2LwGTGA@V;N(qBUN4YCfI}8 zP0szNC$ss@gUe6(@y9^moSHh=`FP=gO4|giwEz|nLi-~v_v4?$iiK%Qok$^~PSgVO zQaq~&B80b;rgUFxjvRdDp{!YX9?i)#Y=w>L%%0KwPWHcSb5+mDC&3U_bXaK%7Z(&0 z>bP7nTeKc(4|3qp@8hU0MT2zYKydhUX2RS<1siHfk0vas!w9M;#8G4GXgUH9-Y5Q3 z{Y*Unaa-9FCm*R2?xfoM2#^ecTV{NlTF`W$uNKw&D(A7Zzcn{|w+W;X1gj@uyDL9MoH;nJQu3}$rN${|kY ztyDR_bNo9A5n3^-WTW&)8r6|mOQNDkwgfA@rk z11bW0#o6RR7!tO|pRU!k$vk{=FnMozmi*-LvXlnMT^$$>Up!-5%2X0 z2<3aCP?fQKTWMZL`GeFc(AW>(Xdqt|5BYO5J)O~7Wh@t_u4Uv(D88Mw0x34lxS#e^ zps6`M%FoZ{=Qy;!ye;?N29DhI508~EfK8tpnMmZz-lz|@YVe&#VssJ4#BfZfe$P1qGChA!Yb6@HL>&i(kKXk9APY(>Z4-im+-HNPcHp(su z?aI-TgK|BLU;*P9N#``&HuQR{#jFNGW)tve)-vcPkNn2_j?4~f| z6S@9U;$n1|Bd! z0dtJPxA_gr(}$d_r?U-{wT+u;f;c;J{~E)F$t?YvNDtWqaJVtrj)nZC1$SqB^bddNxCk~lUkM&$nZ(pb(-(kDnwqZRBgb#R9X|bIRnW#Pw z^ubD=glr%o!D>^f^c8FUI!D&;Qm^o%l1VGVlG!jK778}w7KDdv6~@|5GdPycGTy8a zFGP4{AZsg#2p|5aX>Vj^M`N|b^_HPpe|TOHm(7B>qP{GIGNQ7qw-nznRtbSf?dXWu z2!OOEf_Qm!uR9vvBJlcLxExoa_teD(?-i05x zO^NSUG^u>~DKrLw4CnsyPN=eQl-Kc`Jq9jWFp=@<8w=ER^KEaH1L*z7w`|ShYw90g zKULBCq-G%+eE*sXub2efa%A4!LF;VBKH9kKNf+>1m;~&ZX@OYE|Z>Jj$f6VzmFiUONtwfb8$dX+3TeXn&Q2QbO#}bd1 z)>EXhP<=e~779GhFx?x?RhWEw_RNqENJ4`jbcP-0a#v*id#$_y7Q4RnthvJMe=yH5 z7N&B!kwOx1i;EBe{VofB3-+RiNexU;)}Q7_p@%AGhYHgr$4TtTQd$O=bEnq5;BbpF zLhi6~g!KNy+^M+lt58DrA2tiS)b0!Wm$;u{$=anZlx)*(s)PN2GTd)N;YQGN@-=zTVP#&%p*2B+79$-z0n zwi$TbyHej7F-S&s&T)2GzhC;>0I1wV-eqE=sZ?a(+}`@9$k!K}wdc(p|9smElDD|u zCO)aJb=}AAvXV^~M)i49KvL!VDW7JcJ7J5yqDsYLzIzY|L<;fYR{0a9&ztyf8P=$* z={$A;Hu#X}aXwZX0(riv6?1|+$^5(Bm+|z``LZ`q?me?UM;NgyS6aPL52IBFMC7|6*yPUt8rwxdj_XkymmcDmQV5jiP(RrgUrOk^oCa0i0-aZ!rl*f7eU zjz|_7U-^yhBhC(zfWdCZcbvvR?-qrrOYc+?o~6b|;F$@1yT4hCW8_uuforj@LB`*H zMaAjPpjhv`S;p%V!c>=}L&WC#maIbbPS6Mnr!xoulw;Hd90Ijiy6xIQ- z%K~Qgtatk4(t82iF%A`Co4*PSgcEzWn!PaZ(cug5$jM-|DchuxxR+-ANZ6a5Odg_1 z%W>nKWT9EzpxuVjN^1pV&4u8@2*&AOf2h@e%F53`xHE}5f(Ad@?}Cys@DsTk{l%+L zn0^Mvx2t>9c*p!^Zbq3Syem!6`u_WHbN@7`ff8Im_VP7fUe_Poxzg~s+G~hEXCYc~ z@GqbSbiNJvKE^-M-|og|j${kC9UC`T+uTxAMmLf7S;gFtCfY>HM!?N(om0t1-o48# zd3;ebl~=@8M9qLK)3Z*A5p(u3>`LT&R1jHmWWG6nnO12vusMBy3ROXt``Fry5euwo z1aOXpOwUFS+}_Q91yF6Q{6Hq1$_ylh08D2Z4FI-iwZPb}UWD~Q->wS~7=_D-+Vkjj zUQ3^-oht$W+5wh&f=dEUwo^s24^LlOHyjk=sd#lQwX@8gn9~3xgBgPJY+AhsO<^)0 zSK~K3EKw_k_N@mNoLKZgY-f7JsRj*^w#+5hsEKE`=v7l}Jd0Zs!zy5$vkJ7MaeBnQ z%+VZ<#Tu2Fd}MM{#PJCI%?-Aij7G;ghqVp&!ORqsLAs{B0Ynai2Ru7mh@e=+C3mH$ ziE@h@pX+XX(uZM0U^U>V0G2)$tBC+1huJ=DB=bBvT!qT}!yphDi>Qt(uh%clJYA?i z13N#=DVK8x>hE1JmE{(&?|!WiDyI3deTDm#w%IE;Nb{-j7}hKCEiX9L{ef{=iEQ$% zcb+0xpe+0N$N$sXwLnK%Wa%?!hgE|;(jy9pn3gz%z$RVq`YVJ)AS4R%I04@SvFYwW zBqX8Jfdn5JfswF8Vsy{}2WA6|x^Xl3LXlSviez<=6%JVD7^nb8v=<0&m-h<26r!Btg(|JR@d%s+g8!bvX^2~et(>I>o-gI=t zrWaeH8*9$q-+Va!UqkC&DcD~y{@Mj8-a+EvsNJ&%UAdgqc>8$QZX2_D!)^b1%&LCp zo#-ETO=udk>h#d{M}{&sbSN3|>qf7);kAnECZ;T2{Fj2-lbw_5R(kSxH0-;%_2=Fj zt{Awe{>HmssI}L&p142fH}8*F`~4MfhslijqoU;t@(Wh83C~AXquSbG>sC#Shc)|AC{!&i-Mcx!C+KmBAvdj7ui&t37=kldQn zTXU=SuiH1YvabH=G5lWrA12OzeE;oJC*Sz|R|^LXZ*Qr$JDaw2FZf}m-FDc%zTLa4 z;oN;o2c_S!X5h+dZ)bLX?WrMpzqFP{15YoXeeHw8`&%noPj8$4-VcMw?IVZh-E^V) zvr`v-n@@)4u6bb&_5R_i6-kf&2gwwcjisfeyHEq6pHA@1>Z9BC z>>S+E;J3fI>d~1k?dsW=QqIgsdTi6;zSnFy@nz$*Wq%DkUt8C{cjaSw@#w!NoU2|yj{S9kUj{iq|In@)Qorb*V?VsCd&l$snzpWeXFlk9_>KV`cE9msPmu|Qr;?M; z_P1-gL%-Snz~d_#yHmbAlwLEx`;6Un_K7#UL$u?tUEk7WkE%U+UtxF4u?ai=ZQs|@ z_71S?PmFw|W=EuC)j3@O!CtlTV0WnLNY1&)8}+9?Jl zpM8ABl2eDf$ItJu?GFx)8fx!28MH&U_LDSJxxF6kR>dA8rM+Tu5+v1?vFcXZ3J!ePfZef@{GzZ^VbcV6oL@|!X| zukRpRpR4&`*SdahW!0rTa?9@OA>(g8Rlo6HvhBLRT$xs$y~Mg~@f+pEk7vo6OhQL z?!5{DPpOQS6qkl8K+#%VM>k$=&EuaMDGOBw!x7)`siC5bae?w^WhCrd5ROz7mzDZ> z21(Opal?UVaan1uE`d8dHxubU7~$Bz=$e@ta`PFch^Jk8^uR_T=H)jv-!j+TUD zKTQl*FD#3MDqV}`)75J z+f1;-kdXK?X}lmZp$ z_2-CxQaBn21)>3;Hl1j7dD!Q_Ytn7Lp89t};#kq=ifAMpnCD5#%Bd<31m}jMzFFbf z#igTDQ+>su(W!UxNoZ2}xbU3fTNXva(-uvh9$Yjxs6wf}S=G^S#pqPcC^aWLDJd%w zD#|R#&GS{wD=DqWjD(6tr_PB+%QOA{g$oyEETkD_k=cH%l=36uCnP-*DoU@YE{z7N z(n~8+Qj_8xi|^{`S6Yz~2$jtWX9UaU`HS!J;|%0a%}z@4#m34FR|F%)<=TaOfmvmh z(b1`?Nj`_mrCF4Riu^c(`g_PS%X`hzHChj8c9PGRRURtJOt^IRk9c&J?sJhU(XF?a zXQOn4(-EGIP-g7!Jx(VVO`@aY{Mimg{3Fp8j|TC^#8;v<79Zkm&d-UKM7)SM_IxJV z<6fVwT|OPDbc&{9nu%3r%$AW54v-8!{nuxR6lVifHx(NJZ z#aR_7cN`|+6PZhNH`5W$`m)?sqvHV0d{(p6kNA4Ky-)$4+m64KI+UGBB*i|lQu-l-SW9UfBPjNG0Kh1g1|6jq#IPlaiRpdT z&5t1c=zDPfGulqACF zD|Jfb;>R(g)WmcG1L(L;UR;=Dm_vS&ah>l0I&R2bGOpklk~0BiDml~Hpqn2TIu~?d zmXaJ|3dK@F7o9>_LYXRrb*ky6!&1M>0Wo4?76W}T5(?5`Bni|nMv_vnHjU}jxc9gi zDWNlJh?(OmDS%8d5m;xbuD(QYXyY2w$t$E2K);w+T&K})I*aS4K>#KZoC{MN!!ek$ z^f|)SmnlVojx@&M7@Q!Tp}YEWf{2M>2IVXXGGrwQGh`|W(}xn*7?N=PdW#!l-0aIt zSxF}JdnT^FN?7{E7&j)dNhb-62UtmBjH@gQ#sjP@W$0Wf1Z{(0P9?BEg1O;a8iPJV zFt;#R8^Mw@gP-L3K-7D^1WTb0+%AlAp^xisOdz8#6&Tu@#`G!8-B(IuE>udBpR|m* za3-Nl3Fon+q-zY$3Dl*=^byrfCzL*}LW~=jMEaQOqLUcIm`x-$_8E=Ac&{;i{B`pq zMrPt9f!2UD_{eu!A^aX~yuaNrTDu7uq2cgtr46cJ( z7KQw%Wx;(~V=(4Wsw_i(R4IK^6~LsSHz6e4e>Dd83M!<9j4`BsrVETAl`&^2l%XRjsi7k&si7k& zDa`Arv;>TQ8iTQkN=w2#kt#%CEEZ0 z`WcMgI%0@gFrG3!8z6g)LHRMn5zG@c2JMs~js=K0408f=LWa43`H;r+#j9)1m+@~2;Ouv)o8iOhe z?iEbO2q;sk6g)RFh7sJ)H3s7vV;CDU;0(bWgmK0Yv?0zI%)K=Rb8p5ugYjNtFcvd@ z2|Ex}8FnBTHRdN6)mQQ^`3Xi1yVs!!#CwgwSi*!f@=2zsah_pH2WT*^V#t`YV#u%q z#TDG6GzN1=rUZs@gJVLV-E&L?j5!*EzMwI9f50*2m%xNME|qZa;Y4rfZW(ZbEw~O& zu!8YaW6=IM;avY_qqiQkrE(wTNoLLN>k2td|=$9IUdk<%pf;P@M=Fl&7`V4)L zb1Y#V#w8N)4uDH+oCCPTvELE7)+;eK)+VvB&u9$BAuh3kc_OzEGS+69afn+wECShE zh`~LITNJ^2293ek&Mk^zj1UMJIuZyOI?@=_kw8d6TNB9CkwB)71Tu9bkfq=rDv*l3 z{MlO{0x1gjJdMG;Q(%JNeU8Rp92b}nV_eFNvz4HnLR-@qyu;I&F$NU`p0_jx&uW4S z3hxR8W5!ucFvj&SN?mecI+B~1F&8EcyV4lU*94PX0^b)xB6vO*LQ;5U5<)U~FQqYf zb`iod{8wWX>~BI?QhSjE41*I)EwVK_r7#KoybD mEMc)(EF2~*`~Rkx;mOYSR73-jXzU6dOX~T>FUC*F^ZYMx07NqY literal 122344 zcmeIb+jiSHlLmU9r{K@5`RAgW*7;z!rGFCV*g3Z2q?7Emmj)z32{uJA04Q0xn#b7t z1@zT!(Nkpy|rP3G!ncy5k3qb2`H)bW(;Ray@eC^u(D7k)AXf zbebN`aUq z5;5FJ5JwY61rmfNlMqKoX&5<3IMHy}YW2Ivfq&eJg5fa0(ZFxFyMFsP=m)*1-RVWG za2PuO-~a2p|J-dDil+^ggUT%?$(6%!JaRckESR~DSfzO6qBM<3ATw>y6esF!h|Fb#E$TnWU^ZDWfT7Vl{Fj{{*G!goGAkTis@>I~?|pJKavd z*B-j#2NFT1ZspbIKa>t#jefBtLSS~niNLPY80$)EDjUz{bHrBbsRP8qiqtla*FTY% ztNz9@*mokzocH8V?5YoMXX_g~^L5pL#)<*d^Zl zdWn6H)8GmVLt)9mSjS|6?Jp-P5pTSG5`2IAJy^Y)|2q5f{Y&rN^S9*d{7dic^N+o^ z&%a#1ZT~udck%K2+wbx0?UOiucQLzqcloII^~tmN?d7BEx6glTeQEzXdwcov`@4%@ z$=By!I&Z!|>b|>p)A@24^xi%RXJ3B*`2F3Jr|qx5f1Q1O@^$v+NzncJ`_tB&`J2wy z`PZwj7mwO+p8q!Tyk@uG4|{`tFlhIWk9)0tf6(%eqxKM?<{)Zz+wD&OxZmj-#x13! zm+0CPWR7WOH{Y#h(=^Gv`)w>s^o-zXZEr zS>MKzBq3dLPmmbf4VG2dO)6(Jrp%)9Fp^gVqa4RL5IFPzGp@5hafU}O!zrC`ny~=8 zPKX5Zlt36tIKhdiU}Z|_G{zoSdvAdmiL?`8mEzS!Z_0NELe_Qd-o$HLf{#a2`odHTvyb>hf7U7SNyw0G1+&^x4Z4k2(PF_O;8UvG* zY0RQDg(_-HG7SV(B)u8sqQan*8#XIFN>dLS%Z=8p+wHW^y1mv(e{kGAIUDpJ_n$sF z>GeCu!{PC9Mb06a;{+h%G5jsVT*yXvlkT810FObL4!b14Uv*h7r!h}76#}As#fj{hZ zf~^_O5TAk2HZ*mPNX&nBz;XWB@nh;g10k|m|396TK z$-OD^I9M|!zg*}o3rw%+bc#dgW!a;@l|Vz0;%i?_d+Tp z5_7Cdrc4u5P7dIN53P)fRxyHTfu zhMlM#cALGR83co77X?v&(D4Jm+YAi|BFg4oLK84`07=h%Y` z0Ur9z?5^^v^{lGj(gv*Bvm zd~}sOd-i+yx&Qhs{PjE-xy~Gi1dUu2$FA=AiB*jG3`333UTDpnx4q-z=s0K&k6XuJ zAW$dj^t%3WFBmj&yWb635e|FZcGSb|sMQOboyb4#c5x4*sN2J>!EhVv^C)>l&aZw; zU%mhS>2(|g?|!{nMuShkEk2Xsr{;BG{XD%R>r(UTAB_Up#)8viVh7i% z9b8}rrrN5A-A=35?GK{kb};b!y$DVu-JKZ%Z-vYK}E;fBKQ9DZ5}L` z2vt5sXG%RXUkf%A)}iD>J5wSgS8M%l+s}rUQk8kFcInQIsXSH-lp9kI3{Q3Q_5Sl6 zzTDOv_1ee7!ExS`s>~WJE+>Mr)z$*!@sJyNum~kfTG7JWta+lQI;Q+OoGLdva1QBbc>r|L*dS1vZ-pB0Z64ORpBDj|JVY|MnLCtB6#Dj z5w0U7z>SkpEEEgO5(KdZ9fUf^0W`vAil`%K-YGn}YX((8G00QKz+{y^Z9tS%I~zU? zSH@F_r5iCJiQ_mpS$HXHV}pVK`WrrpiCB4vgw7@R_!UV#LGv%iAFfCWQqZJM8%P_alHrp- z9OpD73qu|_#LQ8Dz@wPr&?AYXssN)g9=SeB63moYvOa~p5J@m|f*2zfk!xcKPf?jX z(4`(p7MMwQ!t^*RFr)p!85LJ}HFBp;=sJiI7hCc)LneIXh7 z*_l$1Lx}jyr-+3=JK$2BKmim3JVl8q-5gI5xHyo+(SN-;VppE-6^u_Ckbe9?3A93f zvQMPqsM00$ctBGubp*X76Mt2L)V~TB&~Z-x;d#z!L*Q$H7)E2q^TzVozq|h_@4==TfEWfsm zN1k?$#f*j{cZ!8OmI#r~$H<){HYLeP^OqEbAxWku&0j*o(-^HzND`9-yW>-mq?ynS zT_&QTsg^SmhA@hud#(R`c- zqp_)q7MP{lJRiw1f{Pj9Qk$x|$@6m@U0mhig3?@#iEY9TGQI`|FCsV&<){o)8yJ&u z*2`_EN-dbWz|B+T6?`*4(-;MKM&l5(k^4af{B^19nxo!0qRg8~DRVM_00?^(WE~y0 z)YL7EZ2Q6_wJn<|TL!iuB?86dJ07_-QZbCvhSVz5InbG@ELsWrdhdQkKb{Z3-sp2z_2yFUT>dI|&BhBI%q7iu~Gmohh^yT-)f+lF8!!1gp z8}><>tDl{>XyMFpk~y9O*`LUal=;3EC*WmmSi)34$%_E3FCXbbI;yPDIU&;ohvxSj zC(tnE4=icG^*)PZM~5Z2G;>-8pa)`vFPnNJg}X_PaGv46MRY2sn`K9~$xeT)|60;h zFKqE?jtZH;^-{8VgW&EgI%l)lEWotxV{u`}XpKGJ0GnzIr-X~29k5m>aO;kr6RunY zqwBJ^Pa9cm+=uFlCc_U<;~1IFgzJ!Sq(c$_NhzW`RJBrD3|@^4M?))@Bsd1MnWa#R z{21q+PF`eLy>!x%n^2KQCFRp84o~uUNckhx(Ai&b>F8+}2d=^Zl#-QQkuNlJW@v$( zEMYL3zLr$m46C+CZ`n@ektBprDrJtKG!`UHacJFo{1(mH#JF~KRB7~wrtO$Iwi$HF zqMsuY%i)iVYhDV+$3lqhIjuWQK91w!Bk-00Qp$INj)Jr$s>e_v7_fj&$Y>hUWdeE! z%UHDCy2@>Mm8N=F60>eS+3-qA0x|GS%)oYnmpLTt7V?Z?B(Rg<<$wRz|C6WKX28q0!wV3TewCJ{B%izYwhNPgkxLJ{NVYT~dTPv< zRk2GS=6X(aUK*Z$iI<|r!Cpr1!lQclK5L}KPr6f+j669iW2f&Hu79*^$vO4 zA8FPgfBUfnEOekGVl5{zXF4PcBJD-)8dfG#bzkSAw5$8Cwjb?o`kSiaK)unPuH87~ zr6`Hsrf3>30Qwz7A{(|`%^(f=WDROi8fX_30F4L!*H&!sbge3F-EObl8&==0;-3g! z!T>SMJ#tVII&;eKZB-q{DWtPzYPy^ykPGaT%%={D#mN1SJa1#s-PzCtu<0PYZ{!|Ut7_PnMZ5Pf3aTK#Q@8t<#VeAg%H$jJ_e*= zI8;X4E|&VZ$jnhil8=iL{77-|bs9r`+-9?sgmfxh6!VQ;j;D%Fbs=t-iW-Yi&B`rh zv6Jco*^f%4a-5fPkVg^D3kT4H^$SOh~PZ2e+kSy})sr7pCwm)MeM$ z9M*rL5^yX8Nv7P)^1P+oCb>4e=4Yw=j`Kki&AHGbwSU(VW`iiAoHL@r0qUn6QIkO? zIo>$>fw4*xKTBbT!ru}=vx9CZ6Elbr1VpSRf?h$;O~tp?LU7OK-v;=%w>^FLOe*N2MR0`=8*QuWgLGxH`j=oZ7!GmCj)X5e%9o{=M6B^_xt}BB_c*&k@WD(K*16yn|hcMo|`cu0q;yr*WaCit}KG=je#C zY2$b7zlWf_`q(xa5UYmVMD7QARA4iuW>0L*HF??o7-gS>RZINJf0_u?BUE?= zqfL3w+P*#}ODI-}lg*SRFU@u$^O_6-R$)w4von~irWaF`6ezR9Y~7D(4f|FZ%C6WJ zJgKRvo*Mlr3FO8P92-IscZyIB20e~!R4&Kjw8G0$-8WAemD%0MUnziEEMpHUD zm)xc)AKCQaLAipKRim!0!hp}^`?^GGtS(z>}y+;QkE zXEYQmBl*PMAwtw9GnM>N{HO#APJ1e;Z zT)vFkS$=vmaH`<0Dlb4pyRA6+%V7Vv!CzJ{9FAOlqlV8yI?4USTdRbf^3PQYsq|VZ z1dSXN$1n^FQz%uCWB)2al`mkf|FLTDcfkK|v-+~nXZ-7}HeaXubKrgnRQ@oy-{J*k zj$hdP9YgaxgMj#UP{Q>=(A1H_B*}Ec9K*H!`yaCHRTh7Pz}f@-vzX^&k0vP(0=nl` zPwJ9;f=;I~W`&Cd?MCi`n;D5RXibu-m5jo0pA)wan5RN}^5Iy1VfU)u;N=&S`QH~Yv6A&zqSe%|OJ|DtB{s5~r3yX3a6cdaBk zH*AHXp*bwVozgCVX~;*k^7?h>E-qv^Mc>yux!q2;AP>VHMdkl%=EB}oE0v&OYzs_? zKnGqc-}SE3$8SV`b#`*2)h8ZLgE^2=-?ZVf~h=1^UFTFf)bt{ge$ z4HLm&*Ba2sEt+%27I&I9_<>=9=4gh%(LsN*as2Mct`fyCS zU?2=YsUv^+S5*%;iAc4oDWW#+U@rRAzYMKWYfUT=+cL9&UQ-ot$|wEwyX%vFD)(rR z3ubwP%cZxBH}u+DPe1Tl?cvdsMEUF=AiLH-I&G}W$`+;VqvsX4%%xuFl~-W9;m=ua z{oFh5Nto%Fcxm)gR}T=$tR+Vcw~QZ3NiS%C{47RnB?l58!&qRzvbmoZ0Vjg3ROr^x zYpP^PN;Rc&B@a{=yPlN3fMIXS+;K?|d8QeQohWf-@l!_A5j-)g(ae`}!WD#3RSF$l ze*d|vt0qXt-2TJ!9>CHbdy-a)#H^T1(bz~T=QEWHXf1G*;)AUlM()E)u55$c$)N~7 z=NnGxk|=_5%(GmMsh(hcExee*f-tS?0@MYXTm4$l+-aA<3{)kUjahqe+L*OA=VvK& zSslp|sI9J|B?a@5^|lz-Q=?;?gxE(+j#3u_gsH$@NO+LR9Y5rzA+T&o0ZKX6L@*Mj!8k$)JvOiKWnpW|F z@&Zio*bIFaeRK0>V|c~9aP0D{aTY0(Vmf`G+dK1xS&Rd~(z~ljZBAfHJJcz)plqU- z!K!x*#~5*}e+e|zcRoW&FvHv_8Ry*o-r^+$Qf9gym5pAM#j&@fEOf^pSyR_EluOlJ zOKVONVr)X*p#7yL0BjW$D0e;Ok7D80op7U;<=7H4%Wg{|HEViGZlnIzNFX1c!4-HZ z>TWemwyisoFi|x~K|!v0)Aw@{V=id24ggbHW6-2vY(u`@>sK`xcKWj%#;u4@e6M3- z4Q!WOQ)O5#5LEU78jOk$bC)O==Kma=N`U%NIF(k(Lsj?m&ErAMSsdD{Z6ikrGPE)SwgB3 zdgOPtfW|Bbscf|%<2B64vfLRmKBdL9fvqqBZYt2Ri?#x6hFbDsdwI6e=Qu?S7Vts! zFl%CpwaIo;;|9sr_74~!UN`_-kdtO|$B{L|0~2ZP;`&rKW$Q?hd90yCGB>oD0VkXWYRN45E!p>%d@J2F+NO8V4a)~Ha~UZ|{;Cjxy8M*K`r zw&sAE65UbLlIZQthGJLV;QX*RI5+_qx*8}^DOYQ|R zO)zw{oZ=3;W2)1}sGtFjyM^p*C9}>OOx-oJc+1jOBZJmrNb5FVG9J*B z;Lw{9*!}!W{`iNPUuWjemKa$#)KJ27mDk_$@L*A0b+cE5VeW!!=#p&1Hs`Zip#9;) zi+c&|DG_=%ZrJGb#12y54b&e#y!c;8!>&%XLV7ElGv90}C{600G}s?2^AP`S*6SGU&g7&bu(8yU>yzY$I2#(# z8ZZh~dnFjxMXim?9arVajP)#{pZ`weaX$NB;FY%JldiB{ICtk&#gDrm8=ZHLd&l3! zO7t77ahVM+kE7qdzE68(`MB}s@%hKjn`O5b{`%|mEJTBM7ni>cJ}r;0@N4uj#gD$8 zXK3+ub@8V4^c#Eh`0=X$GA_+J`s2U@S5&Y0Gq{spq0_)Yv1r86<@d|3vc zP&Rz`@zwJWZ->vGJbn9Vz=mo1=+l?dO4C1qzg*KBFwEcNPOP?pN6`M7!7kGYUfV6g z9K*#M%NYq~dWo>?XRFyc9)Z1A@&*(>xB8gYt(TNL%+Ilqn@u=0aU^ZMHcw(+YWyxsU8HkucFa1 zU2;9ZZ~FWj;hj>i|A`(1cEk*uJ$m`Z)HcK&LDhlwk0&8aZK$! zzRYz?Y=CB=XNIChS+2a`{%C`I)iz=mfPQw|!iUir?Dg7e9EV~)fuCcgYzeg0d{ zgIf9rj!}x)9D$bv^^%DIHXkWXL|D1w_a=>$=mY6{L-{1%jQGwKUY*D%rO@ulqTM=a zwY#_-wA;fbKJNGYuoDe?ojz)I1OK=ap%&~wET;=u!A$_CHF07yCYQ@n*YZ-QLb=^{ zTMMr@$%A^YLtYituvj{8;$r0m?dAQW%F@%@0P1?BYMctN>Ihk>5`S0{SiGK3&VXGT z(Ug~$;Hody*2wE_7a3nLj89G*dT~psisjP`3>%djSQVR_+nqS=kF0CTmW`Zz<0c0u&y zy)_*-K*5Ei;VJ^1^4AvbBLZ927ehSTB_K_cN}fwgQdZuyf+HjBDX=^JvlRA~l8)wNAj z0{OO_9GFH{5RsxNCjXRFhRmM&#g*IZhZ?*B`I^I#Yih23r3F&j=lTZ5jPWTdDy&9^ z49xOOS)j*y?p8(nX78t5Ctu16$#!8YPY7(4M2EJax3F;`fp6_gCJVgAf*BoGS4rP@ zt0r>mgf*Rdeg>z~0Sv3(+^E@Now!-;CkqbM)Dn^pHYJur}!Ev9MQfy=U0f$RL@^%_@YW3R5ws{HpU`P0R_*AsO% zA9RN5Q1}|j4ZTXp-z(*>bG!+JwG=xJ3M2#(S%@dF>}n3vk0#$H3ksW%)B%ti$R7Y$ zZsL9uI5(u;br5BOPC~*Fo7V!Gg4`j1#NxIB6vf*;06|J(DkcF+)gFul^Sbb`N%=sa zQNegMN;VVjIADAv#02KN&TB!5MeYEgVRO5Q2kY&wg8&OON$_%#WI|j|WX!b=n^8sg z5MWUu&MJIVB-;a^)CG(K0m2r=@4BM7s723wb4C9B>y84K73QCpw;zX4vz(?_QvLsA zEFzerE9|wsEFnT*E^4v)8$=JFo^SG8Rx(^0X-Y8IL2%F{BGU?pqf0CtBhC*Bi64q%R030@0-o(Uul3fQzOyy4Lla!J~Oz<_FYF^W*);8LQ z0F*6atpd!Jq`M9r%H}ZAQqTBSLG2L0k&CVh4*APn2f%U?qXf=znE2T=BGGcF33nVYQ!HpIJl#?8 z7VSE$$p+B_fXOD$o7Q9_&8~wZZtyj)Bz~naJpIH z^_%@rdQ5zV*s4a|Yl?>h0mJZCBeqt=Md}bBpgFD3y?V3jN~hClJ&vEE zbOw%I$_k$xJWRsWlB?-;sJnQ zjp0q3Urw<5fPmR;b$EVrBuO0x1VCujx`#JAuXG6X{1ubhRS0RF@Kk92uhBdR5R}DO35Rl$Jpl&8!J-~}px6g`2LuSo zZk6j;NMlccuz(HU{TNSToJ_^6PE4$kJ|K9kbG{uZYbkdfG{GdLd@{`tyZcUYYdonn zQffOFn_hLgd$qMkiQNiJSkhe++ODmxnv-kHCa}9+Jwb?q+#$fg;#oK)V0UQ@u zOQQj71F=H^faG$7F?y` z^}AhHzT8bGM)iz671Rzv{kiC>^q;@n3jieeTC5Kj)nfmp7^8r3 zzvE!|mZ5O65VV#p9dcp^0D^+oO?!~P+i~SHG_P|qHL%9BYEC1jkyMJphMZs8dI93Sgnh9S9%{w-tUwA&Y$g0p=V{ag0`& zP3D+QF>E#&h*+P4 zsr)E7E2-=ONI98jF`P@ArCczK=F(c$)p}M_KM=@mVZIt!)rt22Kud6%eUPw^v}PrI{&7;o#tL zD=u~%5FAAqHtVPZ3WnAJfFNge(=3=*yRLXY<=hv>3J5+9~KyH2EsmoV2*0pvO^+Zjt*hhj-1skMqrM1 zeeVv*0T+mgES>Oxk+hb@uoYwv#Tt}_xeXcRRJ(2+gxnbvmdWxNO(!_6$53pNJp_xs#{t*^8 zktD07{%@mw0MOXV`eqBUE$OZU2hY=>p1`CgbqKIfLaRc7db9INXAF^Kg1I1bm||Cl zn;_PS9t0591X&4*wKTg9jv1pu#CReYspYKV62U_Ng)P7;K-lkh9Sk&`(4?NVOorAW zKtPMFO8ffNt}C9Q;Hsweu7=hjC|--LO7Z&D?khgwL=c)xq8Lr<>QD-{LH01>iAHFbQZ9k!daFVV&q9*o6(AD*&;cX4fr&DsM!oNEu1QgyAp?pe3mh zB^A^U2QF32Z^cbT;{5=SnhaW(o2pS+5Ir2YSUhhpxMs-w4q1rUnaEkKYj z_W}UR`J|?kI28mGy@LUPW_KG5)a!i!!h$dXJ3UT#TAMwvXdVh6Y?ilx!b-9Sz^Drh z2LgaCO5brsuh5bqQOjg(P3i#DZ8+Vm=K9T#D*dz(lEwIe_1Wn^JkL382z)IN!)WYy z-dH~SclST#eMH&ZK|z31;RQ1|j82T)j~CCpq3a+yST%AR?>~1N&j_0@5yK6ip(L1L z?m9t?I3Kx}+zS{+0(r^5GSs)Kyijg?mr)1w+F4xFRs%le}ghH!-*gP5vz%ySMW_Gh3QB3`s=qw zHXmkh`4xZqWc6vVYGp58{CfT&dEtK^CWOAE@BBso`04WTS+Di#)9csoo?d*t^x4bw z(`Dy-BMlyB=bziJrqiFkwm-f2eD-ZR8p#qVP&n3g%2SjW_0d3(fF_Rq>rIK+rbrJG zy5rLZd|yVb6s-oty8b=%gu%*58-~aW0MZ;mM)$jiIfBoN86sjbtAW~MU0*ow>L&A~1D{4y)Z;78Z!Q4Pm z$w1LG_Zot_;KzY~+=_zXFu>8kZ@0UC`#9(ay{O&kMXhic-aWGv37wU?(;1;O<&8NK zvzYkuZzDk*O&Aqwj#P-FqcnuA@lG31!wpKxrfC~mV!}nqS_tHOeimF|0d~PgN%2M- z2zU^YSYS4C1)AD>XUOc76_E*GaVZ#-kqfJc@U?&wFXluLKGP(;h~PLhrlZO!*D!u6B^MtrppR4R_!U; z3!37j1Q#hJP^c4d?g^G90klg3u_@l{QaX+x0@?yy__6wX+CXI~R@HlGNw%1~-PCil zMm;wx6eO$HKIplr_1wItdS*fEkB{XdlZ8?Z)ukE>FK-qM8 ze}DB}t8HgNYrpNgWT4Rd{k8MQbvEfNINozBe_Sa2_}?Wxujjo&=e>KXbC`(P zsZ;Bc;9l!paiHCI`QskzzScku2y4G1HHrgE_xCkc1B})htdRuwzTUTN-QU-EjmLs+ zohBdX?X~751G>_~{XMn!9t&!1>Ve+A>%C*?{l2#I9t&!1=7HY6>pdTj0cP%ReXq5N z_gJvsExcr)u=Dq?ea|?Wgm_LTHQD)s-k#QXi-B=*fA8vh&RR`&zM!}7dT(2LzkhaK zZ<#+wNrvJ{6qD)fkFTaJg>9=S?fT`{ zUa0OxyV>ft+O3+V|EyEpQ-o}=Fh#SkvHF1>t*xjaC&l?%%kWTGTs{$HUYU60<4p zDH=*FjO}0dt}haiYaA{~GM&`6+`L3`UlCx7#T}P^-eU}?p`V)UKrTW>b?=d&*|5N% zp4>w`FfL%1LpV4^Fk0{UX|#p<-r}QLSb&r2H}?)Nde2<1-E8%m!*)|{5LAy5sU*Fp zNU7#!T>1F^W5h?iriNxifI#}bU_|n=i4k~w&oR>K{AG4TlfD-iF}$o{L_fa&82PL0 zNUL*y?1VqE@x?`#E%#f-+G#sN&t=y=Vp*RE+x zo~`8f6&>5e<&L+$x`&uaXK2zqs%c~m8FG7z2`vu5fWE!AI$j5MQ(SE4XT0^*y~9lN==i8B57({7Tom;76crW&b+C5-W9z) z*1Kjv>RsL6OTD*h*1Mv&$9mTcNWH83d#v}#jEac-@$+v>n?8VrR1(u<_Z|g?4+{+X z(Y?e(vu0bM=i!<;y{3`A=H8yF1SKCgZ$D3|d<5L~v(ggkG0d}AaCiKc ziWy0!j-U>o(Pil*E}LHdLf@3$S!Z?mBJrk-W~swqx1Rj?wJpb_MI;FucRpLMbo5$r zU>Ot~j+Mh6ki*RJMFRhOeD2_RDpu-PH$iDENSfl%y7iK^!_ee0TX2$EDKq(WM#U9g zjoh`F1Bemi#mI*P)_%)Ka22nd%WR%HJ{C)i698ly zGsF$7wRF`fl%u;JKUv^cp9E+#m9f}eI|xwg1~^X{O-HUgvCkcw(`fZEoq)UiRvu1T z5-Z0kVn|TtjvFSK1o{8GL}jF4XT%Dpdl~^*BDD>|uFKLKPP#KP)rY0t6R}G1?v!l* zh+qYy$<)}gh$JZX+usz})a^!o;75JS=$hidr9aR8 z2&?UOoKr#O7>qTBn~|&LwY9uf=c3&{Y4=XLy|1oA_{e2AMuIG`2MOKruPAX^ou3`} z;IskHOrBa#IzNz@xp$mXGM_pq79;mRE~hk2F%vn)&;kj>TxW(sY)}-};Vc-r(C+b* zMnfgw&7&z1v&_#pX7X6yL>vWl-pCr=L1!>%|7$Vo{1eU7U-+oobe$y$#Y|CaSOv+C z%iSmk(1kP2<%!X%nUYJFh@Z)p#e7hbox-{FP5O*n)Gsw-i7h zC~r=WPbi!nZ|Kh2hD%*Ux!?dZtw8e-$eVjO`W!QN{E=hEo#l)=Gqk`(p=Afb5i`Q2 zFMZmWwe#$Rv0ou+SVqtvVf9^Jni`!smd1nXx&I3<{IZD+v@&(RfjD084ILpioBbY7ivG{_2Qd)~T`d0_=Zd=?<+z^Xn^ z!MD{(H9{#nDH5C{iKx!5f823iJuaYMe6{Z0fD!bT3_&9;dvj8{^3e6X=xdoV3}FxR zkxpe-1)TuQG9n3P4&k1Dmf|FY0MKRrMD?E?6K#>*UJ^pPELJ1;xas$!5cfUg4_jWh z8FsznsC(?;)^XQwMp3`p$;a4r)P#$|mr%J@TclEs3Q}npSgTgV(uF>mP4d4mRm21t1Nf!AsekESHb4I+@u4Pu3G7X&Xc^Dtx3 z4gNqGTm9^CI>#!&w#12Wmf#j26?NTsSjw@I#VT1Qz(W01e|(N(io$ItRt%}-pbVq_DS)iDNImx_wI)pp=rNgO1gvrXsCN~_e zG%5m&Y<7!z<*u&_qgBb zzPQTRyZlXa~raOkR z_o6GjA(aZF*yUq({F9sLW_7h>NAL{Z|DW1jG(qLqt@d+&g-EiX&TEpW z#lo_Zf;(HzWt)?H`VY@@P8$MW3&b!QJDxX|&;H&0PkA3vHg`}E;8b|Q3^9(y$o+Wn z%p1Cn@~$8nT14CJY(4ncb->2aaO6%ggi^tX=+ev)o088^9vYZ%f{%>b@7aFJw^1Aua%bI zI5hM@BCeChD8R7546~7IWDR8gIm2;G(qG(??_sBK9h3u4yO$ep5euEEv$~a#c0{Rn9~r&o{xg7kkJ$zl>DpwR^MpHSc6pB`BL+h zI|Z_#wVMD=1ZbEFXk8hN@kk~HPoQvYtR9h-UUoM5+8B`R?-XHj)A(_LM8@r=SyzoI zg292{YUDnXh4|T-QrX#-AN=fq22a!vcl<#nwjqQHjv0PMrShp_!0d1alTSU0+QUunogy2 zG~bNhtB;FZWerqaVs&c*Vx~G25-ppa7j%wOh)kJoNU85K$5Z63cVOm-U3rS0Yr}=iqOVJMK1D;$@rfEO;^7_0J5jcpd(|=qgH!3=yNAxbnd8py$H8D zEiXu0UdqBFfkZH7bRQmA+d{$^i znZ`S2nKH6K!Ri*g>r@3OvF-SG$g{g3A?TZ!PdN~crl ze9brGGw62)cddFe9RGmvg48-cxOK-baJ*)`OaMx^fu<=`^-ro@{iCV@xG&&dp-XhF zdUIYL6V`4<6eB)!89Fx?@_M6yR;&ZA4;5WnXGvhX!3+uMMq@6HocA#d&^Usv95h8F zIa1=)eu&{-IqOcqDCf#cAGs)@$!bnB?m8q9cnXLgxqOD&y}tK4X*_ApKajI`PrL8& z%%6UG+gtGOjZgeVFYG*f_AI=3b=`gWZt%T3TI>8(#{tyShU`KvDZAoc8xNwO6Sn(Z z)NT%Ot269`c-ZrYtzKtv?BgJaqFz5}MaP4|pw;cQdSN#}!C=^KVjOkw(IuBcl>HDR zcEc&+t0Wk?@{juie6!#CuNUVZ2jRQNPaCZk{`~YBU%ojHeu{AV`0115tbacL^dxQj zFQ-4mw>Hx#?Bk*Dhpk@6A9QiE+l``L*u%Y`8}#rn2)ex>I*tbDxY_MCqtN$Jx8Lt| zJ801F2g6|{&sxb!@m6f%l6zdhQ9c}VPH3Wl?NmLptJ)H=MAteWLCnX|eS|{BDN0Nw zy<6?Gzu;t=;Lsz9Cy=ko Date: Wed, 4 Nov 2015 18:58:29 -0500 Subject: [PATCH 029/388] Added kalman filter. --- matrix/Matrix.hpp | 7 +++++++ matrix/SquareMatrix.hpp | 7 +++++++ matrix/filtering.hpp | 18 ++++++++++++++++++ matrix/matrix.hpp | 9 +++++++++ test/dcm.cpp | 10 +++++++--- 5 files changed, 48 insertions(+), 3 deletions(-) create mode 100644 matrix/filtering.hpp create mode 100644 matrix/matrix.hpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index dc72f85921..5103626282 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -295,6 +295,13 @@ public: }; +template +Matrix & zero() { + Matrix m; + m.setZero(); + return m; +} + typedef Matrix Matrix3f; }; // namespace matrix diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 059a2d5cc5..0bbd8d601a 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -202,6 +202,13 @@ public: typedef SquareMatrix SquareMatrix3f; +template +SquareMatrix eye() { + SquareMatrix m; + m.setIdentity(); + return m; +} + }; // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/filtering.hpp b/matrix/filtering.hpp new file mode 100644 index 0000000000..f70d329ec8 --- /dev/null +++ b/matrix/filtering.hpp @@ -0,0 +1,18 @@ +#pragma once + +#include "matrix.hpp" + +template +void kalman_correct( + const Matrix & P, + const Matrix & R, + const Matrix & C, + const Vector &r, + Vector & dx, + float beta + ) +{ + SuareMatrix S_I = SquarMatrix(C*P*C.T() + R).I(); + dx = P*C.T()*S_I*r; + beta = Scalar(r.T()*S_I*r); +} diff --git a/matrix/matrix.hpp b/matrix/matrix.hpp new file mode 100644 index 0000000000..e7ea9ca1d4 --- /dev/null +++ b/matrix/matrix.hpp @@ -0,0 +1,9 @@ +#pragma once + +#include "Matrix.hpp" +#include "Vector.hpp" +#include "Vector3.hpp" +#include "Euler.hpp" +#include "Dcm.hpp" +#include "Scalar.hpp" +#include "SquareMatrix.hpp" diff --git a/test/dcm.cpp b/test/dcm.cpp index 2779d46113..a01c8e05db 100644 --- a/test/dcm.cpp +++ b/test/dcm.cpp @@ -1,15 +1,19 @@ -#include "Dcm.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; int main() { Dcmf dcm; - Quatf q = Quatf(dcm); + Quatf q(1,0,0,0); + dcm = Dcmf(q); + Matrix3f I = eye(); + dcm = Dcmf(q); Eulerf e = Eulerf(dcm); return 0; -} +}; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 52956e360a73f384123f9db0808bb066e10f1ed3 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 20:43:22 -0500 Subject: [PATCH 030/388] Added filtering test. --- CMakeLists.txt | 2 +- matrix/SquareMatrix.hpp | 9 +++++++++ matrix/Vector.hpp | 10 ++++++++++ matrix/{filtering.hpp => filter.hpp} | 12 ++++++++---- test/CMakeLists.txt | 1 + test/filter.cpp | 27 +++++++++++++++++++++++++++ test/quaternion.cpp | 6 ++++++ 7 files changed, 62 insertions(+), 5 deletions(-) rename matrix/{filtering.hpp => filter.hpp} (62%) create mode 100644 test/filter.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 10040a237c..622559c982 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,7 +22,7 @@ set(CMAKE_CXX_FLAGS -Wall -Weffc++ -Werror - -Wfatal-errors + #-Wfatal-errors ) if (COVERALLS) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 0bbd8d601a..56bd5d37cc 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -209,6 +209,15 @@ SquareMatrix eye() { return m; } +template +SquareMatrix diag(Vector d) { + SquareMatrix m; + for (size_t i=0; i & other) : + Matrix(other) + { + } + + Vector(const Matrix & other) : + Matrix(other) + { + } + inline Type operator()(size_t i) const { const Matrix &v = *this; diff --git a/matrix/filtering.hpp b/matrix/filter.hpp similarity index 62% rename from matrix/filtering.hpp rename to matrix/filter.hpp index f70d329ec8..d04d70c699 100644 --- a/matrix/filtering.hpp +++ b/matrix/filter.hpp @@ -2,17 +2,21 @@ #include "matrix.hpp" +namespace matrix { + template void kalman_correct( const Matrix & P, - const Matrix & R, const Matrix & C, + const Matrix & R, const Vector &r, Vector & dx, - float beta + float & beta ) { - SuareMatrix S_I = SquarMatrix(C*P*C.T() + R).I(); + SquareMatrix S_I = SquareMatrix(C*P*C.T() + R).I(); dx = P*C.T()*S_I*r; - beta = Scalar(r.T()*S_I*r); + beta = Scalar(r.T()*S_I*r); } + +}; // namespace matrix diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 4c37fe51c9..53702b78c1 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -11,6 +11,7 @@ set(tests vector vector3 euler + filter ) foreach(test ${tests}) diff --git a/test/filter.cpp b/test/filter.cpp new file mode 100644 index 0000000000..71745c133a --- /dev/null +++ b/test/filter.cpp @@ -0,0 +1,27 @@ +#include "filter.hpp" +#include +#include + +using namespace matrix; + +template class Vector; + +int main() +{ + const size_t n_x = 6; + const size_t n_y = 5; + SquareMatrix P = eye()*0.1; + SquareMatrix R = eye()*0.1; + Matrix C; + C(0,0) = 1; + Vector r; + r.setZero(); + r(0) = 1; + + Vector dx; + float beta = 0; + kalman_correct(P, C, R, r, dx, beta); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/quaternion.cpp b/test/quaternion.cpp index 1e0ffd3424..018f03a6ad 100644 --- a/test/quaternion.cpp +++ b/test/quaternion.cpp @@ -18,6 +18,12 @@ int main() assert(q(2) == 0); assert(q(3) == 0); + q = Quatf(1,2,3,4); + assert(q(0) == 1); + assert(q(1) == 2); + assert(q(2) == 3); + assert(q(3) == 4); + q = Quatf(0.1825742f, 0.3651484f, 0.5477226f, 0.7302967f); assert(q(0) == 0.1825742f); assert(q(1) == 0.3651484f); From 76cf91c5fd5c176b4fecf4ec60ba446aecefdc16 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 20:56:44 -0500 Subject: [PATCH 031/388] Work on filter. --- CMakeLists.txt | 1 + test/filter.cpp | 14 ++++++++------ 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 622559c982..50bfeebe45 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,6 +22,7 @@ set(CMAKE_CXX_FLAGS -Wall -Weffc++ -Werror + -std=c++11 #-Wfatal-errors ) diff --git a/test/filter.cpp b/test/filter.cpp index 71745c133a..b88b61244a 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -10,17 +10,19 @@ int main() { const size_t n_x = 6; const size_t n_y = 5; - SquareMatrix P = eye()*0.1; - SquareMatrix R = eye()*0.1; + SquareMatrix P = eye(); + SquareMatrix R = eye(); Matrix C; - C(0,0) = 1; - Vector r; - r.setZero(); - r(0) = 1; + C.setIdentity(); + float data[] = {1,2,3,4,5}; + Vector r(data); Vector dx; float beta = 0; kalman_correct(P, C, R, r, dx, beta); + + dx.print(); + return 0; } From eddc55827a3c8c9ca0547620f8bcf1e788c75376 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 20:58:56 -0500 Subject: [PATCH 032/388] More filter testing. --- matrix/filter.hpp | 20 ++++++++++---------- test/filter.cpp | 6 ++++++ 2 files changed, 16 insertions(+), 10 deletions(-) diff --git a/matrix/filter.hpp b/matrix/filter.hpp index d04d70c699..666db0926e 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -6,17 +6,17 @@ namespace matrix { template void kalman_correct( - const Matrix & P, - const Matrix & C, - const Matrix & R, - const Vector &r, - Vector & dx, - float & beta - ) + const Matrix & P, + const Matrix & C, + const Matrix & R, + const Vector &r, + Vector & dx, + float & beta +) { - SquareMatrix S_I = SquareMatrix(C*P*C.T() + R).I(); - dx = P*C.T()*S_I*r; - beta = Scalar(r.T()*S_I*r); + SquareMatrix S_I = SquareMatrix(C*P*C.T() + R).I(); + dx = P*C.T()*S_I*r; + beta = Scalar(r.T()*S_I*r); } }; // namespace matrix diff --git a/test/filter.cpp b/test/filter.cpp index b88b61244a..8e723e8c63 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -22,6 +22,12 @@ int main() kalman_correct(P, C, R, r, dx, beta); dx.print(); + printf("beta: %g\n", beta); + + float data_check[] = {0.5,1,1.5,2,2.5,0}; + Vector dx_check(data_check); + assert(dx == dx_check); + return 0; } From b818774f6aed2238cb7500b4d5d3073f23d6c44b Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 22:48:13 -0500 Subject: [PATCH 033/388] Work on format testing. --- .travis.yml | 8 +++++++- CMakeLists.txt | 13 ++++++++----- scripts/format.sh | 21 +++++++++++++++++++++ 3 files changed, 36 insertions(+), 6 deletions(-) create mode 100755 scripts/format.sh diff --git a/.travis.yml b/.travis.yml index 5ad6695ec6..631c927450 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,6 +1,12 @@ language: c script: - - mkdir -p build && cd build && cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. && make && ctest -V && make coveralls + - mkdir -p build + - cd build + - cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. + - make + - make check_format + - ctest -V + - make coveralls env: global: - export COVERALLS_SERVICE_NAME=travis-ci diff --git a/CMakeLists.txt b/CMakeLists.txt index 50bfeebe45..80e163f20d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,7 +22,6 @@ set(CMAKE_CXX_FLAGS -Wall -Weffc++ -Werror - -std=c++11 #-Wfatal-errors ) @@ -65,12 +64,16 @@ endif() add_subdirectory(test) add_custom_target(format - COMMAND astyle --recursive - ${CMAKE_SOURCE_DIR}/matrix/*.*pp - ${CMAKE_SOURCE_DIR}/test/*.*pp + COMMAND scripts/format.sh 1 WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} VERBATIM - ) +) + +add_custom_target(check_format + COMMAND scripts/format.sh + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + VERBATIM +) set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) diff --git a/scripts/format.sh b/scripts/format.sh new file mode 100755 index 0000000000..f5faa735ec --- /dev/null +++ b/scripts/format.sh @@ -0,0 +1,21 @@ +#!/bin/bash +echo pwd:$PWD +format=$1 +format_wildcards=""" +./matrix/*.*pp +./test/*.*pp +""" + +if [[ $format ]] +then + echo formatting + astyle ${format_wildcards} +else + echo checking format + astyle --dry-run ${format_wildcards} | grep Formatted + if [[ $? -eq 0 ]] + then + echo need to format + exit 1 + fi +fi From 04f24310b5c328a7584f8d159ec399a779e03051 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 22:51:25 -0500 Subject: [PATCH 034/388] Added astyle install to travis. --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index 631c927450..1d18b01803 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,4 +1,6 @@ language: c +before_install: + - if [ $TRAVIS_OS_NAME == linux ]; then sudo apt-get update && sudo apt-get install -y astyle; fi script: - mkdir -p build - cd build From 3fc5ec9751ca34c14d961779401e0237f069a3d8 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 22:53:45 -0500 Subject: [PATCH 035/388] Tried apt addon. --- .travis.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index 1d18b01803..1b837e5e10 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,6 +1,4 @@ language: c -before_install: - - if [ $TRAVIS_OS_NAME == linux ]; then sudo apt-get update && sudo apt-get install -y astyle; fi script: - mkdir -p build - cd build @@ -23,3 +21,7 @@ addons: build_command_prepend: mkdir -p build && cd build && cmake .. && make build_command: make -C build -j 4 branch_pattern: coverity_scan + apt: + packages: + - cmake + - astyle From f23bed6823f99d5867840a3c2256393b18f20aa2 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 22:54:39 -0500 Subject: [PATCH 036/388] Explicity disabled sudo. --- .travis.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.travis.yml b/.travis.yml index 1b837e5e10..0b19fadce9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,4 +1,5 @@ language: c +sudo: false script: - mkdir -p build - cd build From a703c8169e0eec00225feefce645b90e651854f7 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 4 Nov 2015 23:19:20 -0500 Subject: [PATCH 037/388] Working on formatting. --- .travis.yml | 1 - CMakeLists.txt | 18 ++++++++++++++---- scripts/format.sh | 7 ++++--- 3 files changed, 18 insertions(+), 8 deletions(-) diff --git a/.travis.yml b/.travis.yml index 0b19fadce9..55d027c767 100644 --- a/.travis.yml +++ b/.travis.yml @@ -25,4 +25,3 @@ addons: apt: packages: - cmake - - astyle diff --git a/CMakeLists.txt b/CMakeLists.txt index 80e163f20d..f7fe1540a3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -63,16 +63,26 @@ endif() add_subdirectory(test) -add_custom_target(format - COMMAND scripts/format.sh 1 +set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) +add_custom_command(OUTPUT ${astyle_exe} + COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.05.1/astyle_2.05.1_linux.tar.gz -O /tmp/astyle.tar.gz + COMMAND tar -xvf /tmp/astyle.tar.gz + COMMAND cd astyle/src && make -f ../build/gcc/Makefile + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + ) + +add_custom_target(check_format + COMMAND scripts/format.sh ${astyle_exe} 0 WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + DEPENDS ${astyle_exe} VERBATIM ) -add_custom_target(check_format - COMMAND scripts/format.sh +add_custom_target(format + COMMAND scripts/format.sh ${astyle_exe} 1 WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} VERBATIM + DEPENDS ${astyle_exe} ) set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) diff --git a/scripts/format.sh b/scripts/format.sh index f5faa735ec..37f746ac1f 100755 --- a/scripts/format.sh +++ b/scripts/format.sh @@ -1,6 +1,7 @@ #!/bin/bash echo pwd:$PWD -format=$1 +astyle=$1 +format=$2 format_wildcards=""" ./matrix/*.*pp ./test/*.*pp @@ -9,10 +10,10 @@ format_wildcards=""" if [[ $format ]] then echo formatting - astyle ${format_wildcards} + $astyle ${format_wildcards} else echo checking format - astyle --dry-run ${format_wildcards} | grep Formatted + $astyle --dry-run ${format_wildcards} | grep Formatted if [[ $? -eq 0 ]] then echo need to format From f7b1c63b8688af14b4c8008a1edfbe68fea6dbb8 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 10:44:21 -0500 Subject: [PATCH 038/388] Work on testing. --- .gitignore | 1 + matrix/Dcm.hpp | 8 ++++ matrix/Euler.hpp | 4 +- matrix/Matrix.hpp | 39 +++++++++++++++++ matrix/Vector.hpp | 19 +++++--- test/CMakeLists.txt | 4 +- test/attitude.cpp | 73 +++++++++++++++++++++++++++++++ test/dcm.cpp | 19 -------- test/euler.cpp | 20 --------- test/quaternion.cpp | 50 --------------------- test/test_data.py | 104 ++++++++++++++++++++++++++++++++++++++++++++ test/test_math.py | 66 ---------------------------- 12 files changed, 242 insertions(+), 165 deletions(-) create mode 100644 test/attitude.cpp delete mode 100644 test/dcm.cpp delete mode 100644 test/euler.cpp delete mode 100644 test/quaternion.cpp create mode 100644 test/test_data.py delete mode 100644 test/test_math.py diff --git a/.gitignore b/.gitignore index f1feb3e425..b486f209c8 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,3 @@ build*/ *.orig +*.swp diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 40de899688..cbee44f810 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -31,6 +31,14 @@ public: Matrix::setIdentity(); } + Dcm(const Type *data) : Matrix(data) + { + } + + Dcm(const Matrix &other) : Matrix(other) + { + } + Dcm(const Quaternion & q) { Dcm &dcm = *this; Type a = q(0); diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index a6701a9cec..2924994f06 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -42,11 +42,11 @@ public: Type phi = 0; Type psi = 0; - if (abs(theta - M_PI_2) < 1.0e-3) { + if (fabs(theta - M_PI_2) < 1.0e-3) { psi = atan2(dcm(1, 2) - dcm(0, 1), dcm(0, 2) + dcm(1, 1)); - } else if (abs(theta + M_PI_2) < 1.0e-3) { + } else if (fabs(theta + M_PI_2) < 1.0e-3) { psi = atan2(dcm(1, 2) - dcm(0, 1), dcm(0, 2) + dcm(1, 1)); diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 5103626282..b73dece8b3 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -293,6 +293,45 @@ public: } } + Matrix abs() + { + Matrix r; + for (int i=0; i max) { + max = val; + } + } + } + return max; + } + + Type min() + { + Type min = (*this)(0,0); + for (int i=0; i diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 6b77cfc7ff..671b26c614 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -47,20 +47,24 @@ public: return v(i, 0); } - Type dot(const Vector & b) { - Vector &a(*this); + Type dot(const Vector & b) const { + const Vector &a(*this); Type r = 0; - for (int i = 0; i<3; i++) { + for (int i = 0; i operator/(Type scalar) const + { + return (*this)*(1.0/scalar); + } + Vector operator+(Type scalar) const { Vector res; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 53702b78c1..97bf5b5963 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -6,11 +6,9 @@ set(tests matrixAssignment matrixScalarMult transpose - quaternion - dcm vector vector3 - euler + attitude filter ) diff --git a/test/attitude.cpp b/test/attitude.cpp new file mode 100644 index 0000000000..3dc96d329f --- /dev/null +++ b/test/attitude.cpp @@ -0,0 +1,73 @@ +#include +#include + +#include "Quaternion.hpp" +#include "Vector3.hpp" +#include "matrix.hpp" + +using namespace matrix; + +template class Quaternion; +template class Euler; +template class Dcm; + +int main() +{ + double eps = 1e-6; + + // check data + Eulerf euler_check(0.1, 0.2, 0.3); + Quatf q_check(0.98334744, 0.0342708, 0.10602051, .14357218); + float dcm_data[] = { + 0.93629336, -0.27509585, 0.21835066, + 0.28962948, 0.95642509, -0.03695701, + -0.19866933, 0.0978434 , 0.97517033}; + Dcmf dcm_check(dcm_data); + + // euler ctor + euler_check.T().print(); + assert((euler_check - Vector3f(0.1, 0.2, 0.3)).norm() < eps); + + // quaternion ctor + Quatf q(1, 2, 3, 4); + assert(q(0) == 1); + assert(q(1) == 2); + assert(q(2) == 3); + assert(q(3) == 4); + + q.T().print(); + q.normalize(); + q.T().print(); + assert((q - Quatf( + 0.18257419, 0.36514837, 0.54772256, 0.73029674) + ).norm() < eps); + + // euler to quaternion + q = Quatf(euler_check); + q.T().print(); + assert((q - q_check).norm() < eps); + + // euler to dcm + Dcmf dcm(euler_check); + dcm.print(); + assert((dcm - dcm_check).abs().max() < eps); + + // quaternion to euler + Eulerf e1(q_check); + assert((e1 - euler_check).norm() < eps); + + // quaternion to dcm + Dcmf dcm1(q_check); + assert((dcm1 - dcm_check).abs().max() < eps); + + // dcm to euler + Eulerf e2(dcm_check); + assert((e2 - euler_check).norm() < eps); + + // dcm to quaterion + Quatf q2(dcm_check); + assert((q2 - q_check).norm() < eps); + +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/dcm.cpp b/test/dcm.cpp deleted file mode 100644 index a01c8e05db..0000000000 --- a/test/dcm.cpp +++ /dev/null @@ -1,19 +0,0 @@ -#include -#include - -#include "matrix.hpp" - -using namespace matrix; - -int main() -{ - Dcmf dcm; - Quatf q(1,0,0,0); - dcm = Dcmf(q); - Matrix3f I = eye(); - dcm = Dcmf(q); - Eulerf e = Eulerf(dcm); - return 0; -}; - -/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/euler.cpp b/test/euler.cpp deleted file mode 100644 index 236f6e0225..0000000000 --- a/test/euler.cpp +++ /dev/null @@ -1,20 +0,0 @@ -#include "Euler.hpp" -#include "Scalar.hpp" -#include -#include - -using namespace matrix; - -int main() -{ - Eulerf e; - float dp = Scalarf(e.T()*e); - (void)dp; - Dcmf dcm = Dcmf(e); - Quatf q = Quatf(e); - float n = e.norm(); - (void)n; - return 0; -} - -/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/quaternion.cpp b/test/quaternion.cpp deleted file mode 100644 index 018f03a6ad..0000000000 --- a/test/quaternion.cpp +++ /dev/null @@ -1,50 +0,0 @@ -#include "Quaternion.hpp" -#include -#include - -using namespace matrix; - -// instantiate so coverage works -template class Quaternion; -template class Euler; -template class Dcm; - -int main() -{ - // test default ctor - Quatf q; - assert(q(0) == 1); - assert(q(1) == 0); - assert(q(2) == 0); - assert(q(3) == 0); - - q = Quatf(1,2,3,4); - assert(q(0) == 1); - assert(q(1) == 2); - assert(q(2) == 3); - assert(q(3) == 4); - - q = Quatf(0.1825742f, 0.3651484f, 0.5477226f, 0.7302967f); - assert(q(0) == 0.1825742f); - assert(q(1) == 0.3651484f); - assert(q(2) == 0.5477226f); - assert(q(3) == 0.7302967f); - - // test euler ctor - q = Quatf(Eulerf(0.1f, 0.2f, 0.3f)); - assert((q - Quatf(0.983347f, 0.034271f, 0.106021f, 0.143572f)).norm() < 1e-5); - - // test dcm ctor - q = Quatf(Dcmf()); - assert(q == Quatf(1.0f, 0.0f, 0.0f, 0.0f)); - // TODO test derivative - // test accessors - q(0) = 0.1f; - q(1) = 0.2f; - q(2) = 0.3f; - q(3) = 0.4f; - assert(q == Quatf(0.1f, 0.2f, 0.3f, 0.4f)); - return 0; -} - -/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/test_data.py b/test/test_data.py new file mode 100644 index 0000000000..5f64994b06 --- /dev/null +++ b/test/test_data.py @@ -0,0 +1,104 @@ +from __future__ import print_function +from pylab import * +from pprint import pprint + +# test cases, derived from doc/nasa_rotation_def.pdf + +#pylint: disable=all + +def euler_to_quat(phi, theta, psi): + "Quaternion from (body 3(psi)-2(theta)-1(phi) euler angles" + s1 = sin(psi/2) + c1 = cos(psi/2) + s2 = sin(theta/2) + c2 = cos(theta/2) + s3 = sin(phi/2) + c3 = cos(phi/2) + return array([ + s1*s2*s3 + c1*c2*c3, + -s1*s2*c3 + s3*c1*c2, + s1*s3*c2 + s2*c1*c3, + s1*c2*c3 - s2*s3*c1 + ]) + +def euler_to_dcm(phi, theta, psi): + s1 = sin(psi) + c1 = cos(psi) + s2 = sin(theta) + c2 = cos(theta) + s3 = sin(phi) + c3 = cos(phi) + return array([ + [c1*c2, c1*s2*s3 - s1*c3, c1*s2*c3 + s1*s3], + [s1*c2, s1*s2*s3 + c1*c3, s1*s2*c3 - c1*s3], + [-s2, c2*s3, c2*c3], + ]) + +def quat_prod(q, r): + "Quaternion product" + return array([ + r[0]*q[0] - r[1]*q[1] - r[2]*q[2] - r[3]*q[3], + r[0]*q[1] + r[1]*q[0] - r[2]*q[3] + r[3]*q[2], + r[0]*q[2] + r[1]*q[3] + r[2]*q[0] - r[3]*q[1], + r[0]*q[3] - r[1]*q[2] + r[2]*q[1] + r[3]*q[0] + ]) + +def dcm_to_euler(dcm): + return array([ + arctan(dcm[2,1]/ dcm[2,2]), + arctan(-dcm[2,0]/ sqrt(1 - dcm[2,0]**2)), + arctan(dcm[1,0]/ dcm[0,0]), + ]) + +def dcm_from_quat(q): + q1 = q[0] + q2 = q[1] + q3 = q[2] + q4 = q[3] + return array([ + [q1*q1 + q2*q2 - q3*q3 - q4*q4, 2*(q2*q3 - q1*q4), 2*(q2*q4 + q1*q3)], + [2*(q2*q3 + q1*q4), q1*q1 - q2*q2 + q3*q3 - q4*q4, 2*(q3*q4 - q1*q2)], + [2*(q2*q4 - q1*q3), 2*(q3*q4 + q1*q2), q1*q1 - q2*q2 - q3*q3 + q4*q4] + ]) + +def quat_to_euler(q): + "Quaternion to (body 3(psi)-2(theta)-1(phi) euler angles" + return dcm_to_euler(dcm_from_quat(q)) + +def quat_to_dcm(q): + return euler_to_dcm(quat_to_euler(q)) + +phi = 0.1 +theta = 0.2 +psi = 0.3 +print('euler', phi, theta, psi) + +q = euler_to_quat(phi, theta, psi) +assert(abs(norm(q) - 1) < 1e-10) +assert(abs(norm(q) - 1) < 1e-10) +assert(norm(array(quat_to_euler(q)) - array([phi, theta, psi])) < 1e-10) +print('\nq:') +pprint(q) + +dcm = euler_to_dcm(phi, theta, psi) +assert(norm(dcm[:,0]) == 1) +assert(norm(dcm[:,1]) == 1) +assert(norm(dcm[:,2]) == 1) +assert(abs(dcm[:,0].dot(dcm[:,1])) < 1e-10) +assert(abs(dcm[:,0].dot(dcm[:,2])) < 1e-10) +print('\ndcm:') +pprint(dcm) + + +q2 = quat_prod(q, q) +pprint(q2) +print(norm(q2)) + +print('\nq3:') +q3 = array([1,2,3,4]) +pprint(q3) +print('\nq3_norm:') +q3_norm =q3 / norm(q3) +pprint(q3_norm) + +# vim: set et ft=python fenc=utf-8 ff=unix sts=4 sw=4 ts=8 : diff --git a/test/test_math.py b/test/test_math.py deleted file mode 100644 index d5d24da60c..0000000000 --- a/test/test_math.py +++ /dev/null @@ -1,66 +0,0 @@ -from __future__ import print_function -from pylab import * -from pprint import pprint - -#pylint: disable=all - -phi = 0.1 -theta = 0.2 -psi = 0.3 - -cosPhi = cos(phi) -cosPhi_2 = cos(phi/2) -sinPhi = sin(phi) -sinPhi_2 = sin(phi/2) - -cosTheta = cos(theta) -cosTheta_2 = cos(theta/2) -sinTheta = sin(theta) -sinTheta_2 = sin(theta/2) - -cosPsi = cos(psi) -cosPsi_2 = cos(psi/2) -sinPsi = sin(psi) -sinPsi_2 = sin(psi/2) - -C_nb = array([ - [cosTheta*cosPsi, -cosPhi*sinPsi + sinPhi*sinTheta*cosPsi, sinPhi*sinPsi + cosPhi*sinTheta*cosPsi], - [cosTheta*sinPsi, cosPhi*cosPsi + sinPhi*sinTheta*sinPsi, -sinPhi*cosPsi + cosPhi*sinTheta*sinPsi], - [-sinTheta, sinPhi*cosTheta, cosPhi*cosTheta]]) - -print('\nC_nb') -pprint(C_nb) - -theta = arcsin(-C_nb[2,0]) -phi = arctan(C_nb[2,1]/ C_nb[2,2]) -psi = arctan(C_nb[1,0]/ C_nb[0,0]) -print('\nphi {:f}, theta {:f}, psi {:f}\n'.format(phi, theta, psi)) - -q = array([ - cosPhi_2*cosTheta_2*cosPsi_2 + sinPhi_2*sinTheta_2*sinPsi_2, - sinPhi_2*cosTheta_2*cosPsi_2 - cosPhi_2*sinTheta_2*sinPsi_2, - cosPhi_2*sinTheta_2*cosPsi_2 + sinPhi_2*cosTheta_2*sinPsi_2, - cosPhi_2*cosTheta_2*sinPsi_2 - sinPhi_2*sinTheta_2*cosPsi_2]) - -a = q[0] -b = q[1] -c = q[2] -d = q[3] - -print('\nq') -pprint(q.T) - -a2 = a*a -b2 = b*b -c2 = c*c -d2 = d*d - -C2_nb = array([ - [a2 + b2 - c2 - d2, 2*(b*c - a*d), 2*(b*d + a*c)], - [2*(b*c + a*d), a2 - b2 + c2 - d2, 2*(c*d - a*b)], - [2*(b*d - a*c), 2*(c*d + a*b), a2 - b2 - c2 + d2]]) - -print('\nC2_nb') -pprint(C2_nb) - -# vim: set et ft=python fenc=utf-8 ff=unix sts=4 sw=4 ts=8 : From 7c4b2c590e105122134ba33bf980677f83167ec7 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 10:46:22 -0500 Subject: [PATCH 039/388] Update for travis. --- .travis.yml | 1 + test/filter.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 55d027c767..0427c78579 100644 --- a/.travis.yml +++ b/.travis.yml @@ -6,6 +6,7 @@ script: - cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. - make - make check_format + - ctest - ctest -V - make coveralls env: diff --git a/test/filter.cpp b/test/filter.cpp index 8e723e8c63..687c8fae61 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -21,7 +21,7 @@ int main() float beta = 0; kalman_correct(P, C, R, r, dx, beta); - dx.print(); + dx.T().print(); printf("beta: %g\n", beta); float data_check[] = {0.5,1,1.5,2,2.5,0}; From 6ba15eeaa09f23c1cfbb510af195ba49dfa219ab Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 10:51:53 -0500 Subject: [PATCH 040/388] Formatting. --- CMakeLists.txt | 2 +- scripts/format.sh | 3 +++ test/attitude.cpp | 7 ++++--- 3 files changed, 8 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f7fe1540a3..f20bf3939b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,7 +22,7 @@ set(CMAKE_CXX_FLAGS -Wall -Weffc++ -Werror - #-Wfatal-errors + -Wfatal-errors ) if (COVERALLS) diff --git a/scripts/format.sh b/scripts/format.sh index 37f746ac1f..5e5863f141 100755 --- a/scripts/format.sh +++ b/scripts/format.sh @@ -7,6 +7,9 @@ format_wildcards=""" ./test/*.*pp """ +echo astyle: $astyle +echo format: $format + if [[ $format ]] then echo formatting diff --git a/test/attitude.cpp b/test/attitude.cpp index 3dc96d329f..173f1de2c8 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -21,7 +21,8 @@ int main() float dcm_data[] = { 0.93629336, -0.27509585, 0.21835066, 0.28962948, 0.95642509, -0.03695701, - -0.19866933, 0.0978434 , 0.97517033}; + -0.19866933, 0.0978434 , 0.97517033 + }; Dcmf dcm_check(dcm_data); // euler ctor @@ -39,8 +40,8 @@ int main() q.normalize(); q.T().print(); assert((q - Quatf( - 0.18257419, 0.36514837, 0.54772256, 0.73029674) - ).norm() < eps); + 0.18257419, 0.36514837, 0.54772256, 0.73029674) + ).norm() < eps); // euler to quaternion q = Quatf(euler_check); From 0062cbcbe293f53148a0a10d2805c94f2db6a686 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 11:17:54 -0500 Subject: [PATCH 041/388] Added more warnings, and fixed issues. --- CMakeLists.txt | 19 +++++++++++++++++-- matrix/Dcm.hpp | 2 +- matrix/Euler.hpp | 31 +++++++++++++------------------ matrix/Matrix.hpp | 25 +++++++++++++------------ matrix/Quaternion.hpp | 30 +++++++++++++++--------------- matrix/SquareMatrix.hpp | 6 +++--- matrix/Vector.hpp | 16 +--------------- test/attitude.cpp | 22 +++++++++++----------- test/setIdentity.cpp | 4 ++-- test/vectorAssignment.cpp | 14 ++++++++------ 10 files changed, 84 insertions(+), 85 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f20bf3939b..3788e92bbb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,9 +20,24 @@ set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} -Wall - -Weffc++ - -Werror + -Wno-sign-compare + -Wextra + -Wshadow + -Wfloat-equal + -Wpointer-arith + -Wmissing-declarations + -Wno-unused-parameter + -Werror=format-security + -Werror=array-bounds -Wfatal-errors + -Werror=unused-variable + -Werror=reorder + -Werror=uninitialized + -Werror=init-self + -Wcast-qual + -Wconversion + -Wcast-align + -Werror ) if (COVERALLS) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index cbee44f810..89d08f0dd3 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -31,7 +31,7 @@ public: Matrix::setIdentity(); } - Dcm(const Type *data) : Matrix(data) + Dcm(const Type *data_) : Matrix(data_) { } diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 2924994f06..a309f1f3c9 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -30,33 +30,28 @@ public: { } - Euler(Type phi, Type theta, Type psi) : Vector() + Euler(Type phi_, Type theta_, Type psi_) : Vector() { - this->phi() = phi; - this->theta() = theta; - this->psi() = psi; + phi() = phi_; + theta() = theta_; + psi() = psi_; } Euler(const Dcm & dcm) { - Type theta = asin(-dcm(2, 0)); - Type phi = 0; - Type psi = 0; + theta() = Type(asin(-dcm(2, 0))); - if (fabs(theta - M_PI_2) < 1.0e-3) { - psi = atan2(dcm(1, 2) - dcm(0, 1), - dcm(0, 2) + dcm(1, 1)); + if (fabs(theta() - M_PI_2) < 1.0e-3) { + psi() = Type(atan2(dcm(1, 2) - dcm(0, 1), + dcm(0, 2) + dcm(1, 1))); - } else if (fabs(theta + M_PI_2) < 1.0e-3) { - psi = atan2(dcm(1, 2) - dcm(0, 1), - dcm(0, 2) + dcm(1, 1)); + } else if (fabs(theta() + M_PI_2) < 1.0e-3) { + psi() = Type(atan2(dcm(1, 2) - dcm(0, 1), + dcm(0, 2) + dcm(1, 1))); } else { - phi = atan2f(dcm(2, 1), dcm(2, 2)); - psi = atan2f(dcm(1, 0), dcm(0, 0)); + phi() = Type(atan2f(dcm(2, 1), dcm(2, 2))); + psi() = Type(atan2f(dcm(1, 0), dcm(0, 0))); } - this->phi() = phi; - this->theta() = theta; - this->psi() = psi; } Euler(const Quaternion & q) { diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index b73dece8b3..31cb1dbfe4 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -38,10 +38,10 @@ public: { } - Matrix(const Type *data) : + Matrix(const Type *data_) : _data() { - memcpy(_data, data, sizeof(_data)); + memcpy(_data, data_, sizeof(_data)); } Matrix(const Matrix &other) : @@ -113,10 +113,11 @@ public: { Matrix res; const Matrix &self = *this; + static const Type eps = Type(1e-7); for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - if (self(i , j) != other(i, j)) { + if (fabs(self(i , j) - other(i, j)) > eps) { return false; } } @@ -298,7 +299,7 @@ public: Matrix r; for (int i=0; i max) { - max = val; + if (val > max_val) { + max_val = val; } } } - return max; + return max_val; } Type min() { - Type min = (*this)(0,0); + Type min_val = (*this)(0,0); for (int i=0; i() { Quaternion &q = *this; - q(0) = 0.5 * sqrt(1 + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2)); - q(1) = (dcm(2, 1) - dcm(1, 2)) / - (4 * q(0)); - q(2) = (dcm(0, 2) - dcm(2, 0)) / - (4 * q(0)); - q(3) = (dcm(1, 0) - dcm(0, 1)) / - (4 * q(0)); + q(0) = Type(0.5 * sqrt(1 + dcm(0, 0) + + dcm(1, 1) + dcm(2, 2))); + q(1) = Type((dcm(2, 1) - dcm(1, 2)) / + (4 * q(0))); + q(2) = Type((dcm(0, 2) - dcm(2, 0)) / + (4 * q(0))); + q(3) = Type((dcm(1, 0) - dcm(0, 1)) / + (4 * q(0))); } Quaternion(const Euler & euler) { Quaternion &q = *this; - Type cosPhi_2 = cos(euler.phi() / 2.0); - Type cosTheta_2 = cos(euler.theta() / 2.0); - Type cosPsi_2 = cos(euler.psi() / 2.0); - Type sinPhi_2 = sin(euler.phi() / 2.0); - Type sinTheta_2 = sin(euler.theta() / 2.0); - Type sinPsi_2 = sin(euler.psi() / 2.0); + Type cosPhi_2 = Type(cos(euler.phi() / 2.0)); + Type cosTheta_2 = Type(cos(euler.theta() / 2.0)); + Type cosPsi_2 = Type(cos(euler.psi() / 2.0)); + Type sinPhi_2 = Type(sin(euler.phi() / 2.0)); + Type sinTheta_2 = Type(sin(euler.theta() / 2.0)); + Type sinPsi_2 = Type(sin(euler.psi() / 2.0)); q(0) = cosPhi_2 * cosTheta_2 * cosPsi_2 + sinPhi_2 * sinTheta_2 * sinPsi_2; q(1) = sinPhi_2 * cosTheta_2 * cosPsi_2 - @@ -102,7 +102,7 @@ public: v(1) = w(0); v(2) = w(1); v(3) = w(2); - return Q * v * 0.5; + return Q * v * Type(0.5); } }; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 56bd5d37cc..931bbb94a8 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -31,8 +31,8 @@ public: { } - SquareMatrix(const Type *data) : - Matrix(data) + SquareMatrix(const Type *data_) : + Matrix(data_) { } @@ -181,7 +181,7 @@ public: SquareMatrix res; res.setIdentity(); SquareMatrix A_pow = *this; - float k_fact = 1; + size_t k_fact = 1; size_t k = 1; while (k < n) { diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 671b26c614..381a857117 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -58,7 +58,7 @@ public: Type norm() const { const Vector &a(*this); - return sqrt(a.dot(a)); + return Type(sqrt(a.dot(a))); } inline void normalize() { @@ -81,20 +81,6 @@ public: return res; } - bool operator==(const Vector &other) const - { - Vector res; - const Vector &self = *this; - - for (size_t i = 0; i < M; i++) { - if (self(i) != other(i)) { - return false; - } - } - - return true; - } - Vector operator-(const Vector &other) const { Vector res; diff --git a/test/attitude.cpp b/test/attitude.cpp index 173f1de2c8..38e2476bb2 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -16,31 +16,31 @@ int main() double eps = 1e-6; // check data - Eulerf euler_check(0.1, 0.2, 0.3); - Quatf q_check(0.98334744, 0.0342708, 0.10602051, .14357218); + Eulerf euler_check(0.1f, 0.2f, 0.3f); + Quatf q_check(0.98334744f, 0.0342708f, 0.10602051f, .14357218f); float dcm_data[] = { - 0.93629336, -0.27509585, 0.21835066, - 0.28962948, 0.95642509, -0.03695701, - -0.19866933, 0.0978434 , 0.97517033 + 0.93629336f, -0.27509585f, 0.21835066f, + 0.28962948f, 0.95642509f, -0.03695701f, + -0.19866933f, 0.0978434f, 0.97517033f }; Dcmf dcm_check(dcm_data); // euler ctor euler_check.T().print(); - assert((euler_check - Vector3f(0.1, 0.2, 0.3)).norm() < eps); + assert((euler_check - Vector3f(0.1f, 0.2f, 0.3f)).norm() < eps); // quaternion ctor Quatf q(1, 2, 3, 4); - assert(q(0) == 1); - assert(q(1) == 2); - assert(q(2) == 3); - assert(q(3) == 4); + assert(fabs(q(0) - 1) < eps); + assert(fabs(q(1) - 2) < eps); + assert(fabs(q(2) - 3) < eps); + assert(fabs(q(3) - 4) < eps); q.T().print(); q.normalize(); q.T().print(); assert((q - Quatf( - 0.18257419, 0.36514837, 0.54772256, 0.73029674) + 0.18257419f, 0.36514837f, 0.54772256f, 0.73029674f) ).norm() < eps); // euler to quaternion diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index e3b4a2e7dc..75e1c8e69a 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -13,10 +13,10 @@ int main() for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { if (i == j) { - assert(A(i, j) == 1); + assert( fabs(A(i, j) - 1) < 1e-7); } else { - assert(A(i, j) == 0); + assert( fabs(A(i, j) - 0) < 1e-7); } } } diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 9295fc1936..258616f338 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -14,17 +14,19 @@ int main() v.print(); - assert(v(0) == 1); - assert(v(1) == 2); - assert(v(2) == 3); + static const float eps = 1e-7f; + + assert(fabs(v(0) - 1) < eps); + assert(fabs(v(1) - 2) < eps); + assert(fabs(v(2) - 3) < eps); Vector3f v2(4, 5, 6); v2.print(); - assert(v2(0) == 4); - assert(v2(1) == 5); - assert(v2(2) == 6); + assert(fabs(v2(0) - 4) < eps); + assert(fabs(v2(1) - 5) < eps); + assert(fabs(v2(2) - 6) < eps); return 0; } From b8dc26258266b0d7b153ffa48b12d4817287a8c8 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 11:18:33 -0500 Subject: [PATCH 042/388] Formatting. --- matrix/Euler.hpp | 4 ++-- matrix/Quaternion.hpp | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index a309f1f3c9..fb339cdab5 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -42,11 +42,11 @@ public: if (fabs(theta() - M_PI_2) < 1.0e-3) { psi() = Type(atan2(dcm(1, 2) - dcm(0, 1), - dcm(0, 2) + dcm(1, 1))); + dcm(0, 2) + dcm(1, 1))); } else if (fabs(theta() + M_PI_2) < 1.0e-3) { psi() = Type(atan2(dcm(1, 2) - dcm(0, 1), - dcm(0, 2) + dcm(1, 1))); + dcm(0, 2) + dcm(1, 1))); } else { phi() = Type(atan2f(dcm(2, 1), dcm(2, 2))); diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 68162118d4..06c8f9e11f 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -41,13 +41,13 @@ public: { Quaternion &q = *this; q(0) = Type(0.5 * sqrt(1 + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2))); + dcm(1, 1) + dcm(2, 2))); q(1) = Type((dcm(2, 1) - dcm(1, 2)) / - (4 * q(0))); + (4 * q(0))); q(2) = Type((dcm(0, 2) - dcm(2, 0)) / - (4 * q(0))); + (4 * q(0))); q(3) = Type((dcm(1, 0) - dcm(0, 1)) / - (4 * q(0))); + (4 * q(0))); } Quaternion(const Euler & euler) { From cbe8b4ef6f60aa22da6798468a78e0e978cad5ae Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 11:21:48 -0500 Subject: [PATCH 043/388] Travis fix. --- matrix/Vector.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 381a857117..99074f2053 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -123,7 +123,7 @@ public: Vector operator/(Type scalar) const { - return (*this)*(1.0/scalar); + return (*this)*(Type(1.0)/scalar); } Vector operator+(Type scalar) const From 5b0ea675c33b3e0a882f491b97a0f0a3c51a338d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 11:23:54 -0500 Subject: [PATCH 044/388] Fixed float in square matrix. --- matrix/SquareMatrix.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 931bbb94a8..6dd138dda8 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -36,7 +36,7 @@ public: { } - SquareMatrix(const Matrix &other) : + SquareMatrix(const Matrix &other) : Matrix(other) { } @@ -176,16 +176,16 @@ public: return res; } - SquareMatrix expm(float dt, size_t n) const + SquareMatrix expm(Type dt, size_t n) const { - SquareMatrix res; + SquareMatrix res; res.setIdentity(); - SquareMatrix A_pow = *this; + SquareMatrix A_pow = *this; size_t k_fact = 1; size_t k = 1; while (k < n) { - res += A_pow * (float(pow(dt, k)) / k_fact); + res += A_pow * (Type(pow(dt, k)) / k_fact); if (k == n) { break; From bb6b375390854ddcd716e49b35c64521d0e909d9 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 11:25:47 -0500 Subject: [PATCH 045/388] Travis fix. --- matrix/SquareMatrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 6dd138dda8..a86763465d 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -185,7 +185,7 @@ public: size_t k = 1; while (k < n) { - res += A_pow * (Type(pow(dt, k)) / k_fact); + res += A_pow * (Type(pow(dt, k)) / Type(k_fact)); if (k == n) { break; From 9d88b0d573d5fa888c619de6f1225b289d761eb5 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 11:29:18 -0500 Subject: [PATCH 046/388] Fix for gcc 4.6 --- matrix/SquareMatrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index a86763465d..06061b420d 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -185,7 +185,7 @@ public: size_t k = 1; while (k < n) { - res += A_pow * (Type(pow(dt, k)) / Type(k_fact)); + res += A_pow * (Type(pow(dt, Type(k))) / Type(k_fact)); if (k == n) { break; From fd64e7e93a04392c8af05ab8583db2dd64331f79 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 12:28:39 -0500 Subject: [PATCH 047/388] More testing and cleanup. --- CMakeLists.txt | 4 +- matrix/Dcm.hpp | 10 +++-- matrix/Euler.hpp | 17 ++++++++- matrix/Matrix.hpp | 10 ++--- matrix/Quaternion.hpp | 17 ++++++++- matrix/Vector.hpp | 89 ------------------------------------------- matrix/matrix.hpp | 2 +- test/attitude.cpp | 39 +++++++++++++------ test/filter.cpp | 3 +- test/transpose.cpp | 3 +- 10 files changed, 74 insertions(+), 120 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3788e92bbb..8a2f66c1a7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,7 +29,7 @@ set(CMAKE_CXX_FLAGS -Wno-unused-parameter -Werror=format-security -Werror=array-bounds - -Wfatal-errors + #-Wfatal-errors -Werror=unused-variable -Werror=reorder -Werror=uninitialized @@ -37,7 +37,7 @@ set(CMAKE_CXX_FLAGS -Wcast-qual -Wconversion -Wcast-align - -Werror + #-Werror ) if (COVERALLS) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 89d08f0dd3..6740a44384 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -8,9 +8,8 @@ #pragma once -#include -#include -#include +#include "matrix.hpp" + namespace matrix { @@ -18,6 +17,9 @@ namespace matrix template class Quaternion; +template +class Euler; + template class Dcm : public Matrix { @@ -28,7 +30,7 @@ public: Dcm() : Matrix() { - Matrix::setIdentity(); + (*this) = eye(); } Dcm(const Type *data_) : Matrix(data_) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index fb339cdab5..3321906ded 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -30,6 +30,16 @@ public: { } + Euler(const Vector & other) : + Vector(other) + { + } + + Euler(const Matrix & other) : + Vector(other) + { + } + Euler(Type phi_, Type theta_, Type psi_) : Vector() { phi() = phi_; @@ -37,7 +47,8 @@ public: psi() = psi_; } - Euler(const Dcm & dcm) { + Euler(const Dcm & dcm) : Vector() + { theta() = Type(asin(-dcm(2, 0))); if (fabs(theta() - M_PI_2) < 1.0e-3) { @@ -54,7 +65,9 @@ public: } } - Euler(const Quaternion & q) { + Euler(const Quaternion & q) : + Vector() + { *this = Euler(Dcm(q)); } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 31cb1dbfe4..ce8fa2833d 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -26,11 +26,10 @@ template class Matrix { -protected: - Type _data[M][N]; - public: + Type _data[M][N]; + virtual ~Matrix() {}; Matrix() : @@ -111,9 +110,8 @@ public: bool operator==(const Matrix &other) const { - Matrix res; const Matrix &self = *this; - static const Type eps = Type(1e-7); + static const Type eps = Type(1e-6); for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { @@ -336,7 +334,7 @@ public: }; template -Matrix & zero() { +Matrix zero() { Matrix m; m.setZero(); return m; diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 06c8f9e11f..05c6f0e1cc 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -36,6 +36,16 @@ public: q(3) = 0; } + Quaternion(const Vector & other) : + Vector(other) + { + } + + Quaternion(const Matrix & other) : + Vector(other) + { + } + Quaternion(const Dcm & dcm) : Vector() { @@ -50,7 +60,9 @@ public: (4 * q(0))); } - Quaternion(const Euler & euler) { + Quaternion(const Euler & euler) : + Vector() + { Quaternion &q = *this; Type cosPhi_2 = Type(cos(euler.phi() / 2.0)); Type cosTheta_2 = Type(cos(euler.theta() / 2.0)); @@ -68,7 +80,8 @@ public: sinPhi_2 * sinTheta_2 * cosPsi_2; } - Quaternion(Type a, Type b, Type c, Type d) : Vector() + Quaternion(Type a, Type b, Type c, Type d) : + Vector() { Quaternion &q = *this; q(0) = a; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 99074f2053..785db2fb8d 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -64,95 +64,6 @@ public: inline void normalize() { (*this) /= norm(); } - - /** - * Vector Operations - */ - - Vector operator+(const Vector &other) const - { - Vector res; - const Vector &self = *this; - - for (size_t i = 0; i < M; i++) { - res(i) = self(i) + other(i); - } - - return res; - } - - Vector operator-(const Vector &other) const - { - Vector res; - const Vector &self = *this; - - for (size_t i = 0; i < M; i++) { - res(i) = self(i) - other(i); - } - - return res; - } - - void operator+=(const Vector &other) - { - Vector &self = *this; - self = self + other; - } - - void operator-=(const Vector &other) - { - Vector &self = *this; - self = self - other; - } - - /** - * Scalar Operations - */ - - Vector operator*(Type scalar) const - { - Vector res; - const Vector &self = *this; - - for (size_t i = 0; i < M; i++) { - res(i) = self(i) * scalar; - } - - return res; - } - - Vector operator/(Type scalar) const - { - return (*this)*(Type(1.0)/scalar); - } - - Vector operator+(Type scalar) const - { - Vector res; - const Vector &self = *this; - - for (size_t i = 0; i < M; i++) { - res(i) = self(i) + scalar; - } - - return res; - } - - void operator*=(Type scalar) - { - Vector &self = *this; - - for (size_t i = 0; i < M; i++) { - self(i) = self(i) * scalar; - } - } - - void operator/=(Type scalar) - { - Vector &self = *this; - self = self * (1.0f / scalar); - } - }; }; // namespace matrix diff --git a/matrix/matrix.hpp b/matrix/matrix.hpp index e7ea9ca1d4..7e17375eae 100644 --- a/matrix/matrix.hpp +++ b/matrix/matrix.hpp @@ -1,9 +1,9 @@ #pragma once #include "Matrix.hpp" +#include "SquareMatrix.hpp" #include "Vector.hpp" #include "Vector3.hpp" #include "Euler.hpp" #include "Dcm.hpp" #include "Scalar.hpp" -#include "SquareMatrix.hpp" diff --git a/test/attitude.cpp b/test/attitude.cpp index 38e2476bb2..52af8cdd48 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -1,8 +1,6 @@ #include #include -#include "Quaternion.hpp" -#include "Vector3.hpp" #include "matrix.hpp" using namespace matrix; @@ -27,7 +25,13 @@ int main() // euler ctor euler_check.T().print(); - assert((euler_check - Vector3f(0.1f, 0.2f, 0.3f)).norm() < eps); + assert(euler_check == Vector3f(0.1f, 0.2f, 0.3f)); + + // euler default ctor + Eulerf e; + Eulerf e_zero = zero(); + assert(e == e_zero); + assert(e == e); // quaternion ctor Quatf q(1, 2, 3, 4); @@ -36,38 +40,49 @@ int main() assert(fabs(q(2) - 3) < eps); assert(fabs(q(3) - 4) < eps); + // quat normalization q.T().print(); q.normalize(); q.T().print(); - assert((q - Quatf( - 0.18257419f, 0.36514837f, 0.54772256f, 0.73029674f) - ).norm() < eps); + assert(q == Quatf(0.18257419f, 0.36514837f, + 0.54772256f, 0.73029674f)); + + // quat default ctor + q = Quatf(); + assert(q == Quatf(1, 0, 0, 0)); // euler to quaternion q = Quatf(euler_check); q.T().print(); - assert((q - q_check).norm() < eps); + assert(q == q_check); // euler to dcm Dcmf dcm(euler_check); dcm.print(); - assert((dcm - dcm_check).abs().max() < eps); + assert(dcm == dcm_check); // quaternion to euler Eulerf e1(q_check); - assert((e1 - euler_check).norm() < eps); + assert(e1 == euler_check); // quaternion to dcm Dcmf dcm1(q_check); - assert((dcm1 - dcm_check).abs().max() < eps); + dcm1.print(); + assert(dcm1 == dcm_check); + + // dcm default ctor + Dcmf dcm2; + dcm2.print(); + SquareMatrix I = eye(); + assert(dcm2 == I); // dcm to euler Eulerf e2(dcm_check); - assert((e2 - euler_check).norm() < eps); + assert(e2 == euler_check); // dcm to quaterion Quatf q2(dcm_check); - assert((q2 - q_check).norm() < eps); + assert(q2 == q_check); } diff --git a/test/filter.cpp b/test/filter.cpp index 687c8fae61..b2fa0f8b27 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -1,7 +1,8 @@ -#include "filter.hpp" #include #include +#include "filter.hpp" + using namespace matrix; template class Vector; diff --git a/test/transpose.cpp b/test/transpose.cpp index fd466a48c0..fe28077063 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -1,7 +1,8 @@ -#include "Matrix.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; template class Matrix; From 537c683d5885ce01c366cc06795908bc31c65b80 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 12:34:14 -0500 Subject: [PATCH 048/388] More cleanup. --- CMakeLists.txt | 2 +- matrix/matrix.hpp | 2 ++ test/filter.cpp | 2 +- test/inverse.cpp | 3 ++- test/matrixAssignment.cpp | 3 ++- test/matrixMult.cpp | 3 ++- test/matrixScalarMult.cpp | 3 ++- test/setIdentity.cpp | 3 ++- test/vector.cpp | 3 ++- test/vector3.cpp | 3 ++- test/vectorAssignment.cpp | 3 ++- 11 files changed, 20 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8a2f66c1a7..d2cdffb905 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -52,7 +52,7 @@ if (COVERALLS) add_custom_target(coverage COMMAND lcov --capture --directory . --output-file coverage.info COMMAND genhtml coverage.info --output-directory out - COMMAND firefox out/index.html + COMMAND x-www-browser out/index.html WORKING_DIRECTORY ${CMAKE_BUILD_DIR} DEPENDS coveralls ) diff --git a/matrix/matrix.hpp b/matrix/matrix.hpp index 7e17375eae..0b49dc895c 100644 --- a/matrix/matrix.hpp +++ b/matrix/matrix.hpp @@ -7,3 +7,5 @@ #include "Euler.hpp" #include "Dcm.hpp" #include "Scalar.hpp" + +#include "filter.hpp" diff --git a/test/filter.cpp b/test/filter.cpp index b2fa0f8b27..b4103d566c 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -1,7 +1,7 @@ #include #include -#include "filter.hpp" +#include "matrix.hpp" using namespace matrix; diff --git a/test/inverse.cpp b/test/inverse.cpp index 21a2309659..1bd92ae47c 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -1,7 +1,8 @@ -#include "SquareMatrix.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; static const size_t n_large = 50; diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 44e0e3a055..e9f5d3152c 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -1,6 +1,7 @@ -#include "Matrix.hpp" #include +#include "matrix.hpp" + using namespace matrix; template class Matrix; diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 0af96180c6..6ac0670065 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -1,7 +1,8 @@ -#include "Matrix.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; int main() diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index c0b8932604..be093d03fb 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -1,7 +1,8 @@ -#include "Matrix.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; int main() diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index 75e1c8e69a..c4e8830603 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -1,6 +1,7 @@ -#include "Matrix.hpp" #include +#include "matrix.hpp" + using namespace matrix; template class Matrix; diff --git a/test/vector.cpp b/test/vector.cpp index c7ee34ec75..5c63140311 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -1,7 +1,8 @@ -#include "Vector.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; template class Vector; diff --git a/test/vector3.cpp b/test/vector3.cpp index 1535efd549..a7a033bf38 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -1,7 +1,8 @@ -#include "Vector3.hpp" #include #include +#include "matrix.hpp" + using namespace matrix; template class Vector; diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 258616f338..86b3571f8e 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -1,6 +1,7 @@ -#include "Vector3.hpp" #include +#include "matrix.hpp" + using namespace matrix; template class Vector; From 9af1604daa0d24d67bb4d138cb89aae498837ca8 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 12:45:53 -0500 Subject: [PATCH 049/388] Formatting. --- test/attitude.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 52af8cdd48..cd4e3c15af 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -45,7 +45,7 @@ int main() q.normalize(); q.T().print(); assert(q == Quatf(0.18257419f, 0.36514837f, - 0.54772256f, 0.73029674f)); + 0.54772256f, 0.73029674f)); // quat default ctor q = Quatf(); From 31821a44aaee33b303502c98fae19b321595a0e6 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 13:33:35 -0500 Subject: [PATCH 050/388] Fixed formatting script. --- scripts/format.sh | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/scripts/format.sh b/scripts/format.sh index 5e5863f141..bd06600bff 100755 --- a/scripts/format.sh +++ b/scripts/format.sh @@ -7,10 +7,10 @@ format_wildcards=""" ./test/*.*pp """ -echo astyle: $astyle -echo format: $format +#echo astyle: $astyle +#echo format: $format -if [[ $format ]] +if [[ $format -eq 1 ]] then echo formatting $astyle ${format_wildcards} @@ -22,4 +22,6 @@ else echo need to format exit 1 fi + echo no formatting needed + exit 0 fi From 6aa8a7265154e958d810ab0210856a334706b314 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 13:34:49 -0500 Subject: [PATCH 051/388] Renamed coverage option. --- .travis.yml | 2 +- CMakeLists.txt | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index 0427c78579..4d5ddf4973 100644 --- a/.travis.yml +++ b/.travis.yml @@ -3,7 +3,7 @@ sudo: false script: - mkdir -p build - cd build - - cmake -DCOVERALLS=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. + - cmake -DCOVERAGE=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. - make - make check_format - ctest diff --git a/CMakeLists.txt b/CMakeLists.txt index d2cdffb905..6ea868538e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ set(VERSION_PATCH "0") project(matrix CXX) -option(COVERALLS "Turn on coveralls support" OFF) +option(COVERAGE "Enable code coverage" OFF) option(COVERALLS_UPLOAD "Upload the generated coveralls json" OFF) if (NOT CMAKE_BUILD_TYPE) @@ -40,7 +40,7 @@ set(CMAKE_CXX_FLAGS #-Werror ) -if (COVERALLS) +if (COVERAGE) list(APPEND CMAKE_CXX_FLAGS -fno-inline -fno-inline-small-functions From 5517532c907caf21fc2e53e41eb9e4fc0e0e28ae Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 13:37:14 -0500 Subject: [PATCH 052/388] Fixed coveralls build. --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6ea868538e..8e63caf230 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,6 +41,7 @@ set(CMAKE_CXX_FLAGS ) if (COVERAGE) + set(COVERALLS ON) list(APPEND CMAKE_CXX_FLAGS -fno-inline -fno-inline-small-functions From 5566b3dc777e4e6534dedb532bd7bd908be4b2e5 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 15:39:41 -0500 Subject: [PATCH 053/388] expm testing and fixes. --- matrix/Matrix.hpp | 7 ++++++- matrix/SquareMatrix.hpp | 40 +++++++++++++++++----------------------- test/CMakeLists.txt | 1 + test/inverse.cpp | 12 +++++++++--- test/squareMatrix.cpp | 34 ++++++++++++++++++++++++++++++++++ test/test_data.py | 22 ++++++++++++++++++++++ test/vector.cpp | 4 ++++ 7 files changed, 93 insertions(+), 27 deletions(-) create mode 100644 test/squareMatrix.cpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index ce8fa2833d..ba16ef801f 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -14,7 +14,7 @@ #include #include -#include "Vector.hpp" +#include "matrix.hpp" namespace matrix { @@ -175,6 +175,11 @@ public: return res; } + inline Matrix operator/(Type scalar) const + { + return (*this)*(1/scalar); + } + Matrix operator+(Type scalar) const { Matrix res; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 06061b420d..ec3a450188 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -165,7 +165,7 @@ public: return inverse(); } - Vector diagonal() const + Vector diag() const { Vector res; const SquareMatrix &self = *this; @@ -176,28 +176,6 @@ public: return res; } - SquareMatrix expm(Type dt, size_t n) const - { - SquareMatrix res; - res.setIdentity(); - SquareMatrix A_pow = *this; - size_t k_fact = 1; - size_t k = 1; - - while (k < n) { - res += A_pow * (Type(pow(dt, Type(k))) / Type(k_fact)); - - if (k == n) { - break; - } - - A_pow *= A_pow; - k_fact *= k; - k++; - } - - return res; - } }; typedef SquareMatrix SquareMatrix3f; @@ -218,6 +196,22 @@ SquareMatrix diag(Vector d) { return m; } +template +SquareMatrix expm(const SquareMatrix & A, size_t order=5) +{ + SquareMatrix res; + SquareMatrix A_pow = A; + res.setIdentity(); + size_t i_factorial = 1; + for (size_t i=1; i<=order; i++) { + i_factorial *= i; + res += A_pow / Type(i_factorial); + A_pow *= A_pow; + } + + return res; +} + }; // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 97bf5b5963..2f0570c7a6 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -10,6 +10,7 @@ set(tests vector3 attitude filter + squareMatrix ) foreach(test ${tests}) diff --git a/test/inverse.cpp b/test/inverse.cpp index 1bd92ae47c..c2d60c9003 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -12,12 +12,18 @@ template class SquareMatrix; int main() { - float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; + float data[9] = {1, 2, 3, + 4, 5, 6, + 7, 8, 10}; + float data_check[9] = {-0.66666667f, -1.33333333f, 1. , + -0.66666667f, 3.66666667f, -2. , + 1. , -2. , 1. }; + SquareMatrix A(data); SquareMatrix A_I = A.inverse(); - float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; SquareMatrix A_I_check(data_check); - (void)A_I; + A_I.print(); + A_I_check.print(); assert(A_I == A_I_check); // stess test diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp new file mode 100644 index 0000000000..9b64d122c9 --- /dev/null +++ b/test/squareMatrix.cpp @@ -0,0 +1,34 @@ +#include +#include + +#include "matrix.hpp" + +using namespace matrix; + +template class SquareMatrix; + +int main() +{ + float data[9] = {1, 2, 3, + 4, 5, 6, + 7, 8, 10}; + SquareMatrix A(data); + Vector3 diag_check(1, 5, 10); + A.diag().T().print(); + + assert(A.diag() == diag_check); + + float data_check[9] = { + 1.01158503f, 0.02190432f, 0.03238144f, + 0.04349195f, 1.05428524f, 0.06539627f, + 0.07576783f, 0.08708946f, 1.10894048f}; + + printf("expm(A*t)\n"); + float dt = 0.01f; + SquareMatrix eA = expm(SquareMatrix(A*dt), 5); + SquareMatrix eA_check(data_check); + assert((eA - eA_check).abs().max() < 1e-3); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/test_data.py b/test/test_data.py index 5f64994b06..f6da657d98 100644 --- a/test/test_data.py +++ b/test/test_data.py @@ -1,6 +1,7 @@ from __future__ import print_function from pylab import * from pprint import pprint +import scipy.linalg # test cases, derived from doc/nasa_rotation_def.pdf @@ -101,4 +102,25 @@ print('\nq3_norm:') q3_norm =q3 / norm(q3) pprint(q3_norm) +print('\ninverse') +A = array([[1,2,3], [4,5,6], [7,8,10]]) +pprint(A) +pprint(inv(A)) + +print('\nmatrix exponential') +A = 0.01*array([[1.0,2.0,3.0], [4.0,5.0,6.0], [7.0,8.0,10.0]]) +eA_check = scipy.linalg.expm(A) + +pprint(eA_check) + +eA_approx = eye(3) +k = 1.0 +A_pow = A +for i in range(1,3): + k *= i + # print(i, k, '\n', A_pow/k, '\n') + eA_approx += A_pow/k + A_pow = A_pow.dot(A) +print(eA_approx) + # vim: set et ft=python fenc=utf-8 ff=unix sts=4 sw=4 ts=8 : diff --git a/test/vector.cpp b/test/vector.cpp index 5c63140311..dc27463da4 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -14,6 +14,10 @@ int main() (void)n; float r = v.dot(v); (void)r; + + Vector v2(v); + assert(v == v2); + return 0; } From 00a0b36836e49b61db8b52127e0a42bae34db9ba Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 15:43:36 -0500 Subject: [PATCH 054/388] Moved inverse outside of matrix definition. --- matrix/SquareMatrix.hpp | 240 ++++++++++++++++++++-------------------- test/inverse.cpp | 4 +- 2 files changed, 123 insertions(+), 121 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ec3a450188..ad74b217da 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -41,128 +41,10 @@ public: { } - /** - * inverse based on LU factorization with partial pivotting - */ - SquareMatrix inverse() const - { - SquareMatrix L; - L.setIdentity(); - const SquareMatrix &A = (*this); - SquareMatrix U = A; - SquareMatrix P; - P.setIdentity(); - - //printf("A:\n"); A.print(); - - // for all diagonal elements - for (size_t n = 0; n < M; n++) { - - // if diagonal is zero, swap with row below - if (fabsf(U(n, n)) < 1e-8f) { - //printf("trying pivot for row %d\n",n); - for (size_t i = 0; i < M; i++) { - if (i == n) { - continue; - } - - //printf("\ttrying row %d\n",i); - if (fabsf(U(i, n)) > 1e-8f) { - //printf("swapped %d\n",i); - U.swapRows(i, n); - P.swapRows(i, n); - } - } - } - -#ifdef MATRIX_ASSERT - //printf("A:\n"); A.print(); - //printf("U:\n"); U.print(); - //printf("P:\n"); P.print(); - //fflush(stdout); - ASSERT(fabsf(U(n, n)) > 1e-8f); -#endif - - // failsafe, return zero matrix - if (fabsf(U(n, n)) < 1e-8f) { - SquareMatrix zero; - zero.setZero(); - return zero; - } - - // for all rows below diagonal - for (size_t i = (n + 1); i < M; i++) { - L(i, n) = U(i, n) / U(n, n); - - // add i-th row and n-th row - // multiplied by: -a(i,n)/a(n,n) - for (size_t k = n; k < M; k++) { - U(i, k) -= L(i, n) * U(n, k); - } - } - } - - //printf("L:\n"); L.print(); - //printf("U:\n"); U.print(); - - // solve LY=P*I for Y by forward subst - SquareMatrix Y = P; - - // for all columns of Y - for (size_t c = 0; c < M; c++) { - // for all rows of L - for (size_t i = 0; i < M; i++) { - // for all columns of L - for (size_t j = 0; j < i; j++) { - // for all existing y - // subtract the component they - // contribute to the solution - Y(i, c) -= L(i, j) * Y(j, c); - } - - // divide by the factor - // on current - // term to be solved - // Y(i,c) /= L(i,i); - // but L(i,i) = 1.0 - } - } - - //printf("Y:\n"); Y.print(); - - // solve Ux=y for x by back subst - SquareMatrix X = Y; - - // for all columns of X - for (size_t c = 0; c < M; c++) { - // for all rows of U - for (size_t k = 0; k < M; k++) { - // have to go in reverse order - size_t i = M - 1 - k; - - // for all columns of U - for (size_t j = i + 1; j < M; j++) { - // for all existing x - // subtract the component they - // contribute to the solution - X(i, c) -= U(i, j) * X(j, c); - } - - // divide by the factor - // on current - // term to be solved - X(i, c) /= U(i, i); - } - } - - //printf("X:\n"); X.print(); - return X; - } - // inverse alias inline SquareMatrix I() const { - return inverse(); + return inv(*this); } Vector diag() const @@ -212,6 +94,126 @@ SquareMatrix expm(const SquareMatrix & A, size_t order=5) return res; } +/** + * inverse based on LU factorization with partial pivotting + */ +template +SquareMatrix inv(const SquareMatrix & A) +{ + SquareMatrix L; + L.setIdentity(); + SquareMatrix U = A; + SquareMatrix P; + P.setIdentity(); + + //printf("A:\n"); A.print(); + + // for all diagonal elements + for (size_t n = 0; n < M; n++) { + + // if diagonal is zero, swap with row below + if (fabsf(U(n, n)) < 1e-8f) { + //printf("trying pivot for row %d\n",n); + for (size_t i = 0; i < M; i++) { + if (i == n) { + continue; + } + + //printf("\ttrying row %d\n",i); + if (fabsf(U(i, n)) > 1e-8f) { + //printf("swapped %d\n",i); + U.swapRows(i, n); + P.swapRows(i, n); + } + } + } + +#ifdef MATRIX_ASSERT + //printf("A:\n"); A.print(); + //printf("U:\n"); U.print(); + //printf("P:\n"); P.print(); + //fflush(stdout); + ASSERT(fabsf(U(n, n)) > 1e-8f); +#endif + + // failsafe, return zero matrix + if (fabsf(U(n, n)) < 1e-8f) { + SquareMatrix zero; + zero.setZero(); + return zero; + } + + // for all rows below diagonal + for (size_t i = (n + 1); i < M; i++) { + L(i, n) = U(i, n) / U(n, n); + + // add i-th row and n-th row + // multiplied by: -a(i,n)/a(n,n) + for (size_t k = n; k < M; k++) { + U(i, k) -= L(i, n) * U(n, k); + } + } + } + + //printf("L:\n"); L.print(); + //printf("U:\n"); U.print(); + + // solve LY=P*I for Y by forward subst + SquareMatrix Y = P; + + // for all columns of Y + for (size_t c = 0; c < M; c++) { + // for all rows of L + for (size_t i = 0; i < M; i++) { + // for all columns of L + for (size_t j = 0; j < i; j++) { + // for all existing y + // subtract the component they + // contribute to the solution + Y(i, c) -= L(i, j) * Y(j, c); + } + + // divide by the factor + // on current + // term to be solved + // Y(i,c) /= L(i,i); + // but L(i,i) = 1.0 + } + } + + //printf("Y:\n"); Y.print(); + + // solve Ux=y for x by back subst + SquareMatrix X = Y; + + // for all columns of X + for (size_t c = 0; c < M; c++) { + // for all rows of U + for (size_t k = 0; k < M; k++) { + // have to go in reverse order + size_t i = M - 1 - k; + + // for all columns of U + for (size_t j = i + 1; j < M; j++) { + // for all existing x + // subtract the component they + // contribute to the solution + X(i, c) -= U(i, j) * X(j, c); + } + + // divide by the factor + // on current + // term to be solved + X(i, c) /= U(i, i); + } + } + + //printf("X:\n"); X.print(); + return X; +} + + + }; // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/inverse.cpp b/test/inverse.cpp index c2d60c9003..2dd17eb9a4 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -20,7 +20,7 @@ int main() 1. , -2. , 1. }; SquareMatrix A(data); - SquareMatrix A_I = A.inverse(); + SquareMatrix A_I = inv(A); SquareMatrix A_I_check(data_check); A_I.print(); A_I_check.print(); @@ -33,7 +33,7 @@ int main() A_large_I.setZero(); for (size_t i = 0; i < n_large; i++) { - A_large_I = A_large.inverse(); + A_large_I = inv(A_large); assert(A_large == A_large_I); } From d01e0a10382b4cb80023583f15c3264a59c1b07f Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 15:44:54 -0500 Subject: [PATCH 055/388] Formatting. --- test/inverse.cpp | 6 ++++-- test/squareMatrix.cpp | 6 ++++-- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/test/inverse.cpp b/test/inverse.cpp index 2dd17eb9a4..5cffe7c808 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -14,10 +14,12 @@ int main() { float data[9] = {1, 2, 3, 4, 5, 6, - 7, 8, 10}; + 7, 8, 10 + }; float data_check[9] = {-0.66666667f, -1.33333333f, 1. , -0.66666667f, 3.66666667f, -2. , - 1. , -2. , 1. }; + 1. , -2. , 1. + }; SquareMatrix A(data); SquareMatrix A_I = inv(A); diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 9b64d122c9..91a3f36fbd 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -11,7 +11,8 @@ int main() { float data[9] = {1, 2, 3, 4, 5, 6, - 7, 8, 10}; + 7, 8, 10 + }; SquareMatrix A(data); Vector3 diag_check(1, 5, 10); A.diag().T().print(); @@ -21,7 +22,8 @@ int main() float data_check[9] = { 1.01158503f, 0.02190432f, 0.03238144f, 0.04349195f, 1.05428524f, 0.06539627f, - 0.07576783f, 0.08708946f, 1.10894048f}; + 0.07576783f, 0.08708946f, 1.10894048f + }; printf("expm(A*t)\n"); float dt = 0.01f; From 7136e5b7d1442250f460b0787e4c97fcea336108 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 16:54:19 -0500 Subject: [PATCH 056/388] More work on gimbal lock case. --- matrix/Euler.hpp | 27 +++++++++++++++------------ matrix/Matrix.hpp | 4 ++-- test/attitude.cpp | 28 ++++++++++++++++++++++++++++ 3 files changed, 45 insertions(+), 14 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 3321906ded..472ee3da8d 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -49,19 +49,22 @@ public: Euler(const Dcm & dcm) : Vector() { - theta() = Type(asin(-dcm(2, 0))); + Type psi_val = Type(atan(dcm(1, 0)/ dcm(0, 0))); + Type theta_val = Type(asin(-dcm(2,0))); + Type phi_val = Type(atan(dcm(2, 1)/ dcm(2, 2))); - if (fabs(theta() - M_PI_2) < 1.0e-3) { - psi() = Type(atan2(dcm(1, 2) - dcm(0, 1), - dcm(0, 2) + dcm(1, 1))); - - } else if (fabs(theta() + M_PI_2) < 1.0e-3) { - psi() = Type(atan2(dcm(1, 2) - dcm(0, 1), - dcm(0, 2) + dcm(1, 1))); - - } else { - phi() = Type(atan2f(dcm(2, 1), dcm(2, 2))); - psi() = Type(atan2f(dcm(1, 0), dcm(0, 0))); + // protection against gimbal lock + psi() = 0; + theta() = 0; + phi() = 0; + if (isfinite(psi_val)) { + psi() = psi_val; + } + if (isfinite(theta_val)) { + theta() = theta_val; + } + if (isfinite(phi_val)) { + phi() = phi_val; } } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index ba16ef801f..d260256e7b 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -215,9 +215,9 @@ public: * Misc. Functions */ - void print() + void print() const { - Matrix &self = *this; + const Matrix &self = *this; printf("\n"); for (size_t i = 0; i < M; i++) { diff --git a/test/attitude.cpp b/test/attitude.cpp index cd4e3c15af..32020bccd6 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -33,6 +33,14 @@ int main() assert(e == e_zero); assert(e == e); + // euler vector ctor + Vector v; + v(0) = 0.1f; + v(1) = 0.2f; + v(2) = 0.3f; + Eulerf euler_copy(v); + assert(euler_copy == euler_check); + // quaternion ctor Quatf q(1, 2, 3, 4); assert(fabs(q(0) - 1) < eps); @@ -84,6 +92,26 @@ int main() Quatf q2(dcm_check); assert(q2 == q_check); + + // euler gimbal lock check + // note if theta = pi/2, then roll is set to zero + float pi_2 = float(M_PI_2); + Eulerf euler_gimbal_lock(0.0f, pi_2, 0.0f); + Dcmf dcm_lock(euler_gimbal_lock); + Eulerf euler_gimbal_lock_out(dcm_lock); + euler_gimbal_lock_out.print(); + euler_gimbal_lock.print(); + assert(euler_gimbal_lock == euler_gimbal_lock_out); + + // note if theta = pi/2, then roll is set to zero + Eulerf euler_gimbal_lock2(0.0f, -pi_2, 0.0f); + Dcmf dcm_lock2(euler_gimbal_lock2); + Eulerf euler_gimbal_lock_out2(dcm_lock2); + euler_gimbal_lock_out2.print(); + euler_gimbal_lock2.print(); + assert(euler_gimbal_lock2 == euler_gimbal_lock_out2); + + } /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 6ff42b7b3135d2873b1efa6a46ce9a510d1979d6 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 16:59:59 -0500 Subject: [PATCH 057/388] Added some more vectors tests. --- test/vector.cpp | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/test/vector.cpp b/test/vector.cpp index dc27463da4..fbca45d129 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -9,15 +9,12 @@ template class Vector; int main() { - Vector v; - float n = v.norm(); - (void)n; - float r = v.dot(v); - (void)r; - - Vector v2(v); - assert(v == v2); - + float data1[] = {1,2,3,4,5}; + float data2[] = {6,7,8,9,10}; + Vector v1(data1); + assert(fabs(v1.norm() - 7.416198487095663f) < 1e-5); + Vector v2(data2); + assert(fabs(v1.dot(v2) - 130.0f) < 1e-5); return 0; } From 455cb58ebf67306682e6ff42a1237b06b8603cbb Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 17:03:22 -0500 Subject: [PATCH 058/388] New tests. --- test/vector.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/test/vector.cpp b/test/vector.cpp index fbca45d129..7cdd426a4f 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -15,6 +15,9 @@ int main() assert(fabs(v1.norm() - 7.416198487095663f) < 1e-5); Vector v2(data2); assert(fabs(v1.dot(v2) - 130.0f) < 1e-5); + v2.normalize(); + Vector v3(v2); + assert(v2 == v3); return 0; } From 75399fb15e84faadef014ac74e67089053896498 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 17:13:03 -0500 Subject: [PATCH 059/388] Cleanup of printing. --- test/attitude.cpp | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 32020bccd6..5ce509701b 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -96,22 +96,35 @@ int main() // euler gimbal lock check // note if theta = pi/2, then roll is set to zero float pi_2 = float(M_PI_2); - Eulerf euler_gimbal_lock(0.0f, pi_2, 0.0f); + Eulerf euler_gimbal_lock(0.1f, pi_2, 0.2f); Dcmf dcm_lock(euler_gimbal_lock); Eulerf euler_gimbal_lock_out(dcm_lock); - euler_gimbal_lock_out.print(); - euler_gimbal_lock.print(); + euler_gimbal_lock_out.T().print(); + euler_gimbal_lock.T().print(); assert(euler_gimbal_lock == euler_gimbal_lock_out); // note if theta = pi/2, then roll is set to zero - Eulerf euler_gimbal_lock2(0.0f, -pi_2, 0.0f); + Eulerf euler_gimbal_lock2(0.1f, -pi_2, 0.2f); Dcmf dcm_lock2(euler_gimbal_lock2); Eulerf euler_gimbal_lock_out2(dcm_lock2); - euler_gimbal_lock_out2.print(); - euler_gimbal_lock2.print(); + euler_gimbal_lock_out2.T().print(); + euler_gimbal_lock2.T().print(); assert(euler_gimbal_lock2 == euler_gimbal_lock_out2); + // quaterion copy ctors + float data_v4[] = {1, 2, 3, 4}; + Vector v4(data_v4); + Quatf q_from_v(v4); + assert(q_from_v == v4); -} + Matrix m4(data_v4); + Quatf q_from_m(m4); + assert(q_from_m == m4); + + // quaternion derivate + Vector q_dot = q.derivative(Vector3f(1, 2, 3)); + printf("q_dot:\n"); + q_dot.T().print(); +}; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 550108cf1d2c9a98816cfb63910eb455f3319a63 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 17:29:57 -0500 Subject: [PATCH 060/388] More testing. --- matrix/Matrix.hpp | 16 ++++++++++++++++ test/matrixAssignment.cpp | 23 +++++++++++++++++++++++ 2 files changed, 39 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index d260256e7b..45e22b6307 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -194,6 +194,11 @@ public: return res; } + inline Matrix operator-(Type scalar) const + { + return (*this) + (-1*scalar); + } + void operator*=(Type scalar) { Matrix &self = *this; @@ -211,6 +216,17 @@ public: self = self * (1.0f / scalar); } + inline void operator+=(Type scalar) + { + *this = (*this) + scalar; + } + + inline void operator-=(Type scalar) + { + *this = (*this) - scalar; + } + + /** * Misc. Functions */ diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index e9f5d3152c..635d0291e8 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -26,7 +26,30 @@ int main() Matrix3f m2(data); m2.print(); + for(int i=0; i<9; i++) { + assert(fabs(data[i] - m2.data()[i]) < 1e-6f); + } + + float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; + Matrix3f m3(data_times_2); + assert(m == m2); + assert(!(m == m3)); + + m2 *= 2; + assert(m2 == m3); + + m2 /= 2; + m2 -= 1; + float data_minus_1[9] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; + assert(Matrix3f(data_minus_1) == m2); + + m2 += 1; + assert(Matrix3f(data) == m2); + + m3 -= m2; + + assert(m3 == m2); return 0; } From 4a6369cee578e703d9f4103c17a383896e19cd52 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 18:07:05 -0500 Subject: [PATCH 061/388] More coverage testing. --- test/attitude.cpp | 6 ++++++ test/inverse.cpp | 15 +++++++++------ test/matrixAssignment.cpp | 20 ++++++++++++++++++++ test/test_data.py | 3 ++- 4 files changed, 37 insertions(+), 7 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 5ce509701b..5ce3c45b4a 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -125,6 +125,12 @@ int main() Vector q_dot = q.derivative(Vector3f(1, 2, 3)); printf("q_dot:\n"); q_dot.T().print(); + + // quaternion product + Quatf q_prod_check( + 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); + assert(q_prod_check == q_check*q_check); + }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/inverse.cpp b/test/inverse.cpp index 5cffe7c808..7a438d0859 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -12,21 +12,21 @@ template class SquareMatrix; int main() { - float data[9] = {1, 2, 3, + float data[9] = {0, 2, 3, 4, 5, 6, 7, 8, 10 }; - float data_check[9] = {-0.66666667f, -1.33333333f, 1. , - -0.66666667f, 3.66666667f, -2. , - 1. , -2. , 1. - }; + float data_check[9] = { + -0.4f, -0.8f, 0.6f, + -0.4f, 4.2f, -2.4f, + 0.6f, -2.8f, 1.6f}; SquareMatrix A(data); SquareMatrix A_I = inv(A); SquareMatrix A_I_check(data_check); A_I.print(); A_I_check.print(); - assert(A_I == A_I_check); + assert((A_I - A_I_check).abs().max() < 1e-5); // stess test SquareMatrix A_large; @@ -39,6 +39,9 @@ int main() assert(A_large == A_large_I); } + SquareMatrix zero_test = zero(); + inv(zero_test); + return 0; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 635d0291e8..6083a92554 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -51,6 +51,26 @@ int main() assert(m3 == m2); + float data_row_02_swap[9] = { + 7, 8, 9, + 4, 5, 6, + 1, 2, 3, + }; + + float data_col_02_swap[9] = { + 3, 2, 1, + 6, 5, 4, + 9, 8, 7}; + + Matrix3f m4(data); + + + m4.swapCols(0, 2); + assert(m4 == Matrix3f(data_col_02_swap)); + m4.swapCols(0, 2); + m4.swapRows(0, 2); + assert(m4 == Matrix3f(data_row_02_swap)); + assert(fabs(m4.min() - 1) < 1e-5); return 0; } diff --git a/test/test_data.py b/test/test_data.py index f6da657d98..0ae4e958ae 100644 --- a/test/test_data.py +++ b/test/test_data.py @@ -90,6 +90,7 @@ assert(abs(dcm[:,0].dot(dcm[:,2])) < 1e-10) print('\ndcm:') pprint(dcm) +print('\nq*q', quat_prod(q, q)) q2 = quat_prod(q, q) pprint(q2) @@ -103,7 +104,7 @@ q3_norm =q3 / norm(q3) pprint(q3_norm) print('\ninverse') -A = array([[1,2,3], [4,5,6], [7,8,10]]) +A = array([[0,2,3], [4,5,6], [7,8,10]]) pprint(A) pprint(inv(A)) From c70994e6a5b3135815b6656f5f9f7e1c1219181b Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 18:10:06 -0500 Subject: [PATCH 062/388] Formatting. --- test/attitude.cpp | 2 +- test/inverse.cpp | 3 ++- test/matrixAssignment.cpp | 3 ++- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 5ce3c45b4a..3d38aa9d94 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -128,7 +128,7 @@ int main() // quaternion product Quatf q_prod_check( - 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); + 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); assert(q_prod_check == q_check*q_check); }; diff --git a/test/inverse.cpp b/test/inverse.cpp index 7a438d0859..ba85fae463 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -19,7 +19,8 @@ int main() float data_check[9] = { -0.4f, -0.8f, 0.6f, -0.4f, 4.2f, -2.4f, - 0.6f, -2.8f, 1.6f}; + 0.6f, -2.8f, 1.6f + }; SquareMatrix A(data); SquareMatrix A_I = inv(A); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 6083a92554..8202920a4a 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -60,7 +60,8 @@ int main() float data_col_02_swap[9] = { 3, 2, 1, 6, 5, 4, - 9, 8, 7}; + 9, 8, 7 + }; Matrix3f m4(data); From b06c557a2afb54642499583d20fb969615ce340d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 18:16:07 -0500 Subject: [PATCH 063/388] Comment fix. --- matrix/Quaternion.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 05c6f0e1cc..cf29a646f5 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -1,5 +1,5 @@ /** - * @file Matrix.hpp + * @file Quaternion.hpp * * A quaternion class. * From cefe7b3e804997a7c92c2e99f0d52f47ca6d789c Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 19:25:44 -0500 Subject: [PATCH 064/388] Cleaned up header includes. --- matrix/Euler.hpp | 5 ++--- matrix/Quaternion.hpp | 5 ++--- matrix/Scalar.hpp | 2 +- matrix/SquareMatrix.hpp | 2 +- matrix/Vector.hpp | 2 +- matrix/Vector3.hpp | 3 ++- matrix/matrix.hpp | 2 +- 7 files changed, 10 insertions(+), 11 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 472ee3da8d..61e26753b6 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -7,9 +7,8 @@ */ #pragma once -#include -#include -#include + +#include "matrix.hpp" namespace matrix { diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index cf29a646f5..96a9497277 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -7,9 +7,8 @@ */ #pragma once -#include -#include -#include + +#include "matrix.hpp" namespace matrix { diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index fdf2df6fb8..6523060f12 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -14,7 +14,7 @@ #include #include -#include "Matrix.hpp" +#include "matrix.hpp" namespace matrix { diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ad74b217da..a3dbdc6c78 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -14,7 +14,7 @@ #include #include -#include "Matrix.hpp" +#include "matrix.hpp" namespace matrix { diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 785db2fb8d..db42f6bdbf 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -7,7 +7,7 @@ */ #pragma once -#include +#include "matrix.hpp" namespace matrix { diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 8f667f90a7..86ee427209 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -7,7 +7,8 @@ */ #pragma once -#include + +#include "matrix.hpp" namespace matrix { diff --git a/matrix/matrix.hpp b/matrix/matrix.hpp index 0b49dc895c..b3c2997712 100644 --- a/matrix/matrix.hpp +++ b/matrix/matrix.hpp @@ -7,5 +7,5 @@ #include "Euler.hpp" #include "Dcm.hpp" #include "Scalar.hpp" - +#include "Quaternion.hpp" #include "filter.hpp" From 44768fad35354c4be996c05f34d14274ac45ebfc Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 19:32:28 -0500 Subject: [PATCH 065/388] Added vector data ctor. --- matrix/Vector.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index db42f6bdbf..a65b5dfff0 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -35,6 +35,11 @@ public: { } + Vector(const Type *data_) : + Matrix(data_) + { + } + inline Type operator()(size_t i) const { const Matrix &v = *this; From 5b5cfcfecadb7d0aacbdb3d2b1310ee335a8d98b Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 19:37:31 -0500 Subject: [PATCH 066/388] Added more vector ctors. --- matrix/Vector3.hpp | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 86ee427209..ad852a88d9 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -13,13 +13,32 @@ namespace matrix { +template +class Vector; + template class Vector3 : public Vector { public: virtual ~Vector3() {}; - Vector3() : Vector() + Vector3() : + Vector() + { + } + + Vector3(const Vector & other) : + Vector(other) + { + } + + Vector3(const Matrix & other) : + Vector(other) + { + } + + Vector3(const Type *data_) : + Vector(data_) { } From 32839006f33f988daf86cadc4de715233a9dc858 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 20:22:17 -0500 Subject: [PATCH 067/388] Implemented vector 3 cross product. --- matrix/Vector3.hpp | 12 +++++------- test/vector3.cpp | 2 ++ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index ad852a88d9..0629099088 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -50,14 +50,12 @@ public: v(2) = z; } - Vector3 cross(const Vector3 & b) { - // TODO - Vector3 &a(*this); - (void)a; + Vector3 cross(const Vector3 & b) const { + const Vector3 &a(*this); Vector3 c; - c(0) = 0; - c(1) = 0; - c(2) = 0; + c(0) = a(1)*b(2) - a(2)*b(1); + c(1) = -a(0)*b(2) + a(2)*b(0); + c(2) = a(0)*b(1) - a(1)*b(0); return c; } }; diff --git a/test/vector3.cpp b/test/vector3.cpp index a7a033bf38..e60a3f201f 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -12,6 +12,8 @@ int main() Vector3f a(1, 0, 0); Vector3f b(0, 1, 0); Vector3f c = a.cross(b); + c.print(); + assert (c == Vector3f(0,0,1)); return 0; } From 7abbdcd88fffb44d081e9a212c7d655b6ff5e9ca Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 5 Nov 2015 20:27:03 -0500 Subject: [PATCH 068/388] License fix. --- LICENSE | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/LICENSE b/LICENSE index 1d5f729548..b11acfd585 100644 --- a/LICENSE +++ b/LICENSE @@ -11,7 +11,7 @@ modification, are permitted provided that the following conditions are met: this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. -* Neither the name of ocr nor the names of its +* Neither the name of matrix nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. From a2696fcee4f16547925d67e417bc1c8aa855f6af Mon Sep 17 00:00:00 2001 From: jgoppert Date: Fri, 6 Nov 2015 21:09:34 -0500 Subject: [PATCH 069/388] Fix for isfinite. --- matrix/Euler.hpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 61e26753b6..eb5d2fc759 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -10,6 +10,8 @@ #include "matrix.hpp" +#include + namespace matrix { @@ -56,13 +58,13 @@ public: psi() = 0; theta() = 0; phi() = 0; - if (isfinite(psi_val)) { + if (std::isfinite(psi_val)) { psi() = psi_val; } - if (isfinite(theta_val)) { + if (std::isfinite(theta_val)) { theta() = theta_val; } - if (isfinite(phi_val)) { + if (std::isfinite(phi_val)) { phi() = phi_val; } } From 713aee154b53566bec41b14cecdeca55fad00be9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 7 Nov 2015 09:41:38 +0100 Subject: [PATCH 070/388] Remove both versions of matrix / Matrix --- matrix/Matrix.hpp | 368 ---------------------------------------------- matrix/matrix.hpp | 11 -- 2 files changed, 379 deletions(-) delete mode 100644 matrix/Matrix.hpp delete mode 100644 matrix/matrix.hpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp deleted file mode 100644 index 45e22b6307..0000000000 --- a/matrix/Matrix.hpp +++ /dev/null @@ -1,368 +0,0 @@ -/** - * @file Matrix.hpp - * - * A simple matrix template library. - * - * @author James Goppert - */ - -#pragma once - -#include -#include -#include -#include -#include - -#include "matrix.hpp" - -namespace matrix -{ - -template -class Vector; - -template -class Matrix -{ - -public: - - Type _data[M][N]; - - virtual ~Matrix() {}; - - Matrix() : - _data() - { - } - - Matrix(const Type *data_) : - _data() - { - memcpy(_data, data_, sizeof(_data)); - } - - Matrix(const Matrix &other) : - _data() - { - memcpy(_data, other._data, sizeof(_data)); - } - - /** - * Accessors/ Assignment etc. - */ - - Type *data() - { - return _data[0]; - } - - inline Type operator()(size_t i, size_t j) const - { - return _data[i][j]; - } - - inline Type &operator()(size_t i, size_t j) - { - return _data[i][j]; - } - - /** - * Matrix Operations - */ - - // this might use a lot of programming memory - // since it instantiates a class for every - // required mult pair, but it provides - // compile time size_t checking - template - Matrix operator*(const Matrix &other) const - { - const Matrix &self = *this; - Matrix res; - res.setZero(); - - for (size_t i = 0; i < M; i++) { - for (size_t k = 0; k < P; k++) { - for (size_t j = 0; j < N; j++) { - res(i, k) += self(i, j) * other(j, k); - } - } - } - - return res; - } - - Matrix operator+(const Matrix &other) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) + other(i, j); - } - } - - return res; - } - - bool operator==(const Matrix &other) const - { - const Matrix &self = *this; - static const Type eps = Type(1e-6); - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - if (fabs(self(i , j) - other(i, j)) > eps) { - return false; - } - } - } - - return true; - } - - Matrix operator-(const Matrix &other) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) - other(i, j); - } - } - - return res; - } - - void operator+=(const Matrix &other) - { - Matrix &self = *this; - self = self + other; - } - - void operator-=(const Matrix &other) - { - Matrix &self = *this; - self = self - other; - } - - template - void operator*=(const Matrix &other) - { - Matrix &self = *this; - self = self * other; - } - - /** - * Scalar Operations - */ - - Matrix operator*(Type scalar) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) * scalar; - } - } - - return res; - } - - inline Matrix operator/(Type scalar) const - { - return (*this)*(1/scalar); - } - - Matrix operator+(Type scalar) const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) + scalar; - } - } - - return res; - } - - inline Matrix operator-(Type scalar) const - { - return (*this) + (-1*scalar); - } - - void operator*=(Type scalar) - { - Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - self(i, j) = self(i, j) * scalar; - } - } - } - - void operator/=(Type scalar) - { - Matrix &self = *this; - self = self * (1.0f / scalar); - } - - inline void operator+=(Type scalar) - { - *this = (*this) + scalar; - } - - inline void operator-=(Type scalar) - { - *this = (*this) - scalar; - } - - - /** - * Misc. Functions - */ - - void print() const - { - const Matrix &self = *this; - printf("\n"); - - for (size_t i = 0; i < M; i++) { - printf("["); - - for (size_t j = 0; j < N; j++) { - printf("%10g\t", double(self(i, j))); - } - - printf("]\n"); - } - } - - Matrix transpose() const - { - Matrix res; - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - res(j, i) = self(i, j); - } - } - - return res; - } - - - // tranpose alias - inline Matrix T() const - { - return transpose(); - } - - void setZero() - { - memset(_data, 0, sizeof(_data)); - } - - void setIdentity() - { - setZero(); - Matrix &self = *this; - - for (size_t i = 0; i < M and i < N; i++) { - self(i, i) = 1; - } - } - - inline void swapRows(size_t a, size_t b) - { - if (a == b) { - return; - } - - Matrix &self = *this; - - for (size_t j = 0; j < N; j++) { - Type tmp = self(a, j); - self(a, j) = self(b, j); - self(b, j) = tmp; - } - } - - inline void swapCols(size_t a, size_t b) - { - if (a == b) { - return; - } - - Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - Type tmp = self(i, a); - self(i, a) = self(i, b); - self(i, b) = tmp; - } - } - - Matrix abs() - { - Matrix r; - for (int i=0; i max_val) { - max_val = val; - } - } - } - return max_val; - } - - Type min() - { - Type min_val = (*this)(0,0); - for (int i=0; i -Matrix zero() { - Matrix m; - m.setZero(); - return m; -} - -typedef Matrix Matrix3f; - -}; // namespace matrix - -/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/matrix.hpp b/matrix/matrix.hpp deleted file mode 100644 index b3c2997712..0000000000 --- a/matrix/matrix.hpp +++ /dev/null @@ -1,11 +0,0 @@ -#pragma once - -#include "Matrix.hpp" -#include "SquareMatrix.hpp" -#include "Vector.hpp" -#include "Vector3.hpp" -#include "Euler.hpp" -#include "Dcm.hpp" -#include "Scalar.hpp" -#include "Quaternion.hpp" -#include "filter.hpp" From 6abd2f782acf10c529c1c9a924cedb95d097b9b6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 7 Nov 2015 09:42:33 +0100 Subject: [PATCH 071/388] Re-add Matrix.hpp --- matrix/Matrix.hpp | 368 ++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 368 insertions(+) create mode 100644 matrix/Matrix.hpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp new file mode 100644 index 0000000000..45e22b6307 --- /dev/null +++ b/matrix/Matrix.hpp @@ -0,0 +1,368 @@ +/** + * @file Matrix.hpp + * + * A simple matrix template library. + * + * @author James Goppert + */ + +#pragma once + +#include +#include +#include +#include +#include + +#include "matrix.hpp" + +namespace matrix +{ + +template +class Vector; + +template +class Matrix +{ + +public: + + Type _data[M][N]; + + virtual ~Matrix() {}; + + Matrix() : + _data() + { + } + + Matrix(const Type *data_) : + _data() + { + memcpy(_data, data_, sizeof(_data)); + } + + Matrix(const Matrix &other) : + _data() + { + memcpy(_data, other._data, sizeof(_data)); + } + + /** + * Accessors/ Assignment etc. + */ + + Type *data() + { + return _data[0]; + } + + inline Type operator()(size_t i, size_t j) const + { + return _data[i][j]; + } + + inline Type &operator()(size_t i, size_t j) + { + return _data[i][j]; + } + + /** + * Matrix Operations + */ + + // this might use a lot of programming memory + // since it instantiates a class for every + // required mult pair, but it provides + // compile time size_t checking + template + Matrix operator*(const Matrix &other) const + { + const Matrix &self = *this; + Matrix res; + res.setZero(); + + for (size_t i = 0; i < M; i++) { + for (size_t k = 0; k < P; k++) { + for (size_t j = 0; j < N; j++) { + res(i, k) += self(i, j) * other(j, k); + } + } + } + + return res; + } + + Matrix operator+(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) + other(i, j); + } + } + + return res; + } + + bool operator==(const Matrix &other) const + { + const Matrix &self = *this; + static const Type eps = Type(1e-6); + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + if (fabs(self(i , j) - other(i, j)) > eps) { + return false; + } + } + } + + return true; + } + + Matrix operator-(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) - other(i, j); + } + } + + return res; + } + + void operator+=(const Matrix &other) + { + Matrix &self = *this; + self = self + other; + } + + void operator-=(const Matrix &other) + { + Matrix &self = *this; + self = self - other; + } + + template + void operator*=(const Matrix &other) + { + Matrix &self = *this; + self = self * other; + } + + /** + * Scalar Operations + */ + + Matrix operator*(Type scalar) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) * scalar; + } + } + + return res; + } + + inline Matrix operator/(Type scalar) const + { + return (*this)*(1/scalar); + } + + Matrix operator+(Type scalar) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j) + scalar; + } + } + + return res; + } + + inline Matrix operator-(Type scalar) const + { + return (*this) + (-1*scalar); + } + + void operator*=(Type scalar) + { + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) = self(i, j) * scalar; + } + } + } + + void operator/=(Type scalar) + { + Matrix &self = *this; + self = self * (1.0f / scalar); + } + + inline void operator+=(Type scalar) + { + *this = (*this) + scalar; + } + + inline void operator-=(Type scalar) + { + *this = (*this) - scalar; + } + + + /** + * Misc. Functions + */ + + void print() const + { + const Matrix &self = *this; + printf("\n"); + + for (size_t i = 0; i < M; i++) { + printf("["); + + for (size_t j = 0; j < N; j++) { + printf("%10g\t", double(self(i, j))); + } + + printf("]\n"); + } + } + + Matrix transpose() const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(j, i) = self(i, j); + } + } + + return res; + } + + + // tranpose alias + inline Matrix T() const + { + return transpose(); + } + + void setZero() + { + memset(_data, 0, sizeof(_data)); + } + + void setIdentity() + { + setZero(); + Matrix &self = *this; + + for (size_t i = 0; i < M and i < N; i++) { + self(i, i) = 1; + } + } + + inline void swapRows(size_t a, size_t b) + { + if (a == b) { + return; + } + + Matrix &self = *this; + + for (size_t j = 0; j < N; j++) { + Type tmp = self(a, j); + self(a, j) = self(b, j); + self(b, j) = tmp; + } + } + + inline void swapCols(size_t a, size_t b) + { + if (a == b) { + return; + } + + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + Type tmp = self(i, a); + self(i, a) = self(i, b); + self(i, b) = tmp; + } + } + + Matrix abs() + { + Matrix r; + for (int i=0; i max_val) { + max_val = val; + } + } + } + return max_val; + } + + Type min() + { + Type min_val = (*this)(0,0); + for (int i=0; i +Matrix zero() { + Matrix m; + m.setZero(); + return m; +} + +typedef Matrix Matrix3f; + +}; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 222e42f9342e4ab50ea6a14fccc5051b45acd6d6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 7 Nov 2015 09:43:28 +0100 Subject: [PATCH 072/388] Re-add convenience header --- matrix/math.hpp | 10 ++++++++++ 1 file changed, 10 insertions(+) create mode 100644 matrix/math.hpp diff --git a/matrix/math.hpp b/matrix/math.hpp new file mode 100644 index 0000000000..10f3973e1b --- /dev/null +++ b/matrix/math.hpp @@ -0,0 +1,10 @@ +#pragma once + +#include "Matrix.hpp" +#include "SquareMatrix.hpp" +#include "Vector.hpp" +#include "Vector3.hpp" +#include "Euler.hpp" +#include "Dcm.hpp" +#include "Scalar.hpp" +#include "Quaternion.hpp" From 4058e32f735c3e3cb36dc8ac174a15c4208560f8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 7 Nov 2015 17:05:56 +0100 Subject: [PATCH 073/388] Fix include path --- matrix/Matrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 45e22b6307..d06cef3755 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -14,7 +14,7 @@ #include #include -#include "matrix.hpp" +#include "math.hpp" namespace matrix { From 1fb0f33eb4db5e7b77f5692c64faf161ad7d7160 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 11:08:17 -0500 Subject: [PATCH 074/388] Removed old references to matrix.hpp. --- CMakeLists.txt | 2 +- matrix/Dcm.hpp | 2 +- matrix/Euler.hpp | 2 +- matrix/Matrix.hpp | 2 +- matrix/Quaternion.hpp | 2 +- matrix/Scalar.hpp | 2 +- matrix/SquareMatrix.hpp | 2 +- matrix/Vector.hpp | 2 +- matrix/Vector3.hpp | 2 +- matrix/filter.hpp | 2 +- test/attitude.cpp | 2 +- test/filter.cpp | 2 +- test/inverse.cpp | 2 +- test/matrixAssignment.cpp | 2 +- test/matrixMult.cpp | 2 +- test/matrixScalarMult.cpp | 2 +- test/setIdentity.cpp | 2 +- test/squareMatrix.cpp | 2 +- test/transpose.cpp | 2 +- test/vector.cpp | 2 +- test/vector3.cpp | 2 +- test/vectorAssignment.cpp | 2 +- 22 files changed, 22 insertions(+), 22 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8e63caf230..63619ebcfc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -63,7 +63,7 @@ string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") enable_testing() -include_directories(matrix) +include_directories(${CMAKE_SOURCE_DIR}) file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 6740a44384..c94e890cfb 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -8,7 +8,7 @@ #pragma once -#include "matrix.hpp" +#include "math.hpp" namespace matrix diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index eb5d2fc759..3fe125d62c 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -8,7 +8,7 @@ #pragma once -#include "matrix.hpp" +#include "math.hpp" #include diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 45e22b6307..d06cef3755 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -14,7 +14,7 @@ #include #include -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 96a9497277..a6b25b281f 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -8,7 +8,7 @@ #pragma once -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 6523060f12..628e8b10e7 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -14,7 +14,7 @@ #include #include -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index a3dbdc6c78..ffbe1045af 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -14,7 +14,7 @@ #include #include -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index a65b5dfff0..c0184dac8c 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -7,7 +7,7 @@ */ #pragma once -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 0629099088..5a3d5c8376 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -8,7 +8,7 @@ #pragma once -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/matrix/filter.hpp b/matrix/filter.hpp index 666db0926e..e202bb8827 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -1,6 +1,6 @@ #pragma once -#include "matrix.hpp" +#include "math.hpp" namespace matrix { diff --git a/test/attitude.cpp b/test/attitude.cpp index 3d38aa9d94..88faeaff69 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/filter.cpp b/test/filter.cpp index b4103d566c..86ca564bec 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/inverse.cpp b/test/inverse.cpp index ba85fae463..d00fcd6cf2 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 8202920a4a..86c05527e5 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -1,6 +1,6 @@ #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 6ac0670065..5ba8b72254 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index be093d03fb..e6bb8323a9 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index c4e8830603..68c2acf31b 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -1,6 +1,6 @@ #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 91a3f36fbd..e2a56ed048 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/transpose.cpp b/test/transpose.cpp index fe28077063..f032862a4d 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/vector.cpp b/test/vector.cpp index 7cdd426a4f..053e22dec8 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/vector3.cpp b/test/vector3.cpp index e60a3f201f..9f2ea8f525 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -1,7 +1,7 @@ #include #include -#include "matrix.hpp" +#include using namespace matrix; diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 86b3571f8e..8a72b29a38 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -1,6 +1,6 @@ #include -#include "matrix.hpp" +#include using namespace matrix; From f6e8cdd9708a0460a19af4cab213d91a7d8406d4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 7 Nov 2015 17:16:30 +0100 Subject: [PATCH 075/388] First attempt at enabling coveralls --- .travis.yml | 11 +---------- README.md | 2 +- 2 files changed, 2 insertions(+), 11 deletions(-) diff --git a/.travis.yml b/.travis.yml index 4d5ddf4973..e647d7a405 100644 --- a/.travis.yml +++ b/.travis.yml @@ -12,17 +12,8 @@ script: env: global: - export COVERALLS_SERVICE_NAME=travis-ci - - export COVERALLS_REPO_TOKEN=4MDwjIvimPGcxcHZQf0iS1aLHNfeQG9dN - - secure: vj6Y9LaNhnfWH+3AoqOIY/k5Ymb0zKlXJSlfa1qBnWC94/NDQjbV+6Lk1Ct1izzPmFbCiRwp/auwcUT0p3aUNNFshEUrL5rlHOwr4zLMqxdwKfUXA7X7NSJS2EJSgMm0to0iSzuCeub3E5Y7fdDpmWTZ9bD5E31wck/5kzjiuw0G8mtdOLeOnfERCZw/VTxLwKkdjU3+m64IYzAh9tWsyM1ZpVX0c7KjjPt29qYb45xmQ7XrWlKl9fHabKbTvopISas56Q95K46pcF9sDraP0+KVk6f5rVOjYppvRmT6BJwRjDRG/rC6Q0BSfZuUm8a0OgFxc2MG3sxKT/QfMMDzuxJWbewakam0hcPJl34cFzqgIuMeQ7bK1yitsFBCqo9b/noMMp4vX9Hkm8b1f4QHTuk2fqOqorP0hOQxhWUcNs8J2jG1nDOjB5wrv9fOyerAZjZ8fvzHkMh/aZ3Xj9Sw7PVxiue1eyRXHQgn2/IcerrhlujawGbjsvLvrmQ+v5A3xvh4q6iJ5glIv1dhGaEEGMrp8httjLUAzZJpSAdyyWnJtnD+5KLH7BOKT+ptuXRnU6H97nUlXIHujx4btEpIhYebEX+pmAfOwK8WP3DDG5ikbmf2BuaI/qOhPtUzf5PJiN/+vRKNYf6ijXBBr4Cq7pWSJotQRfoHXvfE4vFa+zA= + - secure: "dA+jGAR9O3f+xsh6h7e7coeM0dU1vHiiM7kIPh5TvbbifDQiF5s2uxFQziZVSnLuohRD9oNODiJFz077n+svp7S9t77sdks0+7r61pkD5LlVItZ6ol5jQCfiksyMw6q5ChEes9KSKEfdFRjuDvQUHwShgpsXVAurizA2Hs3MziWxfIlOPULY4UCCm5+TLoY+vXmfFc4bwk2knxpIP8pYRd+xKYAiN9QC1fJiglipuKHaYbo2+ZYrM92RD0Cl+BZdWyI7vD7zmeXV6mstzAFZ20c63NhNNCYRy0VIC3hLB8zKMuvCZdJnpmSRfFt5uJYJPNcORc1ypeY7/CGMm5Rq1lNwxehFO3/++/aHE8H7GR0cTiKndPO0jDu48j+GUB4k1HHSsVEpj7vO7F3FOO0619xxybDFk1zFjHw8KTbdSXmBERldYAKZOP0JKZxp6CU5DXOO2dunumZAzl6WHJjhRMPFqPheE4e+I2YOEHvXTwDcEO/lMwacr6nuaZZXxEh/TwEdqsIRd9bvsoG1zuVQnZm+atLp3oF4QW8nI5l6qe6R+3l5dEgJGtz5hOsiEpWrwWk6ub2VCdELcgpPZyZcdwu/bKvXx3ndW6LjqzcLxMGxM3rdxx6J+b7Es/vkmT1SXFcxiUjpKkUf04Bb8SmGdbJdAKRZuSRFtjqsU0tHPfo=" addons: - coverity_scan: - project: - name: dronecrew/matrix - description: Build submitted via Travis CI - notification_email: james.goppert@gmail.com - build_command_prepend: mkdir -p build && cd build && cmake .. && make - build_command: make -C build -j 4 - branch_pattern: coverity_scan apt: packages: - cmake diff --git a/README.md b/README.md index 8dd6160162..7b8a65a843 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,3 @@ -# matrix [![Build Status](https://travis-ci.org/dronecrew/matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) [![Coverage Status](https://coveralls.io/repos/dronecrew/matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/dronecrew/matrix?branch=master) +# matrix [![Build Status](https://travis-ci.org/PX4/Matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) [![Coverage Status](https://coveralls.io/repos/PX4/Matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/PX4/Matrix?branch=master) A simple and efficient template based matrix library. From ace275171533f527abebcedbfd5dfb8bc0f880a5 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 11:29:08 -0500 Subject: [PATCH 076/388] Badge fix. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 7b8a65a843..eca12ed3ac 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,3 @@ -# matrix [![Build Status](https://travis-ci.org/PX4/Matrix.svg?branch=master)](https://travis-ci.org/dronecrew/matrix) [![Coverage Status](https://coveralls.io/repos/PX4/Matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/PX4/Matrix?branch=master) +# matrix [![Build Status](https://travis-ci.org/PX4/Matrix.svg?branch=master)](https://travis-ci.org/PX4/Matrix) [![Coverage Status](https://coveralls.io/repos/PX4/Matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/PX4/Matrix?branch=master) A simple and efficient template based matrix library. From f621f68fe17e5e7a14c817072fed9b0b20cb8fe8 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 11:55:24 -0500 Subject: [PATCH 077/388] Changed license holder to development team. --- LICENSE | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/LICENSE b/LICENSE index b11acfd585..a8b6be7e12 100644 --- a/LICENSE +++ b/LICENSE @@ -1,4 +1,6 @@ -Copyright (c) 2015, James Goppert +The Matrix library is licensed under a permissive 3-clause BSD license. Contributions must be made under the same license. + +Copyright (c) 2015, Matrix Development Team. All rights reserved. Redistribution and use in source and binary forms, with or without From 9884a4c42379e4c602c6daf1645bf03e70afa1a3 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 11:59:30 -0500 Subject: [PATCH 078/388] Improved README. --- README.md | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/README.md b/README.md index eca12ed3ac..05a8107e85 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,14 @@ # matrix [![Build Status](https://travis-ci.org/PX4/Matrix.svg?branch=master)](https://travis-ci.org/PX4/Matrix) [![Coverage Status](https://coveralls.io/repos/PX4/Matrix/badge.svg?branch=master&service=github)](https://coveralls.io/github/PX4/Matrix?branch=master) A simple and efficient template based matrix library. + +## License (BSD) +* The Matrix library is licensed under a permissive 3-clause BSD license. Contributions must be made under the same license. + +## Features +* Compile time size checking. +* Euler angle (321), DCM, Quaternion conversion through constructors. +* High testing coverage. + +## Limitation +* No dynamically sized matrices. From 3a2c3bdae11279df8bd783ed50a3b093315e6b5b Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 12:00:21 -0500 Subject: [PATCH 079/388] README formatting. --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 05a8107e85..9f5b56764b 100644 --- a/README.md +++ b/README.md @@ -2,8 +2,8 @@ A simple and efficient template based matrix library. -## License (BSD) -* The Matrix library is licensed under a permissive 3-clause BSD license. Contributions must be made under the same license. +## License +* (BSD) The Matrix library is licensed under a permissive 3-clause BSD license. Contributions must be made under the same license. ## Features * Compile time size checking. From 835cdd2f915fa38bc62b08a5b967547822e5ff0c Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 12:03:10 -0500 Subject: [PATCH 080/388] README fix. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 9f5b56764b..c840ebf349 100644 --- a/README.md +++ b/README.md @@ -10,5 +10,5 @@ A simple and efficient template based matrix library. * Euler angle (321), DCM, Quaternion conversion through constructors. * High testing coverage. -## Limitation +## Limitations * No dynamically sized matrices. From 1f723095201bff25056cd3f5c37b53e183cea79d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 12:17:45 -0500 Subject: [PATCH 081/388] Added some docs. --- README.md | 62 +++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 62 insertions(+) diff --git a/README.md b/README.md index c840ebf349..718d5dbf5b 100644 --- a/README.md +++ b/README.md @@ -12,3 +12,65 @@ A simple and efficient template based matrix library. ## Limitations * No dynamically sized matrices. + +## Example + +```c++ + // define an euler angle (Body 3(yaw)-2(pitch)-1(roll) rotation) + float roll = 0.1f; + float pitch = 0.2f; + float yaw = 0.3f; + Eulerf euler(roll, pitch, yaw); + + // convert to quaternion from euler + Quatf q_nb(euler); + + // convert to DCM from quaternion + Dcmf dcm(q_nb); + + // do some kalman filtering + const size_t n_x = 5; + const size_t n_y = 3; + + // define matrix sizes + SquareMatrix P; + Vector x; + Vector y; + Matrix C; + SquareMatrix R; + SquareMatrix S; + Matrix K; + + // define measurement matrix + C = zero(); // or C.setZero() + C(0,0) = 1; + C(1,1) = 2; + C(2,2) = 3; + + // set x to zero + x = zero(); // or x.setZero() + + // set P to identity * 0.01 + P = eye()*0.01; + + // set R to identity * 0.1 + R = eye()*0.1; + + // measurement + y(0) = 1; + y(1) = 2; + y(2) = 3; + + // innovation + r = y - C*x; + + // innovations variance + S = C*P*C.T() + R; + + // Kalman gain matrix + K = P*C.T()*S.I(); + // S.I() is the inverse, defined for SquareMatrix + + // correction + x += K*r; +``` From 9b995e19f3da68751e69181cb36177e39d4ff851 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 7 Nov 2015 14:27:12 -0500 Subject: [PATCH 082/388] Added vector2. --- CMakeLists.txt | 7 ----- matrix/Matrix.hpp | 14 +++++++++ matrix/Quaternion.hpp | 18 +++++------- matrix/SquareMatrix.hpp | 2 +- matrix/Vector.hpp | 27 ++++++++--------- matrix/Vector2.hpp | 65 +++++++++++++++++++++++++++++++++++++++++ matrix/Vector3.hpp | 23 ++++++++------- matrix/math.hpp | 1 + test/CMakeLists.txt | 23 ++++++++++++--- test/matrixMult.cpp | 6 ++++ test/vector.cpp | 1 + test/vector2.cpp | 18 ++++++++++++ 12 files changed, 160 insertions(+), 45 deletions(-) create mode 100644 matrix/Vector2.hpp create mode 100644 test/vector2.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 63619ebcfc..fecbf88934 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -50,13 +50,6 @@ if (COVERAGE) ) include(Coveralls) coveralls_turn_on_coverage() - add_custom_target(coverage - COMMAND lcov --capture --directory . --output-file coverage.info - COMMAND genhtml coverage.info --output-directory out - COMMAND x-www-browser out/index.html - WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS coveralls - ) endif() string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index d06cef3755..2f10bcf46a 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -94,6 +94,20 @@ public: return res; } + Matrix emult(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j)*other(i, j); + } + } + + return res; + } + Matrix operator+(const Matrix &other) const { Matrix res; diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a6b25b281f..a0f0441db3 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -25,6 +25,9 @@ class Quaternion : public Vector public: virtual ~Quaternion() {}; + typedef Matrix Matrix41; + typedef Matrix Matrix31; + Quaternion() : Vector() { @@ -35,12 +38,7 @@ public: q(3) = 0; } - Quaternion(const Vector & other) : - Vector(other) - { - } - - Quaternion(const Matrix & other) : + Quaternion(const Matrix41 & other) : Vector(other) { } @@ -100,7 +98,7 @@ public: return r; } - Matrix derivative(const Vector & w) const { + Matrix41 derivative(const Matrix31 & w) const { const Quaternion &q = *this; Type dataQ[] = { q(0), -q(1), -q(2), -q(3), @@ -111,9 +109,9 @@ public: Matrix Q(dataQ); Vector v; v(0) = 0; - v(1) = w(0); - v(2) = w(1); - v(3) = w(2); + v(1) = w(0,0); + v(2) = w(1,0); + v(3) = w(2,0); return Q * v * Type(0.5); } }; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ffbe1045af..ee06ccdd29 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -79,7 +79,7 @@ SquareMatrix diag(Vector d) { } template -SquareMatrix expm(const SquareMatrix & A, size_t order=5) +SquareMatrix expm(const Matrix & A, size_t order=5) { SquareMatrix res; SquareMatrix A_pow = A; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index c0184dac8c..fb771ecc18 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -21,42 +21,39 @@ class Vector : public Matrix public: virtual ~Vector() {}; - Vector() : Matrix() + typedef Matrix MatrixM1; + + Vector() : MatrixM1() { } - Vector(const Vector & other) : - Matrix(other) - { - } - - Vector(const Matrix & other) : - Matrix(other) + Vector(const MatrixM1 & other) : + MatrixM1(other) { } Vector(const Type *data_) : - Matrix(data_) + MatrixM1(data_) { } inline Type operator()(size_t i) const { - const Matrix &v = *this; + const MatrixM1 &v = *this; return v(i, 0); } inline Type &operator()(size_t i) { - Matrix &v = *this; + MatrixM1 &v = *this; return v(i, 0); } - Type dot(const Vector & b) const { + Type dot(const MatrixM1 & b) const { const Vector &a(*this); Type r = 0; for (int i = 0; i + */ + +#pragma once + +#include "math.hpp" + +namespace matrix +{ + +template +class Vector; + +template +class Vector2 : public Vector +{ +public: + + typedef Matrix Matrix21; + + virtual ~Vector2() {}; + + Vector2() : + Vector() + { + } + + Vector2(const Matrix21 & other) : + Vector(other) + { + } + + Vector2(const Type *data_) : + Vector(data_) + { + } + + Vector2(Type x, Type y) : Vector() + { + Vector2 &v(*this); + v(0) = x; + v(1) = y; + } + + Type cross(const Matrix21 & b) const { + const Vector2 &a(*this); + return a(0)*b(1, 0) - a(1)*b(0, 0); + } + + Type operator%(const Matrix21 & b) const { + return (*this).cross(b); + } + +}; + +typedef Vector2 Vector2f; + +}; // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 5a3d5c8376..c33ff77e58 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -20,6 +20,9 @@ template class Vector3 : public Vector { public: + + typedef Matrix Matrix31; + virtual ~Vector3() {}; Vector3() : @@ -27,12 +30,7 @@ public: { } - Vector3(const Vector & other) : - Vector(other) - { - } - - Vector3(const Matrix & other) : + Vector3(const Matrix31 & other) : Vector(other) { } @@ -50,14 +48,19 @@ public: v(2) = z; } - Vector3 cross(const Vector3 & b) const { + Vector3 cross(const Matrix31 & b) const { const Vector3 &a(*this); Vector3 c; - c(0) = a(1)*b(2) - a(2)*b(1); - c(1) = -a(0)*b(2) + a(2)*b(0); - c(2) = a(0)*b(1) - a(1)*b(0); + c(0) = a(1)*b(2,0) - a(2)*b(1,0); + c(1) = -a(0)*b(2,0) + a(2)*b(0,0); + c(2) = a(0)*b(1,0) - a(1)*b(0,0); return c; } + + Vector3 operator%(const Matrix31 & b) const { + return (*this).cross(b); + } + }; typedef Vector3 Vector3f; diff --git a/matrix/math.hpp b/matrix/math.hpp index 10f3973e1b..da1d73d992 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -3,6 +3,7 @@ #include "Matrix.hpp" #include "SquareMatrix.hpp" #include "Vector.hpp" +#include "Vector2.hpp" #include "Vector3.hpp" #include "Euler.hpp" #include "Dcm.hpp" diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 2f0570c7a6..c7ae87b675 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -7,14 +7,29 @@ set(tests matrixScalarMult transpose vector + vector2 vector3 attitude filter squareMatrix ) -foreach(test ${tests}) - add_executable(${test} - ${test}.cpp) - add_test(${test} ${test}) +add_custom_target(test_build) +foreach(test_name ${tests}) + add_executable(${test_name} + ${test_name}.cpp) + add_test(test_${test_name} ${test_name}) + add_dependencies(test_build ${test_name}) endforeach() + +if (COVERAGE) + add_custom_target(coverage + COMMAND lcov --capture --directory . --output-file coverage.info + COMMAND genhtml coverage.info --output-directory out + COMMAND x-www-browser out/index.html + WORKING_DIRECTORY ${CMAKE_BUILD_DIR} + DEPENDS coveralls test_build + ) +endif() + + diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 5ba8b72254..613d61db7d 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -23,6 +23,12 @@ int main() R2 *= A_I; R2.print(); assert(R2 == I); + + + Matrix3f A2 = eye()*2; + Matrix3f B = A2.emult(A2); + Matrix3f B_check = eye()*4; + assert(B == B_check); return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index 053e22dec8..c340997f11 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -15,6 +15,7 @@ int main() assert(fabs(v1.norm() - 7.416198487095663f) < 1e-5); Vector v2(data2); assert(fabs(v1.dot(v2) - 130.0f) < 1e-5); + assert(fabs(v1*v2 - 130.0f) < 1e-5); v2.normalize(); Vector v3(v2); assert(v2 == v3); diff --git a/test/vector2.cpp b/test/vector2.cpp new file mode 100644 index 0000000000..671d9f9b72 --- /dev/null +++ b/test/vector2.cpp @@ -0,0 +1,18 @@ +#include +#include + +#include + +using namespace matrix; + +template class Vector; + +int main() +{ + Vector2f a(1, 0); + Vector2f b(0, 1); + assert (fabs(a % b - 1.0f) < 1e-5); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 5c573b075f7bae9bf1bacd654b2bfb5db0bb0a70 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sun, 8 Nov 2015 12:08:19 -0500 Subject: [PATCH 083/388] Fixes for nuttx. --- matrix/Euler.hpp | 10 ++++------ matrix/SquareMatrix.hpp | 3 +++ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 3fe125d62c..74e364940f 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -10,8 +10,6 @@ #include "math.hpp" -#include - namespace matrix { @@ -54,17 +52,17 @@ public: Type theta_val = Type(asin(-dcm(2,0))); Type phi_val = Type(atan(dcm(2, 1)/ dcm(2, 2))); - // protection against gimbal lock + // protection against NaN if dcm(0,0) or dcm(2,2) == 0 psi() = 0; theta() = 0; phi() = 0; - if (std::isfinite(psi_val)) { + if (psi() >= -M_PI_2 && psi() <= M_PI_2) { psi() = psi_val; } - if (std::isfinite(theta_val)) { + if (theta() >= -M_PI_2 && theta() <= M_PI_2) { theta() = theta_val; } - if (std::isfinite(phi_val)) { + if (phi() >= -M_PI_2 && phi() <= M_PI_2) { phi() = phi_val; } } diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ffbe1045af..8281f8e4a4 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -22,6 +22,9 @@ namespace matrix template class Matrix; +template +class Vector; + template class SquareMatrix : public Matrix { From e972a0a111e35132f87e77d2bac096ba4e2728b2 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Mon, 9 Nov 2015 19:52:55 -0500 Subject: [PATCH 084/388] Made kalman filter correction function usable. --- matrix/filter.hpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/matrix/filter.hpp b/matrix/filter.hpp index e202bb8827..53fc99d92a 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -6,17 +6,20 @@ namespace matrix { template void kalman_correct( - const Matrix & P, + const SquareMatrix & P, const Matrix & C, - const Matrix & R, + const SquareMatrix & R, const Vector &r, Vector & dx, + SquareMatrix & dP, float & beta ) { SquareMatrix S_I = SquareMatrix(C*P*C.T() + R).I(); - dx = P*C.T()*S_I*r; + Matrix K = P*C.T()*S_I; + dx = K*r; beta = Scalar(r.T()*S_I*r); + dP = K*C*P*(-1); } }; // namespace matrix From 2c7a375e3d7ce143dd1991c9135a5a55952a8977 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Mon, 9 Nov 2015 19:58:00 -0500 Subject: [PATCH 085/388] Fixed kalman correct test. --- test/filter.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/test/filter.cpp b/test/filter.cpp index 86ca564bec..b3b137cdcd 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -19,8 +19,9 @@ int main() Vector r(data); Vector dx; + SquareMatrix dP; float beta = 0; - kalman_correct(P, C, R, r, dx, beta); + kalman_correct(P, C, R, r, dx, dP, beta); dx.T().print(); printf("beta: %g\n", beta); From 42f2e60b245c4592410bcd1b80605591cd00d7e9 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 11 Nov 2015 23:31:43 -0500 Subject: [PATCH 086/388] Added runge kutta integration. --- CMakeLists.txt | 2 +- matrix/Matrix.hpp | 40 ++++++++++++++++++++++++++++++++++++++- matrix/Scalar.hpp | 15 +++++++++++---- matrix/Vector.hpp | 3 --- matrix/integration.hpp | 26 +++++++++++++++++++++++++ test/CMakeLists.txt | 1 + test/attitude.cpp | 2 +- test/integration.cpp | 26 +++++++++++++++++++++++++ test/inverse.cpp | 2 +- test/matrixAssignment.cpp | 6 ++++++ test/vector.cpp | 1 - 11 files changed, 112 insertions(+), 12 deletions(-) create mode 100644 matrix/integration.hpp create mode 100644 test/integration.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index fecbf88934..f22119ba5b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -37,7 +37,7 @@ set(CMAKE_CXX_FLAGS -Wcast-qual -Wconversion -Wcast-align - #-Werror + -Werror ) if (COVERAGE) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 2f10bcf46a..2e32fc29b2 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -152,6 +152,21 @@ public: return res; } + // unary minus + Matrix operator-() const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = -self(i, j); + } + } + + return res; + } + void operator+=(const Matrix &other) { Matrix &self = *this; @@ -287,6 +302,22 @@ public: memset(_data, 0, sizeof(_data)); } + void setAll(Type val) + { + Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) = val; + } + } + } + + inline void setOne() + { + setAll(1); + } + void setIdentity() { setZero(); @@ -369,12 +400,19 @@ public: }; template -Matrix zero() { +Matrix zeros() { Matrix m; m.setZero(); return m; } +template +Matrix ones() { + Matrix m; + m.setOne(); + return m; +} + typedef Matrix Matrix3f; }; // namespace matrix diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 628e8b10e7..022ab5f7de 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -20,24 +20,31 @@ namespace matrix { template -class Scalar : public Matrix +class Scalar { public: virtual ~Scalar() {}; - Scalar() : Matrix() + Scalar() : _value() { } Scalar(const Matrix & other) { - (*this)(0,0) = other(0,0); + _value = other(0,0); + } + + Scalar(float other) + { + _value = other; } operator Type() { - return (*this)(0,0); + return _value; } +private: + Type _value; }; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index fb771ecc18..4c75ce5694 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -67,9 +67,6 @@ public: (*this) /= norm(); } - Type operator*(const MatrixM1 & b) const { - return (*this).dot(b); - } }; }; // namespace matrix diff --git a/matrix/integration.hpp b/matrix/integration.hpp new file mode 100644 index 0000000000..61f7574cca --- /dev/null +++ b/matrix/integration.hpp @@ -0,0 +1,26 @@ +#pragma once + +#include "math.hpp" + +namespace matrix { + +template +int integrate_rk4( + Vector (*f)(Type, Vector), + Vector & y, + Type & t, + Type h + ) +{ + // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods + Vector k1, k2, k3, k4; + k1 = f(t, y); + k2 = f(t + h/2, y + k1*h/2); + k3 = f(t + h/2, y + k2*h/2); + k4 = f(t + h, y + k3*h); + y += (k1 + k2*2 + k3*2 + k4)*(h/6); + t += h; + return 0; +} + +}; // namespace matrix diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index c7ae87b675..5f4557dd83 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -11,6 +11,7 @@ set(tests vector3 attitude filter + integration squareMatrix ) diff --git a/test/attitude.cpp b/test/attitude.cpp index 88faeaff69..8449287df5 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -29,7 +29,7 @@ int main() // euler default ctor Eulerf e; - Eulerf e_zero = zero(); + Eulerf e_zero = zeros(); assert(e == e_zero); assert(e == e); diff --git a/test/integration.cpp b/test/integration.cpp new file mode 100644 index 0000000000..e8b3889420 --- /dev/null +++ b/test/integration.cpp @@ -0,0 +1,26 @@ +#include +#include + +#include + +using namespace matrix; + +Vector f(float t, Vector y); + +Vector f(float t, Vector y) { + return ones(); +} + +int main() +{ + Vector y = ones(); + float h = 1; + float t = 1; + y.T().print(); + integrate_rk4(f, y, t, h); + y.T().print(); + assert(y == (ones()*2)); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/inverse.cpp b/test/inverse.cpp index d00fcd6cf2..743d877a9f 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -40,7 +40,7 @@ int main() assert(A_large == A_large_I); } - SquareMatrix zero_test = zero(); + SquareMatrix zero_test = zeros(); inv(zero_test); return 0; diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 86c05527e5..cc1ad6945a 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -65,6 +65,7 @@ int main() Matrix3f m4(data); + assert(-m4 == m4*(-1)); m4.swapCols(0, 2); assert(m4 == Matrix3f(data_col_02_swap)); @@ -72,6 +73,11 @@ int main() m4.swapRows(0, 2); assert(m4 == Matrix3f(data_row_02_swap)); assert(fabs(m4.min() - 1) < 1e-5); + + Scalar s; + s = 1; + assert(fabs(s - 1) < 1e-5); + return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index c340997f11..053e22dec8 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -15,7 +15,6 @@ int main() assert(fabs(v1.norm() - 7.416198487095663f) < 1e-5); Vector v2(data2); assert(fabs(v1.dot(v2) - 130.0f) < 1e-5); - assert(fabs(v1*v2 - 130.0f) < 1e-5); v2.normalize(); Vector v3(v2); assert(v2 == v3); From 787606b6b8b7be8eb3492bf84a03314e1e3bb5a2 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Wed, 11 Nov 2015 23:33:26 -0500 Subject: [PATCH 087/388] Formatting. --- matrix/integration.hpp | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/matrix/integration.hpp b/matrix/integration.hpp index 61f7574cca..2582819078 100644 --- a/matrix/integration.hpp +++ b/matrix/integration.hpp @@ -6,21 +6,21 @@ namespace matrix { template int integrate_rk4( - Vector (*f)(Type, Vector), + Vector (*f)(Type, Vector), Vector & y, Type & t, - Type h - ) + Type h +) { - // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods - Vector k1, k2, k3, k4; - k1 = f(t, y); - k2 = f(t + h/2, y + k1*h/2); - k3 = f(t + h/2, y + k2*h/2); - k4 = f(t + h, y + k3*h); - y += (k1 + k2*2 + k3*2 + k4)*(h/6); - t += h; - return 0; + // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods + Vector k1, k2, k3, k4; + k1 = f(t, y); + k2 = f(t + h/2, y + k1*h/2); + k3 = f(t + h/2, y + k2*h/2); + k4 = f(t + h, y + k3*h); + y += (k1 + k2*2 + k3*2 + k4)*(h/6); + t += h; + return 0; } }; // namespace matrix From 10b89a2594e5eb83de0b05b424b2bc9797bbc223 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 00:18:18 -0500 Subject: [PATCH 088/388] Switching coverage upload mechanism. --- .gitmodules | 3 --- .travis.yml | 12 ++++++------ CMakeLists.txt | 38 ++++++++++---------------------------- cmake/coveralls-cmake | 1 - test/CMakeLists.txt | 5 +++-- 5 files changed, 19 insertions(+), 40 deletions(-) delete mode 100644 .gitmodules delete mode 160000 cmake/coveralls-cmake diff --git a/.gitmodules b/.gitmodules deleted file mode 100644 index 37bc2b63dd..0000000000 --- a/.gitmodules +++ /dev/null @@ -1,3 +0,0 @@ -[submodule "cmake/coveralls-cmake"] - path = cmake/coveralls-cmake - url = https://github.com/JoakimSoderberg/coveralls-cmake.git diff --git a/.travis.yml b/.travis.yml index e647d7a405..2a374a0b53 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,14 +1,14 @@ language: c sudo: false +install: + - pip install --user cpp-coveralls script: - - mkdir -p build - - cd build - - cmake -DCOVERAGE=ON -DCOVERALLS_UPLOAD=ON -DCMAKE_BUILD_TYPE=Debug .. + - cmake -DCMAKE_BUILD_TYPE=Profile . - make - make check_format - - ctest - - ctest -V - - make coveralls + - make test +after_success: + - cpp-coveralls env: global: - export COVERALLS_SERVICE_NAME=travis-ci diff --git a/CMakeLists.txt b/CMakeLists.txt index f22119ba5b..639f9b19e2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,16 +6,21 @@ set(VERSION_PATCH "0") project(matrix CXX) -option(COVERAGE "Enable code coverage" OFF) -option(COVERALLS_UPLOAD "Upload the generated coveralls json" OFF) - if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() +set_property(CACHE CMAKE_BUILD_TYPE PROPERTY + STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Profile") -set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} - ${CMAKE_SOURCE_DIR}/cmake/coveralls-cmake/cmake) +set(CMAKE_CXX_FLAGS_PROFILE + ${CMAKE_CXX_FLAGS_DEBUG} + --coverage + -fno-inline + -fno-inline-small-functions + -fno-default-inline + ) +string(REPLACE ";" " " CMAKE_CXX_FLAGS_PROFILE "${CMAKE_CXX_FLAGS_PROFILE}") set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} @@ -39,19 +44,6 @@ set(CMAKE_CXX_FLAGS -Wcast-align -Werror ) - -if (COVERAGE) - set(COVERALLS ON) - list(APPEND CMAKE_CXX_FLAGS - -fno-inline - -fno-inline-small-functions - -fno-default-inline - --coverage - ) - include(Coveralls) - coveralls_turn_on_coverage() -endif() - string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") enable_testing() @@ -60,16 +52,6 @@ include_directories(${CMAKE_SOURCE_DIR}) file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) -# Setup the coveralls target and tell it to gather -# coverage data for all the lib sources. -if (COVERALLS) - coveralls_setup( - "${COV_SRCS}" - ${COVERALLS_UPLOAD} - "${CMAKE_SOURCE_DIR}/cmake/coveralls-cmake/cmake" - ) -endif() - add_subdirectory(test) set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) diff --git a/cmake/coveralls-cmake b/cmake/coveralls-cmake deleted file mode 160000 index 2d53ce3dea..0000000000 --- a/cmake/coveralls-cmake +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 2d53ce3deaea087b2df778c09fe2590763661547 diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 5f4557dd83..76357d890c 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -23,13 +23,14 @@ foreach(test_name ${tests}) add_dependencies(test_build ${test_name}) endforeach() -if (COVERAGE) +if (${CMAKE_BUILD_TYPE} STREQUAL "Profile") add_custom_target(coverage + COMMAND ${CMAKE_CTEST_COMMAND} COMMAND lcov --capture --directory . --output-file coverage.info COMMAND genhtml coverage.info --output-directory out COMMAND x-www-browser out/index.html WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS coveralls test_build + DEPENDS test_build ) endif() From 8054180e891cbc8cf8343d3fd6d7fe0092337d0b Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 01:27:27 -0500 Subject: [PATCH 089/388] Changed root dir for coverage. --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 2a374a0b53..5165811a1c 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,7 +8,7 @@ script: - make check_format - make test after_success: - - cpp-coveralls + - cpp-coveralls -r matrix env: global: - export COVERALLS_SERVICE_NAME=travis-ci From e724ae40781cb9adfe635633aad21125bb3d8d83 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 01:29:47 -0500 Subject: [PATCH 090/388] Set include dir. --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 5165811a1c..f4f8ba684d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,7 +8,7 @@ script: - make check_format - make test after_success: - - cpp-coveralls -r matrix + - cpp-coveralls -i matrix env: global: - export COVERALLS_SERVICE_NAME=travis-ci From c29c44b450dbbcbfca25e33a59f7978db73a09c7 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 09:43:44 -0500 Subject: [PATCH 091/388] Added more testing to instantiate some missing templates. --- test/vector2.cpp | 20 +++++++++++++++++++- test/vector3.cpp | 8 ++++++++ test/vectorAssignment.cpp | 4 ++++ 3 files changed, 31 insertions(+), 1 deletion(-) diff --git a/test/vector2.cpp b/test/vector2.cpp index 671d9f9b72..e1d122fbde 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -11,7 +11,25 @@ int main() { Vector2f a(1, 0); Vector2f b(0, 1); - assert (fabs(a % b - 1.0f) < 1e-5); + assert(fabs(a % b - 1.0f) < 1e-5); + + Vector2f c; + assert(fabs(c(0) - 0) < 1e-5); + assert(fabs(c(1) - 0) < 1e-5); + + Matrix d(a); + assert(fabs(d(0,0) - 1) < 1e-5); + assert(fabs(d(1,0) - 0) < 1e-5); + + Vector2f e(d); + assert(fabs(e(0) - 1) < 1e-5); + assert(fabs(e(1) - 0) < 1e-5); + + float data[] = {4,5}; + Vector2f f(data); + assert(fabs(f(0) - 4) < 1e-5); + assert(fabs(f(1) - 5) < 1e-5); + return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index 9f2ea8f525..ccf94c12a2 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -14,6 +14,14 @@ int main() Vector3f c = a.cross(b); c.print(); assert (c == Vector3f(0,0,1)); + c = a % b; + assert (c == Vector3f(0,0,1)); + Matrix d(c); + Vector3f e(d); + assert (e == d); + float data[] = {4, 5, 6}; + Vector3f f(data); + assert (f == Vector3f(4, 5, 6)); return 0; } diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 8a72b29a38..491ce818bd 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -29,6 +29,10 @@ int main() assert(fabs(v2(1) - 5) < eps); assert(fabs(v2(2) - 6) < eps); + SquareMatrix m = diag(Vector3f(1,2,3)); + assert(fabs(m(0, 0) - 1) < eps); + assert(fabs(m(1, 1) - 2) < eps); + assert(fabs(m(2, 2) - 3) < eps); return 0; } From 410bbc4c71185f2b8385d8f977f8897a80bcc52c Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 09:51:11 -0500 Subject: [PATCH 092/388] Added more to README. --- README.md | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/README.md b/README.md index 718d5dbf5b..7c593cce4a 100644 --- a/README.md +++ b/README.md @@ -13,6 +13,20 @@ A simple and efficient template based matrix library. ## Limitations * No dynamically sized matrices. +## Library Overview + +* matrix/math.hpp : Provides matrix math routines. + * Matrix (MxN) + * Square Matrix (MxM, has inverse) + * Vector (Mx1) + * Scalar (1x1) + +* matrix/filter.hpp : Provides filtering routines. + * kalman_correct + +* matrix/integrate.hpp : Provides integration routines. + * integrate_rk4 (Runge-Kutta 4th order) + ## Example ```c++ @@ -73,4 +87,5 @@ A simple and efficient template based matrix library. // correction x += K*r; + ``` From a334cecfa7aec158331d294042be770851d19cd3 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 10:07:09 -0500 Subject: [PATCH 093/388] Forced function instantiation for coverage testing. --- matrix/filter.hpp | 3 ++- test/filter.cpp | 10 +++++++++- test/integration.cpp | 8 ++++++++ test/vector2.cpp | 2 +- 4 files changed, 20 insertions(+), 3 deletions(-) diff --git a/matrix/filter.hpp b/matrix/filter.hpp index 53fc99d92a..d075fc0f01 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -5,7 +5,7 @@ namespace matrix { template -void kalman_correct( +int kalman_correct( const SquareMatrix & P, const Matrix & C, const SquareMatrix & R, @@ -20,6 +20,7 @@ void kalman_correct( dx = K*r; beta = Scalar(r.T()*S_I*r); dP = K*C*P*(-1); + return 0; } }; // namespace matrix diff --git a/test/filter.cpp b/test/filter.cpp index b3b137cdcd..3470e5f4d4 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -5,7 +5,15 @@ using namespace matrix; -template class Vector; +template int kalman_correct( + const SquareMatrix & P, + const Matrix & C, + const SquareMatrix & R, + const Vector &r, + Vector & dx, + SquareMatrix & dP, + float & beta +); int main() { diff --git a/test/integration.cpp b/test/integration.cpp index e8b3889420..c1dea3b81d 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -5,6 +5,14 @@ using namespace matrix; +// instantiate template to ensure coverage check +template int integrate_rk4( + Vector (*f)(float, Vector), + Vector & y, + float & t, + float h +); + Vector f(float t, Vector y); Vector f(float t, Vector y) { diff --git a/test/vector2.cpp b/test/vector2.cpp index e1d122fbde..d9c63ed71f 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -5,7 +5,7 @@ using namespace matrix; -template class Vector; +template class Vector; int main() { From 606eb1dc2b86ef16889fe37008fb7989d1ec9dca Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 10:09:54 -0500 Subject: [PATCH 094/388] Added attitude classes to README. --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index 7c593cce4a..3da2001634 100644 --- a/README.md +++ b/README.md @@ -20,6 +20,9 @@ A simple and efficient template based matrix library. * Square Matrix (MxM, has inverse) * Vector (Mx1) * Scalar (1x1) + * Quaternion + * Dcm + * Euler (Body 321) * matrix/filter.hpp : Provides filtering routines. * kalman_correct From 7656385ea1d3f0a374a8146430bc63cf02e66d6b Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 10:19:30 -0500 Subject: [PATCH 095/388] Changed rk4 signature. --- matrix/integration.hpp | 18 +++++++++--------- test/integration.cpp | 13 +++++++------ 2 files changed, 16 insertions(+), 15 deletions(-) diff --git a/matrix/integration.hpp b/matrix/integration.hpp index 2582819078..1979bd8753 100644 --- a/matrix/integration.hpp +++ b/matrix/integration.hpp @@ -7,19 +7,19 @@ namespace matrix { template int integrate_rk4( Vector (*f)(Type, Vector), - Vector & y, - Type & t, - Type h + const Vector & y0, + Type t0, + Type h, + Vector & y1 ) { // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods Vector k1, k2, k3, k4; - k1 = f(t, y); - k2 = f(t + h/2, y + k1*h/2); - k3 = f(t + h/2, y + k2*h/2); - k4 = f(t + h, y + k3*h); - y += (k1 + k2*2 + k3*2 + k4)*(h/6); - t += h; + k1 = f(t0, y0); + k2 = f(t0 + h/2, y0 + k1*h/2); + k3 = f(t0 + h/2, y0 + k2*h/2); + k4 = f(t0 + h, y0 + k3*h); + y1 = y0 + (k1 + k2*2 + k3*2 + k4)*(h/6); return 0; } diff --git a/test/integration.cpp b/test/integration.cpp index c1dea3b81d..cdb8eb2466 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -8,9 +8,10 @@ using namespace matrix; // instantiate template to ensure coverage check template int integrate_rk4( Vector (*f)(float, Vector), - Vector & y, - float & t, - float h + const Vector & y0, + float t0, + float h, + Vector & y1 ); Vector f(float t, Vector y); @@ -22,12 +23,12 @@ Vector f(float t, Vector y) { int main() { Vector y = ones(); - float h = 1; float t = 1; + float h = 0.1f; y.T().print(); - integrate_rk4(f, y, t, h); + integrate_rk4(f, y, t, h, y); y.T().print(); - assert(y == (ones()*2)); + assert(y == (ones()*1.1f)); return 0; } From aa3a086cdab9860619e3b271a29fa5a1a803ff10 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 15:13:17 -0500 Subject: [PATCH 096/388] Work on rk4 interface. --- matrix/integration.hpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/matrix/integration.hpp b/matrix/integration.hpp index 1979bd8753..67eae7a453 100644 --- a/matrix/integration.hpp +++ b/matrix/integration.hpp @@ -4,10 +4,11 @@ namespace matrix { -template +template int integrate_rk4( - Vector (*f)(Type, Vector), + Vector (*f)(Type, const Vector &x, const Vector & u), const Vector & y0, + const Vector & u, Type t0, Type h, Vector & y1 @@ -15,10 +16,10 @@ int integrate_rk4( { // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods Vector k1, k2, k3, k4; - k1 = f(t0, y0); - k2 = f(t0 + h/2, y0 + k1*h/2); - k3 = f(t0 + h/2, y0 + k2*h/2); - k4 = f(t0 + h, y0 + k3*h); + k1 = f(t0, y0, u); + k2 = f(t0 + h/2, y0 + k1*h/2, u); + k3 = f(t0 + h/2, y0 + k2*h/2, u); + k4 = f(t0 + h, y0 + k3*h, u); y1 = y0 + (k1 + k2*2 + k3*2 + k4)*(h/6); return 0; } From 0a110a1b02c0ee2e04e2eb067392319e8fce9efa Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 15:15:31 -0500 Subject: [PATCH 097/388] Fixed integration test. --- test/integration.cpp | 16 ++++------------ 1 file changed, 4 insertions(+), 12 deletions(-) diff --git a/test/integration.cpp b/test/integration.cpp index cdb8eb2466..0d6863394d 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -5,28 +5,20 @@ using namespace matrix; -// instantiate template to ensure coverage check -template int integrate_rk4( - Vector (*f)(float, Vector), - const Vector & y0, - float t0, - float h, - Vector & y1 -); +Vector f(float t, const Vector & y, const Vector & u); -Vector f(float t, Vector y); - -Vector f(float t, Vector y) { +Vector f(float t, const Vector & y, const Vector & u) { return ones(); } int main() { Vector y = ones(); + Vector u = ones(); float t = 1; float h = 0.1f; y.T().print(); - integrate_rk4(f, y, t, h, y); + integrate_rk4(f, y, u, t, h, y); y.T().print(); assert(y == (ones()*1.1f)); return 0; From b9924820e1ae5be608e67cfc4ac6d7c593a4b439 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Thu, 12 Nov 2015 16:41:07 -0500 Subject: [PATCH 098/388] Work on kalman filter interface. --- matrix/Quaternion.hpp | 6 ++++++ matrix/filter.hpp | 10 +++++----- test/filter.cpp | 10 ---------- 3 files changed, 11 insertions(+), 15 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a0f0441db3..e1067c6bac 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -98,6 +98,12 @@ public: return r; } + void operator*=(const Quaternion & other) + { + Quaternion &self = *this; + self = self * other; + } + Matrix41 derivative(const Matrix31 & w) const { const Quaternion &q = *this; Type dataQ[] = { diff --git a/matrix/filter.hpp b/matrix/filter.hpp index d075fc0f01..a9d9982b1a 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -6,12 +6,12 @@ namespace matrix { template int kalman_correct( - const SquareMatrix & P, + const Matrix & P, const Matrix & C, - const SquareMatrix & R, - const Vector &r, - Vector & dx, - SquareMatrix & dP, + const Matrix & R, + const Matrix &r, + Matrix & dx, + Matrix & dP, float & beta ) { diff --git a/test/filter.cpp b/test/filter.cpp index 3470e5f4d4..f8eb01f748 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -5,16 +5,6 @@ using namespace matrix; -template int kalman_correct( - const SquareMatrix & P, - const Matrix & C, - const SquareMatrix & R, - const Vector &r, - Vector & dx, - SquareMatrix & dP, - float & beta -); - int main() { const size_t n_x = 6; From f2c0669c0d9cac4ce378b8a9c33ad03753cd801d Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 14 Nov 2015 08:55:34 -0500 Subject: [PATCH 099/388] Changed rk4 to use generic matrix interface. --- matrix/integration.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/matrix/integration.hpp b/matrix/integration.hpp index 67eae7a453..afc0cb7556 100644 --- a/matrix/integration.hpp +++ b/matrix/integration.hpp @@ -6,12 +6,12 @@ namespace matrix { template int integrate_rk4( - Vector (*f)(Type, const Vector &x, const Vector & u), - const Vector & y0, - const Vector & u, + Vector (*f)(Type, const Matrix &x, const Matrix & u), + const Matrix & y0, + const Matrix & u, Type t0, Type h, - Vector & y1 + Matrix & y1 ) { // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods From dc0eb16880488a1a25bfc15a46babed71c38e266 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 14 Nov 2015 09:01:09 -0500 Subject: [PATCH 100/388] Fixed integration test. --- test/integration.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test/integration.cpp b/test/integration.cpp index 0d6863394d..f33dc866cf 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -5,9 +5,9 @@ using namespace matrix; -Vector f(float t, const Vector & y, const Vector & u); +Vector f(float t, const Matrix & y, const Matrix & u); -Vector f(float t, const Vector & y, const Vector & u) { +Vector f(float t, const Matrix & y, const Matrix & u) { return ones(); } From 9cd6ac3dd9a255a1a2ef299da413c38a9040b8c7 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Sat, 14 Nov 2015 09:04:38 -0500 Subject: [PATCH 101/388] Fixed coverage. --- test/attitude.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/test/attitude.cpp b/test/attitude.cpp index 8449287df5..58f8f93fc8 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -130,6 +130,8 @@ int main() Quatf q_prod_check( 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); assert(q_prod_check == q_check*q_check); + q_check *= q_check; + assert(q_prod_check == q_check); }; From 10b395a7829cad0a0647bcd4f8da35e88c0e9a66 Mon Sep 17 00:00:00 2001 From: Roman Date: Fri, 27 Nov 2015 08:52:47 +0100 Subject: [PATCH 102/388] added more quaternion methods --- matrix/Matrix.hpp | 12 +++--- matrix/Quaternion.hpp | 76 ++++++++++++++++++++++++++++++++++--- matrix/Vector.hpp | 2 +- matrix/helper_functions.hpp | 30 +++++++++++++++ test/attitude.cpp | 60 +++++++++++++++++++++++++++++ 5 files changed, 167 insertions(+), 13 deletions(-) create mode 100644 matrix/helper_functions.hpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 2e32fc29b2..bad33f7a9a 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -361,8 +361,8 @@ public: Matrix abs() { Matrix r; - for (int i=0; i max_val) { max_val = val; @@ -386,8 +386,8 @@ public: Type min() { Type min_val = (*this)(0,0); - for (int i=0; i() { Quaternion &q = *this; - Type cosPhi_2 = Type(cos(euler.phi() / 2.0)); - Type cosTheta_2 = Type(cos(euler.theta() / 2.0)); - Type cosPsi_2 = Type(cos(euler.psi() / 2.0)); - Type sinPhi_2 = Type(sin(euler.phi() / 2.0)); - Type sinTheta_2 = Type(sin(euler.theta() / 2.0)); - Type sinPsi_2 = Type(sin(euler.psi() / 2.0)); + Type cosPhi_2 = Type(cos(euler.phi() / (Type)2.0)); + Type cosTheta_2 = Type(cos(euler.theta() / (Type)2.0)); + Type cosPsi_2 = Type(cos(euler.psi() / (Type)2.0)); + Type sinPhi_2 = Type(sin(euler.phi() / (Type)2.0)); + Type sinTheta_2 = Type(sin(euler.theta() / (Type)2.0)); + Type sinPsi_2 = Type(sin(euler.psi() / (Type)2.0)); q(0) = cosPhi_2 * cosTheta_2 * cosPsi_2 + sinPhi_2 * sinTheta_2 * sinPsi_2; q(1) = sinPhi_2 * cosTheta_2 * cosPsi_2 - @@ -120,6 +121,69 @@ public: v(3) = w(2,0); return Q * v * Type(0.5); } + + void invert() { + Quaternion &q = *this; + q(1) *= -1; + q(2) *= -1; + q(3) *= -1; + } + + Quaternion inversed() { + Quaternion &q = *this; + Quaternion ret; + ret(0) = q(0); + ret(1) = -q(1); + ret(2) = -q(2); + ret(3) = -q(3); + return ret; + } + + void rotate(const Vector &vec) { + Quaternion res; + res.from_axis_angle(vec); + (*this) = (*this) * res; + } + + void from_axis_angle(Vector vec) { + Quaternion &q = *this; + Type theta = vec.norm(); + if(theta < (Type)1e-10) { + q(0) = (Type)1.0; + q(1)=q(2)=q(3)=0; + return; + } + vec /= theta; + from_axis_angle(vec,theta); + } + + void from_axis_angle(const Vector &axis, Type theta) { + Quaternion &q = *this; + if(theta < (Type)1e-10) { + q(0) = (Type)1.0; + q(1)=q(2)=q(3)=0; + } + Type magnitude = sinf(theta/2.0f); + + q(0) = cosf(theta/2.0f); + q(1) = axis(0) * magnitude; + q(2) = axis(1) * magnitude; + q(3) = axis(2) * magnitude; + } + + Vector to_axis_angle() { + Quaternion &q = *this; + Type axis_magnitude = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); + Vector vec; + vec(0) = q(1); + vec(1) = q(2); + vec(2) = q(3); + if(axis_magnitude >= (Type)1e-10) { + vec = vec / axis_magnitude; + vec = vec * wrap_pi((Type)2.0 * atan2f(axis_magnitude,q(0))); + } + return vec; + } }; typedef Quaternion Quatf; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 4c75ce5694..67f6e98f6a 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -52,7 +52,7 @@ public: Type dot(const MatrixM1 & b) const { const Vector &a(*this); Type r = 0; - for (int i = 0; i + + +namespace matrix +{ +template +float wrap_pi(Type x) +{ + if (!isfinite(x)) { + return x; + } + + while (x >= (Type)M_PI) { + x -= (Type)(2.0 * M_PI); + + } + + while (x < (Type)(-M_PI)) { + x += (Type)(2.0 * M_PI); + + } + + return x; +} + + +}; \ No newline at end of file diff --git a/test/attitude.cpp b/test/attitude.cpp index 58f8f93fc8..4946498634 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -133,6 +133,66 @@ int main() q_check *= q_check; assert(q_prod_check == q_check); + // quaternion inverse + q = q_check.inversed(); + assert(fabsf(q_check(0) - q(0)) < eps); + assert(fabsf(q_check(1) + q(1)) < eps); + assert(fabsf(q_check(2) + q(2)) < eps); + assert(fabsf(q_check(3) + q(3)) < eps); + + q = q_check; + q.invert(); + assert(fabsf(q_check(0) - q(0)) < eps); + assert(fabsf(q_check(1) + q(1)) < eps); + assert(fabsf(q_check(2) + q(2)) < eps); + assert(fabsf(q_check(3) + q(3)) < eps); + + // rotate quaternion (nonzero rotation) + Quatf qI(1.0f, 0.0f, 0.0f, 0.0f); + Vector rot; + rot(0) = 1.0f; + rot(1) = rot(2) = 0.0f; + qI.rotate(rot); + Quatf q_true(cosf(1.0f / 2), sinf(1.0f / 2), 0.0f, 0.0f); + assert(fabsf(qI(0) - q_true(0)) < eps); + assert(fabsf(qI(1) - q_true(1)) < eps); + assert(fabsf(qI(2) - q_true(2)) < eps); + assert(fabsf(qI(3) - q_true(3)) < eps); + + // rotate quaternion (zero rotation) + qI = Quatf(1.0f, 0.0f, 0.0f, 0.0f); + rot(0) = 0.0f; + rot(1) = rot(2) = 0.0f; + qI.rotate(rot); + q_true = Quatf(cosf(0.0f), sinf(0.0f), 0.0f, 0.0f); + assert(fabsf(qI(0) - q_true(0)) < eps); + assert(fabsf(qI(1) - q_true(1)) < eps); + assert(fabsf(qI(2) - q_true(2)) < eps); + assert(fabsf(qI(3) - q_true(3)) < eps); + + // get rotation axis from quaternion (nonzero rotation) + q = Quatf(cosf(1.0f / 2), 0.0f, sinf(1.0f / 2), 0.0f); + rot = q.to_axis_angle(); + assert(fabsf(rot(0)) < eps); + assert(fabsf(rot(1) -1.0f) < eps); + assert(fabsf(rot(2)) < eps); + + // get rotation axis from quaternion (zero rotation) + q = Quatf(1.0f, 0.0f, 0.0f, 0.0f); + rot = q.to_axis_angle(); + assert(fabsf(rot(0)) < eps); + assert(fabsf(rot(1)) < eps); + assert(fabsf(rot(2)) < eps); + + // from axis angle (zero rotation) + rot(0) = rot(1) = rot(2) = 0.0f; + q.from_axis_angle(rot, 0.0f); + q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f); + assert(fabsf(q(0) - q_true(0)) < eps); + assert(fabsf(q(1) - q_true(1)) < eps); + assert(fabsf(q(2) - q_true(2)) < eps); + assert(fabsf(q(3) - q_true(3)) < eps); + }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From c3c6a0a9df19ffa782e095e4ec3993bac738d935 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Thu, 10 Dec 2015 16:40:30 +0100 Subject: [PATCH 103/388] fix euler calculation --- matrix/Euler.hpp | 27 ++++++++++++--------------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 74e364940f..c055b0d827 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -48,22 +48,19 @@ public: Euler(const Dcm & dcm) : Vector() { - Type psi_val = Type(atan(dcm(1, 0)/ dcm(0, 0))); - Type theta_val = Type(asin(-dcm(2,0))); - Type phi_val = Type(atan(dcm(2, 1)/ dcm(2, 2))); + theta() = (Type)asin(-dcm(2,0)); - // protection against NaN if dcm(0,0) or dcm(2,2) == 0 - psi() = 0; - theta() = 0; - phi() = 0; - if (psi() >= -M_PI_2 && psi() <= M_PI_2) { - psi() = psi_val; - } - if (theta() >= -M_PI_2 && theta() <= M_PI_2) { - theta() = theta_val; - } - if (phi() >= -M_PI_2 && phi() <= M_PI_2) { - phi() = phi_val; + if (fabs(theta() - (Type)M_PI_2) < 1.0e-3) { + phi() = (Type)0.0; + psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) + theta(); + + } else if (fabs(theta() + (Type)M_PI_2) < (Type)1.0e-3) { + phi() = (Type)0.0; + psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) - theta(); + + } else { + phi() = (Type)atan2(dcm(2,1), dcm(2,2)); + psi() = (Type)atan2(dcm(1,0), dcm(0,0)); } } From cc1658db15d720e05d577787363823be0f2bd161 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 22 Dec 2015 11:23:18 +0100 Subject: [PATCH 104/388] fixed wrong type conversion --- matrix/Euler.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index c055b0d827..346acf2c51 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -54,7 +54,7 @@ public: phi() = (Type)0.0; psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) + theta(); - } else if (fabs(theta() + (Type)M_PI_2) < (Type)1.0e-3) { + } else if ((Type)fabs(theta() + (Type)M_PI_2) < (Type)1.0e-3) { phi() = (Type)0.0; psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) - theta(); From d999923a354f8a337e2aa4d9349f67482ed7e394 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 18 Dec 2015 13:23:19 +0100 Subject: [PATCH 105/388] support for std::cout --- CMakeLists.txt | 7 +++++++ matrix/Matrix.hpp | 21 +++++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 639f9b19e2..19cb107e5e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,6 +13,13 @@ endif() set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Profile") +option (SUPPORT_STDIOSTREAM + "If enabled provides support for << operator (as used with + std::cout)" OFF) +if((SUPPORT_STDIOSTREAM)) + add_definitions(-DSUPPORT_STDIOSTREAM) +endif() + set(CMAKE_CXX_FLAGS_PROFILE ${CMAKE_CXX_FLAGS_DEBUG} --coverage diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 2e32fc29b2..8d85946ed6 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -13,6 +13,10 @@ #include #include #include +#if defined(SUPPORT_STDIOSTREAM) +#include +#include +#endif // defined(SUPPORT_STDIOSTREAM) #include "math.hpp" @@ -413,6 +417,23 @@ Matrix ones() { return m; } +#if defined(SUPPORT_STDIOSTREAM) +template +std::ostream& operator<<(std::ostream& os, + const matrix::Matrix& matrix) +{ + for (size_t i = 0; i < M; ++i) { + os << "["; + for (size_t j = 0; j < N; ++j) { + os << std::setw(10) << static_cast(matrix(i, j)); + os << "\t"; + } + os << "]" << std::endl; + } + return os; +} +#endif // defined(SUPPORT_STDIOSTREAM) + typedef Matrix Matrix3f; }; // namespace matrix From 99ac5327465fddf5d6d2859941157d4c3fb04ee8 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 26 Dec 2015 10:07:25 +0100 Subject: [PATCH 106/388] remove unnecessary ; --- matrix/Dcm.hpp | 2 +- matrix/Euler.hpp | 2 +- matrix/Matrix.hpp | 2 +- matrix/Quaternion.hpp | 2 +- matrix/Scalar.hpp | 2 +- matrix/SquareMatrix.hpp | 2 +- matrix/Vector.hpp | 2 +- matrix/Vector2.hpp | 2 +- matrix/Vector3.hpp | 2 +- matrix/filter.hpp | 2 +- matrix/integration.hpp | 2 +- 11 files changed, 11 insertions(+), 11 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index c94e890cfb..646fa7e2ec 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -87,6 +87,6 @@ public: typedef Dcm Dcmf; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 74e364940f..53d23d02b1 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -97,6 +97,6 @@ public: typedef Euler Eulerf; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 8d85946ed6..f54ad2d2e0 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -436,6 +436,6 @@ std::ostream& operator<<(std::ostream& os, typedef Matrix Matrix3f; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index e1067c6bac..590cbac9be 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -124,6 +124,6 @@ public: typedef Quaternion Quatf; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 022ab5f7de..0e722eed8c 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -50,6 +50,6 @@ private: typedef Scalar Scalarf; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 36cc716bec..c10d0a4b4d 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -217,6 +217,6 @@ SquareMatrix inv(const SquareMatrix & A) -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 4c75ce5694..8255d6e9c6 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -69,6 +69,6 @@ public: }; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index 9956560594..50e9855c9f 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -60,6 +60,6 @@ public: typedef Vector2 Vector2f; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index c33ff77e58..4bbfeb0745 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -65,6 +65,6 @@ public: typedef Vector3 Vector3f; -}; // namespace matrix +} // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/filter.hpp b/matrix/filter.hpp index a9d9982b1a..1841d1460e 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -23,4 +23,4 @@ int kalman_correct( return 0; } -}; // namespace matrix +} // namespace matrix diff --git a/matrix/integration.hpp b/matrix/integration.hpp index afc0cb7556..a0ad55c68a 100644 --- a/matrix/integration.hpp +++ b/matrix/integration.hpp @@ -24,4 +24,4 @@ int integrate_rk4( return 0; } -}; // namespace matrix +} // namespace matrix From 45e6012818419a1bdb57db39623bcaf1f7ca5c05 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 26 Dec 2015 13:04:07 +0100 Subject: [PATCH 107/388] matrix scalar pre multiplication and general scalar multiplication for quaternions --- matrix/Matrix.hpp | 6 ++++++ matrix/Quaternion.hpp | 12 ++++++++++++ test/attitude.cpp | 13 +++++++++++++ 3 files changed, 31 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index f54ad2d2e0..59498f6556 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -417,6 +417,12 @@ Matrix ones() { return m; } +template +Matrix operator*(Type scalar, const Matrix &other) +{ + return other * scalar; +} + #if defined(SUPPORT_STDIOSTREAM) template std::ostream& operator<<(std::ostream& os, diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 590cbac9be..dc813ab2ae 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -104,6 +104,18 @@ public: self = self * other; } + Quaternion operator*(Type scalar) const + { + const Quaternion &q = *this; + return scalar * q; + } + + void operator*=(Type scalar) + { + Quaternion &q = *this; + q = q * scalar; + } + Matrix41 derivative(const Matrix31 & w) const { const Quaternion &q = *this; Type dataQ[] = { diff --git a/test/attitude.cpp b/test/attitude.cpp index 58f8f93fc8..b06409d2ba 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -133,6 +133,19 @@ int main() q_check *= q_check; assert(q_prod_check == q_check); + // Quaternion scalar multiplication + float scalar = 0.5; + Quatf q_scalar_mul(1.0f, 2.0f, 3.0f, 4.0f); + Quatf q_scalar_mul_check(1.0f * scalar, 2.0f * scalar, + 3.0f * scalar, 4.0f * scalar); + Quatf q_scalar_mul_res = scalar * q_scalar_mul; + assert(q_scalar_mul_check == q_scalar_mul_res); + Quatf q_scalar_mul_res2 = q_scalar_mul * scalar; + assert(q_scalar_mul_check == q_scalar_mul_res2); + Quatf q_scalar_mul_res3(q_scalar_mul); + q_scalar_mul_res3 *= scalar; + assert(q_scalar_mul_check == q_scalar_mul_res3); + }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From cc800454d2b48f7101608e99dac267d174d58697 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 11 Jan 2016 22:05:34 -0600 Subject: [PATCH 108/388] Formatting. --- matrix/Matrix.hpp | 16 ++++++++-------- test/attitude.cpp | 2 +- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index f8e35697b0..9461fb2619 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -426,16 +426,16 @@ Matrix operator*(Type scalar, const Matrix &other) #if defined(SUPPORT_STDIOSTREAM) template std::ostream& operator<<(std::ostream& os, - const matrix::Matrix& matrix) + const matrix::Matrix& matrix) { - for (size_t i = 0; i < M; ++i) { - os << "["; - for (size_t j = 0; j < N; ++j) { - os << std::setw(10) << static_cast(matrix(i, j)); - os << "\t"; - } - os << "]" << std::endl; + for (size_t i = 0; i < M; ++i) { + os << "["; + for (size_t j = 0; j < N; ++j) { + os << std::setw(10) << static_cast(matrix(i, j)); + os << "\t"; } + os << "]" << std::endl; + } return os; } #endif // defined(SUPPORT_STDIOSTREAM) diff --git a/test/attitude.cpp b/test/attitude.cpp index 9ae0f27938..1d008d2b28 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -137,7 +137,7 @@ int main() float scalar = 0.5; Quatf q_scalar_mul(1.0f, 2.0f, 3.0f, 4.0f); Quatf q_scalar_mul_check(1.0f * scalar, 2.0f * scalar, - 3.0f * scalar, 4.0f * scalar); + 3.0f * scalar, 4.0f * scalar); Quatf q_scalar_mul_res = scalar * q_scalar_mul; assert(q_scalar_mul_check == q_scalar_mul_res); Quatf q_scalar_mul_res2 = q_scalar_mul * scalar; From 4034c916c7fc41048306f1f7e8226c824868662b Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 12 Jan 2016 07:49:41 +0100 Subject: [PATCH 109/388] added missing cast --- matrix/Euler.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 53d23d02b1..98eae6e9e9 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -56,13 +56,13 @@ public: psi() = 0; theta() = 0; phi() = 0; - if (psi() >= -M_PI_2 && psi() <= M_PI_2) { + if (psi() >= -(Type)M_PI_2 && psi() <= (Type)M_PI_2) { psi() = psi_val; } - if (theta() >= -M_PI_2 && theta() <= M_PI_2) { + if (theta() >= -(Type)M_PI_2 && theta() <= (Type)M_PI_2) { theta() = theta_val; } - if (phi() >= -M_PI_2 && phi() <= M_PI_2) { + if (phi() >= -(Type)M_PI_2 && phi() <= (Type)M_PI_2) { phi() = phi_val; } } From f1968f51d6eb5d4680434c103b2e95cb66ddd1e9 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 12 Jan 2016 01:28:48 -0600 Subject: [PATCH 110/388] Fixed coverage issues. --- matrix/helper_functions.hpp | 5 +++-- test/CMakeLists.txt | 1 + test/helper.cpp | 18 ++++++++++++++++++ 3 files changed, 22 insertions(+), 2 deletions(-) create mode 100644 test/helper.cpp diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index f7e737ef42..d42d0c949a 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -6,8 +6,9 @@ namespace matrix { + template -float wrap_pi(Type x) +Type wrap_pi(Type x) { if (!isfinite(x)) { return x; @@ -27,4 +28,4 @@ float wrap_pi(Type x) } -}; \ No newline at end of file +}; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 76357d890c..7351b3ae7c 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -13,6 +13,7 @@ set(tests filter integration squareMatrix + helper ) add_custom_target(test_build) diff --git a/test/helper.cpp b/test/helper.cpp new file mode 100644 index 0000000000..68bdced00b --- /dev/null +++ b/test/helper.cpp @@ -0,0 +1,18 @@ +#include +#include + +#include + +using namespace matrix; + + +int main() +{ + assert(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5); + assert(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); + assert(fabs(wrap_pi(3.0) - (3.0)) < 1e-3); + wrap_pi(NAN); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 67c8c8b331d0fb311fbc351fda88d940865d6f98 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 12 Jan 2016 01:35:33 -0600 Subject: [PATCH 111/388] Cast to float for isfinite. --- matrix/helper_functions.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index d42d0c949a..db23bc576a 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -10,7 +10,7 @@ namespace matrix template Type wrap_pi(Type x) { - if (!isfinite(x)) { + if (!isfinite(float(x))) { return x; } From 187830164d6b43fca7f7de39040367ebb387d68f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 12 Jan 2016 11:50:21 +0100 Subject: [PATCH 112/388] Fix cast --- matrix/helper_functions.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index db23bc576a..284644657a 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -10,7 +10,7 @@ namespace matrix template Type wrap_pi(Type x) { - if (!isfinite(float(x))) { + if (!isfinite(Type(x))) { return x; } From 1d9d8e6f9b0c2ed930ea1c8996f5fb398b3cf322 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 12 Jan 2016 12:14:53 +0100 Subject: [PATCH 113/388] Use a slight ifdef hack to let things default to C++11 for most platforms --- matrix/helper_functions.hpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 284644657a..96d2b82751 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -1,8 +1,14 @@ #pragma once #include "math.hpp" -#include +// grody hack - this should go once C++11 is supported +// on all platforms. +#ifdef __PX4_NUTTX +#include +#else +#include +#endif namespace matrix { @@ -10,7 +16,11 @@ namespace matrix template Type wrap_pi(Type x) { - if (!isfinite(Type(x))) { +#ifdef __PX4_NUTTX + if (!isfinite(x)) { +#else + if (!std::isfinite(x)) { +#endif return x; } From a22a47fe154f2c6d0579eef3f4f03bb9530d362c Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Thu, 10 Dec 2015 16:40:30 +0100 Subject: [PATCH 114/388] fix euler calculation Conflicts: matrix/Euler.hpp --- matrix/Euler.hpp | 27 ++++++++++++--------------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 98eae6e9e9..d23ba6b153 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -48,22 +48,19 @@ public: Euler(const Dcm & dcm) : Vector() { - Type psi_val = Type(atan(dcm(1, 0)/ dcm(0, 0))); - Type theta_val = Type(asin(-dcm(2,0))); - Type phi_val = Type(atan(dcm(2, 1)/ dcm(2, 2))); + theta() = (Type)asin(-dcm(2,0)); - // protection against NaN if dcm(0,0) or dcm(2,2) == 0 - psi() = 0; - theta() = 0; - phi() = 0; - if (psi() >= -(Type)M_PI_2 && psi() <= (Type)M_PI_2) { - psi() = psi_val; - } - if (theta() >= -(Type)M_PI_2 && theta() <= (Type)M_PI_2) { - theta() = theta_val; - } - if (phi() >= -(Type)M_PI_2 && phi() <= (Type)M_PI_2) { - phi() = phi_val; + if (fabs(theta() - (Type)M_PI_2) < 1.0e-3) { + phi() = (Type)0.0; + psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) + theta(); + + } else if ((Type)fabs(theta() + (Type)M_PI_2) < (Type)1.0e-3) { + phi() = (Type)0.0; + psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) - theta(); + + } else { + phi() = (Type)atan2(dcm(2,1), dcm(2,2)); + psi() = (Type)atan2(dcm(1,0), dcm(0,0)); } } From fa31c61f2cd00abbbfdde3b92dd099ec79ed0e8e Mon Sep 17 00:00:00 2001 From: James Goppert Date: Thu, 14 Jan 2016 15:04:27 -0500 Subject: [PATCH 115/388] Fix for euler. --- .gitmodules | 0 .travis.yml | 3 +- CMakeLists.txt | 52 ++++---- doc/.gitignore | 1 + doc/euler_gimbal_lock.ipynb | 240 ++++++++++++++++++++++++++++++++++++ matrix/Euler.hpp | 6 +- test/CMakeLists.txt | 4 +- test/attitude.cpp | 7 +- 8 files changed, 281 insertions(+), 32 deletions(-) create mode 100644 .gitmodules create mode 100644 doc/.gitignore create mode 100644 doc/euler_gimbal_lock.ipynb diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000000..e69de29bb2 diff --git a/.travis.yml b/.travis.yml index f4f8ba684d..9e51c82c45 100644 --- a/.travis.yml +++ b/.travis.yml @@ -3,9 +3,10 @@ sudo: false install: - pip install --user cpp-coveralls script: - - cmake -DCMAKE_BUILD_TYPE=Profile . + - cmake -DCMAKE_BUILD_TYPE=Profile -DTEST=ON -DFORMAT=ON . - make - make check_format + - ctest -V - make test after_success: - cpp-coveralls -i matrix diff --git a/CMakeLists.txt b/CMakeLists.txt index 19cb107e5e..56b221022e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,10 +13,13 @@ endif() set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Profile") -option (SUPPORT_STDIOSTREAM +option(SUPPORT_STDIOSTREAM "If enabled provides support for << operator (as used with std::cout)" OFF) -if((SUPPORT_STDIOSTREAM)) +option(TEST "Enable testing" OFF) +option(FORMAT "Enable formatting" OFF) + +if(SUPPORT_STDIOSTREAM) add_definitions(-DSUPPORT_STDIOSTREAM) endif() @@ -59,29 +62,34 @@ include_directories(${CMAKE_SOURCE_DIR}) file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) -add_subdirectory(test) +if(TEST) + enable_testing() + add_subdirectory(test) +endif() -set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) -add_custom_command(OUTPUT ${astyle_exe} - COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.05.1/astyle_2.05.1_linux.tar.gz -O /tmp/astyle.tar.gz - COMMAND tar -xvf /tmp/astyle.tar.gz - COMMAND cd astyle/src && make -f ../build/gcc/Makefile - WORKING_DIRECTORY ${CMAKE_BINARY_DIR} +if(FORMAT) + set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) + add_custom_command(OUTPUT ${astyle_exe} + COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.05.1/astyle_2.05.1_linux.tar.gz -O /tmp/astyle.tar.gz + COMMAND tar -xvf /tmp/astyle.tar.gz + COMMAND cd astyle/src && make -f ../build/gcc/Makefile + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + ) + + add_custom_target(check_format + COMMAND scripts/format.sh ${astyle_exe} 0 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + DEPENDS ${astyle_exe} + VERBATIM ) -add_custom_target(check_format - COMMAND scripts/format.sh ${astyle_exe} 0 - WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} - DEPENDS ${astyle_exe} - VERBATIM -) - -add_custom_target(format - COMMAND scripts/format.sh ${astyle_exe} 1 - WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} - VERBATIM - DEPENDS ${astyle_exe} -) + add_custom_target(format + COMMAND scripts/format.sh ${astyle_exe} 1 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + VERBATIM + DEPENDS ${astyle_exe} + ) +endif() set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) diff --git a/doc/.gitignore b/doc/.gitignore new file mode 100644 index 0000000000..87620ac7e7 --- /dev/null +++ b/doc/.gitignore @@ -0,0 +1 @@ +.ipynb_checkpoints/ diff --git a/doc/euler_gimbal_lock.ipynb b/doc/euler_gimbal_lock.ipynb new file mode 100644 index 0000000000..9131c84848 --- /dev/null +++ b/doc/euler_gimbal_lock.ipynb @@ -0,0 +1,240 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 4, + "metadata": { + "collapsed": true + }, + "outputs": [], + "source": [ + "from sympy import *\n", + "init_printing()" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": { + "collapsed": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAA6cAAABMBAMAAABjWdyfAAAAMFBMVEX///8AAAAAAAAAAAAAAAAA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\nKMBQ2em6pwAAAABJRU5ErkJggg==\n", + "text/latex": [ + "$$\\left[\\begin{matrix}\\cos{\\left (\\theta_{1} \\right )} \\cos{\\left (\\theta_{2} \\right )} & - \\sin{\\left (\\theta_{1} \\right )} \\cos{\\left (\\theta_{3} \\right )} + \\sin{\\left (\\theta_{2} \\right )} \\sin{\\left (\\theta_{3} \\right )} \\cos{\\left (\\theta_{1} \\right )} & \\sin{\\left (\\theta_{1} \\right )} \\sin{\\left (\\theta_{3} \\right )} + \\sin{\\left (\\theta_{2} \\right )} \\cos{\\left (\\theta_{1} \\right )} \\cos{\\left (\\theta_{3} \\right )}\\\\\\sin{\\left (\\theta_{1} \\right )} \\cos{\\left (\\theta_{2} \\right )} & \\sin{\\left (\\theta_{1} \\right )} \\sin{\\left (\\theta_{2} \\right )} \\sin{\\left (\\theta_{3} \\right )} + \\cos{\\left (\\theta_{1} \\right )} \\cos{\\left (\\theta_{3} \\right )} & \\sin{\\left (\\theta_{1} \\right )} \\sin{\\left (\\theta_{2} \\right )} \\cos{\\left (\\theta_{3} \\right )} - \\sin{\\left (\\theta_{3} \\right )} \\cos{\\left (\\theta_{1} \\right )}\\\\- \\sin{\\left (\\theta_{2} \\right )} & \\sin{\\left (\\theta_{3} \\right )} \\cos{\\left (\\theta_{2} \\right )} & \\cos{\\left (\\theta_{2} \\right )} \\cos{\\left (\\theta_{3} \\right )}\\end{matrix}\\right]$$" + ], + "text/plain": [ + "⎡cos(θ₁)⋅cos(θ₂) -sin(θ₁)⋅cos(θ₃) + sin(θ₂)⋅sin(θ₃)⋅cos(θ₁) sin(θ₁)⋅sin(θ₃) \n", + "⎢ \n", + "⎢sin(θ₁)⋅cos(θ₂) sin(θ₁)⋅sin(θ₂)⋅sin(θ₃) + cos(θ₁)⋅cos(θ₃) sin(θ₁)⋅sin(θ₂)⋅\n", + "⎢ \n", + "⎣ -sin(θ₂) sin(θ₃)⋅cos(θ₂) cos\n", + "\n", + "+ sin(θ₂)⋅cos(θ₁)⋅cos(θ₃)⎤\n", + " ⎥\n", + "cos(θ₃) - sin(θ₃)⋅cos(θ₁)⎥\n", + " ⎥\n", + "(θ₂)⋅cos(θ₃) ⎦" + ] + }, + "execution_count": 16, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "th1, th2, th3 = symbols('theta_1, theta_2, theta_3')\n", + "dcm_321 = Matrix([[cos(th1)*cos(th2),\n", + " cos(th1)*sin(th2)*sin(th3) - sin(th1)*cos(th3),\n", + " cos(th1)*sin(th2)*cos(th3) + sin(th1)*sin(th3)],\n", + " [sin(th1)*cos(th2),\n", + " sin(th1)*sin(th2)*sin(th3) + cos(th1)*cos(th3),\n", + " sin(th1)*sin(th2)*cos(th3) - cos(th1)*sin(th3)],\n", + " [-sin(th2),\n", + " cos(th2)*sin(th3),\n", + " cos(th2)*cos(th3)]\n", + " ])\n", + "dcm_321" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": { + "collapsed": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAA1oAAABMBAMAAACG69u2AAAAMFBMVEX///8AAAAAAAAAAAAAAAAA\nAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAv3aB7AAAAD3RSTlMAMquZdlQQ3SJEie/N\nZrv3ZvUrAAAACXBIWXMAAA7EAAAOxAGVKw4bAAARq0lEQVR4Ae1dfYhcVxU/292dnZ2d3U1rS5FY\nklYRRKQrprZUlKHdVg2KAy2oLbSjSUH6lYUiBj/oiBSEkHT9QwoGzTOJ2pYK0WpJRXFE6+dSVwwS\n69dSgxRq2jS1pa228Xfux7z7/d7LvsQV9sLcd++75/zO756z896b3V8mtOnUqZO03tZ+Bu4+deoE\nbdoyf83ap7rOkI7MX4VqbVjPxP9JBqZj1bpIbACF/F14JyPLRI2/0HS61GxF1I+ZcZA7llMhiEYo\n5m0QK8M2wcNAQsBizkTYdiQxOVZBigTnZhRH0rB3H6tWc0VEzYjOCddjD9a/dsscXSzszG5jJ5+x\nFVFGudnI98Qp0XGQyX9clwpB1IKpHwRJdYBgliXZ2jxgbrRqnOGYRUK5QOEUcWSZYewukWB397Fq\ntXuMyKRogJfffo58PUIvUttb2pTlp2CFllFuNvKKOCU6DrKxN9uLh4AZV8sPgugOEMwyvAZ4+c3n\nYdtU4wzfDK8BXm5zgCIpYi+ZYd7dgKdek5Tt3ceqtVV4N/miIIcO2lhGNLFMLxAPok0uNjoUNmPk\nz9FsNx4CBrvxSgbBehm2uHB3ipG0RdQ2EKrRBwW/FaRIAm2Hnxw5AGrL9u5j1TosnKf7ONzm4Ijp\nFFb+RPQqNQ6FltU5tsLFDtfSoBmCTB+i2eV4CHgfxSvozdCqlWGb4KFhxLGYM8ysxIx3LAA9KUiR\n5PwlWEcTjDV795FqTS6ImC3u210xtrv7ML2LRl4gesxeIPo8iqMaW8lr2dCsea5aQ/YQZGKONnXj\nIWCbsb0XBNd9GwhGabYOD0bNWyXOcLNCmdVygCIpAoLKcIZhNMFY4/V897pa2x78BjUObl2k86//\nANZbc0S3bgGp98oxNa58sEu3zj9AI9fMD2BwAPFeprGXxQhz1eDdfHbzyG/ePv8mPgMronNH7+nL\nIfvuOUlvePj8qzpY4CD7FulDi2IUCtE40KFsDEUVQHBRLQBUxNbkoWHksTJnKxQwdLV8IDNFgQzT\nyIYrPhJPsL97Va3m92lj/8I+HWus0AQIzCyjrDfTPfShHk0PcGJXd+TwyE6a6dxJhOzRcTzLnLzk\nrSeI/oyZbsJ7ZjO1j9G9fZyEFY12d9MvpZnwfZLo8U7zJaxwkEsvueTHuLAMMA2EaI2faHbHXrSD\nwDQAVMTW5AGEvFXnbIUCkKpWAMhIUSjDdFlzud2vsHtVrfaAbt7waaJNr39EvMsnutTsXk5/oCmQ\n4eos0fhzExmNPLe3J96dn8RFbECzA6IP5xunSfZGtWbE3YgIVqjYUdovzYQvqvU03/AA0CX6LNF/\n4iHuGV2Y7tEhOwg8faBCtiYPgzEuEVU526GApaoVADJSFMgwflyn+63N0QT7u1fV2jGHR2LchGaz\nu4/1QWBqkRr0A9RlFOdP4Db/PE7iBkOvTLz2PgzpUbYVZzbxVDf25mqhkB2cgxWuYxldDmdMhS+q\n9U+if2GKIPSKCBsL0ZvKcIcANxHk9k9x+0kQqJCtyQMIRqvK2QrFOPpK6AMZKQpkGLeZFo0uRBNs\n754jqWrt6yAobkKzK7f+lgvDiZx8CXnGEyancpKzezNOvtZ46BSyx3XY0aV3YWRVi725WivDak3M\nAeVxaSZ8Ua1nhtVqvECjh+IhaF+/JR68rSD44WESFlAhW5MHWButKmcrFLWWln7xw6UlzokPZKQo\nlOG7UK32SjTB/u7d99YVffobisIXqdZCs0vfRKUWjPfW81+kaVSVr3E7FsU7RD73yd032duoFqxm\nl5vLTbxr2Uz45klGkMbLoqyxEPQt3DpbPektQ4jeBypka/IwkPBsWZWzFYqh1HsrAGSkaPjeMjL8\nKj5M3tuNJtjfvaoWrqrUfRiPaF/O6JxlEg8AoyvTvfFF9QiwBFJTc3gOvIHobWCI54epxRbqaD1l\njLO3US1YtTvT/Zk5aSZ882rxU8ajoBQPQe/BrfOjThBMA0BFbE0eQMjbeGXOVigAqWoFgIwUhTL8\nM9zS/15l96pazR9Rq79xA/16/BGa6eN9tRnvqUNj9EeQGUWuadcy3T/yHWpnN/boKcz343xnVx+j\nd+Clm/DGZVBfCWE1udBiRsJM+OIyqK6EHGRL8zAWYyFoL3WmF5U3DroFgIrYmjw0jDhW52yFAoau\nFqfO3ryRolCG76OMf5DL715Viz6+5X5qXrl/cfLbH3wABCYX0F1305E+Dm1OV+ONW/v0hQffQl85\n8gTPcWFrbHknBvQr7lRj75FLT37s0pMXPPtdnOPL3+v++sQGHNiMfc879ebzTl180783yyDbru5h\nIRaCxi87Lh5qzCCwDwAVsTV5ACFv1TlboQCkqhUAMlMUyPDIu49/Hf7ld6+rlbOXo518uECMd8kz\ndj/RV/PmIXvBmgmr3XwqaCaC8Go8xEg36s0LqpViG+ehYcSxDGc7MapaFgomBSlizs1ldiq/+1i1\nfs8w13JHB0XvdNNz6kSr46yYU2F1lM8EzUQQXo2HGOvxetCbF1QrxTbOQ8OIYxnOdmImRc4tEJ4U\npIg5T/fZsPzuY9XimxcevdEaA3R+e0qdut1fMs6wVcbzoJkIgsXGAJ3f2LklTge9DYdSbDN2KEKC\nSQnOAqoxgHGqpVPEnMXuGoMgSGj3sWo1VwDRYRiRCR7YbY+aakr2qp6xVYcnQTMRBIuJEGPsHPYW\nK7IrxbbDtkEeEkT3JTh32DbCWsMQpVPEnMXuIjjs7e4+Vi3xZyURWFxAcgp6JC+56r2sT3pHZRUz\nE7cS+WcBz1Vf1bEgLxgBi+EpBVQIVYyUh43YFoUaclJ3pSh7DZROsLX7aLXyoOujNZOB9WqtmVKU\nILJerRJJWjMm69VaM6UoQWS9WiWStGZMYtUKaQ8t0qxdvCMq3NSmEqYf028ySEJJyd7FClOGEEDN\nSkpKdou3AuIyYGkNKP4mhGe7DaFwIlA8kTYPs1obOzmc/KzQwomL85PGiD8tRISbPkxmoBSJNl3v\nuHzSYSM+a1ZQUhruauiGFh/s49uHVwa9Q6gGPpKVSTMHnOhIIpmWrAPiCB5mtTbhpG4h7aFe42O7\nFxVu+jAZ7NmJW5Fo0/FOyCclnuiZjfzNwIAHXivajXRwQuNkZhC3QGVA8WuagbUgJz4SVyuYA6ZW\nqIDNlLNZLRlJ9GNYR+MPcGoo5nm3FcO4cFPbSd9GJ4LCIOrTqByK+bBj7wlLYfqJ4Zo9kN7bcTKE\no7cQ342NhlkB8ZDctNH3UPiESl8stliOJ9LhEanWlAzNH7PDysvDuA7HhZtMk5uESak/YSR+Z3Cb\nsLc79rYVptfbBsMZ2KBVU1IOnUODAuIkA1rMI7+JL8gkLycS6fAwq+UoF7GLjHfyGHdOm1zAj31E\nuOnBtNhZoxSJNh1vWz4ZqRazQcvwand55DQlRsj4tObhmPDUCa1+6RpyUAHFxnREs1oekuA2jG3k\ngKnFEoklyXyYQF0tX7loaQ9d8WdrzhJu8l5F82FM1WWRaNP3NuWTCKCrVYeSUjFWBz+0SZwCActr\nQK1MOjk4gPj7cgWsE8eVz6pqNVZogsVKhmzTUl66ysyZZUu4qXcegDFVl3eycvRJS/1pKikD3oZ8\nkmOoatWipNScxTEQ2iQeCmgyZwz13gogWZl0cnAcnrkC1o3jymdVtQLKRUt76Io/HeGm2DG6AIyp\nutzbwxUB1Xp6qP60lJQB7wkIEwe5+FNVq+1rVamyklJzFsdAaJN4IKDFnDFUtQJIViadHEAVZihg\n3TiufBbVuqUHj7uP9YUQENnpYPookak99MSfrDfMhZtwUM2HGUuqP20lpe89m1kKU1WtHbgOO1rV\n6kpKZpzrSf3QJvFAQJs5sPR9y0cyM+kqYJFoI5FuHFc+2+zShX14+MpFU3voiT9RLUO4CX/VfBhT\ndVkg2gyQ2GEoTB9aWvrM0tJPEakWJaWmLI9p4qGApjg2rQE1M+kKV1EtI5FuHK6WmcDxBfGvxJu+\nBNLUHg7fW1r8aQs3hxsPwJiqywLRZsDbkE9yEPe9tRol5ZA0DwKhTeLDn3kjYMsQxzKEem8FkMxM\nugpYXAkNBawbh6+EJg913xr3JZCW8nIJbKYM8Sc/ZRjCTWbLbdyHMVWXN7ByFPetZ6SymkFMJWXA\n25BPAl5XC5d3T6taWUnJeMM2niYeCmgyZxxVrQCSlUknB/yUkSfSjcNPGWYCdbV85aKlvNzliD9b\nmy3hJkKKtjolZcDbkE9yAP1MGNCqVlZSSsaqD4Q25aIh6WZ5DaiVyRt70Ibgx1X9xO4HgVwB68Zh\nka3JQ1UroFy0lJeu+HNygWjb1T2Eai+i0y0Ek1Z/mkrKgLcpn0QQVa2QVrWyklJzFsdAaEsuGpBu\nmswZQz8TBgSwpobVEa7yx18jkU4cVz6rqiUoG51QLqaUlzu1cVC6qBcFzG6exdWftpJSe/JRePNg\n6KyrxSfNxmyauK5WUVKa/t64gDiJ7dvM9TOhg1WQyeEeExrQPIGRagnl4liPI7c63LstLdzU1tWV\nlNqTj7588qvmsjE+HSWl4e4PC4iT2P61wu+g8k5pQOOZHO4xoQE9yhFEGSLVErq7luBxu2JjH2b6\nct4YyGOkfwrnM14LoggQsdwYwMZr7M0t6CyXZM9Agm1jIE84PQOJ9WIo5ZkmLrWEGds2BuhSrSC2\n3mNjEASxecSqtQe+rvbQhGuuyJlIuLlgjxmmw6c0KR4PmwDp8DQMw97cgs5ySfYMJNiGccTf9FK7\nMbHkOE2cipgbgAWZ1HtMMO8wmshBrFryLgCriAZSq0PFu5TRwk3DRFDEFZk9wzDKO+JsRtRAYRyt\nw4zvxsQS4wLievsx5gaeRopkUi8XMJc5iFXLCLc+XDMZWK/WmilFCSLr1SqRpDVjsl6tNVOKEkTW\nq1UiSWvGpFK1WIpYTo25qv1dxN7NqJRTKC/jeslVhT5tZ6nSjJOuJ3WF1drYyXfAnw1KqTFzl5Ij\nUw8pP8q1IsJK1HElqZcsGbFmM/mxKU66ntQVVssRMpZTY1ZOha8JxcZpEMRp95J6yaDPGT/JIk75\n+5KBGLkd1mtIXWG1jLBjGX7TaqkxjcX6hlsF1Hb0cuQi89m4XtK1PjtzTg1alHRNqatSram+q8YU\nFOvuDgvAqJSTlZfTxcLTulml8Tg1aFHSNaWusFqOkNFWYwqKdXSGHnISfzpDy/Bqd3nkNF5P6CUd\n67M0NfSlQdK8XkPqktXyJZGOGrOWXDh6SBaWUuJLMWPC01q4lAVx1bAH2NEgHVBx1pG6VLUaK+RK\nQh01ZtnNJe3u9DWhqS/FZDVHrpdMIp+5RVcNe5xD5d/kGVJx1pG6VLUCQsYJW41ZSzr2eprQpJQz\nIjythUppEFcNC22SSbrtyFNZu1RH6gLVSkkiZ201ZundpQwD3wia+lLMmPA0FaLutaFiz/gqVFN/\nugNXc1OeyrrAOlIXqFa+NV8Saaoxc7vVjQKa0NSXYsaEp6sjUc3bU8OiGniKGH6TZ0jFWUfqUtVq\n+pJQR41ZbY8R64AmNPWlmBHhaQT8zJwevre0GpavhAbp4XtLqUUjX5VamVyqWuO+JNJRY1YOF3Jw\n9JD8FJGScvJ6rpcMAZ6Fc0uOGpafMgzSuG9Z8lRWcdaRumS1fEmoo8asJS832npIFpampJwR4Wkt\nVEqD7HLUsCziNEiHVJx1pC5VrYAk0lFjlt5dytDRQ04u4A6d+FJMXt92dQ+I7cUU7Bldc9Ww/OnX\nJB1QcdaRulS13P0OlYpDNaZrUct8J1CauNxFpJxSeRlf5pWz3kRqEqRrSl2Vag2Viq3OmUxHgZRT\nKi+ZwMEzyaIatkiN1CUFWdWUuirVGur6CtWY1bbqWM/001JOXufWGKBbK43lfi0m0xig8xuvc1td\n6ipVS/7JrYQaUzI7zb65kpZy8jo3XTU5+x/3nJox5hBhVU/qKlVLXpgjMsb60lUg5dTKy6P1RVw9\nkkpNVA1aT+oqVWv1m1pHWFUGuFrr/5f4qlJ41pzF/yW+fX7+/Wct4nqg08/Akfn5zn8BWl1wGCkH\nlOIAAAAASUVORK5CYII=\n", + "text/latex": [ + "$$\\left[\\begin{matrix}\\cos{\\left (\\psi \\right )} \\cos{\\left (\\theta \\right )} & \\sin{\\left (\\phi \\right )} \\sin{\\left (\\theta \\right )} \\cos{\\left (\\psi \\right )} - \\sin{\\left (\\psi \\right )} \\cos{\\left (\\phi \\right )} & \\sin{\\left (\\phi \\right )} \\sin{\\left (\\psi \\right )} + \\sin{\\left (\\theta \\right )} \\cos{\\left (\\phi \\right )} \\cos{\\left (\\psi \\right )}\\\\\\sin{\\left (\\psi \\right )} \\cos{\\left (\\theta \\right )} & \\sin{\\left (\\phi \\right )} \\sin{\\left (\\psi \\right )} \\sin{\\left (\\theta \\right )} + \\cos{\\left (\\phi \\right )} \\cos{\\left (\\psi \\right )} & - \\sin{\\left (\\phi \\right )} \\cos{\\left (\\psi \\right )} + \\sin{\\left (\\psi \\right )} \\sin{\\left (\\theta \\right )} \\cos{\\left (\\phi \\right )}\\\\- \\sin{\\left (\\theta \\right )} & \\sin{\\left (\\phi \\right )} \\cos{\\left (\\theta \\right )} & \\cos{\\left (\\phi \\right )} \\cos{\\left (\\theta \\right )}\\end{matrix}\\right]$$" + ], + "text/plain": [ + "⎡cos(ψ)⋅cos(θ) sin(φ)⋅sin(θ)⋅cos(ψ) - sin(ψ)⋅cos(φ) sin(φ)⋅sin(ψ) + sin(θ)⋅c\n", + "⎢ \n", + "⎢sin(ψ)⋅cos(θ) sin(φ)⋅sin(ψ)⋅sin(θ) + cos(φ)⋅cos(ψ) -sin(φ)⋅cos(ψ) + sin(ψ)⋅\n", + "⎢ \n", + "⎣ -sin(θ) sin(φ)⋅cos(θ) cos(φ)⋅cos(θ\n", + "\n", + "os(φ)⋅cos(ψ) ⎤\n", + " ⎥\n", + "sin(θ)⋅cos(φ)⎥\n", + " ⎥\n", + ") ⎦" + ] + }, + "execution_count": 18, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "phi, theta, psi = symbols('phi, theta, psi')\n", + "sub_eulers = {\n", + " th1: psi, th2: theta, th3: phi\n", + "}\n", + "dcm_321_euler = dcm_321.subs(sub_eulers)\n", + "dcm_321_euler" + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": { + "collapsed": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAOAAAABLCAMAAABeKHv+AAAAPFBMVEX///8AAAAAAAAAAAAAAAAA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\nRK5CYII=\n", + "text/latex": [ + "$$\\left[\\begin{matrix}0 & - \\sin{\\left (\\psi \\right )} & \\cos{\\left (\\psi \\right )}\\\\0 & \\cos{\\left (\\psi \\right )} & \\sin{\\left (\\psi \\right )}\\\\-1 & 0 & 0\\end{matrix}\\right]$$" + ], + "text/plain": [ + "⎡0 -sin(ψ) cos(ψ)⎤\n", + "⎢ ⎥\n", + "⎢0 cos(ψ) sin(ψ)⎥\n", + "⎢ ⎥\n", + "⎣-1 0 0 ⎦" + ] + }, + "execution_count": 38, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "dcm_pitch_up = dcm_321_euler.subs({theta:pi/2, phi:0})\n", + "dcm_pitch_up" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": { + "collapsed": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAMUAAAAVBAMAAAAEKDfsAAAAMFBMVEX///8AAAAAAAAAAAAAAAAA\nAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAv3aB7AAAAD3RSTlMAZnaJVN0imavvMkQQ\nzbsZbzSbAAAACXBIWXMAAA7EAAAOxAGVKw4bAAADfUlEQVRIDcVVS4gUVxQ91VVdM139mWYWGvLB\n0iEhi4ilJo6QQJqQ4CLgNCi69AlukoUZxi9Z6JAsEtzYQYkhcdGKgQwmTEMSQTdT6MIPiE0yiwTF\ntLNQAjFOxC8K47n31fQ4XW22Xrivzjv3njrvUz0DPO84klpAUBYqAJx6qjZLWBXrL5KR/L/wW1od\nC+eatip0Oe6bI+ejRBUBvXWbtp6f35bMirGCcbbPxhUF4lGcpTqfiUpEzSS15Wxno84HUmzG2m1m\nIYGpFliVX2ZFYPslC9OtZL5OsTmj1AKOhVqqagmrcgxn55OUgndfxs7IVy3zcb1d+dUi3c1km50H\nEpUrZLFis38gxAt3v6xAwE+Hjr4eSlXCHQaOvrfUvzUa/Pnpks+EGuT6B0NEGdoTa5xd+SYKKwYa\n0ktCVGdG4OJVizn3NmA3sJF7UXA19O9RfiNmd6mMQgtZlEZRnMInhtQ16rxpv5J5DLzCOcM/iDHz\nvcGU9qoK0RC2YFkMp8mPvAnvW0zE6qHgb+A/uKaXRWQryB/mguhRqqGvTGo9sKWn6sSoAR9wzig2\nMVRfB4wfl15V+ZUdeBk5rrtqMxjYa8QDCm4Ct5E1ATeDXAPYNGXUo4m+kNR3QJyL+KphvpRzxiXC\n4A7QF0mvqgo4gAg95Kc1C1fNeF08LPhXPHIN/5Htxpm/7qtHq+2BCeOiELY9Jgg9tve1pNeuLH+P\nHqfbHsUqxn+MNyK0QD0o4nnLWfkGixpyVokHzwpv8azdGEi+sfY+dkqvquBW/QreAeQbY16KMHS8\n/gciCxKPbMiX8c69CL3lpzx459jDs/6Qz+TOeR+oHAImfpFeVaGn5cQe/ZI7z7Xw7pF4ByILEo9B\nvgPuKLzDKBluYnYfq0mfROhQj128C77f/wquGavjd+1VFfK1DF5iS8+wpv/FktO/ofdzo+CHmX1r\nH47CYU13mV+++O1g/4ML+x8cu/UNKTkfb/u116R8meciR3puZBX8basb0sup/gbXrO03xEWuRbJb\n/IxTQm9I1bKGVFAR3q9xOCGoI1R1TMmPOEp2iWDy/X+EXpiq6QYzsfBuyKEsqCNU9YaSKzhKdonc\nzMy00CWTKl4no3+KcJGo0M1DVZEoC02bgp8VfitV2Uomo6y4Oak6CVWFUhG3LuuU0lxsnoMJ0n8L\ngh2TMOlHW7WANeYTnXDuNRzecvUAAAAASUVORK5CYII=\n", + "text/latex": [ + "$$\\operatorname{atan_{2}}{\\left (\\sin{\\left (\\psi \\right )},\\cos{\\left (\\psi \\right )} \\right )}$$" + ], + "text/plain": [ + "atan2(sin(ψ), cos(ψ))" + ] + }, + "execution_count": 39, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "atan2(dcm_pitch_up[1,2], dcm_pitch_up[0,2])" + ] + }, + { + "cell_type": "code", + "execution_count": 40, + "metadata": { + "collapsed": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAOAAAABLCAMAAABeKHv+AAAAPFBMVEX///8AAAAAAAAAAAAAAAAA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\nRK5CYII=\n", + "text/latex": [ + "$$\\left[\\begin{matrix}0 & - \\sin{\\left (\\psi \\right )} & \\cos{\\left (\\psi \\right )}\\\\0 & \\cos{\\left (\\psi \\right )} & \\sin{\\left (\\psi \\right )}\\\\-1 & 0 & 0\\end{matrix}\\right]$$" + ], + "text/plain": [ + "⎡0 -sin(ψ) cos(ψ)⎤\n", + "⎢ ⎥\n", + "⎢0 cos(ψ) sin(ψ)⎥\n", + "⎢ ⎥\n", + "⎣-1 0 0 ⎦" + ] + }, + "execution_count": 40, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "dcm_pitch_down = dcm_321_euler.subs({theta:pi/2, phi:0})\n", + "dcm_pitch_down" + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": { + "collapsed": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAMUAAAAVBAMAAAAEKDfsAAAAMFBMVEX///8AAAAAAAAAAAAAAAAA\nAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAv3aB7AAAAD3RSTlMAZnaJVN0imavvMkQQ\nzbsZbzSbAAAACXBIWXMAAA7EAAAOxAGVKw4bAAADfUlEQVRIDcVVS4gUVxQ91VVdM139mWYWGvLB\n0iEhi4ilJo6QQJqQ4CLgNCi69AlukoUZxi9Z6JAsEtzYQYkhcdGKgQwmTEMSQTdT6MIPiE0yiwTF\ntLNQAjFOxC8K47n31fQ4XW22Xrivzjv3njrvUz0DPO84klpAUBYqAJx6qjZLWBXrL5KR/L/wW1od\nC+eatip0Oe6bI+ejRBUBvXWbtp6f35bMirGCcbbPxhUF4lGcpTqfiUpEzSS15Wxno84HUmzG2m1m\nIYGpFliVX2ZFYPslC9OtZL5OsTmj1AKOhVqqagmrcgxn55OUgndfxs7IVy3zcb1d+dUi3c1km50H\nEpUrZLFis38gxAt3v6xAwE+Hjr4eSlXCHQaOvrfUvzUa/Pnpks+EGuT6B0NEGdoTa5xd+SYKKwYa\n0ktCVGdG4OJVizn3NmA3sJF7UXA19O9RfiNmd6mMQgtZlEZRnMInhtQ16rxpv5J5DLzCOcM/iDHz\nvcGU9qoK0RC2YFkMp8mPvAnvW0zE6qHgb+A/uKaXRWQryB/mguhRqqGvTGo9sKWn6sSoAR9wzig2\nMVRfB4wfl15V+ZUdeBk5rrtqMxjYa8QDCm4Ct5E1ATeDXAPYNGXUo4m+kNR3QJyL+KphvpRzxiXC\n4A7QF0mvqgo4gAg95Kc1C1fNeF08LPhXPHIN/5Htxpm/7qtHq+2BCeOiELY9Jgg9tve1pNeuLH+P\nHqfbHsUqxn+MNyK0QD0o4nnLWfkGixpyVokHzwpv8azdGEi+sfY+dkqvquBW/QreAeQbY16KMHS8\n/gciCxKPbMiX8c69CL3lpzx459jDs/6Qz+TOeR+oHAImfpFeVaGn5cQe/ZI7z7Xw7pF4ByILEo9B\nvgPuKLzDKBluYnYfq0mfROhQj128C77f/wquGavjd+1VFfK1DF5iS8+wpv/FktO/ofdzo+CHmX1r\nH47CYU13mV+++O1g/4ML+x8cu/UNKTkfb/u116R8meciR3puZBX8basb0sup/gbXrO03xEWuRbJb\n/IxTQm9I1bKGVFAR3q9xOCGoI1R1TMmPOEp2iWDy/X+EXpiq6QYzsfBuyKEsqCNU9YaSKzhKdonc\nzMy00CWTKl4no3+KcJGo0M1DVZEoC02bgp8VfitV2Uomo6y4Oak6CVWFUhG3LuuU0lxsnoMJ0n8L\ngh2TMOlHW7WANeYTnXDuNRzecvUAAAAASUVORK5CYII=\n", + "text/latex": [ + "$$\\operatorname{atan_{2}}{\\left (\\sin{\\left (\\psi \\right )},\\cos{\\left (\\psi \\right )} \\right )}$$" + ], + "text/plain": [ + "atan2(sin(ψ), cos(ψ))" + ] + }, + "execution_count": 41, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "dcm_pitch_down = dcm_321_euler.subs({theta:-pi/2, phi:0})\n", + "atan2(-dcm_pitch_down[1,2], -dcm_pitch_down[0,2])" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 2", + "language": "python", + "name": "python2" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.6" + } + }, + "nbformat": 4, + "nbformat_minor": 0 +} diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index d23ba6b153..89a188eab4 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -52,11 +52,11 @@ public: if (fabs(theta() - (Type)M_PI_2) < 1.0e-3) { phi() = (Type)0.0; - psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) + theta(); - + psi() = (Type)atan2(dcm(0,1), dcm(1,1)); + psi() = (Type)atan2(dcm(1,2), dcm(0,2)); } else if ((Type)fabs(theta() + (Type)M_PI_2) < (Type)1.0e-3) { phi() = (Type)0.0; - psi() = (Type)atan2(dcm(1,2) - dcm(0,1), dcm(0,2) + dcm(1,1)) - theta(); + psi() = (Type)atan2(-dcm(1,2), -dcm(0,2)); } else { phi() = (Type)atan2(dcm(2,1), dcm(2,2)); diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 7351b3ae7c..28c55533de 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -33,6 +33,4 @@ if (${CMAKE_BUILD_TYPE} STREQUAL "Profile") WORKING_DIRECTORY ${CMAKE_BUILD_DIR} DEPENDS test_build ) -endif() - - +endif() \ No newline at end of file diff --git a/test/attitude.cpp b/test/attitude.cpp index 1d008d2b28..f6584aa1b5 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -96,15 +96,16 @@ int main() // euler gimbal lock check // note if theta = pi/2, then roll is set to zero float pi_2 = float(M_PI_2); - Eulerf euler_gimbal_lock(0.1f, pi_2, 0.2f); + Eulerf euler_gimbal_lock(0.0f, pi_2, 0.2f); Dcmf dcm_lock(euler_gimbal_lock); Eulerf euler_gimbal_lock_out(dcm_lock); + printf("gimbal lock test"); euler_gimbal_lock_out.T().print(); euler_gimbal_lock.T().print(); - assert(euler_gimbal_lock == euler_gimbal_lock_out); + //assert(euler_gimbal_lock == euler_gimbal_lock_out); // note if theta = pi/2, then roll is set to zero - Eulerf euler_gimbal_lock2(0.1f, -pi_2, 0.2f); + Eulerf euler_gimbal_lock2(0.0f, -pi_2, 0.2f); Dcmf dcm_lock2(euler_gimbal_lock2); Eulerf euler_gimbal_lock_out2(dcm_lock2); euler_gimbal_lock_out2.T().print(); From 48a3288753a3ec0bbd5e1f826ea413e1a6854fbb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 18 Jan 2016 13:39:46 -0800 Subject: [PATCH 116/388] Fix QuRT build --- matrix/helper_functions.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 96d2b82751..d39b672d75 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -4,7 +4,7 @@ // grody hack - this should go once C++11 is supported // on all platforms. -#ifdef __PX4_NUTTX +#if defined (__PX4_NUTTX) || defined (__PX4_QURT) #include #else #include @@ -16,7 +16,7 @@ namespace matrix template Type wrap_pi(Type x) { -#ifdef __PX4_NUTTX +#if defined (__PX4_NUTTX) || defined (__PX4_QURT) if (!isfinite(x)) { #else if (!std::isfinite(x)) { From 306f0ac25d534118205e6f7fafb592f4634cbb95 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Thu, 21 Jan 2016 12:45:07 -0800 Subject: [PATCH 117/388] Added dspal_math.h for missing constants Signed-off-by: Mark Charlebois --- matrix/math.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/matrix/math.hpp b/matrix/math.hpp index da1d73d992..ef5facc74d 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -1,5 +1,8 @@ #pragma once +#ifdef __PX4_QURT +#include "dspal_math.h" +#endif #include "Matrix.hpp" #include "SquareMatrix.hpp" #include "Vector.hpp" From 38211e1aff3de42636c8dc2b7c3bcf0098bf9616 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 12:00:34 +1100 Subject: [PATCH 118/388] Fix testing mechanism. --- matrix/Matrix.hpp | 49 ++++++++++++--- test/attitude.cpp | 126 +++++++++++++++++--------------------- test/filter.cpp | 8 +-- test/helper.cpp | 8 +-- test/integration.cpp | 6 +- test/inverse.cpp | 8 +-- test/matrixAssignment.cpp | 30 ++++----- test/matrixMult.cpp | 12 ++-- test/matrixScalarMult.cpp | 6 +- test/setIdentity.cpp | 7 +-- test/squareMatrix.cpp | 8 +-- test/test_macros.hpp | 12 ++++ test/transpose.cpp | 6 +- test/vector.cpp | 8 +-- test/vector2.cpp | 21 ++++--- test/vector3.cpp | 10 +-- test/vectorAssignment.cpp | 27 ++++---- 17 files changed, 179 insertions(+), 173 deletions(-) create mode 100644 test/test_macros.hpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 9461fb2619..560bb4ddd3 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -13,6 +13,8 @@ #include #include #include +#include +#include #if defined(SUPPORT_STDIOSTREAM) #include #include @@ -264,20 +266,37 @@ public: * Misc. Functions */ - void print() const + void write_string(char * buf, size_t n) const { const Matrix &self = *this; - printf("\n"); - + char data_buf[500] = {0}; for (size_t i = 0; i < M; i++) { - printf("["); - + char data_line[100] = {0}; + char data_line_formatted[100] = {0}; for (size_t j = 0; j < N; j++) { - printf("%10g\t", double(self(i, j))); + char val_buf[15]; + if (j == N-1) { + snprintf(val_buf, 15, "\t%10g", double(self(i, j))); + } else { + snprintf(val_buf, 15, "\t%10g,", double(self(i, j))); + } + strncat(data_line, val_buf, 300); } - - printf("]\n"); + if (i == M-1) { + snprintf(data_line_formatted, n, "[%s]", data_line); + } else { + snprintf(data_line_formatted, n, "[%s],\n", data_line); + } + strncat(data_buf, data_line_formatted, n); } + snprintf(buf, n, "[%s]", data_buf); + } + + void print() const + { + char buf[200]; + write_string(buf, 200); + printf("%s\n", buf); } Matrix transpose() const @@ -294,7 +313,6 @@ public: return res; } - // tranpose alias inline Matrix T() const { @@ -423,6 +441,19 @@ Matrix operator*(Type scalar, const Matrix &other) return other * scalar; } +template +bool isEqual(const Matrix &x, + const Matrix & y) { + if (!(x == y)) { + char buf_x[100]; + char buf_y[100]; + x.write_string(buf_x, 100); + y.write_string(buf_y, 100); + printf("not equal\nx:\n%s\ny:\n%s\n", buf_x, buf_y); + } + return x == y; +} + #if defined(SUPPORT_STDIOSTREAM) template std::ostream& operator<<(std::ostream& os, diff --git a/test/attitude.cpp b/test/attitude.cpp index 1d008d2b28..0798cae27c 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -1,7 +1,8 @@ -#include #include +#include #include +#include "test_macros.hpp" using namespace matrix; @@ -24,14 +25,13 @@ int main() Dcmf dcm_check(dcm_data); // euler ctor - euler_check.T().print(); - assert(euler_check == Vector3f(0.1f, 0.2f, 0.3f)); + TEST(isEqual(euler_check, Vector3f(0.1f, 0.2f, 0.3f))); // euler default ctor Eulerf e; Eulerf e_zero = zeros(); - assert(e == e_zero); - assert(e == e); + TEST(isEqual(e, e_zero)); + TEST(isEqual(e, e)); // euler vector ctor Vector v; @@ -39,99 +39,87 @@ int main() v(1) = 0.2f; v(2) = 0.3f; Eulerf euler_copy(v); - assert(euler_copy == euler_check); + TEST(isEqual(euler_copy, euler_check)); // quaternion ctor Quatf q(1, 2, 3, 4); - assert(fabs(q(0) - 1) < eps); - assert(fabs(q(1) - 2) < eps); - assert(fabs(q(2) - 3) < eps); - assert(fabs(q(3) - 4) < eps); + TEST(fabs(q(0) - 1) < eps); + TEST(fabs(q(1) - 2) < eps); + TEST(fabs(q(2) - 3) < eps); + TEST(fabs(q(3) - 4) < eps); // quat normalization - q.T().print(); q.normalize(); - q.T().print(); - assert(q == Quatf(0.18257419f, 0.36514837f, - 0.54772256f, 0.73029674f)); + TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, + 0.54772256f, 0.73029674f))); // quat default ctor q = Quatf(); - assert(q == Quatf(1, 0, 0, 0)); + TEST(isEqual(q, Quatf(1, 0, 0, 0))); // euler to quaternion q = Quatf(euler_check); - q.T().print(); - assert(q == q_check); + TEST(isEqual(q, q_check)); // euler to dcm Dcmf dcm(euler_check); - dcm.print(); - assert(dcm == dcm_check); + TEST(isEqual(dcm, dcm_check)); // quaternion to euler Eulerf e1(q_check); - assert(e1 == euler_check); + TEST(isEqual(e1, euler_check)); // quaternion to dcm Dcmf dcm1(q_check); - dcm1.print(); - assert(dcm1 == dcm_check); + TEST(isEqual(dcm1, dcm_check)); // dcm default ctor Dcmf dcm2; - dcm2.print(); SquareMatrix I = eye(); - assert(dcm2 == I); + TEST(isEqual(dcm2, I)); // dcm to euler Eulerf e2(dcm_check); - assert(e2 == euler_check); + TEST(isEqual(e2, euler_check)); // dcm to quaterion Quatf q2(dcm_check); - assert(q2 == q_check); + TEST(isEqual(q2, q_check)); // euler gimbal lock check // note if theta = pi/2, then roll is set to zero float pi_2 = float(M_PI_2); - Eulerf euler_gimbal_lock(0.1f, pi_2, 0.2f); + Eulerf euler_gimbal_lock(0.0f, pi_2, 0.2f); Dcmf dcm_lock(euler_gimbal_lock); Eulerf euler_gimbal_lock_out(dcm_lock); - euler_gimbal_lock_out.T().print(); - euler_gimbal_lock.T().print(); - assert(euler_gimbal_lock == euler_gimbal_lock_out); + TEST(isEqual(euler_gimbal_lock, euler_gimbal_lock_out)); // note if theta = pi/2, then roll is set to zero - Eulerf euler_gimbal_lock2(0.1f, -pi_2, 0.2f); + Eulerf euler_gimbal_lock2(0.0f, -pi_2, 0.2f); Dcmf dcm_lock2(euler_gimbal_lock2); Eulerf euler_gimbal_lock_out2(dcm_lock2); - euler_gimbal_lock_out2.T().print(); - euler_gimbal_lock2.T().print(); - assert(euler_gimbal_lock2 == euler_gimbal_lock_out2); + TEST(isEqual(euler_gimbal_lock2, euler_gimbal_lock_out2)); // quaterion copy ctors float data_v4[] = {1, 2, 3, 4}; Vector v4(data_v4); Quatf q_from_v(v4); - assert(q_from_v == v4); + TEST(isEqual(q_from_v, v4)); Matrix m4(data_v4); Quatf q_from_m(m4); - assert(q_from_m == m4); + TEST(isEqual(q_from_m, m4)); // quaternion derivate Vector q_dot = q.derivative(Vector3f(1, 2, 3)); - printf("q_dot:\n"); - q_dot.T().print(); // quaternion product Quatf q_prod_check( 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); - assert(q_prod_check == q_check*q_check); + TEST(isEqual(q_prod_check, q_check*q_check)); q_check *= q_check; - assert(q_prod_check == q_check); + TEST(isEqual(q_prod_check, q_check)); // Quaternion scalar multiplication float scalar = 0.5; @@ -139,26 +127,26 @@ int main() Quatf q_scalar_mul_check(1.0f * scalar, 2.0f * scalar, 3.0f * scalar, 4.0f * scalar); Quatf q_scalar_mul_res = scalar * q_scalar_mul; - assert(q_scalar_mul_check == q_scalar_mul_res); + TEST(isEqual(q_scalar_mul_check, q_scalar_mul_res)); Quatf q_scalar_mul_res2 = q_scalar_mul * scalar; - assert(q_scalar_mul_check == q_scalar_mul_res2); + TEST(isEqual(q_scalar_mul_check, q_scalar_mul_res2)); Quatf q_scalar_mul_res3(q_scalar_mul); q_scalar_mul_res3 *= scalar; - assert(q_scalar_mul_check == q_scalar_mul_res3); + TEST(isEqual(q_scalar_mul_check, q_scalar_mul_res3)); // quaternion inverse q = q_check.inversed(); - assert(fabsf(q_check(0) - q(0)) < eps); - assert(fabsf(q_check(1) + q(1)) < eps); - assert(fabsf(q_check(2) + q(2)) < eps); - assert(fabsf(q_check(3) + q(3)) < eps); + TEST(fabsf(q_check(0) - q(0)) < eps); + TEST(fabsf(q_check(1) + q(1)) < eps); + TEST(fabsf(q_check(2) + q(2)) < eps); + TEST(fabsf(q_check(3) + q(3)) < eps); q = q_check; q.invert(); - assert(fabsf(q_check(0) - q(0)) < eps); - assert(fabsf(q_check(1) + q(1)) < eps); - assert(fabsf(q_check(2) + q(2)) < eps); - assert(fabsf(q_check(3) + q(3)) < eps); + TEST(fabsf(q_check(0) - q(0)) < eps); + TEST(fabsf(q_check(1) + q(1)) < eps); + TEST(fabsf(q_check(2) + q(2)) < eps); + TEST(fabsf(q_check(3) + q(3)) < eps); // rotate quaternion (nonzero rotation) Quatf qI(1.0f, 0.0f, 0.0f, 0.0f); @@ -167,10 +155,10 @@ int main() rot(1) = rot(2) = 0.0f; qI.rotate(rot); Quatf q_true(cosf(1.0f / 2), sinf(1.0f / 2), 0.0f, 0.0f); - assert(fabsf(qI(0) - q_true(0)) < eps); - assert(fabsf(qI(1) - q_true(1)) < eps); - assert(fabsf(qI(2) - q_true(2)) < eps); - assert(fabsf(qI(3) - q_true(3)) < eps); + TEST(fabsf(qI(0) - q_true(0)) < eps); + TEST(fabsf(qI(1) - q_true(1)) < eps); + TEST(fabsf(qI(2) - q_true(2)) < eps); + TEST(fabsf(qI(3) - q_true(3)) < eps); // rotate quaternion (zero rotation) qI = Quatf(1.0f, 0.0f, 0.0f, 0.0f); @@ -178,33 +166,33 @@ int main() rot(1) = rot(2) = 0.0f; qI.rotate(rot); q_true = Quatf(cosf(0.0f), sinf(0.0f), 0.0f, 0.0f); - assert(fabsf(qI(0) - q_true(0)) < eps); - assert(fabsf(qI(1) - q_true(1)) < eps); - assert(fabsf(qI(2) - q_true(2)) < eps); - assert(fabsf(qI(3) - q_true(3)) < eps); + TEST(fabsf(qI(0) - q_true(0)) < eps); + TEST(fabsf(qI(1) - q_true(1)) < eps); + TEST(fabsf(qI(2) - q_true(2)) < eps); + TEST(fabsf(qI(3) - q_true(3)) < eps); // get rotation axis from quaternion (nonzero rotation) q = Quatf(cosf(1.0f / 2), 0.0f, sinf(1.0f / 2), 0.0f); rot = q.to_axis_angle(); - assert(fabsf(rot(0)) < eps); - assert(fabsf(rot(1) -1.0f) < eps); - assert(fabsf(rot(2)) < eps); + TEST(fabsf(rot(0)) < eps); + TEST(fabsf(rot(1) -1.0f) < eps); + TEST(fabsf(rot(2)) < eps); // get rotation axis from quaternion (zero rotation) q = Quatf(1.0f, 0.0f, 0.0f, 0.0f); rot = q.to_axis_angle(); - assert(fabsf(rot(0)) < eps); - assert(fabsf(rot(1)) < eps); - assert(fabsf(rot(2)) < eps); + TEST(fabsf(rot(0)) < eps); + TEST(fabsf(rot(1)) < eps); + TEST(fabsf(rot(2)) < eps); // from axis angle (zero rotation) rot(0) = rot(1) = rot(2) = 0.0f; q.from_axis_angle(rot, 0.0f); q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f); - assert(fabsf(q(0) - q_true(0)) < eps); - assert(fabsf(q(1) - q_true(1)) < eps); - assert(fabsf(q(2) - q_true(2)) < eps); - assert(fabsf(q(3) - q_true(3)) < eps); + TEST(fabsf(q(0) - q_true(0)) < eps); + TEST(fabsf(q(1) - q_true(1)) < eps); + TEST(fabsf(q(2) - q_true(2)) < eps); + TEST(fabsf(q(3) - q_true(3)) < eps); }; diff --git a/test/filter.cpp b/test/filter.cpp index f8eb01f748..368b788f7b 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -21,13 +21,9 @@ int main() float beta = 0; kalman_correct(P, C, R, r, dx, dP, beta); - dx.T().print(); - printf("beta: %g\n", beta); - float data_check[] = {0.5,1,1.5,2,2.5,0}; Vector dx_check(data_check); - assert(dx == dx_check); - + TEST(isEqual(dx, dx_check)); return 0; } diff --git a/test/helper.cpp b/test/helper.cpp index 68bdced00b..adb27678d7 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -1,16 +1,16 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; int main() { - assert(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5); - assert(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); - assert(fabs(wrap_pi(3.0) - (3.0)) < 1e-3); + TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5); + TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); + TEST(fabs(wrap_pi(3.0) - (3.0)) < 1e-3); wrap_pi(NAN); return 0; } diff --git a/test/integration.cpp b/test/integration.cpp index f33dc866cf..ebc456adb0 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -17,10 +17,8 @@ int main() Vector u = ones(); float t = 1; float h = 0.1f; - y.T().print(); integrate_rk4(f, y, u, t, h, y); - y.T().print(); - assert(y == (ones()*1.1f)); + TEST(isEqual(y, (ones()*1.1f))); return 0; } diff --git a/test/inverse.cpp b/test/inverse.cpp index 743d877a9f..f8af641aea 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -25,9 +25,7 @@ int main() SquareMatrix A(data); SquareMatrix A_I = inv(A); SquareMatrix A_I_check(data_check); - A_I.print(); - A_I_check.print(); - assert((A_I - A_I_check).abs().max() < 1e-5); + TEST((A_I - A_I_check).abs().max() < 1e-5); // stess test SquareMatrix A_large; @@ -37,7 +35,7 @@ int main() for (size_t i = 0; i < n_large; i++) { A_large_I = inv(A_large); - assert(A_large == A_large_I); + TEST(isEqual(A_large, A_large_I)); } SquareMatrix zero_test = zeros(); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index cc1ad6945a..21557541af 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -1,6 +1,5 @@ -#include - #include +#include "test_macros.hpp" using namespace matrix; @@ -20,36 +19,33 @@ int main() m(2, 1) = 8; m(2, 2) = 9; - m.print(); - float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; Matrix3f m2(data); - m2.print(); for(int i=0; i<9; i++) { - assert(fabs(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); } float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; Matrix3f m3(data_times_2); - assert(m == m2); - assert(!(m == m3)); + TEST(isEqual(m, m2)); + TEST(!(m == m3)); m2 *= 2; - assert(m2 == m3); + TEST(m2 == m3); m2 /= 2; m2 -= 1; float data_minus_1[9] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; - assert(Matrix3f(data_minus_1) == m2); + TEST(Matrix3f(data_minus_1) == m2); m2 += 1; - assert(Matrix3f(data) == m2); + TEST(Matrix3f(data) == m2); m3 -= m2; - assert(m3 == m2); + TEST(m3 == m2); float data_row_02_swap[9] = { 7, 8, 9, @@ -65,18 +61,18 @@ int main() Matrix3f m4(data); - assert(-m4 == m4*(-1)); + TEST(-m4 == m4*(-1)); m4.swapCols(0, 2); - assert(m4 == Matrix3f(data_col_02_swap)); + TEST(m4 == Matrix3f(data_col_02_swap)); m4.swapCols(0, 2); m4.swapRows(0, 2); - assert(m4 == Matrix3f(data_row_02_swap)); - assert(fabs(m4.min() - 1) < 1e-5); + TEST(m4 == Matrix3f(data_row_02_swap)); + TEST(fabs(m4.min() - 1) < 1e-5); Scalar s; s = 1; - assert(fabs(s - 1) < 1e-5); + TEST(fabs(s - 1) < 1e-5); return 0; } diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 613d61db7d..f7b7eeefed 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -13,22 +13,18 @@ int main() Matrix3f A_I(data_check); Matrix3f I; I.setIdentity(); - A.print(); - A_I.print(); Matrix3f R = A * A_I; - R.print(); - assert(R == I); + TEST(isEqual(R, I)); Matrix3f R2 = A; R2 *= A_I; - R2.print(); - assert(R2 == I); + TEST(isEqual(R2, I)); Matrix3f A2 = eye()*2; Matrix3f B = A2.emult(A2); Matrix3f B_check = eye()*4; - assert(B == B_check); + TEST(isEqual(B, B_check)); return 0; } diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index e6bb8323a9..147459d42b 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -12,9 +12,7 @@ int main() A = A * 2; float data_check[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; Matrix3f A_check(data_check); - A.print(); - A_check.print(); - assert(A == A_check); + TEST(isEqual(A, A_check)); return 0; } diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index 68c2acf31b..a59b186a4d 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -1,6 +1,5 @@ -#include - #include +#include "test_macros.hpp" using namespace matrix; @@ -14,10 +13,10 @@ int main() for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { if (i == j) { - assert( fabs(A(i, j) - 1) < 1e-7); + TEST( fabs(A(i, j) - 1) < 1e-7); } else { - assert( fabs(A(i, j) - 0) < 1e-7); + TEST( fabs(A(i, j) - 0) < 1e-7); } } } diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index e2a56ed048..f8f1caac54 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -1,5 +1,5 @@ -#include #include +#include "test_macros.hpp" #include @@ -15,9 +15,8 @@ int main() }; SquareMatrix A(data); Vector3 diag_check(1, 5, 10); - A.diag().T().print(); - assert(A.diag() == diag_check); + TEST(isEqual(A.diag(), diag_check)); float data_check[9] = { 1.01158503f, 0.02190432f, 0.03238144f, @@ -25,11 +24,10 @@ int main() 0.07576783f, 0.08708946f, 1.10894048f }; - printf("expm(A*t)\n"); float dt = 0.01f; SquareMatrix eA = expm(SquareMatrix(A*dt), 5); SquareMatrix eA_check(data_check); - assert((eA - eA_check).abs().max() < 1e-3); + TEST((eA - eA_check).abs().max() < 1e-3); return 0; } diff --git a/test/test_macros.hpp b/test/test_macros.hpp new file mode 100644 index 0000000000..998264db82 --- /dev/null +++ b/test/test_macros.hpp @@ -0,0 +1,12 @@ +/** + * @file test_marcos.hpp + * + * Helps with cmake testing. + * + * @author James Goppert + */ +#pragma once + +#include + +#define TEST(X) if(!(X)) { fprintf(stderr, "test failed on %s:%d\n", __FILE__, __LINE__); return -1;} diff --git a/test/transpose.cpp b/test/transpose.cpp index f032862a4d..9da5e32d98 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -15,9 +15,7 @@ int main() Matrix A_T = A.transpose(); float data_check[6] = {1, 4, 2, 5, 3, 6}; Matrix A_T_check(data_check); - A_T.print(); - A_T_check.print(); - assert(A_T == A_T_check); + TEST(isEqual(A_T, A_T_check)); return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index 053e22dec8..e1f5ed3a72 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -12,12 +12,12 @@ int main() float data1[] = {1,2,3,4,5}; float data2[] = {6,7,8,9,10}; Vector v1(data1); - assert(fabs(v1.norm() - 7.416198487095663f) < 1e-5); + TEST(fabs(v1.norm() - 7.416198487095663f) < 1e-5); Vector v2(data2); - assert(fabs(v1.dot(v2) - 130.0f) < 1e-5); + TEST(fabs(v1.dot(v2) - 130.0f) < 1e-5); v2.normalize(); Vector v3(v2); - assert(v2 == v3); + TEST(v2 == v3); return 0; } diff --git a/test/vector2.cpp b/test/vector2.cpp index d9c63ed71f..a0625a7ee7 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -1,8 +1,9 @@ -#include #include #include +#include "test_macros.hpp" + using namespace matrix; template class Vector; @@ -11,24 +12,24 @@ int main() { Vector2f a(1, 0); Vector2f b(0, 1); - assert(fabs(a % b - 1.0f) < 1e-5); + TEST(fabs(a % b - 1.0f) < 1e-5); Vector2f c; - assert(fabs(c(0) - 0) < 1e-5); - assert(fabs(c(1) - 0) < 1e-5); + TEST(fabs(c(0) - 0) < 1e-5); + TEST(fabs(c(1) - 0) < 1e-5); Matrix d(a); - assert(fabs(d(0,0) - 1) < 1e-5); - assert(fabs(d(1,0) - 0) < 1e-5); + TEST(fabs(d(0,0) - 1) < 1e-5); + TEST(fabs(d(1,0) - 0) < 1e-5); Vector2f e(d); - assert(fabs(e(0) - 1) < 1e-5); - assert(fabs(e(1) - 0) < 1e-5); + TEST(fabs(e(0) - 1) < 1e-5); + TEST(fabs(e(1) - 0) < 1e-5); float data[] = {4,5}; Vector2f f(data); - assert(fabs(f(0) - 4) < 1e-5); - assert(fabs(f(1) - 5) < 1e-5); + TEST(fabs(f(0) - 4) < 1e-5); + TEST(fabs(f(1) - 5) < 1e-5); return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index ccf94c12a2..8b48641137 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -1,7 +1,7 @@ -#include #include #include +#include "test_macros.hpp" using namespace matrix; @@ -13,15 +13,15 @@ int main() Vector3f b(0, 1, 0); Vector3f c = a.cross(b); c.print(); - assert (c == Vector3f(0,0,1)); + TEST (c == Vector3f(0,0,1)); c = a % b; - assert (c == Vector3f(0,0,1)); + TEST (c == Vector3f(0,0,1)); Matrix d(c); Vector3f e(d); - assert (e == d); + TEST (e == d); float data[] = {4, 5, 6}; Vector3f f(data); - assert (f == Vector3f(4, 5, 6)); + TEST (f == Vector3f(4, 5, 6)); return 0; } diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 491ce818bd..215ba0a62b 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -1,7 +1,7 @@ -#include - #include +#include "test_macros.hpp" + using namespace matrix; template class Vector; @@ -13,26 +13,23 @@ int main() v(1) = 2; v(2) = 3; - v.print(); - static const float eps = 1e-7f; - assert(fabs(v(0) - 1) < eps); - assert(fabs(v(1) - 2) < eps); - assert(fabs(v(2) - 3) < eps); + TEST(fabs(v(0) - 1) < eps); + TEST(fabs(v(1) - 2) < eps); + TEST(fabs(v(2) - 3) < eps); Vector3f v2(4, 5, 6); - v2.print(); - - assert(fabs(v2(0) - 4) < eps); - assert(fabs(v2(1) - 5) < eps); - assert(fabs(v2(2) - 6) < eps); + TEST(fabs(v2(0) - 4) < eps); + TEST(fabs(v2(1) - 5) < eps); + TEST(fabs(v2(2) - 6) < eps); SquareMatrix m = diag(Vector3f(1,2,3)); - assert(fabs(m(0, 0) - 1) < eps); - assert(fabs(m(1, 1) - 2) < eps); - assert(fabs(m(2, 2) - 3) < eps); + TEST(fabs(m(0, 0) - 1) < eps); + TEST(fabs(m(1, 1) - 2) < eps); + TEST(fabs(m(2, 2) - 3) < eps); + return 0; } From d761bd372184659bf1afc34093cb3e2bfe00af4f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 23 Jan 2016 23:33:25 -0500 Subject: [PATCH 119/388] Fixed formatting. Made traivs more verbose. --- .travis.yml | 2 +- matrix/Matrix.hpp | 2 +- test/attitude.cpp | 2 +- test/helper.cpp | 6 ++++++ 4 files changed, 9 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index f4f8ba684d..758354c48e 100644 --- a/.travis.yml +++ b/.travis.yml @@ -6,7 +6,7 @@ script: - cmake -DCMAKE_BUILD_TYPE=Profile . - make - make check_format - - make test + - ctest -V after_success: - cpp-coveralls -i matrix env: diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 560bb4ddd3..3cc563ea5a 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -443,7 +443,7 @@ Matrix operator*(Type scalar, const Matrix &other) template bool isEqual(const Matrix &x, - const Matrix & y) { + const Matrix & y) { if (!(x == y)) { char buf_x[100]; char buf_y[100]; diff --git a/test/attitude.cpp b/test/attitude.cpp index 0798cae27c..86ce68e45c 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -51,7 +51,7 @@ int main() // quat normalization q.normalize(); TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, - 0.54772256f, 0.73029674f))); + 0.54772256f, 0.73029674f))); // quat default ctor q = Quatf(); diff --git a/test/helper.cpp b/test/helper.cpp index adb27678d7..e1cd2bf009 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -12,6 +12,12 @@ int main() TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); TEST(fabs(wrap_pi(3.0) - (3.0)) < 1e-3); wrap_pi(NAN); + + Vector3f a(1, 2, 3); + Vector3f b(4, 5, 6); + a.T().print(); + TEST(!isEqual(a, b)); + TEST(isEqual(a, a)); return 0; } From 0969b0ae567b7fdd92dfa7fbd151702bc0a7a230 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 23 Jan 2016 23:35:44 -0500 Subject: [PATCH 120/388] Removed uncessary print. --- test/vector3.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/test/vector3.cpp b/test/vector3.cpp index 8b48641137..a8ccc7325b 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -12,7 +12,6 @@ int main() Vector3f a(1, 0, 0); Vector3f b(0, 1, 0); Vector3f c = a.cross(b); - c.print(); TEST (c == Vector3f(0,0,1)); c = a % b; TEST (c == Vector3f(0,0,1)); From faee66273bd0ed75885a73d78e59d8f85ca8fc25 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 23 Jan 2016 23:58:43 -0500 Subject: [PATCH 121/388] Turned back on testing flag. --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 758354c48e..6b13ff0d5c 100644 --- a/.travis.yml +++ b/.travis.yml @@ -3,7 +3,7 @@ sudo: false install: - pip install --user cpp-coveralls script: - - cmake -DCMAKE_BUILD_TYPE=Profile . + - cmake -DCMAKE_BUILD_TYPE=Profile -DTEST=ON . - make - make check_format - ctest -V From b9bfadb0cc703306e9b54d00162dabb73a6d91f1 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 00:00:22 -0500 Subject: [PATCH 122/388] Fix for travis. --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 6b13ff0d5c..c8949e20e8 100644 --- a/.travis.yml +++ b/.travis.yml @@ -3,7 +3,7 @@ sudo: false install: - pip install --user cpp-coveralls script: - - cmake -DCMAKE_BUILD_TYPE=Profile -DTEST=ON . + - cmake -DCMAKE_BUILD_TYPE=Profile -DTEST=ON -DFORMAT=ON . - make - make check_format - ctest -V From ffbe58ca10262e3ff3ae3a69eb0d3ca3dd7a7c73 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 00:39:21 -0500 Subject: [PATCH 123/388] Added better roundtrip euler test. --- matrix/Dcm.hpp | 12 ++++++------ matrix/Matrix.hpp | 2 +- test/attitude.cpp | 40 ++++++++++++++++++++++++++++------------ 3 files changed, 35 insertions(+), 19 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 646fa7e2ec..2118dab3c2 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -64,12 +64,12 @@ public: Dcm(const Euler & euler) { Dcm &dcm = *this; - Type cosPhi = cosf(euler.phi()); - Type sinPhi = sinf(euler.phi()); - Type cosThe = cosf(euler.theta()); - Type sinThe = sinf(euler.theta()); - Type cosPsi = cosf(euler.psi()); - Type sinPsi = sinf(euler.psi()); + Type cosPhi = Type(cos(euler.phi())); + Type sinPhi = Type(sin(euler.phi())); + Type cosThe = Type(cos(euler.theta())); + Type sinThe = Type(sin(euler.theta())); + Type cosPsi = Type(cos(euler.psi())); + Type sinPsi = Type(sin(euler.psi())); dcm(0, 0) = cosThe * cosPsi; dcm(0, 1) = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 3cc563ea5a..276d691e4e 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -131,7 +131,7 @@ public: bool operator==(const Matrix &other) const { const Matrix &self = *this; - static const Type eps = Type(1e-6); + static const Type eps = Type(1e-4); for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { diff --git a/test/attitude.cpp b/test/attitude.cpp index 86ce68e45c..5ac84e911b 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -86,20 +86,36 @@ int main() Quatf q2(dcm_check); TEST(isEqual(q2, q_check)); + // constants + double deg2rad = M_PI/180.0; + double rad2deg = 180.0/M_PI; - // euler gimbal lock check - // note if theta = pi/2, then roll is set to zero - float pi_2 = float(M_PI_2); - Eulerf euler_gimbal_lock(0.0f, pi_2, 0.2f); - Dcmf dcm_lock(euler_gimbal_lock); - Eulerf euler_gimbal_lock_out(dcm_lock); - TEST(isEqual(euler_gimbal_lock, euler_gimbal_lock_out)); + // euler dcm round trip check + for (int roll=-90; roll<90; roll+=1) { + for (int pitch=-90; pitch<90; pitch+=1) { + for (int yaw=0; yaw<360; yaw+=1) { + // note if theta = pi/2, then roll is set to zero + if (pitch == 90 || pitch == -90) { + roll = 0; + } + printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); + Euler euler(deg2rad*double(roll), + deg2rad*double(pitch), + deg2rad*double(yaw)); + Dcm dcm_from_euler(euler); + Euler euler_out(dcm_from_euler); + TEST(isEqual(rad2deg*euler, rad2deg*euler_out)); - // note if theta = pi/2, then roll is set to zero - Eulerf euler_gimbal_lock2(0.0f, -pi_2, 0.2f); - Dcmf dcm_lock2(euler_gimbal_lock2); - Eulerf euler_gimbal_lock_out2(dcm_lock2); - TEST(isEqual(euler_gimbal_lock2, euler_gimbal_lock_out2)); + Eulerf eulerf(float(deg2rad)*float(roll), + float(deg2rad)*float(pitch), + float(deg2rad)*float(yaw)); + Dcm dcm_from_eulerf(eulerf); + Euler euler_outf(dcm_from_eulerf); + TEST(isEqual(float(rad2deg)*eulerf, + float(rad2deg)*euler_outf)); + } + } + } // quaterion copy ctors float data_v4[] = {1, 2, 3, 4}; From b98ac75452f74448c4cd37358b154187ba0ed04d Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 00:39:59 -0500 Subject: [PATCH 124/388] Formatting. --- test/attitude.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 5ac84e911b..71d26b86a1 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -100,19 +100,19 @@ int main() } printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); Euler euler(deg2rad*double(roll), - deg2rad*double(pitch), - deg2rad*double(yaw)); + deg2rad*double(pitch), + deg2rad*double(yaw)); Dcm dcm_from_euler(euler); Euler euler_out(dcm_from_euler); TEST(isEqual(rad2deg*euler, rad2deg*euler_out)); Eulerf eulerf(float(deg2rad)*float(roll), - float(deg2rad)*float(pitch), - float(deg2rad)*float(yaw)); + float(deg2rad)*float(pitch), + float(deg2rad)*float(yaw)); Dcm dcm_from_eulerf(eulerf); Euler euler_outf(dcm_from_eulerf); TEST(isEqual(float(rad2deg)*eulerf, - float(rad2deg)*euler_outf)); + float(rad2deg)*euler_outf)); } } } From 5aef810e7c8771f633a8425693fb069eb27f27fc Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 01:50:34 -0500 Subject: [PATCH 125/388] Fixed euler angles. --- matrix/Euler.hpp | 28 ++++++++++++++++------------ test/attitude.cpp | 45 ++++++++++++++++++++++++++++++++------------- 2 files changed, 48 insertions(+), 25 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 89a188eab4..23c970b375 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -48,20 +48,24 @@ public: Euler(const Dcm & dcm) : Vector() { - theta() = (Type)asin(-dcm(2,0)); + Type phi_val = Type(atan2(dcm(2,1), dcm(2,2))); + Type theta_val = Type(asin(-dcm(2,0))); + Type psi_val = Type(atan2(dcm(1,0), dcm(0,0))); + Type pi = Type(M_PI); - if (fabs(theta() - (Type)M_PI_2) < 1.0e-3) { - phi() = (Type)0.0; - psi() = (Type)atan2(dcm(0,1), dcm(1,1)); - psi() = (Type)atan2(dcm(1,2), dcm(0,2)); - } else if ((Type)fabs(theta() + (Type)M_PI_2) < (Type)1.0e-3) { - phi() = (Type)0.0; - psi() = (Type)atan2(-dcm(1,2), -dcm(0,2)); - - } else { - phi() = (Type)atan2(dcm(2,1), dcm(2,2)); - psi() = (Type)atan2(dcm(1,0), dcm(0,0)); + if (fabs(theta_val - pi/2) < 1.0e-3) { + phi_val = Type(0.0); + psi_val = Type(atan2(dcm(1,2), dcm(0,2))); + } else if (Type(fabs(theta_val + pi/2) < Type(1.0e-3))) { + phi_val = Type(0.0); + psi_val = Type(atan2(-dcm(1,2), -dcm(0,2))); } + + if (psi_val < 0) psi_val += 2*pi; + + phi() = phi_val; + theta() = theta_val; + psi() = psi_val; } Euler(const Quaternion & q) : diff --git a/test/attitude.cpp b/test/attitude.cpp index 71d26b86a1..6206eb1713 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -91,27 +91,46 @@ int main() double rad2deg = 180.0/M_PI; // euler dcm round trip check - for (int roll=-90; roll<90; roll+=1) { - for (int pitch=-90; pitch<90; pitch+=1) { - for (int yaw=0; yaw<360; yaw+=1) { + for (int roll=-90; roll<=90; roll+=90) { + for (int pitch=-90; pitch<=90; pitch+=90) { + for (int yaw=1; yaw<=360; yaw+=90) { // note if theta = pi/2, then roll is set to zero - if (pitch == 90 || pitch == -90) { - roll = 0; + int roll_expected = roll; + int yaw_expected = yaw; + if (pitch == 90) { + roll_expected = 0; + yaw_expected = yaw - roll; + } else if (pitch == -90) { + roll_expected = 0; + yaw_expected = yaw + roll; } - printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); - Euler euler(deg2rad*double(roll), - deg2rad*double(pitch), - deg2rad*double(yaw)); - Dcm dcm_from_euler(euler); - Euler euler_out(dcm_from_euler); - TEST(isEqual(rad2deg*euler, rad2deg*euler_out)); + if (yaw_expected < 0) yaw_expected += 360; + if (yaw_expected > 360) yaw_expected -= 360; + printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); + Euler euler_expected( + deg2rad*double(roll_expected), + deg2rad*double(pitch), + deg2rad*double(yaw_expected)); + Euler euler( + deg2rad*double(roll), + deg2rad*double(pitch), + deg2rad*double(yaw)); + Dcm dcm_from_euler(euler); + dcm_from_euler.print(); + Euler euler_out(dcm_from_euler); + TEST(isEqual(rad2deg*euler_expected, rad2deg*euler_out)); + + Eulerf eulerf_expected( + float(deg2rad)*float(roll_expected), + float(deg2rad)*float(pitch), + float(deg2rad)*float(yaw_expected)); Eulerf eulerf(float(deg2rad)*float(roll), float(deg2rad)*float(pitch), float(deg2rad)*float(yaw)); Dcm dcm_from_eulerf(eulerf); Euler euler_outf(dcm_from_eulerf); - TEST(isEqual(float(rad2deg)*eulerf, + TEST(isEqual(float(rad2deg)*eulerf_expected, float(rad2deg)*euler_outf)); } } From e639a3612fa4a205393581b637aba57d98abbac7 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 02:30:54 -0500 Subject: [PATCH 126/388] Fix typo. --- matrix/Euler.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 23c970b375..41d34d0a0e 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -56,7 +56,7 @@ public: if (fabs(theta_val - pi/2) < 1.0e-3) { phi_val = Type(0.0); psi_val = Type(atan2(dcm(1,2), dcm(0,2))); - } else if (Type(fabs(theta_val + pi/2) < Type(1.0e-3))) { + } else if (Type(fabs(theta_val + pi/2)) < Type(1.0e-3)) { phi_val = Type(0.0); psi_val = Type(atan2(-dcm(1,2), -dcm(0,2))); } From a92d5c13389df17eaae1b27ed7b3e767c845bf31 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 24 Jan 2016 02:44:25 -0500 Subject: [PATCH 127/388] Removed unneeded headers. --- matrix/Matrix.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 276d691e4e..dedd2065a7 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -13,8 +13,6 @@ #include #include #include -#include -#include #if defined(SUPPORT_STDIOSTREAM) #include #include From 1778ac199c0dd0ae58722c8c397c2526a9e2775e Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 25 Jan 2016 13:40:51 -0500 Subject: [PATCH 128/388] Fixed euler wrapping. --- matrix/Euler.hpp | 2 -- test/attitude.cpp | 4 ++-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 41d34d0a0e..2928baa6ad 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -61,8 +61,6 @@ public: psi_val = Type(atan2(-dcm(1,2), -dcm(0,2))); } - if (psi_val < 0) psi_val += 2*pi; - phi() = phi_val; theta() = theta_val; psi() = psi_val; diff --git a/test/attitude.cpp b/test/attitude.cpp index 6206eb1713..784ffb29f3 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -104,8 +104,8 @@ int main() roll_expected = 0; yaw_expected = yaw + roll; } - if (yaw_expected < 0) yaw_expected += 360; - if (yaw_expected > 360) yaw_expected -= 360; + if (yaw_expected < -180) yaw_expected += 360; + if (yaw_expected > 180) yaw_expected -= 360; printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); Euler euler_expected( From ce30542dbaa3e6f5e68b742a34cda993a351e15d Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 25 Jan 2016 13:54:13 -0500 Subject: [PATCH 129/388] Fix output for unit test. --- test/attitude.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 784ffb29f3..59efa084a2 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -93,7 +93,7 @@ int main() // euler dcm round trip check for (int roll=-90; roll<=90; roll+=90) { for (int pitch=-90; pitch<=90; pitch+=90) { - for (int yaw=1; yaw<=360; yaw+=90) { + for (int yaw=-179; yaw<=180; yaw+=90) { // note if theta = pi/2, then roll is set to zero int roll_expected = roll; int yaw_expected = yaw; From 1ae114b3d2af724a3003a99c133f7c29fdcb3b62 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Feb 2016 10:53:12 -0500 Subject: [PATCH 130/388] Improved rk4 integration to allow longer time interval than 1 step. --- matrix/integration.hpp | 27 +++++++++++++++++++++------ test/integration.cpp | 13 ++++++++----- 2 files changed, 29 insertions(+), 11 deletions(-) diff --git a/matrix/integration.hpp b/matrix/integration.hpp index a0ad55c68a..8909a17c60 100644 --- a/matrix/integration.hpp +++ b/matrix/integration.hpp @@ -10,18 +10,33 @@ int integrate_rk4( const Matrix & y0, const Matrix & u, Type t0, - Type h, + Type tf, + Type h0, Matrix & y1 ) { // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods + Type t1 = t0; + y1 = y0; + Type h = h0; Vector k1, k2, k3, k4; - k1 = f(t0, y0, u); - k2 = f(t0 + h/2, y0 + k1*h/2, u); - k3 = f(t0 + h/2, y0 + k2*h/2, u); - k4 = f(t0 + h, y0 + k3*h, u); - y1 = y0 + (k1 + k2*2 + k3*2 + k4)*(h/6); + if (tf < t0) return -1; // make sure t1 > t0 + while (t1 < tf) { + if (t1 + h0 < tf) { + h = h0; + } else { + h = tf - t1; + } + k1 = f(t1, y1, u); + k2 = f(t1 + h/2, y1 + k1*h/2, u); + k3 = f(t1 + h/2, y1 + k2*h/2, u); + k4 = f(t1 + h, y1 + k3*h, u); + y1 += (k1 + k2*2 + k3*2 + k4)*(h/6); + t1 += h; + } return 0; } } // namespace matrix + +// vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : diff --git a/test/integration.cpp b/test/integration.cpp index ebc456adb0..abbfe885b3 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -8,17 +8,20 @@ using namespace matrix; Vector f(float t, const Matrix & y, const Matrix & u); Vector f(float t, const Matrix & y, const Matrix & u) { - return ones(); + float v = -sinf(t); + return v*ones(); } int main() { Vector y = ones(); Vector u = ones(); - float t = 1; - float h = 0.1f; - integrate_rk4(f, y, u, t, h, y); - TEST(isEqual(y, (ones()*1.1f))); + float t0 = 0; + float tf = 2; + float h = 0.001f; + integrate_rk4(f, y, u, t0, tf, h, y); + float v = 1 + cosf(tf) - cosf(t0); + TEST(isEqual(y, (ones()*v))); return 0; } From 5a01e6c93947d86e0a7021ae596530a31ba9bb92 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Feb 2016 12:22:08 -0500 Subject: [PATCH 131/388] Added slice function for matrix. --- README.md | 16 ++++++++++++++++ matrix/Matrix.hpp | 7 +++++++ test/CMakeLists.txt | 3 ++- test/slice.cpp | 25 +++++++++++++++++++++++++ 4 files changed, 50 insertions(+), 1 deletion(-) create mode 100644 test/slice.cpp diff --git a/README.md b/README.md index 3da2001634..cf5c05c62c 100644 --- a/README.md +++ b/README.md @@ -32,6 +32,8 @@ A simple and efficient template based matrix library. ## Example +See the test directory for detailed examples. Some simple examples are included below: + ```c++ // define an euler angle (Body 3(yaw)-2(pitch)-1(roll) rotation) float roll = 0.1f; @@ -91,4 +93,18 @@ A simple and efficient template based matrix library. // correction x += K*r; + // slicing + float data[9] = {0, 2, 3, + 4, 5, 6, + 7, 8, 10 + }; + SquareMatrix A(data); + + // Slice a 3,3 matrix starting at row 1, col 0, + // with size 2 x 3, warning, no size checking + Matrix B(A.slice<2, 3>(1, 0)); + + // this results in: + // 4, 5, 6 + // 7, 8, 10 ``` diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index dedd2065a7..4991002fd3 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -317,6 +317,13 @@ public: return transpose(); } + template + Matrix slice(size_t x0, size_t y0) const + { + Matrix res(&(_data[x0][y0])); + return res; + } + void setZero() { memset(_data, 0, sizeof(_data)); diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 28c55533de..2cff34c3ac 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,6 +1,7 @@ set(tests setIdentity inverse + slice matrixMult vectorAssignment matrixAssignment @@ -33,4 +34,4 @@ if (${CMAKE_BUILD_TYPE} STREQUAL "Profile") WORKING_DIRECTORY ${CMAKE_BUILD_DIR} DEPENDS test_build ) -endif() \ No newline at end of file +endif() diff --git a/test/slice.cpp b/test/slice.cpp new file mode 100644 index 0000000000..1f0bf99819 --- /dev/null +++ b/test/slice.cpp @@ -0,0 +1,25 @@ +#include + +#include +#include "test_macros.hpp" + +using namespace matrix; + +int main() +{ + float data[9] = {0, 2, 3, + 4, 5, 6, + 7, 8, 10 + }; + float data_check[6] = { + 4, 5, 6, + 7, 8, 10 + }; + SquareMatrix A(data); + Matrix B_check(data_check); + Matrix B(A.slice<2, 3>(1, 0)); + TEST(isEqual(B, B_check)); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 95e3d7d6ce5274d9b7fec76c0093dc5eaa381abf Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Feb 2016 14:54:15 -0500 Subject: [PATCH 132/388] Added set function. --- matrix/Matrix.hpp | 18 ++++++++++++++++++ test/attitude.cpp | 4 ++-- test/slice.cpp | 17 +++++++++++++++++ 3 files changed, 37 insertions(+), 2 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 4991002fd3..18d7984fe9 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -72,6 +72,13 @@ public: return _data[i][j]; } + void operator=(const Matrix &other) + { + if (this != &other) { + memcpy(_data, other._data, sizeof(_data)); + } + } + /** * Matrix Operations */ @@ -324,6 +331,17 @@ public: return res; } + template + void set(const Matrix &m, size_t x0, size_t y0) + { + Matrix &self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i + x0, j + y0) = m(i, j); + } + } + } + void setZero() { memset(_data, 0, sizeof(_data)); diff --git a/test/attitude.cpp b/test/attitude.cpp index 59efa084a2..9117df155d 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -107,7 +107,7 @@ int main() if (yaw_expected < -180) yaw_expected += 360; if (yaw_expected > 180) yaw_expected -= 360; - printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); + //printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); Euler euler_expected( deg2rad*double(roll_expected), deg2rad*double(pitch), @@ -117,7 +117,7 @@ int main() deg2rad*double(pitch), deg2rad*double(yaw)); Dcm dcm_from_euler(euler); - dcm_from_euler.print(); + //dcm_from_euler.print(); Euler euler_out(dcm_from_euler); TEST(isEqual(rad2deg*euler_expected, rad2deg*euler_out)); diff --git a/test/slice.cpp b/test/slice.cpp index 1f0bf99819..36f13f504b 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -19,6 +19,23 @@ int main() Matrix B_check(data_check); Matrix B(A.slice<2, 3>(1, 0)); TEST(isEqual(B, B_check)); + + float data_2[4] = { + 11, 12, + 13, 14 + }; + + Matrix C(data_2); + A.set(C, 1, 1); + + float data_2_check[9] = { + 0, 2, 3, + 4, 11, 12, + 7, 13, 14 + }; + Matrix D(data_2_check); + TEST(isEqual(A, D)); + return 0; } From 46c83a8c187263452a19f365166f547420bdbc25 Mon Sep 17 00:00:00 2001 From: mcsauder Date: Thu, 25 Feb 2016 18:51:28 -0700 Subject: [PATCH 133/388] Correct a few indexing copy/paste errors that likely previously only functioned properly on square matrices. --- matrix/Matrix.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 18d7984fe9..051056422a 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -407,7 +407,7 @@ public: { Matrix r; for (size_t i=0; i max_val) { max_val = val; @@ -432,7 +432,7 @@ public: { Type min_val = (*this)(0,0); for (size_t i=0; i Date: Fri, 26 Feb 2016 03:39:04 -0500 Subject: [PATCH 134/388] Added pow. --- matrix/Vector.hpp | 11 +++++++++++ test/vector.cpp | 3 +++ 2 files changed, 14 insertions(+) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 104742fd1c..5a8718a7e2 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -7,6 +7,9 @@ */ #pragma once + +#include + #include "math.hpp" namespace matrix @@ -67,6 +70,14 @@ public: (*this) /= norm(); } + Vector pow(Type v) const { + const Vector &a(*this); + Vector r; + for (size_t i = 0; i v3(v2); TEST(v2 == v3); + float data1_sq[] = {1,4,9,16,25}; + Vector v4(data1_sq); + TEST(v1 == v4.pow(0.5)); return 0; } From 7b969094cbae7ff73de6aa96bafeabd981d60f97 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 26 Feb 2016 05:33:16 -0500 Subject: [PATCH 135/388] Fix for scalar type. --- matrix/Scalar.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 0e722eed8c..24c99caea7 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -34,7 +34,7 @@ public: _value = other(0,0); } - Scalar(float other) + Scalar(Type other) { _value = other; } From 6974f97b1cfd68b9196986faf8c8ed0b9bcd59d3 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 26 Feb 2016 05:47:24 -0500 Subject: [PATCH 136/388] Added scalar const conversion operator. --- matrix/Scalar.hpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 24c99caea7..da91ff68bf 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -39,10 +39,16 @@ public: _value = other; } - operator Type() + operator Type &() { return _value; } + + operator Type const &() const + { + return _value; + } + private: Type _value; From 2d27cd79d3cc8d91c2853f5d92363f117610b9aa Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 26 Feb 2016 05:56:21 -0500 Subject: [PATCH 137/388] Added scalar to matrix conversion. --- matrix/Scalar.hpp | 6 ++++++ test/matrixAssignment.cpp | 3 +++ 2 files changed, 9 insertions(+) diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index da91ff68bf..111341d797 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -49,6 +49,12 @@ public: return _value; } + operator Matrix() const { + Matrix m; + m(0, 0) = _value; + return m; + } + private: Type _value; diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 21557541af..1484a31189 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -74,6 +74,9 @@ int main() s = 1; TEST(fabs(s - 1) < 1e-5); + Matrix m5 = s; + TEST(fabs(m5(0,0) - s) < 1e-5); + return 0; } From 6c046055319a68217765f77d74083c4010c97f69 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 26 Feb 2016 06:10:09 -0500 Subject: [PATCH 138/388] Added conversion for scalar to vector. --- matrix/Scalar.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 111341d797..df82674f74 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -55,6 +55,12 @@ public: return m; } + operator Vector() const { + Vector m; + m(0) = _value; + return m; + } + private: Type _value; From 0e14e1118327a7994ba87745ea0b5e6cb406e82f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 15 Mar 2016 06:35:13 -0400 Subject: [PATCH 139/388] Added support for attitude_estimator_q functions. --- matrix/Matrix.hpp | 16 ++++++++++++++++ matrix/Quaternion.hpp | 6 ++++++ matrix/Vector.hpp | 4 ++-- test/attitude.cpp | 2 +- test/matrixAssignment.cpp | 4 ++++ 5 files changed, 29 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 051056422a..83e3870757 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -342,6 +342,22 @@ public: } } + void setRow(size_t i, const Matrix &row) + { + Matrix &self = *this; + for (size_t j = 0; j < N; j++) { + self(i, j) = row(j, 0); + } + } + + void setCol(size_t j, const Matrix &col) + { + Matrix &self = *this; + for (size_t i = 0; i < M; i++) { + self(i, j) = col(i, 1); + } + } + void setZero() { memset(_data, 0, sizeof(_data)); diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index e9cf25f2d8..7b845b1475 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -29,6 +29,11 @@ public: typedef Matrix Matrix41; typedef Matrix Matrix31; + Quaternion(const Type *data_) : + Vector(data_) + { + } + Quaternion() : Vector() { @@ -199,6 +204,7 @@ public: }; typedef Quaternion Quatf; +typedef Quaternion Quaternionf; } // namespace matrix diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 5a8718a7e2..0349060c06 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -66,8 +66,8 @@ public: return Type(sqrt(a.dot(a))); } - inline void normalize() { - (*this) /= norm(); + Vector normalize() const { + return (*this) / norm(); } Vector pow(Type v) const { diff --git a/test/attitude.cpp b/test/attitude.cpp index 9117df155d..74ad5379dc 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -49,7 +49,7 @@ int main() TEST(fabs(q(3) - 4) < eps); // quat normalization - q.normalize(); + q = q.normalize(); TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, 0.54772256f, 0.73029674f))); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 1484a31189..7ff4a41a78 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -77,6 +77,10 @@ int main() Matrix m5 = s; TEST(fabs(m5(0,0) - s) < 1e-5); + Matrix m6; + m6.setRow(0, Vector2f(1, 1)); + m6.setCol(0, Vector2f(1, 1)); + return 0; } From 711b57d2d41a159d7b5afba78ee70aeed89fd44b Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 15 Mar 2016 18:09:48 -0400 Subject: [PATCH 140/388] Added unit function that returns normalized vector. --- matrix/Vector.hpp | 8 ++++++-- test/attitude.cpp | 6 ++++-- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 0349060c06..fe9c5a81f6 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -66,8 +66,12 @@ public: return Type(sqrt(a.dot(a))); } - Vector normalize() const { - return (*this) / norm(); + inline void normalize() { + (*this) /= norm(); + } + + Vector unit() const { + return (*this) / norm(); } Vector pow(Type v) const { diff --git a/test/attitude.cpp b/test/attitude.cpp index 74ad5379dc..f7857d3cd4 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -42,16 +42,18 @@ int main() TEST(isEqual(euler_copy, euler_check)); // quaternion ctor - Quatf q(1, 2, 3, 4); + Quatf q0(1, 2, 3, 4); + Quatf q(q0); TEST(fabs(q(0) - 1) < eps); TEST(fabs(q(1) - 2) < eps); TEST(fabs(q(2) - 3) < eps); TEST(fabs(q(3) - 4) < eps); // quat normalization - q = q.normalize(); + q.normalize(); TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, 0.54772256f, 0.73029674f))); + TEST(isEqual(q0.unit(), q)); // quat default ctor q = Quatf(); From 07fba8322a16cb2dac47e6a8ac7d21ec346313ff Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 18 Mar 2016 20:56:41 -0400 Subject: [PATCH 141/388] Fix for effective cpp. --- matrix/Matrix.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 83e3870757..4cf2d431c8 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -72,11 +72,12 @@ public: return _data[i][j]; } - void operator=(const Matrix &other) + Matrix & operator=(const Matrix &other) { if (this != &other) { memcpy(_data, other._data, sizeof(_data)); } + return (*this); } /** From 65679fbcbb4b31a1a77f3dc5268ca78ca95b3bf3 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 28 Apr 2016 21:16:36 +0200 Subject: [PATCH 142/388] Features and fixes * added the trace function for a SquareMatrix * added Vector3.hat() and it's counterpart Dcm.vee() for skewsymskew symmetric matrix operations in relation to the cross product see https://en.wikipedia.org/wiki/Hat_operator * Matrix::write_string produced runtime errors when I used it in PX4 posix simulation, i simplified it * a Matrix3f is a SquareMatrix * added tests for SquareMatrix.trace, Vector3.hat and Dcm.vee * added a test for quaternion initialisation from array * preventing buffer overflows in Matrix.write_string method --- matrix/Dcm.hpp | 9 +++++++++ matrix/Matrix.hpp | 22 +++------------------- matrix/SquareMatrix.hpp | 13 ++++++++++++- matrix/Vector3.hpp | 18 ++++++++++++++++++ test/CMakeLists.txt | 1 + test/attitude.cpp | 6 ++++++ test/hatvee.cpp | 23 +++++++++++++++++++++++ test/squareMatrix.cpp | 1 + 8 files changed, 73 insertions(+), 20 deletions(-) create mode 100644 test/hatvee.cpp diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 2118dab3c2..e7379d916b 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -83,6 +83,15 @@ public: dcm(2, 1) = sinPhi * cosThe; dcm(2, 2) = cosPhi * cosThe; } + + Vector vee() const { // inverse to Vector.hat() operation + const Dcm &A(*this); + Vector v; + v(0) = -A(1,2); + v(1) = A(0,2); + v(2) = -A(0,1); + return v; + } }; typedef Dcm Dcmf; diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 4cf2d431c8..2fcfce321a 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -274,28 +274,14 @@ public: void write_string(char * buf, size_t n) const { + buf[0] = '\0'; // make an empty string to begin with (we need the '\0' for strlen to work) const Matrix &self = *this; - char data_buf[500] = {0}; for (size_t i = 0; i < M; i++) { - char data_line[100] = {0}; - char data_line_formatted[100] = {0}; for (size_t j = 0; j < N; j++) { - char val_buf[15]; - if (j == N-1) { - snprintf(val_buf, 15, "\t%10g", double(self(i, j))); - } else { - snprintf(val_buf, 15, "\t%10g,", double(self(i, j))); - } - strncat(data_line, val_buf, 300); + snprintf(buf + strlen(buf), n - strlen(buf), "\t%.2g", double(self(i, j))); // directly append to the string buffer } - if (i == M-1) { - snprintf(data_line_formatted, n, "[%s]", data_line); - } else { - snprintf(data_line_formatted, n, "[%s],\n", data_line); - } - strncat(data_buf, data_line_formatted, n); + snprintf(buf + strlen(buf), n - strlen(buf), "\n"); } - snprintf(buf, n, "[%s]", data_buf); } void print() const @@ -511,8 +497,6 @@ std::ostream& operator<<(std::ostream& os, } #endif // defined(SUPPORT_STDIOSTREAM) -typedef Matrix Matrix3f; - } // namespace matrix /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index c10d0a4b4d..3e42b64e55 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -61,6 +61,17 @@ public: return res; } + Type trace() const + { + Type res = 0; + const SquareMatrix &self = *this; + + for (size_t i = 0; i < M; i++) { + res += self(i, i); + } + return res; + } + }; typedef SquareMatrix SquareMatrix3f; @@ -215,7 +226,7 @@ SquareMatrix inv(const SquareMatrix & A) return X; } - +typedef SquareMatrix Matrix3f; } // namespace matrix diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 4bbfeb0745..9fed6ac3f6 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -16,6 +16,9 @@ namespace matrix template class Vector; +template +class Dcm; + template class Vector3 : public Vector { @@ -61,6 +64,21 @@ public: return (*this).cross(b); } + Dcm hat() const { // inverse to Dcm.vee() operation + const Vector3 &v(*this); + Dcm A; + A(0,0) = 0; + A(0,1) = -v(2); + A(0,2) = v(1); + A(1,0) = v(2); + A(1,1) = 0; + A(1,2) = -v(0); + A(2,0) = -v(1); + A(2,1) = v(0); + A(2,2) = 0; + return A; + } + }; typedef Vector3 Vector3f; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 2cff34c3ac..30f5c55f57 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -15,6 +15,7 @@ set(tests integration squareMatrix helper + hatvee ) add_custom_target(test_build) diff --git a/test/attitude.cpp b/test/attitude.cpp index f7857d3cd4..abdfeb67da 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -231,6 +231,12 @@ int main() TEST(fabsf(q(2) - q_true(2)) < eps); TEST(fabsf(q(3) - q_true(3)) < eps); + // Quaternion initialisation per array + float q_array[] = {0.9833f, -0.0343f, -0.1060f, -0.1436f}; + Quaternionq_from_array(q_array); + for(int i = 0; i < 4; i++) + TEST(fabsf(q_from_array(i) - q_array[i]) < eps); + }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/hatvee.cpp b/test/hatvee.cpp new file mode 100644 index 0000000000..c79a2b4184 --- /dev/null +++ b/test/hatvee.cpp @@ -0,0 +1,23 @@ +#include +#include "test_macros.hpp" + +#include + +using namespace matrix; + +template class SquareMatrix; + +int main() +{ + Euler euler(0.1f, 0.2f, 0.3f); + Dcm R(euler); + Dcm skew = R - R.T(); + Vector3 w = skew.vee(); + Vector3 w_check(0.1348f, 0.4170f, 0.5647f); + + TEST(isEqual(w, w_check)); + TEST(isEqual(skew, w.hat())); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index f8f1caac54..ff87a3b8be 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -17,6 +17,7 @@ int main() Vector3 diag_check(1, 5, 10); TEST(isEqual(A.diag(), diag_check)); + TEST(A.trace() - 16 < 1e-3); float data_check[9] = { 1.01158503f, 0.02190432f, 0.03238144f, From b2eb4d13d87de4fe4bbe39bc0239c49446401418 Mon Sep 17 00:00:00 2001 From: MaEtUgR Date: Thu, 5 May 2016 12:50:52 +0200 Subject: [PATCH 143/388] Matrix.setCol off by one bug fixed The Column Vector you are copying from, only has one Column and it is indexed by 0 not 1. I also completed the unit test stub that would have found this bug. --- matrix/Matrix.hpp | 2 +- test/matrixAssignment.cpp | 10 ++++++++-- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 2fcfce321a..5c59593318 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -341,7 +341,7 @@ public: { Matrix &self = *this; for (size_t i = 0; i < M; i++) { - self(i, j) = col(i, 1); + self(i, j) = col(i, 0); } } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 7ff4a41a78..4d2ccb0b95 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -78,8 +78,14 @@ int main() TEST(fabs(m5(0,0) - s) < 1e-5); Matrix m6; - m6.setRow(0, Vector2f(1, 1)); - m6.setCol(0, Vector2f(1, 1)); + m6.setRow(0, Vector2f(1, 2)); + float m7_array[] = {1,2,0,0}; + Matrix m7(m7_array); + TEST(isEqual(m6, m7)); + m6.setCol(0, Vector2f(3, 4)); + float m8_array[] = {3,2,4,0}; + Matrix m8(m8_array); + TEST(isEqual(m6, m8)); return 0; } From bd8420fcf61b1d81347e9df361c5200237595d7a Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 11:12:06 -0400 Subject: [PATCH 144/388] Added example of assignment to already created object. --- .travis.yml | 2 +- CMakeLists.txt | 4 ++-- test/attitude.cpp | 3 ++- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index c8949e20e8..6afc49c8f9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -3,7 +3,7 @@ sudo: false install: - pip install --user cpp-coveralls script: - - cmake -DCMAKE_BUILD_TYPE=Profile -DTEST=ON -DFORMAT=ON . + - cmake -DCMAKE_BUILD_TYPE=Profile -DTESTING=ON -DFORMAT=ON . - make - make check_format - ctest -V diff --git a/CMakeLists.txt b/CMakeLists.txt index 56b221022e..550b92aac4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,7 +16,7 @@ set_property(CACHE CMAKE_BUILD_TYPE PROPERTY option(SUPPORT_STDIOSTREAM "If enabled provides support for << operator (as used with std::cout)" OFF) -option(TEST "Enable testing" OFF) + option(TESTING "Enable testing" OFF) option(FORMAT "Enable formatting" OFF) if(SUPPORT_STDIOSTREAM) @@ -62,7 +62,7 @@ include_directories(${CMAKE_SOURCE_DIR}) file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) -if(TEST) +if(TESTING) enable_testing() add_subdirectory(test) endif() diff --git a/test/attitude.cpp b/test/attitude.cpp index abdfeb67da..50405b6003 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -130,7 +130,8 @@ int main() Eulerf eulerf(float(deg2rad)*float(roll), float(deg2rad)*float(pitch), float(deg2rad)*float(yaw)); - Dcm dcm_from_eulerf(eulerf); + Dcm dcm_from_eulerf; + dcm_from_eulerf = eulerf; Euler euler_outf(dcm_from_eulerf); TEST(isEqual(float(rad2deg)*eulerf_expected, float(rad2deg)*euler_outf)); From 6efa3c1cb5792faf14651a5eced31a0fe95621e9 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 11:34:26 -0400 Subject: [PATCH 145/388] Added make coverage to travis. --- .travis.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.travis.yml b/.travis.yml index 6afc49c8f9..8db72e8a4b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -6,6 +6,7 @@ script: - cmake -DCMAKE_BUILD_TYPE=Profile -DTESTING=ON -DFORMAT=ON . - make - make check_format + - make coverage - ctest -V after_success: - cpp-coveralls -i matrix From 155202f6b06686a1c0d4bb7b3257586d1575409b Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 11:49:45 -0400 Subject: [PATCH 146/388] Found a few coverage gaps with local coverage testing. --- test/matrixAssignment.cpp | 32 +++++++++++++++++++++++++------- 1 file changed, 25 insertions(+), 7 deletions(-) diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 4d2ccb0b95..7a3aa56b8b 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -33,19 +33,19 @@ int main() TEST(!(m == m3)); m2 *= 2; - TEST(m2 == m3); + TEST(isEqual(m2, m3)); m2 /= 2; m2 -= 1; float data_minus_1[9] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; - TEST(Matrix3f(data_minus_1) == m2); + TEST(isEqual(Matrix3f(data_minus_1), m2)); m2 += 1; - TEST(Matrix3f(data) == m2); + TEST(isEqual(Matrix3f(data), m2)); m3 -= m2; - TEST(m3 == m2); + TEST(isEqual(m3, m2)); float data_row_02_swap[9] = { 7, 8, 9, @@ -61,14 +61,32 @@ int main() Matrix3f m4(data); - TEST(-m4 == m4*(-1)); + TEST(isEqual(-m4, m4*(-1))); + // col swap m4.swapCols(0, 2); - TEST(m4 == Matrix3f(data_col_02_swap)); + TEST(isEqual(m4, Matrix3f(data_col_02_swap))); m4.swapCols(0, 2); + + // row swap m4.swapRows(0, 2); - TEST(m4 == Matrix3f(data_row_02_swap)); + TEST(isEqual(m4, Matrix3f(data_row_02_swap))); + m4.swapRows(0, 2); + + // swapping with same row should do nothing + m4.swapRows(0, 0); + m4.swapRows(1, 1); + m4.swapRows(2, 2); + TEST(isEqual(m4, Matrix3f(data))); + + // swapping with same col should do nothing + m4.swapCols(0, 0); + m4.swapCols(1, 1); + m4.swapCols(2, 2); + TEST(isEqual(m4, Matrix3f(data))); + TEST(fabs(m4.min() - 1) < 1e-5); + TEST(fabs((-m4).min() + 9) < 1e-5); Scalar s; s = 1; From f4902fafb98f5edfcad9e617c408ee0f75418e42 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 11:53:18 -0400 Subject: [PATCH 147/388] Added lcov package for coverage test. --- .travis.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.travis.yml b/.travis.yml index 8db72e8a4b..d0891d27bd 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,5 +1,9 @@ language: c sudo: false +addons: + apt: + packages: + - lcov install: - pip install --user cpp-coveralls script: From 32ad3989f2b035ee99ff22b032147225bb0f7c0d Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 11:55:45 -0400 Subject: [PATCH 148/388] Fix lcov install on travis. --- .travis.yml | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index d0891d27bd..53c9cbade9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,10 +1,7 @@ language: c -sudo: false -addons: - apt: - packages: - - lcov +sudo: true install: + - sudo apt-get install -y lcov - pip install --user cpp-coveralls script: - cmake -DCMAKE_BUILD_TYPE=Profile -DTESTING=ON -DFORMAT=ON . From 061609322a172a578e096bfb4eaf3ed72b3c0403 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 12:01:20 -0400 Subject: [PATCH 149/388] Added command line output for coverage. --- test/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 30f5c55f57..834ba1359d 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -30,6 +30,7 @@ if (${CMAKE_BUILD_TYPE} STREQUAL "Profile") add_custom_target(coverage COMMAND ${CMAKE_CTEST_COMMAND} COMMAND lcov --capture --directory . --output-file coverage.info + COMMAND lcov --summary coverage.info COMMAND genhtml coverage.info --output-directory out COMMAND x-www-browser out/index.html WORKING_DIRECTORY ${CMAKE_BUILD_DIR} From dd8ff8db12ae831841ecb4bb7e63d3a497d1f848 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 12:13:00 -0400 Subject: [PATCH 150/388] Made coverage html output optional. --- CMakeLists.txt | 11 ++++++----- test/CMakeLists.txt | 23 ++++++++++++++++++++--- 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 550b92aac4..bdb24b8a15 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,14 +10,15 @@ if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() + set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Profile") option(SUPPORT_STDIOSTREAM - "If enabled provides support for << operator (as used with - std::cout)" OFF) - option(TESTING "Enable testing" OFF) + "If enabled provides support for << operator (as used with std::cout)" OFF) +option(TESTING "Enable testing" OFF) option(FORMAT "Enable formatting" OFF) +option(COV_HTML "Display html for coverage" OFF) if(SUPPORT_STDIOSTREAM) add_definitions(-DSUPPORT_STDIOSTREAM) @@ -56,8 +57,6 @@ set(CMAKE_CXX_FLAGS ) string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") -enable_testing() - include_directories(${CMAKE_SOURCE_DIR}) file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) @@ -96,3 +95,5 @@ set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com") include(CPack) + +# vim: set noet fenc=utf-8 ft=cmake ff=unix sts=0 sw=4 ts=4 : diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 834ba1359d..da5e6316b2 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -27,13 +27,30 @@ foreach(test_name ${tests}) endforeach() if (${CMAKE_BUILD_TYPE} STREQUAL "Profile") - add_custom_target(coverage + + add_custom_target(coverage_build COMMAND ${CMAKE_CTEST_COMMAND} COMMAND lcov --capture --directory . --output-file coverage.info COMMAND lcov --summary coverage.info - COMMAND genhtml coverage.info --output-directory out - COMMAND x-www-browser out/index.html WORKING_DIRECTORY ${CMAKE_BUILD_DIR} DEPENDS test_build ) + + add_custom_target(coverage_html + COMMAND genhtml coverage.info --output-directory out + COMMAND x-www-browser out/index.html + WORKING_DIRECTORY ${CMAKE_BUILD_DIR} + DEPENDS coverage_build + ) + + set(coverage_deps + coverage_build) + + if (COV_HTML) + list(APPEND coverage_deps coverage_html) + endif() + + add_custom_target(coverage + DEPENDS ${coverage_deps} + ) endif() From 4d33092bcb39b08934fbb0ab86d4bd0344a9287b Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 9 May 2016 12:19:26 -0400 Subject: [PATCH 151/388] Removed lcov testing from travis. --- .travis.yml | 4 +--- CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index 53c9cbade9..6afc49c8f9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,13 +1,11 @@ language: c -sudo: true +sudo: false install: - - sudo apt-get install -y lcov - pip install --user cpp-coveralls script: - cmake -DCMAKE_BUILD_TYPE=Profile -DTESTING=ON -DFORMAT=ON . - make - make check_format - - make coverage - ctest -V after_success: - cpp-coveralls -i matrix diff --git a/CMakeLists.txt b/CMakeLists.txt index bdb24b8a15..206deffa5c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,7 +7,7 @@ set(VERSION_PATCH "0") project(matrix CXX) if (NOT CMAKE_BUILD_TYPE) - set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) + set(CMAKE_BUILD_TYPE "Profile" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() From 3509329f306b7119939fe1ead2246bf10c5e5859 Mon Sep 17 00:00:00 2001 From: jaredkw Date: Wed, 11 May 2016 16:35:05 -0600 Subject: [PATCH 152/388] Define M_PI float, change logical and to && --- matrix/Euler.hpp | 4 ++++ matrix/Matrix.hpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 2928baa6ad..57dcbb48a2 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -10,6 +10,10 @@ #include "math.hpp" +#ifndef M_PI +#define M_PI (3.14159265358979323846f) +#endif + namespace matrix { diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 5c59593318..c9c88b4efe 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -371,7 +371,7 @@ public: setZero(); Matrix &self = *this; - for (size_t i = 0; i < M and i < N; i++) { + for (size_t i = 0; i < M && i < N; i++) { self(i, i) = 1; } } From 34e6e2a941ce1f8dad6492c8d672a7d5ac5233c3 Mon Sep 17 00:00:00 2001 From: Andreas Bircher Date: Tue, 3 May 2016 17:32:49 +0200 Subject: [PATCH 153/388] refactoring rotation classes and adding initial description --- matrix/Dcm.hpp | 63 ++++++++++++++- matrix/Euler.hpp | 91 +++++++++++++++++++++- matrix/Quaternion.hpp | 176 +++++++++++++++++++++++++++++++++++++++++- 3 files changed, 322 insertions(+), 8 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index e7379d916b..bd622731c9 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -20,6 +20,11 @@ class Quaternion; template class Euler; +/** + * Direction cosine matrix class + * + * More elaborate class description + */ template class Dcm : public Matrix { @@ -28,20 +33,69 @@ public: typedef Matrix Vector3; + /** + * Standard constructor + * + * Initializes to identity + */ Dcm() : Matrix() { (*this) = eye(); } + /** + * Constructor from array + * + * Copies the given scalar value to all matrix fields. + * + * @param other array + */ Dcm(const Type *data_) : Matrix(data_) { } + /** + * Copy constructor + * + * More elaborate function description + * + * @param other Matrix33 to set dcm to + */ Dcm(const Matrix &other) : Matrix(other) { } + /** + * Constructor from quaternion + * + * More elaborate function description + * + * @param q quaternion to set dcm to + */ Dcm(const Quaternion & q) { + set_from_quaternion(q); + } + + /** + * Constructor from euler angles + * + * More elaborate function description + * + * @param euler euler angles to set dcm to + */ + Dcm(const Euler & euler) { + set_from_euler(euler); + } + + + /** + * Set from quaternion + * + * More elaborate function description + * + * @param q quaternion to set dcm to + */ + void set_from_quaternion(const Quaternion & q) { Dcm &dcm = *this; Type a = q(0); Type b = q(1); @@ -62,7 +116,14 @@ public: dcm(2, 2) = aSq - bSq - cSq + dSq; } - Dcm(const Euler & euler) { + /** + * Set from euler angles + * + * More elaborate function description + * + * @param euler euler angles to set dcm to + */ + void set_from_euler(const Euler & euler) { Dcm &dcm = *this; Type cosPhi = Type(cos(euler.phi())); Type sinPhi = Type(sin(euler.phi())); diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 57dcbb48a2..24ffd326df 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -23,34 +23,113 @@ class Dcm; template class Quaternion; +/** + * Euler angles class + * + * More elaborate class description + */ template class Euler : public Vector { public: virtual ~Euler() {}; + /** + * Standard constructor + * + * More elaborate function description + */ Euler() : Vector() { } + /** + * Copy constructor + * + * More elaborate function description + * + * @param other vector to copy + */ Euler(const Vector & other) : Vector(other) { } + /** + * Constructor from Matrix31 + * + * More elaborate function description + * + * @param other Matrix31 to copy + */ Euler(const Matrix & other) : Vector(other) { } + /** + * Constructor from euler angles + * + * More elaborate function description + * + * @param phi_ roll + * @param theta_ pitch + * @param psi_ yaw + */ Euler(Type phi_, Type theta_, Type psi_) : Vector() + { + set_from_euler(phi_, theta_, psi_); + } + + /** + * Constructor from dcm + * + * More elaborate function description + * + * @param dcm_ dcm to set angles to + */ + Euler(const Dcm & dcm) : Vector() + { + set_from_dcm(dcm); + } + + /** + * Constructor from quaternion + * + * More elaborate function description + * + * @param q quaternion to set angles to + */ + Euler(const Quaternion & q) : + Vector() + { + set_from_quaternion(q); + } + + /** + * Set from euler angles + * + * More elaborate function description + * + * @param phi_ roll + * @param theta_ pitch + * @param psi_ yaw + */ + void set_from_euler(Type phi_, Type theta_, Type psi_) { phi() = phi_; theta() = theta_; psi() = psi_; } - Euler(const Dcm & dcm) : Vector() + /** + * Set from dcm + * + * More elaborate function description + * + * @param dcm_ dcm to set angles to + */ + void set_from_dcm(const Dcm & dcm) { Type phi_val = Type(atan2(dcm(2,1), dcm(2,2))); Type theta_val = Type(asin(-dcm(2,0))); @@ -70,8 +149,14 @@ public: psi() = psi_val; } - Euler(const Quaternion & q) : - Vector() + /** + * Set from dcm + * + * More elaborate function description + * + * @param q quaternion to set angles to + */ + void set_from_quaternion(const Quaternion & q) { *this = Euler(Dcm(q)); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 7b845b1475..e135464537 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -20,6 +20,11 @@ class Dcm; template class Euler; +/** + * Quaternion class + * + * More elaborate class description + */ template class Quaternion : public Vector { @@ -29,11 +34,23 @@ public: typedef Matrix Matrix41; typedef Matrix Matrix31; + /** + * Constructor from array + * + * Copies the given scalar value to all quaternion fields. + * + * @param data_ array + */ Quaternion(const Type *data_) : Vector(data_) { } + /** + * Standard constructor + * + * More elaborate function description + */ Quaternion() : Vector() { @@ -44,13 +61,68 @@ public: q(3) = 0; } + /** + * Constructor from Matrix41 + * + * More elaborate function description + * + * @param other Matrix41 to copy + */ Quaternion(const Matrix41 & other) : Vector(other) { } + /** + * Constructor from dcm + * + * More elaborate function description + * + * @param dcm dcm to set quaternion to + */ Quaternion(const Dcm & dcm) : Vector() + { + set_from_dcm(dcm); + } + + /** + * Constructor from euler angles + * + * More elaborate function description + * + * @param euler euler angles to set quaternion to + */ + Quaternion(const Euler & euler) : + Vector() + { + set_from_euler(euler); + } + + /** + * Constructor from quaternion values + * + * More elaborate function description + * + * @param a set quaternion value 0 + * @param b set quaternion value 1 + * @param c set quaternion value 2 + * @param d set quaternion value 3 + */ + Quaternion(Type a, Type b, Type c, Type d) : + Vector() + { + set_from_quaternion(a, b, c, d); + } + + /** + * Set from dcm + * + * More elaborate function description + * + * @param dcm dcm to set quaternion to + */ + void set_from_dcm(const Dcm & dcm) { Quaternion &q = *this; q(0) = Type(0.5 * sqrt(1 + dcm(0, 0) + @@ -63,8 +135,14 @@ public: (4 * q(0))); } - Quaternion(const Euler & euler) : - Vector() + /** + * Set from euler angles + * + * More elaborate function description + * + * @param euler euler angles to set quaternion to + */ + void set_from_euler(const Euler & euler) { Quaternion &q = *this; Type cosPhi_2 = Type(cos(euler.phi() / (Type)2.0)); @@ -83,8 +161,17 @@ public: sinPhi_2 * sinTheta_2 * cosPsi_2; } - Quaternion(Type a, Type b, Type c, Type d) : - Vector() + /** + * Set from quaternion values + * + * More elaborate function description + * + * @param a set quaternion value 0 + * @param b set quaternion value 1 + * @param c set quaternion value 2 + * @param d set quaternion value 3 + */ + void set_from_quaternion(Type a, Type b, Type c, Type d) { Quaternion &q = *this; q(0) = a; @@ -93,6 +180,14 @@ public: q(3) = d; } + /** + * Quaternion multiplication operator + * + * More elaborate function description + * + * @param q quaternion to multiply with + * @return product + */ Quaternion operator*(const Quaternion &q) const { const Quaternion &p = *this; @@ -104,24 +199,53 @@ public: return r; } + /** + * Self-multiplication operator + * + * More elaborate function description + * + * @param other quaternion to multiply with + */ void operator*=(const Quaternion & other) { Quaternion &self = *this; self = self * other; } + /** + * Scalar multiplication operator + * + * More elaborate function description + * + * @param scalar scalar to multiply with + * @return product + */ Quaternion operator*(Type scalar) const { const Quaternion &q = *this; return scalar * q; } + /** + * Scalar self-multiplication operator + * + * More elaborate function description + * + * @param scalar scalar to multiply with + */ void operator*=(Type scalar) { Quaternion &q = *this; q = q * scalar; } + /** + * Computes the derivative + * + * More elaborate function description + * + * @param w direction + */ Matrix41 derivative(const Matrix31 & w) const { const Quaternion &q = *this; Type dataQ[] = { @@ -139,6 +263,11 @@ public: return Q * v * Type(0.5); } + /** + * Invert quaternion + * + * More elaborate function description + */ void invert() { Quaternion &q = *this; q(1) *= -1; @@ -146,6 +275,13 @@ public: q(3) *= -1; } + /** + * Invert quaternion + * + * More elaborate function description + * + * @return inverted quaternion + */ Quaternion inversed() { Quaternion &q = *this; Quaternion ret; @@ -156,12 +292,27 @@ public: return ret; } + /** + * Rotate quaternion from rotation vector + * + * More elaborate function description + * + * @param vec rotation vector + */ void rotate(const Vector &vec) { Quaternion res; res.from_axis_angle(vec); (*this) = (*this) * res; } + /** + * Rotation quaternion from vector + * + * More elaborate function description + * + * @param vec rotation vector + * @return quaternion representing the rotation + */ void from_axis_angle(Vector vec) { Quaternion &q = *this; Type theta = vec.norm(); @@ -174,6 +325,15 @@ public: from_axis_angle(vec,theta); } + /** + * Rotation quaternion from axis and scalar + * + * More elaborate function description + * + * @param axis axis of rotation + * @param theta scalar describing angle of rotation + * @return quaternion representing the rotation + */ void from_axis_angle(const Vector &axis, Type theta) { Quaternion &q = *this; if(theta < (Type)1e-10) { @@ -188,6 +348,14 @@ public: q(3) = axis(2) * magnitude; } + + /** + * Rotation vector from quaternion + * + * More elaborate function description + * + * @return vector, direction representing rotation axis and norm representing angle + */ Vector to_axis_angle() { Quaternion &q = *this; Type axis_magnitude = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); From af2e6d952e9cd1ae2ad6c236791115473ced94de Mon Sep 17 00:00:00 2001 From: Andreas Bircher Date: Tue, 3 May 2016 17:54:38 +0200 Subject: [PATCH 154/388] correcting comments --- matrix/Dcm.hpp | 2 +- matrix/Quaternion.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index bd622731c9..edf165bbdd 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -46,7 +46,7 @@ public: /** * Constructor from array * - * Copies the given scalar value to all matrix fields. + * More elaborate function description * * @param other array */ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index e135464537..835c97a3d1 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -37,7 +37,7 @@ public: /** * Constructor from array * - * Copies the given scalar value to all quaternion fields. + * More elaborate function description * * @param data_ array */ From e3a1d67444b1ae4f56cd92b78a9fd60c3737e5ff Mon Sep 17 00:00:00 2001 From: Andreas Bircher Date: Thu, 5 May 2016 11:04:12 +0200 Subject: [PATCH 155/388] adding detailed comments on rotation classes --- matrix/Dcm.hpp | 19 ++++++++-------- matrix/Euler.hpp | 27 +++++++++++----------- matrix/Quaternion.hpp | 53 ++++++++++++++++--------------------------- 3 files changed, 43 insertions(+), 56 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index edf165bbdd..c5c112d793 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -23,7 +23,8 @@ class Euler; /** * Direction cosine matrix class * - * More elaborate class description + * The rotation between two coordinate frames is + * described by this class. */ template class Dcm : public Matrix @@ -46,8 +47,6 @@ public: /** * Constructor from array * - * More elaborate function description - * * @param other array */ Dcm(const Type *data_) : Matrix(data_) @@ -57,8 +56,6 @@ public: /** * Copy constructor * - * More elaborate function description - * * @param other Matrix33 to set dcm to */ Dcm(const Matrix &other) : Matrix(other) @@ -68,7 +65,8 @@ public: /** * Constructor from quaternion * - * More elaborate function description + * Instance is initialized from quaternion representing + * transformation from inertial frame to body frame. * * @param q quaternion to set dcm to */ @@ -79,7 +77,8 @@ public: /** * Constructor from euler angles * - * More elaborate function description + * Instance is initialized from angle tripplet (3,2,1) representing + * transformation from body frame to inertial frame. * * @param euler euler angles to set dcm to */ @@ -91,7 +90,8 @@ public: /** * Set from quaternion * - * More elaborate function description + * Instance is set from quaternion representing + * transformation from inertial frame to body frame. * * @param q quaternion to set dcm to */ @@ -119,7 +119,8 @@ public: /** * Set from euler angles * - * More elaborate function description + * Instance is set from angle tripplet (3,2,1) representing + * transformation from body frame to inertial frame. * * @param euler euler angles to set dcm to */ diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 24ffd326df..887749b61e 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -26,7 +26,8 @@ class Quaternion; /** * Euler angles class * - * More elaborate class description + * This class describes the transformation from the body fixed frame + * to the inertial frame via 3-2-1 tait brian euler angles. */ template class Euler : public Vector @@ -36,8 +37,6 @@ public: /** * Standard constructor - * - * More elaborate function description */ Euler() : Vector() { @@ -46,8 +45,6 @@ public: /** * Copy constructor * - * More elaborate function description - * * @param other vector to copy */ Euler(const Vector & other) : @@ -58,8 +55,6 @@ public: /** * Constructor from Matrix31 * - * More elaborate function description - * * @param other Matrix31 to copy */ Euler(const Matrix & other) : @@ -70,7 +65,8 @@ public: /** * Constructor from euler angles * - * More elaborate function description + * Instance is initialized from angle tripplet (3,2,1) + * representing transformation from body frame to inertial frame. * * @param phi_ roll * @param theta_ pitch @@ -84,7 +80,8 @@ public: /** * Constructor from dcm * - * More elaborate function description + * Instance is initialized from dcm representing transformation + * from body frame to inertial frame. * * @param dcm_ dcm to set angles to */ @@ -96,7 +93,8 @@ public: /** * Constructor from quaternion * - * More elaborate function description + * Instance is initialized from quaternion representing + * transformation from body frame to inertial frame. * * @param q quaternion to set angles to */ @@ -109,7 +107,8 @@ public: /** * Set from euler angles * - * More elaborate function description + * Instance is set from angle tripplet (3,2,1) representing + * transformation from body frame to inertial frame. * * @param phi_ roll * @param theta_ pitch @@ -125,7 +124,8 @@ public: /** * Set from dcm * - * More elaborate function description + * Instance is set from dcm representing transformation + * from body frame to inertial frame. * * @param dcm_ dcm to set angles to */ @@ -152,7 +152,8 @@ public: /** * Set from dcm * - * More elaborate function description + * Instance is set from quaternion representing + * transformation from body frame to inertial frame. * * @param q quaternion to set angles to */ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 835c97a3d1..a161b42e22 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -23,7 +23,8 @@ class Euler; /** * Quaternion class * - * More elaborate class description + * The rotation between two coordinate frames is + * described by this class. */ template class Quaternion : public Vector @@ -37,8 +38,6 @@ public: /** * Constructor from array * - * More elaborate function description - * * @param data_ array */ Quaternion(const Type *data_) : @@ -48,8 +47,6 @@ public: /** * Standard constructor - * - * More elaborate function description */ Quaternion() : Vector() @@ -64,8 +61,6 @@ public: /** * Constructor from Matrix41 * - * More elaborate function description - * * @param other Matrix41 to copy */ Quaternion(const Matrix41 & other) : @@ -76,7 +71,8 @@ public: /** * Constructor from dcm * - * More elaborate function description + * Instance is initialized from a dcm representing transformation + * from inertial frame to body frame. * * @param dcm dcm to set quaternion to */ @@ -89,7 +85,8 @@ public: /** * Constructor from euler angles * - * More elaborate function description + * Instance is initialized from angle tripplet (3,2,1) representing + * transformation from body frame to inertial frame. * * @param euler euler angles to set quaternion to */ @@ -102,7 +99,8 @@ public: /** * Constructor from quaternion values * - * More elaborate function description + * Instance is initialized from quaternion values representing + * transformation from inertial frame to body frame. * * @param a set quaternion value 0 * @param b set quaternion value 1 @@ -118,7 +116,8 @@ public: /** * Set from dcm * - * More elaborate function description + * Instance is set from a dcm representing transformation + * from inertial frame to body frame. * * @param dcm dcm to set quaternion to */ @@ -138,7 +137,8 @@ public: /** * Set from euler angles * - * More elaborate function description + * Instance is set from angle tripplet (3,2,1) representing + * transformation from body frame to inertial frame. * * @param euler euler angles to set quaternion to */ @@ -164,7 +164,8 @@ public: /** * Set from quaternion values * - * More elaborate function description + * Instance is set from quaternion values representing + * transformation from inertial frame to body frame. * * @param a set quaternion value 0 * @param b set quaternion value 1 @@ -183,8 +184,6 @@ public: /** * Quaternion multiplication operator * - * More elaborate function description - * * @param q quaternion to multiply with * @return product */ @@ -202,8 +201,6 @@ public: /** * Self-multiplication operator * - * More elaborate function description - * * @param other quaternion to multiply with */ void operator*=(const Quaternion & other) @@ -215,8 +212,6 @@ public: /** * Scalar multiplication operator * - * More elaborate function description - * * @param scalar scalar to multiply with * @return product */ @@ -229,8 +224,6 @@ public: /** * Scalar self-multiplication operator * - * More elaborate function description - * * @param scalar scalar to multiply with */ void operator*=(Type scalar) @@ -242,8 +235,6 @@ public: /** * Computes the derivative * - * More elaborate function description - * * @param w direction */ Matrix41 derivative(const Matrix31 & w) const { @@ -265,8 +256,6 @@ public: /** * Invert quaternion - * - * More elaborate function description */ void invert() { Quaternion &q = *this; @@ -278,8 +267,6 @@ public: /** * Invert quaternion * - * More elaborate function description - * * @return inverted quaternion */ Quaternion inversed() { @@ -295,8 +282,6 @@ public: /** * Rotate quaternion from rotation vector * - * More elaborate function description - * * @param vec rotation vector */ void rotate(const Vector &vec) { @@ -308,7 +293,8 @@ public: /** * Rotation quaternion from vector * - * More elaborate function description + * The axis of rotation is given by vector direction and + * the angle is given by the norm. * * @param vec rotation vector * @return quaternion representing the rotation @@ -326,9 +312,7 @@ public: } /** - * Rotation quaternion from axis and scalar - * - * More elaborate function description + * Rotation quaternion from axis and angle * * @param axis axis of rotation * @param theta scalar describing angle of rotation @@ -352,7 +336,8 @@ public: /** * Rotation vector from quaternion * - * More elaborate function description + * The axis of rotation is given by vector direction and + * the angle is given by the norm. * * @return vector, direction representing rotation axis and norm representing angle */ From 3152d3d6cf43e0be3e1492f208286280b7cb8ee5 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 10 May 2016 10:46:28 +0200 Subject: [PATCH 156/388] better function descriptions for rotation classes: - do not talk specifically about body or earth frame, just use frame 1 and frame 2 --- matrix/Dcm.hpp | 23 +++++++++++++++-------- matrix/Euler.hpp | 41 +++++++++++++++++++++++++---------------- matrix/Quaternion.hpp | 28 +++++++++++++++------------- 3 files changed, 55 insertions(+), 37 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index c5c112d793..0c0e15892c 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -3,6 +3,12 @@ * * A direction cosine matrix class. * + * This library uses the convention that premultiplying a three dimensional + * vector represented in coordinate system 1 will apply a rotation from coordinate system + * 1 to coordinate system 2 to the vector. The rotation is performed following the right-hand rule. + * Likewise, a matrix instance of this class also represents a coordinate transformation + * from frame 2 to frame 1. + * * @author James Goppert */ @@ -66,7 +72,7 @@ public: * Constructor from quaternion * * Instance is initialized from quaternion representing - * transformation from inertial frame to body frame. + * coordinate transformation from frame 2 to frame 1. * * @param q quaternion to set dcm to */ @@ -77,10 +83,11 @@ public: /** * Constructor from euler angles * - * Instance is initialized from angle tripplet (3,2,1) representing - * transformation from body frame to inertial frame. + * This sets the transformation matrix from frame 2 to frame 1 where the rotation + * from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence. * - * @param euler euler angles to set dcm to + * + * @param euler euler angle instance */ Dcm(const Euler & euler) { set_from_euler(euler); @@ -91,7 +98,7 @@ public: * Set from quaternion * * Instance is set from quaternion representing - * transformation from inertial frame to body frame. + * transformation from frame 2 to frame 1. * * @param q quaternion to set dcm to */ @@ -119,10 +126,10 @@ public: /** * Set from euler angles * - * Instance is set from angle tripplet (3,2,1) representing - * transformation from body frame to inertial frame. + * This provides the transformation matrix from frame 2 to frame 1 where the rotation + * from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence * - * @param euler euler angles to set dcm to + * @param euler euler angle instannce */ void set_from_euler(const Euler & euler) { Dcm &dcm = *this; diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 887749b61e..7ac71aaf9f 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -1,7 +1,12 @@ /** * @file Euler.hpp * - * Euler angle tait-bryan body 3-2-1 + * An instance of this class defines a rotation from coordinate frame 1 to coordinate frame 2. + * It follows the convention of an intrinsic tait-bryan 3-2-1 sequence. + * In order to go from frame 1 to frame 2 we apply the following rotations consecutively. + * 1) We rotate about our initial Z axis by an angle of _psi. + * 2) We rotate about the newly created Y' axis by an angle of _theta. + * 3) We rotate about the newly created X'' axis by an angle of _phi. * * @author James Goppert */ @@ -68,9 +73,9 @@ public: * Instance is initialized from angle tripplet (3,2,1) * representing transformation from body frame to inertial frame. * - * @param phi_ roll - * @param theta_ pitch - * @param psi_ yaw + * @param phi_ rotation angle about X axis + * @param theta_ rotation angle about Y axis + * @param psi_ rotation angle about Z axis */ Euler(Type phi_, Type theta_, Type psi_) : Vector() { @@ -78,26 +83,30 @@ public: } /** - * Constructor from dcm + * Constructor from DCM matrix * - * Instance is initialized from dcm representing transformation - * from body frame to inertial frame. + * Instance is set from Dcm representing + * transformation from frame 2 to frame 1. + * This instance will hold the angles defining the rotation + * from frame 1 to frame 2. * - * @param dcm_ dcm to set angles to - */ + * @param dcm Direction cosine matrix + */ Euler(const Dcm & dcm) : Vector() { set_from_dcm(dcm); } /** - * Constructor from quaternion + * Constructor from quaternion instance. * - * Instance is initialized from quaternion representing - * transformation from body frame to inertial frame. + * Instance is set from a quaternion representing + * transformation from frame 2 to frame 1. + * This instance will hold the angles defining the rotation + * from frame 1 to frame 2. * - * @param q quaternion to set angles to - */ + * @param q quaternion + */ Euler(const Quaternion & q) : Vector() { @@ -108,7 +117,7 @@ public: * Set from euler angles * * Instance is set from angle tripplet (3,2,1) representing - * transformation from body frame to inertial frame. + * rotation from frame 1 to frame 2. * * @param phi_ roll * @param theta_ pitch @@ -125,7 +134,7 @@ public: * Set from dcm * * Instance is set from dcm representing transformation - * from body frame to inertial frame. + * from frame 2 to frame 1. * * @param dcm_ dcm to set angles to */ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a161b42e22..3f79b1c1f9 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -71,8 +71,8 @@ public: /** * Constructor from dcm * - * Instance is initialized from a dcm representing transformation - * from inertial frame to body frame. + * Instance is initialized from a dcm representing coordinate transformation + * from frame 2 to frame 1. * * @param dcm dcm to set quaternion to */ @@ -85,10 +85,11 @@ public: /** * Constructor from euler angles * - * Instance is initialized from angle tripplet (3,2,1) representing - * transformation from body frame to inertial frame. + * This sets the instance to a quaternion representing coordinate transformation from + * frame 2 to frame 1 where the rotation from frame 1 to frame 2 is described + * by a 3-2-1 intrinsic Tait-Bryan rotation sequence. * - * @param euler euler angles to set quaternion to + * @param euler euler angle instance */ Quaternion(const Euler & euler) : Vector() @@ -99,8 +100,8 @@ public: /** * Constructor from quaternion values * - * Instance is initialized from quaternion values representing - * transformation from inertial frame to body frame. + * Instance is initialized from quaternion values representing coordinate + * transformation from frame 2 to frame 1. * * @param a set quaternion value 0 * @param b set quaternion value 1 @@ -116,8 +117,8 @@ public: /** * Set from dcm * - * Instance is set from a dcm representing transformation - * from inertial frame to body frame. + * Instance is set from a dcm representing coordinate transformation + * from frame 2 to frame 1. * * @param dcm dcm to set quaternion to */ @@ -137,8 +138,9 @@ public: /** * Set from euler angles * - * Instance is set from angle tripplet (3,2,1) representing - * transformation from body frame to inertial frame. + * This sets the instance to a quaternion representing coordinate transformation from + * frame 2 to frame 1 where the rotation from frame 1 to frame 2 is described + * by a 3-2-1 intrinsic Tait-Bryan rotation sequence. * * @param euler euler angles to set quaternion to */ @@ -164,8 +166,8 @@ public: /** * Set from quaternion values * - * Instance is set from quaternion values representing - * transformation from inertial frame to body frame. + * Instance is set from quaternion values representing coordinate + * transformation from frame 2 to frame 1. * * @param a set quaternion value 0 * @param b set quaternion value 1 From 2b3bdb523d60a7980a7f88628a3d0ecf75e6675b Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 10 May 2016 11:40:35 +0200 Subject: [PATCH 157/388] better description for quaternion class --- matrix/Quaternion.hpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 3f79b1c1f9..de06c4ebe7 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -1,7 +1,9 @@ /** * @file Quaternion.hpp * - * A quaternion class. + * A quaternion instance of this class describes a rotation from + * coordinate frame 1 to corrdinate frame 2. The first element of the quaternion + * represents the real part. * * @author James Goppert */ From 1033e145a5f5064289877a007b5fd51102f01ac5 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 10 May 2016 11:48:11 +0200 Subject: [PATCH 158/388] fix some typos and better explanation of quaternion ordering --- matrix/Dcm.hpp | 2 +- matrix/Euler.hpp | 2 +- matrix/Quaternion.hpp | 4 +++- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 0c0e15892c..af40f85d65 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -53,7 +53,7 @@ public: /** * Constructor from array * - * @param other array + * @param _data pointer to array */ Dcm(const Type *data_) : Matrix(data_) { diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 7ac71aaf9f..14fac52aaf 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -136,7 +136,7 @@ public: * Instance is set from dcm representing transformation * from frame 2 to frame 1. * - * @param dcm_ dcm to set angles to + * @param dcm Direction cosine matrix instance to convert from. */ void set_from_dcm(const Dcm & dcm) { diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index de06c4ebe7..2b5443d34a 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -3,7 +3,8 @@ * * A quaternion instance of this class describes a rotation from * coordinate frame 1 to corrdinate frame 2. The first element of the quaternion - * represents the real part. + * represents the real part, thus, a quaternion representing a zero-rotation + * is define as (1,0,0,0). * * @author James Goppert */ @@ -104,6 +105,7 @@ public: * * Instance is initialized from quaternion values representing coordinate * transformation from frame 2 to frame 1. + * A zero-rotation quaternion is represented by (1,0,0,0). * * @param a set quaternion value 0 * @param b set quaternion value 1 From 10c1b49bde0a0870dfdbafcb16a97c7b80284899 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 10 May 2016 11:51:52 +0200 Subject: [PATCH 159/388] fix typo --- matrix/Quaternion.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 2b5443d34a..9efa18d757 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -2,9 +2,9 @@ * @file Quaternion.hpp * * A quaternion instance of this class describes a rotation from - * coordinate frame 1 to corrdinate frame 2. The first element of the quaternion + * coordinate frame 1 to coordinate frame 2. The first element of the quaternion * represents the real part, thus, a quaternion representing a zero-rotation - * is define as (1,0,0,0). + * is defined as (1,0,0,0). * * @author James Goppert */ From 4a405e7f603a35645e352846cd14820eaa7c4813 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 10 May 2016 13:12:51 +0200 Subject: [PATCH 160/388] make it clear that we are using right hand rotation convention --- matrix/Dcm.hpp | 3 ++- matrix/Euler.hpp | 2 ++ matrix/Quaternion.hpp | 2 ++ 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index af40f85d65..c8228ef9a3 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -2,10 +2,11 @@ * @file Dcm.hpp * * A direction cosine matrix class. + * All rotations and axis systems follow the right-hand rule. * * This library uses the convention that premultiplying a three dimensional * vector represented in coordinate system 1 will apply a rotation from coordinate system - * 1 to coordinate system 2 to the vector. The rotation is performed following the right-hand rule. + * 1 to coordinate system 2 to the vector. * Likewise, a matrix instance of this class also represents a coordinate transformation * from frame 2 to frame 1. * diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 14fac52aaf..1808f02152 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -1,6 +1,8 @@ /** * @file Euler.hpp * + * All rotations and axis systems follow the right-hand rule + * * An instance of this class defines a rotation from coordinate frame 1 to coordinate frame 2. * It follows the convention of an intrinsic tait-bryan 3-2-1 sequence. * In order to go from frame 1 to frame 2 we apply the following rotations consecutively. diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 9efa18d757..5730eab3b5 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -1,6 +1,8 @@ /** * @file Quaternion.hpp * + * All rotations and axis systems follow the right-hand rule. + * * A quaternion instance of this class describes a rotation from * coordinate frame 1 to coordinate frame 2. The first element of the quaternion * represents the real part, thus, a quaternion representing a zero-rotation From 81eacb0cfa0feb6930d3be9112fa08244cc367c5 Mon Sep 17 00:00:00 2001 From: Andreas Bircher Date: Thu, 12 May 2016 10:24:37 +0200 Subject: [PATCH 161/388] removing body and intertial frame expressions and establishing consistency --- matrix/Euler.hpp | 57 ++++++++++++++++++++++++++---------------------- 1 file changed, 31 insertions(+), 26 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 1808f02152..0f3e934703 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -4,7 +4,7 @@ * All rotations and axis systems follow the right-hand rule * * An instance of this class defines a rotation from coordinate frame 1 to coordinate frame 2. - * It follows the convention of an intrinsic tait-bryan 3-2-1 sequence. + * It follows the convention of a 3-2-1 intrinsic Tait-Bryan rotation sequence. * In order to go from frame 1 to frame 2 we apply the following rotations consecutively. * 1) We rotate about our initial Z axis by an angle of _psi. * 2) We rotate about the newly created Y' axis by an angle of _theta. @@ -33,8 +33,8 @@ class Quaternion; /** * Euler angles class * - * This class describes the transformation from the body fixed frame - * to the inertial frame via 3-2-1 tait brian euler angles. + * This class describes the rotation from frame 1 + * to frame 2 via 3-2-1 intrinsic Tait-Bryan rotation sequence. */ template class Euler : public Vector @@ -72,8 +72,9 @@ public: /** * Constructor from euler angles * - * Instance is initialized from angle tripplet (3,2,1) - * representing transformation from body frame to inertial frame. + * Instance is initialized from an 3-2-1 intrinsic Tait-Bryan + * rotation sequence representing transformation from frame 1 + * to frame 2. * * @param phi_ rotation angle about X axis * @param theta_ rotation angle about Y axis @@ -87,10 +88,10 @@ public: /** * Constructor from DCM matrix * - * Instance is set from Dcm representing - * transformation from frame 2 to frame 1. - * This instance will hold the angles defining the rotation - * from frame 1 to frame 2. + * Instance is set from Dcm representing transformation from + * frame 2 to frame 1. + * This instance will hold the angles defining the 3-2-1 intrinsic + * Tait-Bryan rotation sequence from frame 1 to frame 2. * * @param dcm Direction cosine matrix */ @@ -102,10 +103,10 @@ public: /** * Constructor from quaternion instance. * - * Instance is set from a quaternion representing - * transformation from frame 2 to frame 1. - * This instance will hold the angles defining the rotation - * from frame 1 to frame 2. + * Instance is set from a quaternion representing transformation + * from frame 2 to frame 1. + * This instance will hold the angles defining the 3-2-1 intrinsic + * Tait-Bryan rotation sequence from frame 1 to frame 2. * * @param q quaternion */ @@ -118,12 +119,12 @@ public: /** * Set from euler angles * - * Instance is set from angle tripplet (3,2,1) representing - * rotation from frame 1 to frame 2. + * Instance is set from an 3-2-1 intrinsic Tait-Bryan rotation + * sequence representing transformation from frame 1 to frame 2. * - * @param phi_ roll - * @param theta_ pitch - * @param psi_ yaw + * @param phi_ rotation angle about X axis + * @param theta_ rotation angle about Y axis + * @param psi_ rotation angle about Z axis */ void set_from_euler(Type phi_, Type theta_, Type psi_) { @@ -133,12 +134,14 @@ public: } /** - * Set from dcm + * Set from DCM matrix * - * Instance is set from dcm representing transformation - * from frame 2 to frame 1. + * Instance is set from Dcm representing transformation from + * frame 2 to frame 1. + * This instance will hold the angles defining the 3-2-1 intrinsic + * Tait-Bryan rotation sequence from frame 1 to frame 2. * - * @param dcm Direction cosine matrix instance to convert from. + * @param dcm Direction cosine matrix */ void set_from_dcm(const Dcm & dcm) { @@ -161,12 +164,14 @@ public: } /** - * Set from dcm + * Set from quaternion instance. * - * Instance is set from quaternion representing - * transformation from body frame to inertial frame. + * Instance is set from a quaternion representing transformation + * from frame 2 to frame 1. + * This instance will hold the angles defining the 3-2-1 intrinsic + * Tait-Bryan rotation sequence from frame 1 to frame 2. * - * @param q quaternion to set angles to + * @param q quaternion */ void set_from_quaternion(const Quaternion & q) { From f4e2b21608192cabe5f811fe45d0598509803548 Mon Sep 17 00:00:00 2001 From: Roman Date: Mon, 16 May 2016 09:21:44 +0200 Subject: [PATCH 162/388] - better description for quaternion class - revert conversion functions to constructor --- matrix/Dcm.hpp | 37 ++++---------------- matrix/Euler.hpp | 59 ++++--------------------------- matrix/Quaternion.hpp | 80 ++++++++++++------------------------------- 3 files changed, 34 insertions(+), 142 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index c8228ef9a3..045ebd94fb 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -78,32 +78,6 @@ public: * @param q quaternion to set dcm to */ Dcm(const Quaternion & q) { - set_from_quaternion(q); - } - - /** - * Constructor from euler angles - * - * This sets the transformation matrix from frame 2 to frame 1 where the rotation - * from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence. - * - * - * @param euler euler angle instance - */ - Dcm(const Euler & euler) { - set_from_euler(euler); - } - - - /** - * Set from quaternion - * - * Instance is set from quaternion representing - * transformation from frame 2 to frame 1. - * - * @param q quaternion to set dcm to - */ - void set_from_quaternion(const Quaternion & q) { Dcm &dcm = *this; Type a = q(0); Type b = q(1); @@ -125,14 +99,15 @@ public: } /** - * Set from euler angles + * Constructor from euler angles * - * This provides the transformation matrix from frame 2 to frame 1 where the rotation - * from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence + * This sets the transformation matrix from frame 2 to frame 1 where the rotation + * from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence. * - * @param euler euler angle instannce + * + * @param euler euler angle instance */ - void set_from_euler(const Euler & euler) { + Dcm(const Euler & euler) { Dcm &dcm = *this; Type cosPhi = Type(cos(euler.phi())); Type sinPhi = Type(sin(euler.phi())); diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 0f3e934703..88abbc58ab 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -82,7 +82,9 @@ public: */ Euler(Type phi_, Type theta_, Type psi_) : Vector() { - set_from_euler(phi_, theta_, psi_); + phi() = phi_; + theta() = theta_; + psi() = psi_; } /** @@ -96,54 +98,6 @@ public: * @param dcm Direction cosine matrix */ Euler(const Dcm & dcm) : Vector() - { - set_from_dcm(dcm); - } - - /** - * Constructor from quaternion instance. - * - * Instance is set from a quaternion representing transformation - * from frame 2 to frame 1. - * This instance will hold the angles defining the 3-2-1 intrinsic - * Tait-Bryan rotation sequence from frame 1 to frame 2. - * - * @param q quaternion - */ - Euler(const Quaternion & q) : - Vector() - { - set_from_quaternion(q); - } - - /** - * Set from euler angles - * - * Instance is set from an 3-2-1 intrinsic Tait-Bryan rotation - * sequence representing transformation from frame 1 to frame 2. - * - * @param phi_ rotation angle about X axis - * @param theta_ rotation angle about Y axis - * @param psi_ rotation angle about Z axis - */ - void set_from_euler(Type phi_, Type theta_, Type psi_) - { - phi() = phi_; - theta() = theta_; - psi() = psi_; - } - - /** - * Set from DCM matrix - * - * Instance is set from Dcm representing transformation from - * frame 2 to frame 1. - * This instance will hold the angles defining the 3-2-1 intrinsic - * Tait-Bryan rotation sequence from frame 1 to frame 2. - * - * @param dcm Direction cosine matrix - */ - void set_from_dcm(const Dcm & dcm) { Type phi_val = Type(atan2(dcm(2,1), dcm(2,2))); Type theta_val = Type(asin(-dcm(2,0))); @@ -164,7 +118,7 @@ public: } /** - * Set from quaternion instance. + * Constructor from quaternion instance. * * Instance is set from a quaternion representing transformation * from frame 2 to frame 1. @@ -172,8 +126,9 @@ public: * Tait-Bryan rotation sequence from frame 1 to frame 2. * * @param q quaternion - */ - void set_from_quaternion(const Quaternion & q) + */ + Euler(const Quaternion & q) : + Vector() { *this = Euler(Dcm(q)); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 5730eab3b5..6965a37e87 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -3,8 +3,13 @@ * * All rotations and axis systems follow the right-hand rule. * - * A quaternion instance of this class describes a rotation from - * coordinate frame 1 to coordinate frame 2. The first element of the quaternion + * In order to rotate a vector v by a righthand rotation defined by the quaternion q + * one can use the following operation: + * v_rotated = q^(-1) * [0;v] * q + * where q^(-1) represents the inverse of the quaternion q. + * The product z of two quaternions z = q1 * q2 represents an intrinsic rotation + * in the order of first q1 followed by q2. + * The first element of the quaternion * represents the real part, thus, a quaternion representing a zero-rotation * is defined as (1,0,0,0). * @@ -84,7 +89,15 @@ public: Quaternion(const Dcm & dcm) : Vector() { - set_from_dcm(dcm); + Quaternion &q = *this; + q(0) = Type(0.5 * sqrt(1 + dcm(0, 0) + + dcm(1, 1) + dcm(2, 2))); + q(1) = Type((dcm(2, 1) - dcm(1, 2)) / + (4 * q(0))); + q(2) = Type((dcm(0, 2) - dcm(2, 0)) / + (4 * q(0))); + q(3) = Type((dcm(1, 0) - dcm(0, 1)) / + (4 * q(0))); } /** @@ -98,59 +111,6 @@ public: */ Quaternion(const Euler & euler) : Vector() - { - set_from_euler(euler); - } - - /** - * Constructor from quaternion values - * - * Instance is initialized from quaternion values representing coordinate - * transformation from frame 2 to frame 1. - * A zero-rotation quaternion is represented by (1,0,0,0). - * - * @param a set quaternion value 0 - * @param b set quaternion value 1 - * @param c set quaternion value 2 - * @param d set quaternion value 3 - */ - Quaternion(Type a, Type b, Type c, Type d) : - Vector() - { - set_from_quaternion(a, b, c, d); - } - - /** - * Set from dcm - * - * Instance is set from a dcm representing coordinate transformation - * from frame 2 to frame 1. - * - * @param dcm dcm to set quaternion to - */ - void set_from_dcm(const Dcm & dcm) - { - Quaternion &q = *this; - q(0) = Type(0.5 * sqrt(1 + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2))); - q(1) = Type((dcm(2, 1) - dcm(1, 2)) / - (4 * q(0))); - q(2) = Type((dcm(0, 2) - dcm(2, 0)) / - (4 * q(0))); - q(3) = Type((dcm(1, 0) - dcm(0, 1)) / - (4 * q(0))); - } - - /** - * Set from euler angles - * - * This sets the instance to a quaternion representing coordinate transformation from - * frame 2 to frame 1 where the rotation from frame 1 to frame 2 is described - * by a 3-2-1 intrinsic Tait-Bryan rotation sequence. - * - * @param euler euler angles to set quaternion to - */ - void set_from_euler(const Euler & euler) { Quaternion &q = *this; Type cosPhi_2 = Type(cos(euler.phi() / (Type)2.0)); @@ -170,17 +130,19 @@ public: } /** - * Set from quaternion values + * Constructor from quaternion values * - * Instance is set from quaternion values representing coordinate + * Instance is initialized from quaternion values representing coordinate * transformation from frame 2 to frame 1. + * A zero-rotation quaternion is represented by (1,0,0,0). * * @param a set quaternion value 0 * @param b set quaternion value 1 * @param c set quaternion value 2 * @param d set quaternion value 3 */ - void set_from_quaternion(Type a, Type b, Type c, Type d) + Quaternion(Type a, Type b, Type c, Type d) : + Vector() { Quaternion &q = *this; q(0) = a; From eeb595d1dbdc53c67e1026eb8a71af8d91bef24f Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 17 May 2016 08:27:35 +0200 Subject: [PATCH 163/388] applied formatting --- matrix/Euler.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 88abbc58ab..4178f21e56 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -74,7 +74,7 @@ public: * * Instance is initialized from an 3-2-1 intrinsic Tait-Bryan * rotation sequence representing transformation from frame 1 - * to frame 2. + * to frame 2. * * @param phi_ rotation angle about X axis * @param theta_ rotation angle about Y axis From 3c87ae78ff4d80d1643b72afd2783478e87b8e5b Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Wed, 25 May 2016 15:24:35 +0200 Subject: [PATCH 164/388] added two more examples to the README --- README.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/README.md b/README.md index cf5c05c62c..5f76ae7bae 100644 --- a/README.md +++ b/README.md @@ -47,6 +47,12 @@ See the test directory for detailed examples. Some simple examples are included // convert to DCM from quaternion Dcmf dcm(q_nb); + // you can assign a rotation instance that already exist to another rotation instance, e.g. + dcm = euler; + + // you can also directly create a DCM instance from euler angles like this + dcm = Eulerf(roll, pitch, yaw); + // do some kalman filtering const size_t n_x = 5; const size_t n_y = 3; From b1f76782f6812f502022fbf2e8505656f262f941 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 5 Jul 2016 23:00:35 +0200 Subject: [PATCH 165/388] Euler, Quaternion: fix compiler errors for GCC 6.1.1 (#23) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Euler, Quaternion: fix compiler errors for GCC 6.1.1 GCC output: error: implicit conversion from ‘float’ to ‘double’ to match other operand of binary expression [-Werror=double-promotion] * astyle: fix formatting for Euler.hpp & Quaternion.hpp --- matrix/Euler.hpp | 41 +++++++++++++--------- matrix/Quaternion.hpp | 81 +++++++++++++++++++++++++------------------ 2 files changed, 71 insertions(+), 51 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 4178f21e56..7c320eb1f6 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -54,7 +54,7 @@ public: * * @param other vector to copy */ - Euler(const Vector & other) : + Euler(const Vector &other) : Vector(other) { } @@ -64,7 +64,7 @@ public: * * @param other Matrix31 to copy */ - Euler(const Matrix & other) : + Euler(const Matrix &other) : Vector(other) { } @@ -97,19 +97,20 @@ public: * * @param dcm Direction cosine matrix */ - Euler(const Dcm & dcm) : Vector() + Euler(const Dcm &dcm) : Vector() { - Type phi_val = Type(atan2(dcm(2,1), dcm(2,2))); - Type theta_val = Type(asin(-dcm(2,0))); - Type psi_val = Type(atan2(dcm(1,0), dcm(0,0))); + Type phi_val = Type(atan2(dcm(2, 1), dcm(2, 2))); + Type theta_val = Type(asin(-dcm(2, 0))); + Type psi_val = Type(atan2(dcm(1, 0), dcm(0, 0))); Type pi = Type(M_PI); - if (fabs(theta_val - pi/2) < 1.0e-3) { + if (Type(fabs(theta_val - pi / Type(2))) < Type(1.0e-3)) { phi_val = Type(0.0); - psi_val = Type(atan2(dcm(1,2), dcm(0,2))); - } else if (Type(fabs(theta_val + pi/2)) < Type(1.0e-3)) { + psi_val = Type(atan2(dcm(1, 2), dcm(0, 2))); + + } else if (Type(fabs(theta_val + pi / Type(2))) < Type(1.0e-3)) { phi_val = Type(0.0); - psi_val = Type(atan2(-dcm(1,2), -dcm(0,2))); + psi_val = Type(atan2(-dcm(1, 2), -dcm(0, 2))); } phi() = phi_val; @@ -127,29 +128,35 @@ public: * * @param q quaternion */ - Euler(const Quaternion & q) : + Euler(const Quaternion &q) : Vector() { *this = Euler(Dcm(q)); } - inline Type phi() const { + inline Type phi() const + { return (*this)(0); } - inline Type theta() const { + inline Type theta() const + { return (*this)(1); } - inline Type psi() const { + inline Type psi() const + { return (*this)(2); } - inline Type & phi() { + inline Type &phi() + { return (*this)(0); } - inline Type & theta() { + inline Type &theta() + { return (*this)(1); } - inline Type & psi() { + inline Type &psi() + { return (*this)(2); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 6965a37e87..fdb46c558f 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -73,7 +73,7 @@ public: * * @param other Matrix41 to copy */ - Quaternion(const Matrix41 & other) : + Quaternion(const Matrix41 &other) : Vector(other) { } @@ -86,18 +86,18 @@ public: * * @param dcm dcm to set quaternion to */ - Quaternion(const Dcm & dcm) : + Quaternion(const Dcm &dcm) : Vector() { Quaternion &q = *this; - q(0) = Type(0.5 * sqrt(1 + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2))); + q(0) = Type(0.5) * Type(sqrt(Type(1) + dcm(0, 0) + + dcm(1, 1) + dcm(2, 2))); q(1) = Type((dcm(2, 1) - dcm(1, 2)) / - (4 * q(0))); + (Type(4) * q(0))); q(2) = Type((dcm(0, 2) - dcm(2, 0)) / - (4 * q(0))); + (Type(4) * q(0))); q(3) = Type((dcm(1, 0) - dcm(0, 1)) / - (4 * q(0))); + (Type(4) * q(0))); } /** @@ -109,7 +109,7 @@ public: * * @param euler euler angle instance */ - Quaternion(const Euler & euler) : + Quaternion(const Euler &euler) : Vector() { Quaternion &q = *this; @@ -161,10 +161,10 @@ public: { const Quaternion &p = *this; Quaternion r; - r(0) = p(0)*q(0) - p(1)*q(1) - p(2)*q(2) - p(3)*q(3); - r(1) = p(0)*q(1) + p(1)*q(0) - p(2)*q(3) + p(3)*q(2); - r(2) = p(0)*q(2) + p(1)*q(3) + p(2)*q(0) - p(3)*q(1); - r(3) = p(0)*q(3) - p(1)*q(2) + p(2)*q(1) + p(3)*q(0); + r(0) = p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3); + r(1) = p(0) * q(1) + p(1) * q(0) - p(2) * q(3) + p(3) * q(2); + r(2) = p(0) * q(2) + p(1) * q(3) + p(2) * q(0) - p(3) * q(1); + r(3) = p(0) * q(3) - p(1) * q(2) + p(2) * q(1) + p(3) * q(0); return r; } @@ -173,7 +173,7 @@ public: * * @param other quaternion to multiply with */ - void operator*=(const Quaternion & other) + void operator*=(const Quaternion &other) { Quaternion &self = *this; self = self * other; @@ -207,7 +207,8 @@ public: * * @param w direction */ - Matrix41 derivative(const Matrix31 & w) const { + Matrix41 derivative(const Matrix31 &w) const + { const Quaternion &q = *this; Type dataQ[] = { q(0), -q(1), -q(2), -q(3), @@ -218,16 +219,17 @@ public: Matrix Q(dataQ); Vector v; v(0) = 0; - v(1) = w(0,0); - v(2) = w(1,0); - v(3) = w(2,0); + v(1) = w(0, 0); + v(2) = w(1, 0); + v(3) = w(2, 0); return Q * v * Type(0.5); } /** * Invert quaternion */ - void invert() { + void invert() + { Quaternion &q = *this; q(1) *= -1; q(2) *= -1; @@ -239,7 +241,8 @@ public: * * @return inverted quaternion */ - Quaternion inversed() { + Quaternion inversed() + { Quaternion &q = *this; Quaternion ret; ret(0) = q(0); @@ -254,7 +257,8 @@ public: * * @param vec rotation vector */ - void rotate(const Vector &vec) { + void rotate(const Vector &vec) + { Quaternion res; res.from_axis_angle(vec); (*this) = (*this) * res; @@ -269,16 +273,19 @@ public: * @param vec rotation vector * @return quaternion representing the rotation */ - void from_axis_angle(Vector vec) { + void from_axis_angle(Vector vec) + { Quaternion &q = *this; Type theta = vec.norm(); - if(theta < (Type)1e-10) { + + if (theta < (Type)1e-10) { q(0) = (Type)1.0; - q(1)=q(2)=q(3)=0; + q(1) = q(2) = q(3) = 0; return; } + vec /= theta; - from_axis_angle(vec,theta); + from_axis_angle(vec, theta); } /** @@ -288,15 +295,18 @@ public: * @param theta scalar describing angle of rotation * @return quaternion representing the rotation */ - void from_axis_angle(const Vector &axis, Type theta) { + void from_axis_angle(const Vector &axis, Type theta) + { Quaternion &q = *this; - if(theta < (Type)1e-10) { - q(0) = (Type)1.0; - q(1)=q(2)=q(3)=0; - } - Type magnitude = sinf(theta/2.0f); - q(0) = cosf(theta/2.0f); + if (theta < (Type)1e-10) { + q(0) = (Type)1.0; + q(1) = q(2) = q(3) = 0; + } + + Type magnitude = sinf(theta / 2.0f); + + q(0) = cosf(theta / 2.0f); q(1) = axis(0) * magnitude; q(2) = axis(1) * magnitude; q(3) = axis(2) * magnitude; @@ -311,17 +321,20 @@ public: * * @return vector, direction representing rotation axis and norm representing angle */ - Vector to_axis_angle() { + Vector to_axis_angle() + { Quaternion &q = *this; Type axis_magnitude = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); Vector vec; vec(0) = q(1); vec(1) = q(2); vec(2) = q(3); - if(axis_magnitude >= (Type)1e-10) { + + if (axis_magnitude >= (Type)1e-10) { vec = vec / axis_magnitude; - vec = vec * wrap_pi((Type)2.0 * atan2f(axis_magnitude,q(0))); + vec = vec * wrap_pi((Type)2.0 * atan2f(axis_magnitude, q(0))); } + return vec; } }; From 42eadb2656dac2433f5a07b67d603b2bbfaf651c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 5 Jul 2016 23:09:25 +0200 Subject: [PATCH 166/388] format.sh: better inform the user what to do on style issues (#24) --- scripts/format.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/scripts/format.sh b/scripts/format.sh index bd06600bff..c56cbef8e1 100755 --- a/scripts/format.sh +++ b/scripts/format.sh @@ -15,11 +15,12 @@ then echo formatting $astyle ${format_wildcards} else - echo checking format - $astyle --dry-run ${format_wildcards} | grep Formatted + echo checking format... + $astyle --dry-run ${format_wildcards} | grep Formatted &>/dev/null if [[ $? -eq 0 ]] then - echo need to format + echo Error: need to format + echo "run './scripts/format.sh astyle 1'" exit 1 fi echo no formatting needed From 3320d57f63cf21ea3495ef5b295409adc0b811b8 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 17:13:41 -0400 Subject: [PATCH 167/388] Fix format.sh user message. --- scripts/format.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/format.sh b/scripts/format.sh index c56cbef8e1..3e1a23f4b3 100755 --- a/scripts/format.sh +++ b/scripts/format.sh @@ -20,7 +20,7 @@ else if [[ $? -eq 0 ]] then echo Error: need to format - echo "run './scripts/format.sh astyle 1'" + echo "From cmake build directory run: 'make format'" exit 1 fi echo no formatting needed From 0f41af271a9998aa1656fb43c56ab8eef80941de Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 20:59:42 -0400 Subject: [PATCH 168/388] Added axis angle attitude representation. (#25) --- CMakeLists.txt | 4 +- matrix/AxisAngle.hpp | 158 ++++++++++++++++++++++++++++++++++++++ matrix/Dcm.hpp | 19 +++++ matrix/Quaternion.hpp | 28 +++++++ matrix/math.hpp | 1 + test/attitude.cpp | 31 ++++++++ test/matrixAssignment.cpp | 4 + 7 files changed, 243 insertions(+), 2 deletions(-) create mode 100644 matrix/AxisAngle.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 206deffa5c..d3eaab047e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8) -set(VERSION_MAJOR "0") -set(VERSION_MINOR "1") +set(VERSION_MAJOR "1") +set(VERSION_MINOR "0") set(VERSION_PATCH "0") project(matrix CXX) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp new file mode 100644 index 0000000000..f52e331e5b --- /dev/null +++ b/matrix/AxisAngle.hpp @@ -0,0 +1,158 @@ +/** + * @file AxisAngle.hpp + * + * @author James Goppert + */ + +#pragma once + +#include "math.hpp" +#include "helper_functions.hpp" + +namespace matrix +{ + +template +class Dcm; + +template +class Euler; + +template +class AxisAngle; + +/** + * AxisAngle class + * + * The rotation between two coordinate frames is + * described by this class. + */ +template +class AxisAngle : public Vector +{ +public: + virtual ~AxisAngle() {}; + + typedef Matrix Matrix31; + + /** + * Constructor from array + * + * @param data_ array + */ + AxisAngle(const Type *data_) : + Vector(data_) + { + } + + /** + * Standard constructor + */ + AxisAngle() : + Vector() + { + } + + /** + * Constructor from Matrix31 + * + * @param other Matrix31 to copy + */ + AxisAngle(const Matrix31 &other) : + Vector(other) + { + } + + /** + * Constructor from quaternion + * + * This sets the instance from a quaternion representing coordinate transformation from + * frame 2 to frame 1 where the rotation from frame 1 to frame 2 is described + * by a 3-2-1 intrinsic Tait-Bryan rotation sequence. + * + * @param q quaternion + */ + AxisAngle(const Quaternion &q) : + Vector() + { + AxisAngle &v = *this; + Type angle = (Type)2.0f*acosf(q(0)); + Type mag = sinf(angle/2.0f); + v(0) = angle*q(1)/mag; + v(1) = angle*q(2)/mag; + v(2) = angle*q(3)/mag; + } + + /** + * Constructor from dcm + * + * Instance is initialized from a dcm representing coordinate transformation + * from frame 2 to frame 1. + * + * @param dcm dcm to set quaternion to + */ + AxisAngle(const Dcm &dcm) : + Vector() + { + AxisAngle &v = *this; + v = Quaternion(dcm); + } + + /** + * Constructor from euler angles + * + * This sets the instance to a quaternion representing coordinate transformation from + * frame 2 to frame 1 where the rotation from frame 1 to frame 2 is described + * by a 3-2-1 intrinsic Tait-Bryan rotation sequence. + * + * @param euler euler angle instance + */ + AxisAngle(const Euler &euler) : + Vector() + { + AxisAngle &v = *this; + v = Quaternion(euler); + } + + /** + * Constructor from 3 axis angle values (unit vector * angle) + * + * @param x r_x*angle + * @param y r_y*angle + * @param z r_z*angle + */ + AxisAngle(Type x, Type y, Type z) : + Vector() + { + AxisAngle &v = *this; + v(0) = x; + v(1) = y; + v(2) = z; + } + + /** + * Constructor from axis and angle + * + * @param x r_x*angle + * @param x r_x*angle + * @param y r_y*angle + * @param z r_z*angle + */ + AxisAngle(const Matrix31 & axis, Type angle) : + Vector() + { + AxisAngle &v = *this; + // make sure axis is a unit vector + Vector a = axis; + a = a.unit(); + v(0) = a(0)*angle; + v(1) = a(1)*angle; + v(2) = a(2)*angle; + } +}; + +typedef AxisAngle AxisAnglef; + +} // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 045ebd94fb..b7b7ac6f00 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -27,6 +27,10 @@ class Quaternion; template class Euler; +template +class AxisAngle; + + /** * Direction cosine matrix class * @@ -129,6 +133,21 @@ public: dcm(2, 2) = cosPhi * cosThe; } + + /** + * Constructor from axis angle + * + * This sets the transformation matrix from frame 2 to frame 1 where the rotation + * from frame 1 to frame 2 is described by a 3-2-1 intrinsic Tait-Bryan rotation sequence. + * + * + * @param euler euler angle instance + */ + Dcm(const AxisAngle & aa) { + Dcm &dcm = *this; + dcm = Quaternion(aa); + } + Vector vee() const { // inverse to Vector.hat() operation const Dcm &A(*this); Vector v; diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index fdb46c558f..2cadf6e2d6 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -30,6 +30,10 @@ class Dcm; template class Euler; +template +class AxisAngle; + + /** * Quaternion class * @@ -129,6 +133,30 @@ public: sinPhi_2 * sinTheta_2 * cosPsi_2; } + /** + * Quaternion from AxisAngle + * + * @param aa axis-angle vector + */ + Quaternion(const AxisAngle &aa) : + Vector() + { + Quaternion &q = *this; + Type angle = aa.norm(); + Vector axis = aa.unit(); + if (angle < (Type)1e-10) { + q(0) = (Type)1.0; + q(1) = q(2) = q(3) = 0; + } else { + Type magnitude = sinf(angle / 2.0f); + q(0) = cosf(angle / 2.0f); + q(1) = axis(0) * magnitude; + q(2) = axis(1) * magnitude; + q(3) = axis(2) * magnitude; + } + } + + /** * Constructor from quaternion values * diff --git a/matrix/math.hpp b/matrix/math.hpp index ef5facc74d..b69d2e0eec 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -12,3 +12,4 @@ #include "Dcm.hpp" #include "Scalar.hpp" #include "Quaternion.hpp" +#include "AxisAngle.hpp" diff --git a/test/attitude.cpp b/test/attitude.cpp index 50405b6003..e0a9642e3a 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -6,9 +6,16 @@ using namespace matrix; +// important to list all classes here for coverage template class Quaternion; template class Euler; template class Dcm; +template class AxisAngle; +template class Scalar; +template class SquareMatrix; +template class Vector; +template class Vector2; +template class Vector3; int main() { @@ -238,6 +245,30 @@ int main() for(int i = 0; i < 4; i++) TEST(fabsf(q_from_array(i) - q_array[i]) < eps); + // axis angle + AxisAnglef aa_true(Vector3f(1.0f, 2.0f, 3.0f)); + TEST(isEqual(aa_true, Vector3f(1.0f, 2.0f, 3.0f))); + AxisAnglef aa_empty; + TEST(isEqual(aa_empty, AxisAnglef(0.0f, 0.0f, 0.0f))); + float aa_data[] = {4.0f, 5.0f, 6.0f}; + AxisAnglef aa_data_init(aa_data); + TEST(isEqual(aa_data_init, AxisAnglef(4.0f, 5.0f, 6.0f))); + + q = Quatf(-0.29555112749297824f, 0.25532186f, 0.51064372f, 0.76596558f); + AxisAnglef aa_q_init(q); + TEST(isEqual(aa_q_init, AxisAnglef(1.0f, 2.0f, 3.0f))); + + AxisAnglef aa_euler_init(Eulerf(0.0f, 0.0f, 0.0f)); + TEST(isEqual(aa_euler_init, Vector3f(0.0f, 0.0f, 1.0f))); + + Dcmf dcm_aa_check = AxisAnglef(dcm_check); + TEST(isEqual(dcm_aa_check, dcm_check)); + + AxisAnglef aa_axis_angle_init(Vector3f(1.0f, 2.0f, 3.0f), 3.0f); + TEST(isEqual(aa_axis_angle_init, Vector3f(0.80178373f, 1.60356745f, 2.40535118f))); + + TEST(isEqual(Quatf((AxisAnglef(Vector3f(0.0f, 0.0f, 1.0f), 0.0f))), + Quatf(1.0f, 0.0f, 0.0f, 0.0f))); }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 7a3aa56b8b..d6097526f1 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -90,7 +90,11 @@ int main() Scalar s; s = 1; + float const & s_float = (const Scalar)s; + const Vector & s_vect = s; TEST(fabs(s - 1) < 1e-5); + TEST(fabs(s_float - 1.0f) < 1e-5); + TEST(fabs(s_vect(0) - 1.0f) < 1e-5); Matrix m5 = s; TEST(fabs(m5(0,0) - s) < 1e-5); From 298e037f3abcb5eb67bee5048cb7f861e79a27c4 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 21:06:48 -0400 Subject: [PATCH 169/388] Added AxisAngle to README. --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/README.md b/README.md index 5f76ae7bae..314c6f2c82 100644 --- a/README.md +++ b/README.md @@ -53,6 +53,15 @@ See the test directory for detailed examples. Some simple examples are included // you can also directly create a DCM instance from euler angles like this dcm = Eulerf(roll, pitch, yaw); + // create an axis angle representation from euler angles + AxisAngle axis_angle = euler; + + // use axis angle to initialize a DCM + Dcmf dcm2(AxisAngle(1, 2, 3)); + + // use axis angle with axis/angle separated to init DCM + Dcmf dcm2(AxisAngle(Vector3f(1, 0, 0), 0.2)); + // do some kalman filtering const size_t n_x = 5; const size_t n_y = 3; From b78e124b73159df3373a877288fdbccd85040a33 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 21:08:12 -0400 Subject: [PATCH 170/388] Fix for README. --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 314c6f2c82..4179692fbb 100644 --- a/README.md +++ b/README.md @@ -23,6 +23,7 @@ A simple and efficient template based matrix library. * Quaternion * Dcm * Euler (Body 321) + * Axis Angle * matrix/filter.hpp : Provides filtering routines. * kalman_correct From 0b1bed6b00096248b81d65ec2be45843e20620b5 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 21:16:17 -0400 Subject: [PATCH 171/388] Added deprecation warnings in source code. --- matrix/Quaternion.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 2cadf6e2d6..1ebb42520f 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -282,6 +282,7 @@ public: /** * Rotate quaternion from rotation vector + * TODO replace with AxisAngle call * * @param vec rotation vector */ @@ -318,6 +319,7 @@ public: /** * Rotation quaternion from axis and angle + * XXX DEPRECATED, use AxisAngle class * * @param axis axis of rotation * @param theta scalar describing angle of rotation @@ -343,6 +345,7 @@ public: /** * Rotation vector from quaternion + * XXX DEPRECATED, use AxisAngle class * * The axis of rotation is given by vector direction and * the angle is given by the norm. From fdf00d163c438e782fd9e180fce0627e6f8aece1 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 21:27:42 -0400 Subject: [PATCH 172/388] Small fix to README. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 4179692fbb..0b2ba53175 100644 --- a/README.md +++ b/README.md @@ -61,7 +61,7 @@ See the test directory for detailed examples. Some simple examples are included Dcmf dcm2(AxisAngle(1, 2, 3)); // use axis angle with axis/angle separated to init DCM - Dcmf dcm2(AxisAngle(Vector3f(1, 0, 0), 0.2)); + Dcmf dcm3(AxisAngle(Vector3f(1, 0, 0), 0.2)); // do some kalman filtering const size_t n_x = 5; From 7b7297b674228f07eadda0bd09aad5c0006e204f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 5 Jul 2016 21:30:22 -0400 Subject: [PATCH 173/388] Fix for ctor comments on axis angle. --- matrix/AxisAngle.hpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index f52e331e5b..05951e24de 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -133,10 +133,8 @@ public: /** * Constructor from axis and angle * - * @param x r_x*angle - * @param x r_x*angle - * @param y r_y*angle - * @param z r_z*angle + * @param axis An axis of rotation, normalized if not unit length + * @param angle The amount to rotate */ AxisAngle(const Matrix31 & axis, Type angle) : Vector() From 9353e4cb647690b1820eb85c5b6ac055b9cb6377 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 6 Jul 2016 01:37:50 -0400 Subject: [PATCH 174/388] Fix bugs in axis angle. --- matrix/AxisAngle.hpp | 16 +++++++++++----- test/attitude.cpp | 2 +- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 05951e24de..d21e893e6d 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -78,9 +78,15 @@ public: AxisAngle &v = *this; Type angle = (Type)2.0f*acosf(q(0)); Type mag = sinf(angle/2.0f); - v(0) = angle*q(1)/mag; - v(1) = angle*q(2)/mag; - v(2) = angle*q(3)/mag; + if (fabs(angle) < 1e-10f) { + v(0) = 0; + v(1) = 0; + v(2) = 0; + } else { + v(0) = angle*q(1)/mag; + v(1) = angle*q(2)/mag; + v(2) = angle*q(3)/mag; + } } /** @@ -95,7 +101,7 @@ public: Vector() { AxisAngle &v = *this; - v = Quaternion(dcm); + v = Quaternion(dcm); } /** @@ -111,7 +117,7 @@ public: Vector() { AxisAngle &v = *this; - v = Quaternion(euler); + v = Quaternion(euler); } /** diff --git a/test/attitude.cpp b/test/attitude.cpp index e0a9642e3a..764f3143f7 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -259,7 +259,7 @@ int main() TEST(isEqual(aa_q_init, AxisAnglef(1.0f, 2.0f, 3.0f))); AxisAnglef aa_euler_init(Eulerf(0.0f, 0.0f, 0.0f)); - TEST(isEqual(aa_euler_init, Vector3f(0.0f, 0.0f, 1.0f))); + TEST(isEqual(aa_euler_init, Vector3f(0.0f, 0.0f, 0.0f))); Dcmf dcm_aa_check = AxisAnglef(dcm_check); TEST(isEqual(dcm_aa_check, dcm_check)); From cbb7e06a1fa7e20304c3ca3099b18c704da6c3a4 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 6 Jul 2016 01:39:06 -0400 Subject: [PATCH 175/388] Replace float with Type in kalman. --- matrix/filter.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/filter.hpp b/matrix/filter.hpp index 1841d1460e..7951cb3cb0 100644 --- a/matrix/filter.hpp +++ b/matrix/filter.hpp @@ -12,7 +12,7 @@ int kalman_correct( const Matrix &r, Matrix & dx, Matrix & dP, - float & beta + Type & beta ) { SquareMatrix S_I = SquareMatrix(C*P*C.T() + R).I(); From c563c41cd40b794a5407647220e1261d000b2e3d Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 6 Jul 2016 01:56:24 -0400 Subject: [PATCH 176/388] Fix cmake version. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d3eaab047e..0aa8052b24 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8) set(VERSION_MAJOR "1") set(VERSION_MINOR "0") -set(VERSION_PATCH "0") +set(VERSION_PATCH "1") project(matrix CXX) From e6a6b4680c84c7796afe0fd8cccef867b8c86cc4 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 01:03:23 -0400 Subject: [PATCH 177/388] Use quaternion multiplaction for quaternion derivative. --- matrix/Matrix.hpp | 2 +- matrix/Quaternion.hpp | 15 ++------------- test/attitude.cpp | 6 +++++- 3 files changed, 8 insertions(+), 15 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index c9c88b4efe..3188c553d1 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -278,7 +278,7 @@ public: const Matrix &self = *this; for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - snprintf(buf + strlen(buf), n - strlen(buf), "\t%.2g", double(self(i, j))); // directly append to the string buffer + snprintf(buf + strlen(buf), n - strlen(buf), "\t%g", double(self(i, j))); // directly append to the string buffer } snprintf(buf + strlen(buf), n - strlen(buf), "\n"); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 1ebb42520f..6917357fbf 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -238,19 +238,8 @@ public: Matrix41 derivative(const Matrix31 &w) const { const Quaternion &q = *this; - Type dataQ[] = { - q(0), -q(1), -q(2), -q(3), - q(1), q(0), -q(3), q(2), - q(2), q(3), q(0), -q(1), - q(3), -q(2), q(1), q(0) - }; - Matrix Q(dataQ); - Vector v; - v(0) = 0; - v(1) = w(0, 0); - v(2) = w(1, 0); - v(3) = w(2, 0); - return Q * v * Type(0.5); + Quaternion v(0, w(0, 0), w(1, 0), w(2, 0)); + return v * q * Type(0.5); } /** diff --git a/test/attitude.cpp b/test/attitude.cpp index 764f3143f7..789b7aeb23 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -157,7 +157,11 @@ int main() TEST(isEqual(q_from_m, m4)); // quaternion derivate - Vector q_dot = q.derivative(Vector3f(1, 2, 3)); + Quatf q1(0, 1, 0, 0); + Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); + float data_q_dot_check[] = {-0.5f, 0.0f, -1.5f, 1.0f}; + Vector q1_dot_check(data_q_dot_check); + TEST(isEqual(q1_dot, q1_dot_check)); // quaternion product Quatf q_prod_check( From 19554c4470cd6322ffd18cb20a96485940f226b6 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 03:59:06 -0400 Subject: [PATCH 178/388] Use Hamilton quaternion definition. --- matrix/Quaternion.hpp | 18 ++++++++++++++---- test/attitude.cpp | 20 +++++++++++++------- 2 files changed, 27 insertions(+), 11 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 6917357fbf..a96d8217bc 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -13,6 +13,16 @@ * represents the real part, thus, a quaternion representing a zero-rotation * is defined as (1,0,0,0). * + * Using Hamilton Quaternion + * - https://en.wikipedia.org/wiki/Quaternion + * - http://www.iri.upc.edu/people/jsola/JoanSola/objectes/notes/kinematics.pdf + * - Components (q_w, q_v) where q_w is the scalar and q_v is a vector + * - algebrea: i*j = k + * - handedness: right + * - function: passive (rotation operator rotates frames) + * - right-to-left product means local-to-global, q_GL + * default operator v_G = q x v_L x q* + * * @author James Goppert */ @@ -190,9 +200,9 @@ public: const Quaternion &p = *this; Quaternion r; r(0) = p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3); - r(1) = p(0) * q(1) + p(1) * q(0) - p(2) * q(3) + p(3) * q(2); - r(2) = p(0) * q(2) + p(1) * q(3) + p(2) * q(0) - p(3) * q(1); - r(3) = p(0) * q(3) - p(1) * q(2) + p(2) * q(1) + p(3) * q(0); + r(1) = p(0) * q(1) + p(1) * q(0) + p(2) * q(3) - p(3) * q(2); + r(2) = p(0) * q(2) - p(1) * q(3) + p(2) * q(0) + p(3) * q(1); + r(3) = p(0) * q(3) + p(1) * q(2) - p(2) * q(1) + p(3) * q(0); return r; } @@ -239,7 +249,7 @@ public: { const Quaternion &q = *this; Quaternion v(0, w(0, 0), w(1, 0), w(2, 0)); - return v * q * Type(0.5); + return q * v * Type(0.5); } /** diff --git a/test/attitude.cpp b/test/attitude.cpp index 789b7aeb23..b13bf73c2c 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -156,6 +156,19 @@ int main() Quatf q_from_m(m4); TEST(isEqual(q_from_m, m4)); + // quaternion product + Quatf q3(0, 0, 0, 1); + Quatf q4(AxisAnglef(0, 0, float(2*M_PI))); + q4 *= q4; + q4 *= q3; + TEST(isEqual(q3, q4)); + + q3 = Quatf(0, 0, 0, 1); + q4 = AxisAnglef(0, 0, float(M_PI/2)); + q4 *= q4; + q4 *= q3; + TEST(isEqual(Quatf(-1, 0, 0, 0), q4)); + // quaternion derivate Quatf q1(0, 1, 0, 0); Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); @@ -163,13 +176,6 @@ int main() Vector q1_dot_check(data_q_dot_check); TEST(isEqual(q1_dot, q1_dot_check)); - // quaternion product - Quatf q_prod_check( - 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); - TEST(isEqual(q_prod_check, q_check*q_check)); - q_check *= q_check; - TEST(isEqual(q_prod_check, q_check)); - // Quaternion scalar multiplication float scalar = 0.5; Quatf q_scalar_mul(1.0f, 2.0f, 3.0f, 4.0f); From 4f13809420704e8bc0ee087b140a216fb8cc8d9d Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 11:05:01 -0400 Subject: [PATCH 179/388] Added axis angle accessors, removed == operator. --- matrix/AxisAngle.hpp | 9 +++++++ matrix/Matrix.hpp | 54 +++++++++++++++++++++++++-------------- test/attitude.cpp | 3 ++- test/matrixAssignment.cpp | 2 +- test/vector.cpp | 4 +-- test/vector3.cpp | 8 +++--- 6 files changed, 53 insertions(+), 27 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index d21e893e6d..0c73b4ccd5 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -153,6 +153,15 @@ public: v(1) = a(1)*angle; v(2) = a(2)*angle; } + + + Vector axis() { + return Vector::unit(); + } + + Type angle() { + return Vector::norm(); + } }; typedef AxisAngle AxisAnglef; diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 3188c553d1..c4e9ec9573 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -134,22 +134,6 @@ public: return res; } - bool operator==(const Matrix &other) const - { - const Matrix &self = *this; - static const Type eps = Type(1e-4); - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - if (fabs(self(i , j) - other(i, j)) > eps) { - return false; - } - } - } - - return true; - } - Matrix operator-(const Matrix &other) const { Matrix res; @@ -469,15 +453,47 @@ Matrix operator*(Type scalar, const Matrix &other) template bool isEqual(const Matrix &x, - const Matrix & y) { - if (!(x == y)) { + const Matrix &y, const Type eps=1e-4f) { + + bool equal = true; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + if (fabs(x(i , j) - y(i, j)) > eps) { + equal = false; + break; + } + } + if (equal == false) break; + } + + + if (!equal) { char buf_x[100]; char buf_y[100]; x.write_string(buf_x, 100); y.write_string(buf_y, 100); printf("not equal\nx:\n%s\ny:\n%s\n", buf_x, buf_y); } - return x == y; + return equal; +} + +bool isEqual(float x, + float y, float eps); + +bool isEqual(float x, + float y, float eps=1e-4f) { + + bool equal = true; + + if (fabs(x - y) > eps) { + equal = false; + } + + if (!equal) { + printf("not equal\nx:\n%g\ny:\n%g\n", x, y); + } + return equal; } #if defined(SUPPORT_STDIOSTREAM) diff --git a/test/attitude.cpp b/test/attitude.cpp index b13bf73c2c..fefd6fe0e1 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -276,7 +276,8 @@ int main() AxisAnglef aa_axis_angle_init(Vector3f(1.0f, 2.0f, 3.0f), 3.0f); TEST(isEqual(aa_axis_angle_init, Vector3f(0.80178373f, 1.60356745f, 2.40535118f))); - + TEST(isEqual(aa_axis_angle_init.axis(), Vector3f(0.26726124f, 0.53452248f, 0.80178373f))); + TEST(isEqual(aa_axis_angle_init.angle(), 3.0f)); TEST(isEqual(Quatf((AxisAnglef(Vector3f(0.0f, 0.0f, 1.0f), 0.0f))), Quatf(1.0f, 0.0f, 0.0f, 0.0f))); }; diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index d6097526f1..8dbbf03bf4 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -30,7 +30,7 @@ int main() Matrix3f m3(data_times_2); TEST(isEqual(m, m2)); - TEST(!(m == m3)); + TEST(!(isEqual(m, m3))); m2 *= 2; TEST(isEqual(m2, m3)); diff --git a/test/vector.cpp b/test/vector.cpp index 38824937de..215985164a 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -17,10 +17,10 @@ int main() TEST(fabs(v1.dot(v2) - 130.0f) < 1e-5); v2.normalize(); Vector v3(v2); - TEST(v2 == v3); + TEST(isEqual(v2, v3)); float data1_sq[] = {1,4,9,16,25}; Vector v4(data1_sq); - TEST(v1 == v4.pow(0.5)); + TEST(isEqual(v1, v4.pow(0.5))); return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index a8ccc7325b..8e456fe156 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -12,15 +12,15 @@ int main() Vector3f a(1, 0, 0); Vector3f b(0, 1, 0); Vector3f c = a.cross(b); - TEST (c == Vector3f(0,0,1)); + TEST(isEqual(c, Vector3f(0,0,1))); c = a % b; - TEST (c == Vector3f(0,0,1)); + TEST (isEqual(c, Vector3f(0,0,1))); Matrix d(c); Vector3f e(d); - TEST (e == d); + TEST (isEqual(e, d)); float data[] = {4, 5, 6}; Vector3f f(data); - TEST (f == Vector3f(4, 5, 6)); + TEST(isEqual(f, Vector3f(4, 5, 6))); return 0; } From 1a87564b85eae9ed3d3db2e70bdcd57af6ef097e Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 11:31:21 -0400 Subject: [PATCH 180/388] Added dcm quat prod consistency check. --- test/attitude.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/test/attitude.cpp b/test/attitude.cpp index fefd6fe0e1..d25a6a756f 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -169,6 +169,12 @@ int main() q4 *= q3; TEST(isEqual(Quatf(-1, 0, 0, 0), q4)); + // check consistentcy of quaternion and dcm product + Dcmf dcm3(Eulerf(1, 2, 3)); + Dcmf dcm4(Eulerf(4, 5, 6)); + Dcmf dcm34 = dcm3*dcm4; + TEST(isEqual(Quatf(dcm3)*Quatf(dcm4), Quatf(dcm34))); + // quaternion derivate Quatf q1(0, 1, 0, 0); Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); From 37b00b088072f721f6a05a641a78ffb23cb7c3fc Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 11:37:45 -0400 Subject: [PATCH 181/388] Added check or consistency of dcm and quaternion product. --- test/attitude.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index d25a6a756f..c365aeda0f 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -169,12 +169,6 @@ int main() q4 *= q3; TEST(isEqual(Quatf(-1, 0, 0, 0), q4)); - // check consistentcy of quaternion and dcm product - Dcmf dcm3(Eulerf(1, 2, 3)); - Dcmf dcm4(Eulerf(4, 5, 6)); - Dcmf dcm34 = dcm3*dcm4; - TEST(isEqual(Quatf(dcm3)*Quatf(dcm4), Quatf(dcm34))); - // quaternion derivate Quatf q1(0, 1, 0, 0); Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); @@ -286,6 +280,12 @@ int main() TEST(isEqual(aa_axis_angle_init.angle(), 3.0f)); TEST(isEqual(Quatf((AxisAnglef(Vector3f(0.0f, 0.0f, 1.0f), 0.0f))), Quatf(1.0f, 0.0f, 0.0f, 0.0f))); + + // check consistentcy of quaternion and dcm product + Dcmf dcm3(Eulerf(1, 2, 3)); + Dcmf dcm4(Eulerf(4, 5, 6)); + Dcmf dcm34 = dcm3*dcm4; + TEST(isEqual(Eulerf(Quatf(dcm3)*Quatf(dcm4)), Eulerf(Quatf(dcm34)))); }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From f02fb372659ba4dbf6bafb4f30fd169ab9471fad Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 11:40:14 -0400 Subject: [PATCH 182/388] Add Testing to git ignore. --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index b486f209c8..433da5d5ba 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,4 @@ build*/ *.orig *.swp +Testing/ From 6197515a519eae9eaad258dc176b2f90daf3fa1b Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 11:50:46 -0400 Subject: [PATCH 183/388] Fix shadow warnings. --- matrix/AxisAngle.hpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 0c73b4ccd5..632e3e4a4f 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -76,16 +76,16 @@ public: Vector() { AxisAngle &v = *this; - Type angle = (Type)2.0f*acosf(q(0)); - Type mag = sinf(angle/2.0f); - if (fabs(angle) < 1e-10f) { + Type ang = (Type)2.0f*acosf(q(0)); + Type mag = sinf(ang/2.0f); + if (fabs(ang) < 1e-10f) { v(0) = 0; v(1) = 0; v(2) = 0; } else { - v(0) = angle*q(1)/mag; - v(1) = angle*q(2)/mag; - v(2) = angle*q(3)/mag; + v(0) = ang*q(1)/mag; + v(1) = ang*q(2)/mag; + v(2) = ang*q(3)/mag; } } @@ -142,16 +142,16 @@ public: * @param axis An axis of rotation, normalized if not unit length * @param angle The amount to rotate */ - AxisAngle(const Matrix31 & axis, Type angle) : + AxisAngle(const Matrix31 & axis_, Type angle_) : Vector() { AxisAngle &v = *this; // make sure axis is a unit vector - Vector a = axis; + Vector a = axis_; a = a.unit(); - v(0) = a(0)*angle; - v(1) = a(1)*angle; - v(2) = a(2)*angle; + v(0) = a(0)*angle_; + v(1) = a(1)*angle_; + v(2) = a(2)*angle_; } From 9af58f7e08355907e95f8f0584c108ba91fc56de Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 12:00:37 -0400 Subject: [PATCH 184/388] Coverage fix. --- test/helper.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/test/helper.cpp b/test/helper.cpp index e1cd2bf009..ccef76d1ab 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -18,6 +18,9 @@ int main() a.T().print(); TEST(!isEqual(a, b)); TEST(isEqual(a, a)); + + TEST(isEqual(1.0f, 1.0f)); + TEST(!isEqual(1.0f, 2.0f)); return 0; } From 4be23552c5abeedd1b5d5516895db59fa3f93624 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 12:13:26 -0400 Subject: [PATCH 185/388] Bump version. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0aa8052b24..3c0284b1e7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8) set(VERSION_MAJOR "1") set(VERSION_MINOR "0") -set(VERSION_PATCH "1") +set(VERSION_PATCH "2") project(matrix CXX) From 262a715d90a9385b0c8111ab28ea8f1cd323ad45 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 12:37:41 -0400 Subject: [PATCH 186/388] Fix some when building in px4. --- matrix/Matrix.hpp | 11 +++++------ test/attitude.cpp | 2 +- test/helper.cpp | 4 ++-- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index c4e9ec9573..9b849c2fcd 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -478,20 +478,19 @@ bool isEqual(const Matrix &x, return equal; } -bool isEqual(float x, - float y, float eps); -bool isEqual(float x, - float y, float eps=1e-4f) { +template +bool isEqualF(Type x, + Type y, Type eps=1e-4f) { bool equal = true; - if (fabs(x - y) > eps) { + if (fabsf(x - y) > eps) { equal = false; } if (!equal) { - printf("not equal\nx:\n%g\ny:\n%g\n", x, y); + printf("not equal\nx:\n%g\ny:\n%g\n", double(x), double(y)); } return equal; } diff --git a/test/attitude.cpp b/test/attitude.cpp index c365aeda0f..60bb28f69e 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -277,7 +277,7 @@ int main() AxisAnglef aa_axis_angle_init(Vector3f(1.0f, 2.0f, 3.0f), 3.0f); TEST(isEqual(aa_axis_angle_init, Vector3f(0.80178373f, 1.60356745f, 2.40535118f))); TEST(isEqual(aa_axis_angle_init.axis(), Vector3f(0.26726124f, 0.53452248f, 0.80178373f))); - TEST(isEqual(aa_axis_angle_init.angle(), 3.0f)); + TEST(isEqualF(aa_axis_angle_init.angle(), 3.0f)); TEST(isEqual(Quatf((AxisAnglef(Vector3f(0.0f, 0.0f, 1.0f), 0.0f))), Quatf(1.0f, 0.0f, 0.0f, 0.0f))); diff --git a/test/helper.cpp b/test/helper.cpp index ccef76d1ab..e4787fc3a2 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -19,8 +19,8 @@ int main() TEST(!isEqual(a, b)); TEST(isEqual(a, a)); - TEST(isEqual(1.0f, 1.0f)); - TEST(!isEqual(1.0f, 2.0f)); + TEST(isEqualF(1.0f, 1.0f)); + TEST(!isEqualF(1.0f, 2.0f)); return 0; } From 558777f34c654e992a1e99083cbbfa23b907d810 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 12:43:42 -0400 Subject: [PATCH 187/388] Fix formatting. --- matrix/Matrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 9b849c2fcd..c3225e31a1 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -481,7 +481,7 @@ bool isEqual(const Matrix &x, template bool isEqualF(Type x, - Type y, Type eps=1e-4f) { + Type y, Type eps=1e-4f) { bool equal = true; From 0eb8aa0c0b5974a83eef64118f177bcf55a4d9f8 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 19:03:54 -0400 Subject: [PATCH 188/388] Support more of mathlib function for easier swap in px4. --- matrix/Matrix.hpp | 30 +++++++++++++++++++++++++ matrix/Quaternion.hpp | 38 ++++++++++++++++++++++++++++++++ matrix/Vector.hpp | 17 +++++++++++++++ matrix/Vector3.hpp | 46 ++++++++++++++++++++++++++++++++++++++- test/attitude.cpp | 16 +++++++++++++- test/matrixAssignment.cpp | 10 +++++++++ test/matrixMult.cpp | 3 +++ test/setIdentity.cpp | 13 +++++++++++ test/vector.cpp | 11 ++++++++-- test/vector3.cpp | 8 +++++++ 10 files changed, 188 insertions(+), 4 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index c3225e31a1..707c39b9d6 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -41,6 +41,12 @@ public: { } + Matrix(const Type data_[][N]) : + _data() + { + memcpy(_data, data_, sizeof(_data)); + } + Matrix(const Type *data_) : _data() { @@ -120,6 +126,20 @@ public: return res; } + Matrix edivide(const Matrix &other) const + { + Matrix res; + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + res(i , j) = self(i, j)/other(i, j); + } + } + + return res; + } + Matrix operator+(const Matrix &other) const { Matrix res; @@ -334,6 +354,11 @@ public: memset(_data, 0, sizeof(_data)); } + inline void zero() + { + setZero(); + } + void setAll(Type val) { Matrix &self = *this; @@ -360,6 +385,11 @@ public: } } + inline void identity() + { + setIdentity(); + } + inline void swapRows(size_t a, size_t b) { if (a == b) { diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a96d8217bc..314a6daeaa 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -292,6 +292,20 @@ public: (*this) = (*this) * res; } + Vector3f conjugate(const Vector3f &vec) { + Quaternion q = *this; + Quaternion v(0, vec(0), vec(1), vec(2)); + Quaternion res = q*v*q.inversed(); + return Vector3f(res(1), res(2), res(3)); + } + + Vector3f conjugate_inversed(const Vector3f &vec) { + Quaternion q = *this; + Quaternion v(0, vec(0), vec(1), vec(2)); + Quaternion res = q.inversed()*v*q; + return Vector3f(res(1), res(2), res(3)); + } + /** * Rotation quaternion from vector * @@ -367,6 +381,30 @@ public: return vec; } + + /** + * Imaginary components of quaternion + */ + Vector3 imag() + { + Quaternion &q = *this; + return Vector3(q(1), q(2), q(3)); + } + + /** + * XXX DEPRECATED, can use assignment or ctor + */ + Quaternion from_dcm(Matrix dcm) { + return Quaternion(Dcmf(dcm)); + } + + /** + * XXX DEPRECATED, can use assignment or ctor + */ + Dcm to_dcm() { + return Dcm(*this); + } + }; typedef Quaternion Quatf; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index fe9c5a81f6..61382d7548 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -61,11 +61,24 @@ public: return r; } + inline Type operator*(const MatrixM1 & b) const { + const Vector &a(*this); + return a.dot(b); + } + + inline Vector operator*(float b) const { + return Vector(MatrixM1::operator*(b)); + } + Type norm() const { const Vector &a(*this); return Type(sqrt(a.dot(a))); } + inline Type length() const { + return norm(); + } + inline void normalize() { (*this) /= norm(); } @@ -74,6 +87,10 @@ public: return (*this) / norm(); } + inline Vector normalized() const { + return unit(); + } + Vector pow(Type v) const { const Vector &a(*this); Vector r; diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 9fed6ac3f6..272d5d7712 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -13,6 +13,9 @@ namespace matrix { +template +class Matrix; + template class Vector; @@ -60,10 +63,51 @@ public: return c; } - Vector3 operator%(const Matrix31 & b) const { + /** + * Override matrix ops so Vector3 type is returned + */ + + inline Vector3 operator+(Vector3 other) const + { + return Matrix31::operator+(other); + } + + inline Vector3 operator-(Vector3 other) const + { + return Matrix31::operator-(other); + } + + inline Vector3 operator-() const + { + return Matrix31::operator-(); + } + + inline Vector3 operator*(Type scalar) const + { + return Matrix31::operator*(scalar); + } + + inline Type operator*(Vector3 b) const + { + return Vector::operator*(b); + } + + inline Vector3 operator%(const Matrix31 & b) const { return (*this).cross(b); } + /** + * Override vector ops so Vector3 type is returned + */ + inline Vector3 unit() const { + return Vector3(Vector::unit()); + } + + inline Vector3 normalized() const { + return unit(); + } + + Dcm hat() const { // inverse to Dcm.vee() operation const Vector3 &v(*this); Dcm A; diff --git a/test/attitude.cpp b/test/attitude.cpp index 60bb28f69e..8d2fb28322 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -61,6 +61,7 @@ int main() TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, 0.54772256f, 0.73029674f))); TEST(isEqual(q0.unit(), q)); + TEST(isEqual(q0.unit(), q0.normalized())); // quat default ctor q = Quatf(); @@ -265,6 +266,19 @@ int main() TEST(isEqual(aa_data_init, AxisAnglef(4.0f, 5.0f, 6.0f))); q = Quatf(-0.29555112749297824f, 0.25532186f, 0.51064372f, 0.76596558f); + TEST(isEqual(q.imag(), Vector3f(0.25532186f, 0.51064372f, 0.76596558f))); + + // from dcm + TEST(isEqual(Eulerf(q.from_dcm(Dcmf(q))), Eulerf(q))); + + // to dcm + TEST(isEqual(Dcmf(q), q.to_dcm())); + + // conjugate + Vector3f v1(1.5f, 2.2f, 3.2f); + TEST(isEqual(q.conjugate(v1), Dcmf(q)*v1)); + TEST(isEqual(q.conjugate_inversed(v1), Dcmf(q).T()*v1)); + AxisAnglef aa_q_init(q); TEST(isEqual(aa_q_init, AxisAnglef(1.0f, 2.0f, 3.0f))); @@ -285,7 +299,7 @@ int main() Dcmf dcm3(Eulerf(1, 2, 3)); Dcmf dcm4(Eulerf(4, 5, 6)); Dcmf dcm34 = dcm3*dcm4; - TEST(isEqual(Eulerf(Quatf(dcm3)*Quatf(dcm4)), Eulerf(Quatf(dcm34)))); + TEST(isEqual(Eulerf(Quatf(dcm3)*Quatf(dcm4)), Eulerf(dcm34))); }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 8dbbf03bf4..f4e9af4226 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -9,6 +9,7 @@ int main() { Matrix3f m; m.setZero(); + m.zero(); m(0, 0) = 1; m(0, 1) = 2; m(0, 2) = 3; @@ -26,6 +27,15 @@ int main() TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); } + float data2d[3][3] = { + {1, 2, 3}, + {4, 5, 6}, + {7, 8, 9}}; + m2 = Matrix3f(data2d); + for(int i=0; i<9; i++) { + TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); + } + float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; Matrix3f m3(data_times_2); diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index f7b7eeefed..ecf9d9b3af 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -24,7 +24,10 @@ int main() Matrix3f A2 = eye()*2; Matrix3f B = A2.emult(A2); Matrix3f B_check = eye()*4; + Matrix3f C_check = eye()*2; TEST(isEqual(B, B_check)); + Matrix3f C = B_check.edivide(C_check); + TEST(isEqual(C, C_check)); return 0; } diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index a59b186a4d..e17614dafd 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -21,6 +21,19 @@ int main() } } + Matrix3f B; + B.identity(); + + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + if (i == j) { + TEST( fabs(B(i, j) - 1) < 1e-7); + + } else { + TEST( fabs(B(i, j) - 0) < 1e-7); + } + } + } return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index 215985164a..66aa109e2e 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -12,15 +12,22 @@ int main() float data1[] = {1,2,3,4,5}; float data2[] = {6,7,8,9,10}; Vector v1(data1); - TEST(fabs(v1.norm() - 7.416198487095663f) < 1e-5); + TEST(isEqualF(v1.norm(), 7.416198487095663f)); + TEST(isEqualF(v1.norm(), v1.length())); Vector v2(data2); - TEST(fabs(v1.dot(v2) - 130.0f) < 1e-5); + TEST(isEqualF(v1.dot(v2), 130.0f)); v2.normalize(); Vector v3(v2); TEST(isEqual(v2, v3)); float data1_sq[] = {1,4,9,16,25}; Vector v4(data1_sq); TEST(isEqual(v1, v4.pow(0.5))); + + // dot product operator + v1 = Vector(data1); + v2 = Vector(data2); + float dprod = v1 * v2; + TEST(isEqualF(dprod, 130.0f)); return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index 8e456fe156..611eef9887 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -21,6 +21,14 @@ int main() float data[] = {4, 5, 6}; Vector3f f(data); TEST(isEqual(f, Vector3f(4, 5, 6))); + + TEST(isEqual(a + b, Vector3f(1, 1, 0))); + TEST(isEqual(a - b, Vector3f(1, -1, 0))); + TEST(isEqualF(a * b, 0.0f)); + TEST(isEqual(-a, Vector3f(-1, 0, 0))); + TEST(isEqual(a.unit(), a)); + TEST(isEqual(a.unit(), a.normalized())); + TEST(isEqual(a*2.0, Vector3f(2, 0, 0))); return 0; } From 4653626d922c599885bf1e8833dc0b3e60df6ce3 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Aug 2016 19:04:23 -0400 Subject: [PATCH 189/388] Format. --- test/matrixAssignment.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index f4e9af4226..69124d9235 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -30,7 +30,8 @@ int main() float data2d[3][3] = { {1, 2, 3}, {4, 5, 6}, - {7, 8, 9}}; + {7, 8, 9} + }; m2 = Matrix3f(data2d); for(int i=0; i<9; i++) { TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); From 3aeb099249027021acef7b38a8c74c85b33d608c Mon Sep 17 00:00:00 2001 From: James Goppert Date: Thu, 18 Aug 2016 16:51:00 -0400 Subject: [PATCH 190/388] Revert "Use Hamilton quaternion definition." This reverts commit 19554c4470cd6322ffd18cb20a96485940f226b6. --- matrix/Quaternion.hpp | 18 ++++-------------- test/attitude.cpp | 20 +++++++------------- 2 files changed, 11 insertions(+), 27 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 314a6daeaa..2e0a768c8a 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -13,16 +13,6 @@ * represents the real part, thus, a quaternion representing a zero-rotation * is defined as (1,0,0,0). * - * Using Hamilton Quaternion - * - https://en.wikipedia.org/wiki/Quaternion - * - http://www.iri.upc.edu/people/jsola/JoanSola/objectes/notes/kinematics.pdf - * - Components (q_w, q_v) where q_w is the scalar and q_v is a vector - * - algebrea: i*j = k - * - handedness: right - * - function: passive (rotation operator rotates frames) - * - right-to-left product means local-to-global, q_GL - * default operator v_G = q x v_L x q* - * * @author James Goppert */ @@ -200,9 +190,9 @@ public: const Quaternion &p = *this; Quaternion r; r(0) = p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3); - r(1) = p(0) * q(1) + p(1) * q(0) + p(2) * q(3) - p(3) * q(2); - r(2) = p(0) * q(2) - p(1) * q(3) + p(2) * q(0) + p(3) * q(1); - r(3) = p(0) * q(3) + p(1) * q(2) - p(2) * q(1) + p(3) * q(0); + r(1) = p(0) * q(1) + p(1) * q(0) - p(2) * q(3) + p(3) * q(2); + r(2) = p(0) * q(2) + p(1) * q(3) + p(2) * q(0) - p(3) * q(1); + r(3) = p(0) * q(3) - p(1) * q(2) + p(2) * q(1) + p(3) * q(0); return r; } @@ -249,7 +239,7 @@ public: { const Quaternion &q = *this; Quaternion v(0, w(0, 0), w(1, 0), w(2, 0)); - return q * v * Type(0.5); + return v * q * Type(0.5); } /** diff --git a/test/attitude.cpp b/test/attitude.cpp index 8d2fb28322..c7b1feadb9 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -157,19 +157,6 @@ int main() Quatf q_from_m(m4); TEST(isEqual(q_from_m, m4)); - // quaternion product - Quatf q3(0, 0, 0, 1); - Quatf q4(AxisAnglef(0, 0, float(2*M_PI))); - q4 *= q4; - q4 *= q3; - TEST(isEqual(q3, q4)); - - q3 = Quatf(0, 0, 0, 1); - q4 = AxisAnglef(0, 0, float(M_PI/2)); - q4 *= q4; - q4 *= q3; - TEST(isEqual(Quatf(-1, 0, 0, 0), q4)); - // quaternion derivate Quatf q1(0, 1, 0, 0); Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); @@ -177,6 +164,13 @@ int main() Vector q1_dot_check(data_q_dot_check); TEST(isEqual(q1_dot, q1_dot_check)); + // quaternion product + Quatf q_prod_check( + 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); + TEST(isEqual(q_prod_check, q_check*q_check)); + q_check *= q_check; + TEST(isEqual(q_prod_check, q_check)); + // Quaternion scalar multiplication float scalar = 0.5; Quatf q_scalar_mul(1.0f, 2.0f, 3.0f, 4.0f); From db4374882bba122cb55370c5ea5efacbb8aa11c1 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Thu, 18 Aug 2016 16:54:43 -0400 Subject: [PATCH 191/388] Fix attitude tests. --- test/attitude.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index c7b1feadb9..ce47257721 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -270,8 +270,8 @@ int main() // conjugate Vector3f v1(1.5f, 2.2f, 3.2f); - TEST(isEqual(q.conjugate(v1), Dcmf(q)*v1)); - TEST(isEqual(q.conjugate_inversed(v1), Dcmf(q).T()*v1)); + TEST(isEqual(q.conjugate_inversed(v1), Dcmf(q)*v1)); + TEST(isEqual(q.conjugate(v1), Dcmf(q).T()*v1)); AxisAnglef aa_q_init(q); TEST(isEqual(aa_q_init, AxisAnglef(1.0f, 2.0f, 3.0f))); @@ -293,7 +293,7 @@ int main() Dcmf dcm3(Eulerf(1, 2, 3)); Dcmf dcm4(Eulerf(4, 5, 6)); Dcmf dcm34 = dcm3*dcm4; - TEST(isEqual(Eulerf(Quatf(dcm3)*Quatf(dcm4)), Eulerf(dcm34))); + TEST(isEqual(Eulerf(Quatf(dcm4)*Quatf(dcm3)), Eulerf(dcm34))); }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 34fccdd6806fbdf7635a6365d7ef112f3bbaab9a Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 2 Nov 2016 12:10:30 -0400 Subject: [PATCH 192/388] add renormalize method (#32) --- matrix/Dcm.hpp | 35 +++++++++++++++++--------- test/attitude.cpp | 62 ++++++++++++++++++++++++++++++++--------------- 2 files changed, 67 insertions(+), 30 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index b7b7ac6f00..cd9c3923c2 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -81,16 +81,17 @@ public: * * @param q quaternion to set dcm to */ - Dcm(const Quaternion & q) { + Dcm(const Quaternion &q) + { Dcm &dcm = *this; Type a = q(0); Type b = q(1); Type c = q(2); Type d = q(3); - Type aSq = a*a; - Type bSq = b*b; - Type cSq = c*c; - Type dSq = d*d; + Type aSq = a * a; + Type bSq = b * b; + Type cSq = c * c; + Type dSq = d * d; dcm(0, 0) = aSq + bSq - cSq - dSq; dcm(0, 1) = 2 * (b * c - a * d); dcm(0, 2) = 2 * (a * c + b * d); @@ -111,7 +112,8 @@ public: * * @param euler euler angle instance */ - Dcm(const Euler & euler) { + Dcm(const Euler &euler) + { Dcm &dcm = *this; Type cosPhi = Type(cos(euler.phi())); Type sinPhi = Type(sin(euler.phi())); @@ -143,19 +145,30 @@ public: * * @param euler euler angle instance */ - Dcm(const AxisAngle & aa) { + Dcm(const AxisAngle &aa) + { Dcm &dcm = *this; dcm = Quaternion(aa); } - Vector vee() const { // inverse to Vector.hat() operation + Vector vee() const // inverse to Vector.hat() operation + { const Dcm &A(*this); Vector v; - v(0) = -A(1,2); - v(1) = A(0,2); - v(2) = -A(0,1); + v(0) = -A(1, 2); + v(1) = A(0, 2); + v(2) = -A(0, 1); return v; } + + void renormalize() + { + /* renormalize rows */ + for (int row = 0; row < 3; row++) { + matrix::Vector3f rvec(this->_data[row]); + this->setRow(row, rvec.normalized()); + } + } }; typedef Dcm Dcmf; diff --git a/test/attitude.cpp b/test/attitude.cpp index ce47257721..ea20c3cdcf 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -96,40 +96,62 @@ int main() Quatf q2(dcm_check); TEST(isEqual(q2, q_check)); + // dcm renormalize + Dcmf A = eye(); + Dcmf R(euler_check); + for (int i = 0; i < 1000; i++) { + A = R * A; + } + A.renormalize(); + float err = 0.0f; + for (int row = 0; row < 3; row++) { + matrix::Vector3f rvec(A._data[row]); + err += fabsf(1.0f - rvec.length()); + } + TEST(err < eps); + // constants - double deg2rad = M_PI/180.0; - double rad2deg = 180.0/M_PI; + double deg2rad = M_PI / 180.0; + double rad2deg = 180.0 / M_PI; // euler dcm round trip check - for (int roll=-90; roll<=90; roll+=90) { - for (int pitch=-90; pitch<=90; pitch+=90) { - for (int yaw=-179; yaw<=180; yaw+=90) { + for (int roll = -90; roll <= 90; roll += 90) { + for (int pitch = -90; pitch <= 90; pitch += 90) { + for (int yaw = -179; yaw <= 180; yaw += 90) { // note if theta = pi/2, then roll is set to zero int roll_expected = roll; int yaw_expected = yaw; + if (pitch == 90) { roll_expected = 0; yaw_expected = yaw - roll; + } else if (pitch == -90) { roll_expected = 0; yaw_expected = yaw + roll; } - if (yaw_expected < -180) yaw_expected += 360; - if (yaw_expected > 180) yaw_expected -= 360; + + if (yaw_expected < -180) { + yaw_expected += 360; + } + + if (yaw_expected > 180) { + yaw_expected -= 360; + } //printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); Euler euler_expected( - deg2rad*double(roll_expected), - deg2rad*double(pitch), - deg2rad*double(yaw_expected)); + deg2rad * double(roll_expected), + deg2rad * double(pitch), + deg2rad * double(yaw_expected)); Euler euler( - deg2rad*double(roll), - deg2rad*double(pitch), - deg2rad*double(yaw)); + deg2rad * double(roll), + deg2rad * double(pitch), + deg2rad * double(yaw)); Dcm dcm_from_euler(euler); //dcm_from_euler.print(); Euler euler_out(dcm_from_euler); - TEST(isEqual(rad2deg*euler_expected, rad2deg*euler_out)); + TEST(isEqual(rad2deg * euler_expected, rad2deg * euler_out)); Eulerf eulerf_expected( float(deg2rad)*float(roll_expected), @@ -160,14 +182,14 @@ int main() // quaternion derivate Quatf q1(0, 1, 0, 0); Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); - float data_q_dot_check[] = {-0.5f, 0.0f, -1.5f, 1.0f}; + float data_q_dot_check[] = { -0.5f, 0.0f, -1.5f, 1.0f}; Vector q1_dot_check(data_q_dot_check); TEST(isEqual(q1_dot, q1_dot_check)); // quaternion product Quatf q_prod_check( 0.93394439f, 0.0674002f, 0.20851f, 0.28236266f); - TEST(isEqual(q_prod_check, q_check*q_check)); + TEST(isEqual(q_prod_check, q_check * q_check)); q_check *= q_check; TEST(isEqual(q_prod_check, q_check)); @@ -225,7 +247,7 @@ int main() q = Quatf(cosf(1.0f / 2), 0.0f, sinf(1.0f / 2), 0.0f); rot = q.to_axis_angle(); TEST(fabsf(rot(0)) < eps); - TEST(fabsf(rot(1) -1.0f) < eps); + TEST(fabsf(rot(1) - 1.0f) < eps); TEST(fabsf(rot(2)) < eps); // get rotation axis from quaternion (zero rotation) @@ -247,8 +269,10 @@ int main() // Quaternion initialisation per array float q_array[] = {0.9833f, -0.0343f, -0.1060f, -0.1436f}; Quaternionq_from_array(q_array); - for(int i = 0; i < 4; i++) + + for (int i = 0; i < 4; i++) { TEST(fabsf(q_from_array(i) - q_array[i]) < eps); + } // axis angle AxisAnglef aa_true(Vector3f(1.0f, 2.0f, 3.0f)); @@ -292,7 +316,7 @@ int main() // check consistentcy of quaternion and dcm product Dcmf dcm3(Eulerf(1, 2, 3)); Dcmf dcm4(Eulerf(4, 5, 6)); - Dcmf dcm34 = dcm3*dcm4; + Dcmf dcm34 = dcm3 * dcm4; TEST(isEqual(Eulerf(Quatf(dcm4)*Quatf(dcm3)), Eulerf(dcm34))); }; From f3e478cbffedfbe674e71da357f7d0a7437019b4 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 22 Nov 2016 10:04:45 -0500 Subject: [PATCH 193/388] Fix matrix inverse pivotting logic. --- matrix/SquareMatrix.hpp | 8 ++++---- test/inverse.cpp | 39 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 43 insertions(+), 4 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 3e42b64e55..fbd61641c8 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -128,16 +128,16 @@ SquareMatrix inv(const SquareMatrix & A) // if diagonal is zero, swap with row below if (fabsf(U(n, n)) < 1e-8f) { //printf("trying pivot for row %d\n",n); - for (size_t i = 0; i < M; i++) { - if (i == n) { - continue; - } + for (size_t i = n + 1; i < M; i++) { //printf("\ttrying row %d\n",i); if (fabsf(U(i, n)) > 1e-8f) { //printf("swapped %d\n",i); U.swapRows(i, n); P.swapRows(i, n); + L.swapRows(i, n); + L.swapCols(i, n); + break; } } } diff --git a/test/inverse.cpp b/test/inverse.cpp index f8af641aea..f04d7f771a 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -41,6 +41,45 @@ int main() SquareMatrix zero_test = zeros(); inv(zero_test); + // test pivotting + float data2[81] = { + -2, 1, 1, -1, -5, 1, 2, -1, 0, + -3, 2, -1, 0, 2, 2, -1, -5, 3, + 0, 0, 0, 1, 4, -3, 3, 0, -2, + 2, 2, -1, -2, -1, 0, 3, 0, 1, + -1, 2, -1, -1, -3, 3, 0, -2, 3, + 0, 1, 1, -3, 3, -2, 0, -4, 0, + 1, 0, 0, 0, 0, 0, -2, 4, -3, + 1, -1, 0, -1, -1, 1, -1, -3, 4, + 0, 3, -1, -2, 2, 1, -2, 0, -1}; + + float data2_check[81] = { + 6, -4, 3, -3 , -9, -8, -10, 8, 14, + -2, -7, -5, -3 , -2, -2, -16, -5, 8, + -2, 0, -23, 7, -24, -5, -28, -14, 9, + 3, -7, 2, -5, -4, -6, -13, 4, 13, + -1, 4, -8, 5, -8, 0, -3, -5, -2, + 6, 7, -7, 7, -21, -7, -5, 3, 6, + 1, 4, -4, 4, -7, -1, 0, -1, -1, + -7, 3, -11, 5, 1, 6, -1, -13, -10, + -8, 0, -11, 3, 3, 6, -5, -14, -8}; + SquareMatrix A2(data2); + SquareMatrix A2_I = inv(A2); + SquareMatrix A2_I_check(data2_check); + TEST((A2_I - A2_I_check).abs().max() < 1e-3); + float data3[9] = { + 0, 1, 2, + 3, 4, 5, + 6, 7, 9}; + float data3_check[9] = { + -0.3333333f, -1.6666666f, 1, + -1, 4, -2, + 1, -2, 1 + }; + SquareMatrix A3(data3); + SquareMatrix A3_I = inv(A3); + SquareMatrix A3_I_check(data3_check); + TEST((A3_I - A3_I_check).abs().max() < 1e-5); return 0; } From bf69be7f17a9d3a94e71d3465dcd59428b878609 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 22 Nov 2016 10:07:08 -0500 Subject: [PATCH 194/388] Fix formatting. --- test/inverse.cpp | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/test/inverse.cpp b/test/inverse.cpp index f04d7f771a..0f7ef054ad 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -51,18 +51,20 @@ int main() 0, 1, 1, -3, 3, -2, 0, -4, 0, 1, 0, 0, 0, 0, 0, -2, 4, -3, 1, -1, 0, -1, -1, 1, -1, -3, 4, - 0, 3, -1, -2, 2, 1, -2, 0, -1}; + 0, 3, -1, -2, 2, 1, -2, 0, -1 + }; - float data2_check[81] = { - 6, -4, 3, -3 , -9, -8, -10, 8, 14, - -2, -7, -5, -3 , -2, -2, -16, -5, 8, - -2, 0, -23, 7, -24, -5, -28, -14, 9, + float data2_check[81] = { + 6, -4, 3, -3 , -9, -8, -10, 8, 14, + -2, -7, -5, -3 , -2, -2, -16, -5, 8, + -2, 0, -23, 7, -24, -5, -28, -14, 9, 3, -7, 2, -5, -4, -6, -13, 4, 13, - -1, 4, -8, 5, -8, 0, -3, -5, -2, + -1, 4, -8, 5, -8, 0, -3, -5, -2, 6, 7, -7, 7, -21, -7, -5, 3, 6, 1, 4, -4, 4, -7, -1, 0, -1, -1, - -7, 3, -11, 5, 1, 6, -1, -13, -10, - -8, 0, -11, 3, 3, 6, -5, -14, -8}; + -7, 3, -11, 5, 1, 6, -1, -13, -10, + -8, 0, -11, 3, 3, 6, -5, -14, -8 + }; SquareMatrix A2(data2); SquareMatrix A2_I = inv(A2); SquareMatrix A2_I_check(data2_check); @@ -70,7 +72,8 @@ int main() float data3[9] = { 0, 1, 2, 3, 4, 5, - 6, 7, 9}; + 6, 7, 9 + }; float data3_check[9] = { -0.3333333f, -1.6666666f, 1, -1, 4, -2, From 8a94f0f8acf0537b8b49613fbba73ad1ee75facf Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 28 Nov 2016 10:43:29 -0500 Subject: [PATCH 195/388] Fix axis angle fabsf usage. --- matrix/AxisAngle.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 632e3e4a4f..ddcceb552f 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -78,7 +78,7 @@ public: AxisAngle &v = *this; Type ang = (Type)2.0f*acosf(q(0)); Type mag = sinf(ang/2.0f); - if (fabs(ang) < 1e-10f) { + if (fabsf(ang) < 1e-10f) { v(0) = 0; v(1) = 0; v(2) = 0; From 945edbc58cc3c8b3b681c3fd50a3c73defaef67f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 30 Nov 2016 00:40:55 -0500 Subject: [PATCH 196/388] Ensure direction is always defined for axis angle. --- matrix/AxisAngle.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index ddcceb552f..8b25bedc48 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -79,7 +79,7 @@ public: Type ang = (Type)2.0f*acosf(q(0)); Type mag = sinf(ang/2.0f); if (fabsf(ang) < 1e-10f) { - v(0) = 0; + v(0) = 1e-10f; v(1) = 0; v(2) = 0; } else { From 74a120f5544103c3bcdf9f2c3c61f41af7cf3032 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Wed, 30 Nov 2016 01:27:48 -0500 Subject: [PATCH 197/388] Handle some divide by zero edge cases on init. --- matrix/AxisAngle.hpp | 16 ++++++++++------ matrix/Quaternion.hpp | 22 ++++++++++++++-------- test/attitude.cpp | 4 ++++ 3 files changed, 28 insertions(+), 14 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 8b25bedc48..b3ad7305e3 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -78,14 +78,14 @@ public: AxisAngle &v = *this; Type ang = (Type)2.0f*acosf(q(0)); Type mag = sinf(ang/2.0f); - if (fabsf(ang) < 1e-10f) { - v(0) = 1e-10f; - v(1) = 0; - v(2) = 0; - } else { + if (fabsf(mag) > 0) { v(0) = ang*q(1)/mag; v(1) = ang*q(2)/mag; v(2) = ang*q(3)/mag; + } else { + v(0) = 0; + v(1) = 0; + v(2) = 0; } } @@ -156,7 +156,11 @@ public: Vector axis() { - return Vector::unit(); + if (Vector::norm() > 0) { + return Vector::unit(); + } else { + return Vector3(1, 0, 0); + } } Type angle() { diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 2e0a768c8a..98f1efddcc 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -94,14 +94,20 @@ public: Vector() { Quaternion &q = *this; - q(0) = Type(0.5) * Type(sqrt(Type(1) + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2))); - q(1) = Type((dcm(2, 1) - dcm(1, 2)) / - (Type(4) * q(0))); - q(2) = Type((dcm(0, 2) - dcm(2, 0)) / - (Type(4) * q(0))); - q(3) = Type((dcm(1, 0) - dcm(0, 1)) / - (Type(4) * q(0))); + q(0) = 1; + q(1) = 0; + q(2) = 0; + q(3) = 0; + if (((Type(1) + dcm(0, 0) + dcm(1, 1) + dcm(2, 2)) > 0) & (fabsf(q(0)) > 0) ) { + q(0) = Type(0.5) * Type(sqrt(Type(1) + dcm(0, 0) + + dcm(1, 1) + dcm(2, 2))); + q(1) = Type((dcm(2, 1) - dcm(1, 2)) / + (Type(4) * q(0))); + q(2) = Type((dcm(0, 2) - dcm(2, 0)) / + (Type(4) * q(0))); + q(3) = Type((dcm(1, 0) - dcm(0, 1)) / + (Type(4) * q(0))); + } } /** diff --git a/test/attitude.cpp b/test/attitude.cpp index ea20c3cdcf..c2606b9b00 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -283,6 +283,10 @@ int main() AxisAnglef aa_data_init(aa_data); TEST(isEqual(aa_data_init, AxisAnglef(4.0f, 5.0f, 6.0f))); + AxisAnglef aa_norm_check(Vector3f(0.0f, 0.0f, 0.0f)); + TEST(isEqual(aa_norm_check.axis(), Vector3f(1, 0, 0))); + TEST(isEqualF(aa_norm_check.angle(), 0.0f)); + q = Quatf(-0.29555112749297824f, 0.25532186f, 0.51064372f, 0.76596558f); TEST(isEqual(q.imag(), Vector3f(0.25532186f, 0.51064372f, 0.76596558f))); From 7eff04742ce0e67fd4b8d205880dbaad711978ea Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 13 Dec 2016 10:17:13 -0500 Subject: [PATCH 198/388] Fix for zero check on quat from dcm ctor. --- matrix/Quaternion.hpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 98f1efddcc..880e63142d 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -98,9 +98,10 @@ public: q(1) = 0; q(2) = 0; q(3) = 0; - if (((Type(1) + dcm(0, 0) + dcm(1, 1) + dcm(2, 2)) > 0) & (fabsf(q(0)) > 0) ) { - q(0) = Type(0.5) * Type(sqrt(Type(1) + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2))); + Type q0_tmp = Type(0.5) * Type(sqrt(Type(1) + dcm(0, 0) + + dcm(1, 1) + dcm(2, 2))); + if (fabsf(q0_tmp) > 0) { + q(0) = q0_tmp; q(1) = Type((dcm(2, 1) - dcm(1, 2)) / (Type(4) * q(0))); q(2) = Type((dcm(0, 2) - dcm(2, 0)) / From bb1a3216397a34b097f732f34771379615142489 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 14 Dec 2016 17:42:45 +0100 Subject: [PATCH 199/388] Changed Dcm to inherit from SquareMatrix because it is square and we can use the trace method --- matrix/Dcm.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index cd9c3923c2..1b4bf03fda 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -38,7 +38,7 @@ class AxisAngle; * described by this class. */ template -class Dcm : public Matrix +class Dcm : public SquareMatrix { public: virtual ~Dcm() {}; @@ -50,7 +50,7 @@ public: * * Initializes to identity */ - Dcm() : Matrix() + Dcm() : SquareMatrix() { (*this) = eye(); } @@ -60,7 +60,7 @@ public: * * @param _data pointer to array */ - Dcm(const Type *data_) : Matrix(data_) + Dcm(const Type *data_) : SquareMatrix(data_) { } @@ -69,7 +69,7 @@ public: * * @param other Matrix33 to set dcm to */ - Dcm(const Matrix &other) : Matrix(other) + Dcm(const Matrix &other) : SquareMatrix(other) { } From 2f4427a9231823f198d8857d98e3a3f6c316a623 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 14 Dec 2016 17:55:05 +0100 Subject: [PATCH 200/388] Quaternion: Implemented the largest pivot element method for conversion from Dcm to Quaternion to avoid numerical problems --- matrix/Quaternion.hpp | 45 ++++++++++++++++++++++++++++--------------- 1 file changed, 30 insertions(+), 15 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 880e63142d..08d18d55bc 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -90,24 +90,39 @@ public: * * @param dcm dcm to set quaternion to */ - Quaternion(const Dcm &dcm) : + Quaternion(const Dcm &R) : Vector() { Quaternion &q = *this; - q(0) = 1; - q(1) = 0; - q(2) = 0; - q(3) = 0; - Type q0_tmp = Type(0.5) * Type(sqrt(Type(1) + dcm(0, 0) + - dcm(1, 1) + dcm(2, 2))); - if (fabsf(q0_tmp) > 0) { - q(0) = q0_tmp; - q(1) = Type((dcm(2, 1) - dcm(1, 2)) / - (Type(4) * q(0))); - q(2) = Type((dcm(0, 2) - dcm(2, 0)) / - (Type(4) * q(0))); - q(3) = Type((dcm(1, 0) - dcm(0, 1)) / - (Type(4) * q(0))); + Type t = R.trace(); + if (t > Type(0)) { + t = sqrtf(Type(1) + t); + q(0) = Type(0.5) * t; + t = Type(0.5) / t; + q(1) = (R(2,1) - R(1,2)) * t; + q(2) = (R(0,2) - R(2,0)) * t; + q(3) = (R(1,0) - R(0,1)) * t; + } else if (R(0,0) > R(1,1) && R(0,0) > R(2,2)) { + t = sqrtf(Type(1) + R(0,0) - R(1,1) - R(2,2)); + q(1) = Type(0.5) * t; + t = Type(0.5) / t; + q(0) = (R(2,1) - R(1,2)) * t; + q(2) = (R(1,0) + R(0,1)) * t; + q(3) = (R(0,2) + R(2,0)) * t; + } else if (R(1,1) > R(2,2)) { + t = sqrtf(Type(1) - R(0,0) + R(1,1) - R(2,2)); + q(2) = Type(0.5) * t; + t = Type(0.5) / t; + q(0) = (R(0,2) - R(2,0)) * t; + q(1) = (R(1,0) + R(0,1)) * t; + q(3) = (R(2,1) + R(1,2)) * t; + } else { + t = sqrtf(Type(1) - R(0,0) - R(1,1) + R(2,2)); + q(3) = Type(0.5) * t; + t = Type(0.5) / t; + q(0) = (R(1,0) - R(0,1)) * t; + q(1) = (R(0,2) + R(2,0)) * t; + q(2) = (R(2,1) + R(1,2)) * t; } } From 47c0a93140cc5b4ed89a24b21ad25874ede9dde1 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 14 Dec 2016 18:25:06 +0100 Subject: [PATCH 201/388] Quaternion: added tests for the corner cases of Dcm to quaternion conversion --- test/attitude.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/test/attitude.cpp b/test/attitude.cpp index c2606b9b00..c2c6089d5c 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -322,6 +322,17 @@ int main() Dcmf dcm4(Eulerf(4, 5, 6)); Dcmf dcm34 = dcm3 * dcm4; TEST(isEqual(Eulerf(Quatf(dcm4)*Quatf(dcm3)), Eulerf(dcm34))); + + // check corner cases of matrix to quaternion conversion + q = Quatf(0,1,0,0); // 180 degree rotation around the x axis + R = Dcmf(q); + TEST(isEqual(q, Quatf(R))); + q = Quatf(0,0,1,0); // 180 degree rotation around the y axis + R = Dcmf(q); + TEST(isEqual(q, Quatf(R))); + q = Quatf(0,0,0,1); // 180 degree rotation around the z axis + R = Dcmf(q); + TEST(isEqual(q, Quatf(R))); }; /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 7e3eff7b2de0eb192a6df66ea669b3383c168be3 Mon Sep 17 00:00:00 2001 From: Siddharth Bharat Purohit Date: Fri, 3 Feb 2017 23:50:09 +0530 Subject: [PATCH 202/388] remove unnecessary duplicate matrices from inverse --- matrix/SquareMatrix.hpp | 63 +++++++++++++++++++++++++++++++++-------- 1 file changed, 51 insertions(+), 12 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index fbd61641c8..72b493e2a3 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -47,9 +47,23 @@ public: // inverse alias inline SquareMatrix I() const { - return inv(*this); + SquareMatrix i; + if(inv(*this, i)) { + return i; + } else { + i.setZero(); + return i; + } } + + // inverse alias + inline bool I(SquareMatrix &i) const + { + return inv(*this, i); + } + + Vector diag() const { Vector res; @@ -108,11 +122,12 @@ SquareMatrix expm(const Matrix & A, size_t order=5) return res; } + /** * inverse based on LU factorization with partial pivotting */ template -SquareMatrix inv(const SquareMatrix & A) +bool inv(const SquareMatrix & A, SquareMatrix & inv) { SquareMatrix L; L.setIdentity(); @@ -147,14 +162,12 @@ SquareMatrix inv(const SquareMatrix & A) //printf("U:\n"); U.print(); //printf("P:\n"); P.print(); //fflush(stdout); - ASSERT(fabsf(U(n, n)) > 1e-8f); + //ASSERT(fabsf(U(n, n)) > 1e-8f); #endif // failsafe, return zero matrix if (fabsf(U(n, n)) < 1e-8f) { - SquareMatrix zero; - zero.setZero(); - return zero; + return false; } // for all rows below diagonal @@ -173,7 +186,7 @@ SquareMatrix inv(const SquareMatrix & A) //printf("U:\n"); U.print(); // solve LY=P*I for Y by forward subst - SquareMatrix Y = P; + //SquareMatrix Y = P; // for all columns of Y for (size_t c = 0; c < M; c++) { @@ -184,7 +197,7 @@ SquareMatrix inv(const SquareMatrix & A) // for all existing y // subtract the component they // contribute to the solution - Y(i, c) -= L(i, j) * Y(j, c); + P(i, c) -= L(i, j) * P(j, c); } // divide by the factor @@ -198,7 +211,7 @@ SquareMatrix inv(const SquareMatrix & A) //printf("Y:\n"); Y.print(); // solve Ux=y for x by back subst - SquareMatrix X = Y; + //SquareMatrix X = Y; // for all columns of X for (size_t c = 0; c < M; c++) { @@ -212,20 +225,46 @@ SquareMatrix inv(const SquareMatrix & A) // for all existing x // subtract the component they // contribute to the solution - X(i, c) -= U(i, j) * X(j, c); + P(i, c) -= U(i, j) * P(j, c); } // divide by the factor // on current // term to be solved - X(i, c) /= U(i, i); + if(fabsf(U(i,i)) < 1e-8f) { + return false; + } + P(i, c) /= U(i, i); } } + //check sanity of results + for (uint8_t i = 0; i < M; i++) { + for (uint8_t j = 0; j < M; j++) { + if (!PX4_ISFINITE(P(i,j))) { + return false; + } + } + } //printf("X:\n"); X.print(); - return X; + inv = P; + return true; } +/** + * inverse based on LU factorization with partial pivotting + */ +template +SquareMatrix inv(const SquareMatrix & A) +{ + SquareMatrix i; + if(inv(A, i)) { + return i; + } else { + i.setZero(); + return i; + } +} typedef SquareMatrix Matrix3f; } // namespace matrix From 230e84702a1ca170fd1c07588acaa3c61bcb5438 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 3 Feb 2017 16:25:55 -0500 Subject: [PATCH 203/388] Fix unit test, create matrix isfinite. --- matrix/SquareMatrix.hpp | 6 +++--- matrix/helper_functions.hpp | 13 +++++++++---- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 72b493e2a3..6b7da78eee 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -239,9 +239,9 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) } //check sanity of results - for (uint8_t i = 0; i < M; i++) { - for (uint8_t j = 0; j < M; j++) { - if (!PX4_ISFINITE(P(i,j))) { + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < M; j++) { + if (!isfinite(P(i,j))) { return false; } } diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index d39b672d75..bfd5b35f11 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -13,14 +13,19 @@ namespace matrix { +template +bool isfinite(Type x) { +#if defined (__PX4_NUTTX) || defined (__PX4_QURT) + return PX4_ISFINITE(x); +#else + return std::isfinite(x); +#endif +} + template Type wrap_pi(Type x) { -#if defined (__PX4_NUTTX) || defined (__PX4_QURT) if (!isfinite(x)) { -#else - if (!std::isfinite(x)) { -#endif return x; } From db6dfeafbe1f9948669fcc302d8a2439a256a47c Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 3 Feb 2017 16:56:33 -0500 Subject: [PATCH 204/388] Add helper_functions include for inverse and in general header --- matrix/SquareMatrix.hpp | 1 + matrix/math.hpp | 1 + 2 files changed, 2 insertions(+) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 6b7da78eee..fe98cbefb0 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -15,6 +15,7 @@ #include #include "math.hpp" +#include "helper_functions.hpp" namespace matrix { diff --git a/matrix/math.hpp b/matrix/math.hpp index b69d2e0eec..4a759efe63 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -13,3 +13,4 @@ #include "Scalar.hpp" #include "Quaternion.hpp" #include "AxisAngle.hpp" +#include "helper_functions.hpp" From a154e1443974c1d128d007a7a40a8f2a39482816 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 3 Feb 2017 17:24:15 -0500 Subject: [PATCH 205/388] Fix coverage for inverse. --- matrix/SquareMatrix.hpp | 5 ++--- test/inverse.cpp | 25 ++++++++++++++++++++++++- 2 files changed, 26 insertions(+), 4 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index fe98cbefb0..912a27a31a 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -232,9 +232,8 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) // divide by the factor // on current // term to be solved - if(fabsf(U(i,i)) < 1e-8f) { - return false; - } + // + // we know that U(i, i) != 0 from above P(i, c) /= U(i, i); } } diff --git a/test/inverse.cpp b/test/inverse.cpp index 0f7ef054ad..3c157388c0 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -82,7 +82,30 @@ int main() SquareMatrix A3(data3); SquareMatrix A3_I = inv(A3); SquareMatrix A3_I_check(data3_check); - TEST((A3_I - A3_I_check).abs().max() < 1e-5); + TEST(isEqual(inv(A3), A3_I_check)); + TEST(isEqual(A3_I, A3_I_check)); + TEST(A3.I(A3_I)); + TEST(isEqual(A3_I, A3_I_check)); + + // cover singular matrices + A3(0, 0) = 0; + A3(0, 1) = 0; + A3(0, 2) = 0; + A3_I = inv(A3); + SquareMatrix Z3 = zeros(); + TEST(!A3.I(A3_I)); + TEST(!Z3.I(A3_I)); + TEST(isEqual(A3_I, Z3)); + TEST(isEqual(A3.I(), Z3)); + + // cover NaN + A3(0, 0) = NAN; + A3(0, 1) = 0; + A3(0, 2) = 0; + A3_I = inv(A3); + TEST(isEqual(A3_I, Z3)); + TEST(isEqual(A3.I(), Z3)); + return 0; } From 63aea23f9ed8dc5a160803804a429efda95b83b6 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 3 Feb 2017 17:54:16 -0500 Subject: [PATCH 206/388] Add cholesky decomp, Closes #30, and dynamic print buf --- CMakeLists.txt | 6 ++++ matrix/AxisAngle.hpp | 2 +- matrix/Dcm.hpp | 2 +- matrix/Matrix.hpp | 20 ++++++----- matrix/Quaternion.hpp | 72 ++++++++++++++++++++++--------------- matrix/Scalar.hpp | 5 --- matrix/SquareMatrix.hpp | 52 +++++++++++++++++++++++++++ matrix/helper_functions.hpp | 10 +++--- test/attitude.cpp | 30 ++++++++++------ test/inverse.cpp | 20 +++++++++++ test/matrixAssignment.cpp | 2 -- test/setIdentity.cpp | 8 ++--- 12 files changed, 165 insertions(+), 64 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3c0284b1e7..ab4e2a0a3f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -54,6 +54,12 @@ set(CMAKE_CXX_FLAGS -Wconversion -Wcast-align -Werror + -pedantic -Wctor-dtor-privacy -Wdisabled-optimization -Wformat=2 + -Winit-self -Wlogical-op -Wmissing-declarations + -Wmissing-include-dirs -Wnoexcept -Wold-style-cast + -Woverloaded-virtual -Wredundant-decls -Wshadow -Wsign-conversion + -Wsign-promo -Wstrict-null-sentinel -Wstrict-overflow=5 + -Wswitch-default -Wundef -Werror -Wno-unused ) string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index b3ad7305e3..ab945379d6 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -76,7 +76,7 @@ public: Vector() { AxisAngle &v = *this; - Type ang = (Type)2.0f*acosf(q(0)); + Type ang = Type(2.0f)*acosf(q(0)); Type mag = sinf(ang/2.0f); if (fabsf(mag) > 0) { v(0) = ang*q(1)/mag; diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 1b4bf03fda..ba61d66a54 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -164,7 +164,7 @@ public: void renormalize() { /* renormalize rows */ - for (int row = 0; row < 3; row++) { + for (size_t row = 0; row < 3; row++) { matrix::Vector3f rvec(this->_data[row]); this->setRow(row, rvec.normalized()); } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 707c39b9d6..9082d6b6a2 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -282,7 +282,7 @@ public: const Matrix &self = *this; for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - snprintf(buf + strlen(buf), n - strlen(buf), "\t%g", double(self(i, j))); // directly append to the string buffer + snprintf(buf + strlen(buf), n - strlen(buf), "\t%8.2g", double(self(i, j))); // directly append to the string buffer } snprintf(buf + strlen(buf), n - strlen(buf), "\n"); } @@ -290,9 +290,11 @@ public: void print() const { - char buf[200]; - write_string(buf, 200); + static const size_t n = 10*N*M; + char * buf = new char[n]; + write_string(buf, n); printf("%s\n", buf); + delete[] buf; } Matrix transpose() const @@ -499,11 +501,13 @@ bool isEqual(const Matrix &x, if (!equal) { - char buf_x[100]; - char buf_y[100]; - x.write_string(buf_x, 100); - y.write_string(buf_y, 100); - printf("not equal\nx:\n%s\ny:\n%s\n", buf_x, buf_y); + static const size_t n = 10*N*M; + char * buf = new char[n]; + x.write_string(buf, n); + printf("not equal\nx:\n%s\n", buf); + y.write_string(buf, n); + printf("y:\n%s\n", buf); + delete[] buf; } return equal; } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 08d18d55bc..a06165fb72 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -2,6 +2,7 @@ * @file Quaternion.hpp * * All rotations and axis systems follow the right-hand rule. + * The Hamilton quaternion product definition is used. * * In order to rotate a vector v by a righthand rotation defined by the quaternion q * one can use the following operation: @@ -139,12 +140,12 @@ public: Vector() { Quaternion &q = *this; - Type cosPhi_2 = Type(cos(euler.phi() / (Type)2.0)); - Type cosTheta_2 = Type(cos(euler.theta() / (Type)2.0)); - Type cosPsi_2 = Type(cos(euler.psi() / (Type)2.0)); - Type sinPhi_2 = Type(sin(euler.phi() / (Type)2.0)); - Type sinTheta_2 = Type(sin(euler.theta() / (Type)2.0)); - Type sinPsi_2 = Type(sin(euler.psi() / (Type)2.0)); + Type cosPhi_2 = Type(cos(euler.phi() / Type(2.0))); + Type cosTheta_2 = Type(cos(euler.theta() / Type(2.0))); + Type cosPsi_2 = Type(cos(euler.psi() / Type(2.0))); + Type sinPhi_2 = Type(sin(euler.phi() / Type(2.0))); + Type sinTheta_2 = Type(sin(euler.theta() / Type(2.0))); + Type sinPsi_2 = Type(sin(euler.psi() / Type(2.0))); q(0) = cosPhi_2 * cosTheta_2 * cosPsi_2 + sinPhi_2 * sinTheta_2 * sinPsi_2; q(1) = sinPhi_2 * cosTheta_2 * cosPsi_2 - @@ -166,8 +167,8 @@ public: Quaternion &q = *this; Type angle = aa.norm(); Vector axis = aa.unit(); - if (angle < (Type)1e-10) { - q(0) = (Type)1.0; + if (angle < Type(1e-10)) { + q(0) = Type(1.0); q(1) = q(2) = q(3) = 0; } else { Type magnitude = sinf(angle / 2.0f); @@ -253,11 +254,29 @@ public: } /** - * Computes the derivative + * Computes the derivative of q_12 when + * rotated with angular velocity expressed in frame 2 + * v_2 = q_12 * v_1 * q_12^-1 + * d/dt q_12 = 0.5 * q_12 * omega_12_2 * - * @param w direction + * @param w angular rate in frame 2 */ - Matrix41 derivative(const Matrix31 &w) const + Matrix41 derivative1(const Matrix31 &w) const + { + const Quaternion &q = *this; + Quaternion v(0, w(0, 0), w(1, 0), w(2, 0)); + return q * v * Type(0.5); + } + + /** + * Computes the derivative of q_12 when + * rotated with angular velocity expressed in frame 2 + * v_2 = q_12 * v_1 * q_12^-1 + * d/dt q_12 = 0.5 * omega_12_1 * q_12 + * + * @param w angular rate in frame (typically reference frame) + */ + Matrix41 derivative2(const Matrix31 &w) const { const Quaternion &q = *this; Quaternion v(0, w(0, 0), w(1, 0), w(2, 0)); @@ -265,14 +284,11 @@ public: } /** - * Invert quaternion + * Invert quaternion in place */ void invert() { - Quaternion &q = *this; - q(1) *= -1; - q(2) *= -1; - q(3) *= -1; + *this = this->inversed(); } /** @@ -283,12 +299,12 @@ public: Quaternion inversed() { Quaternion &q = *this; - Quaternion ret; - ret(0) = q(0); - ret(1) = -q(1); - ret(2) = -q(2); - ret(3) = -q(3); - return ret; + Type normSq = q.dot(q); + return Quaternion( + q(0)/normSq, + -q(1)/normSq, + -q(2)/normSq, + -q(3)/normSq); } /** @@ -332,8 +348,8 @@ public: Quaternion &q = *this; Type theta = vec.norm(); - if (theta < (Type)1e-10) { - q(0) = (Type)1.0; + if (theta < Type(1e-10)) { + q(0) = Type(1.0); q(1) = q(2) = q(3) = 0; return; } @@ -354,8 +370,8 @@ public: { Quaternion &q = *this; - if (theta < (Type)1e-10) { - q(0) = (Type)1.0; + if (theta < Type(1e-10)) { + q(0) = Type(1.0); q(1) = q(2) = q(3) = 0; } @@ -386,9 +402,9 @@ public: vec(1) = q(2); vec(2) = q(3); - if (axis_magnitude >= (Type)1e-10) { + if (axis_magnitude >= Type(1e-10)) { vec = vec / axis_magnitude; - vec = vec * wrap_pi((Type)2.0 * atan2f(axis_magnitude, q(0))); + vec = vec * wrap_pi(Type(2.0) * atan2f(axis_magnitude, q(0))); } return vec; diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index df82674f74..86025dfc0f 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -44,11 +44,6 @@ public: return _value; } - operator Type const &() const - { - return _value; - } - operator Matrix() const { Matrix m; m(0, 0) = _value; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 912a27a31a..0457a03b1f 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -265,6 +265,58 @@ SquareMatrix inv(const SquareMatrix & A) return i; } } + +/** + * cholesky decomposition + * + * Note: A must be positive definite + */ +template +SquareMatrix cholesky(const SquareMatrix & A) +{ + SquareMatrix L; + for (size_t j = 0; j < M; j++) { + for (size_t i = j; i < M; i++) { + if (i==j) { + float sum = 0; + for (size_t k = 0; k < j; k++) { + sum += L(j, k)*L(j, k); + } + Type res = A(j, j) - sum; + if (res <= 0) { + L(j, j) = 0; + } else { + L(j, j) = sqrtf(res); + } + } else { + float sum = 0; + for (size_t k = 0; k < j; k++) { + sum += L(i, k)*L(j, k); + } + if (L(j, j) <= 0) { + L(i, j) = 0; + } else { + L(i, j) = (A(i, j) - sum)/L(j, j); + } + } + } + } + return L; +} + +/** + * cholesky inverse + * + * TODO: Check if gaussian elimination jumps straight to back-substitution + * for L or we need to do it manually. Will impact speed otherwise. + */ +template +SquareMatrix choleskyInv(const SquareMatrix & A) +{ + SquareMatrix L_inv = inv(cholesky(A)); + return L_inv.T()*L_inv; +} + typedef SquareMatrix Matrix3f; } // namespace matrix diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index bfd5b35f11..7e0fd4bff4 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -29,13 +29,13 @@ Type wrap_pi(Type x) return x; } - while (x >= (Type)M_PI) { - x -= (Type)(2.0 * M_PI); + while (x >= Type(M_PI)) { + x -= Type(2.0 * M_PI); } - while (x < (Type)(-M_PI)) { - x += (Type)(2.0 * M_PI); + while (x < Type(-M_PI)) { + x += Type(2.0 * M_PI); } @@ -43,4 +43,4 @@ Type wrap_pi(Type x) } -}; +} diff --git a/test/attitude.cpp b/test/attitude.cpp index c2c6089d5c..bb5baa42d8 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -99,12 +99,12 @@ int main() // dcm renormalize Dcmf A = eye(); Dcmf R(euler_check); - for (int i = 0; i < 1000; i++) { + for (size_t i = 0; i < 1000; i++) { A = R * A; } A.renormalize(); float err = 0.0f; - for (int row = 0; row < 3; row++) { + for (size_t row = 0; row < 3; row++) { matrix::Vector3f rvec(A._data[row]); err += fabsf(1.0f - rvec.length()); } @@ -179,12 +179,18 @@ int main() Quatf q_from_m(m4); TEST(isEqual(q_from_m, m4)); - // quaternion derivate + // quaternion derivative in frame 1 Quatf q1(0, 1, 0, 0); - Vector q1_dot = q1.derivative(Vector3f(1, 2, 3)); - float data_q_dot_check[] = { -0.5f, 0.0f, -1.5f, 1.0f}; - Vector q1_dot_check(data_q_dot_check); - TEST(isEqual(q1_dot, q1_dot_check)); + Vector q1_dot1 = q1.derivative1(Vector3f(1, 2, 3)); + float data_q_dot1_check[] = { -0.5f, 0.0f, 1.5f, -1.0f}; + Vector q1_dot1_check(data_q_dot1_check); + TEST(isEqual(q1_dot1, q1_dot1_check)); + + // quaternion derivative in frame 2 + Vector q1_dot2 = q1.derivative2(Vector3f(1, 2, 3)); + float data_q_dot2_check[] = { -0.5f, 0.0f, -1.5f, 1.0f}; + Vector q1_dot2_check(data_q_dot2_check); + TEST(isEqual(q1_dot2, q1_dot2_check)); // quaternion product Quatf q_prod_check( @@ -220,8 +226,12 @@ int main() TEST(fabsf(q_check(2) + q(2)) < eps); TEST(fabsf(q_check(3) + q(3)) < eps); - // rotate quaternion (nonzero rotation) + // non-unit quaternion invese Quatf qI(1.0f, 0.0f, 0.0f, 0.0f); + Quatf q_nonunit(0.1f, 0.2f, 0.3f, 0.4f); + TEST(isEqual(qI, q_nonunit*q_nonunit.inversed())); + + // rotate quaternion (nonzero rotation) Vector rot; rot(0) = 1.0f; rot(1) = rot(2) = 0.0f; @@ -270,7 +280,7 @@ int main() float q_array[] = {0.9833f, -0.0343f, -0.1060f, -0.1436f}; Quaternionq_from_array(q_array); - for (int i = 0; i < 4; i++) { + for (size_t i = 0; i < 4; i++) { TEST(fabsf(q_from_array(i) - q_array[i]) < eps); } @@ -333,6 +343,6 @@ int main() q = Quatf(0,0,0,1); // 180 degree rotation around the z axis R = Dcmf(q); TEST(isEqual(q, Quatf(R))); -}; +} /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/inverse.cpp b/test/inverse.cpp index 3c157388c0..98f0c92d8f 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -106,6 +106,26 @@ int main() TEST(isEqual(A3_I, Z3)); TEST(isEqual(A3.I(), Z3)); + float data4[9] = { + 1.33471626f, 0.74946721f, -0.0531679f, + 0.74946721f, 1.07519593f, 0.08036323f, + -0.0531679f, 0.08036323f, 1.01618474f + }; + SquareMatrix A4(data4); + + float data4_cholesky[9] = { + 1.15529921f, 0.f, 0.f, + 0.6487213f , 0.80892311f, 0.f, + -0.04602089f, 0.13625271f, 0.99774847f + }; + SquareMatrix A4_cholesky_check(data4_cholesky); + SquareMatrix A4_cholesky = cholesky(A4); + TEST(isEqual(A4_cholesky_check, A4_cholesky)); + + SquareMatrix I3; + I3.setIdentity(); + TEST(isEqual(choleskyInv(A4)*A4, I3)); + TEST(isEqual(cholesky(Z3), Z3)); return 0; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 69124d9235..1cba50f097 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -101,10 +101,8 @@ int main() Scalar s; s = 1; - float const & s_float = (const Scalar)s; const Vector & s_vect = s; TEST(fabs(s - 1) < 1e-5); - TEST(fabs(s_float - 1.0f) < 1e-5); TEST(fabs(s_vect(0) - 1.0f) < 1e-5); Matrix m5 = s; diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index e17614dafd..f266d62732 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -10,8 +10,8 @@ int main() Matrix3f A; A.setIdentity(); - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { + for (size_t i = 0; i < 3; i++) { + for (size_t j = 0; j < 3; j++) { if (i == j) { TEST( fabs(A(i, j) - 1) < 1e-7); @@ -24,8 +24,8 @@ int main() Matrix3f B; B.identity(); - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { + for (size_t i = 0; i < 3; i++) { + for (size_t j = 0; j < 3; j++) { if (i == j) { TEST( fabs(B(i, j) - 1) < 1e-7); From 843be9418b0e7c5fa4fd8e5e1af2a33cdcbe1e78 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 3 Feb 2017 18:15:43 -0500 Subject: [PATCH 207/388] Rename isfinite to is_finite to avoid name conflicts. --- matrix/SquareMatrix.hpp | 2 +- matrix/helper_functions.hpp | 4 ++-- matrix/math.hpp | 1 - 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 0457a03b1f..ddb059840d 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -241,7 +241,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) //check sanity of results for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < M; j++) { - if (!isfinite(P(i,j))) { + if (!is_finite(P(i,j))) { return false; } } diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 7e0fd4bff4..893f4da492 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -14,7 +14,7 @@ namespace matrix { template -bool isfinite(Type x) { +bool is_finite(Type x) { #if defined (__PX4_NUTTX) || defined (__PX4_QURT) return PX4_ISFINITE(x); #else @@ -25,7 +25,7 @@ bool isfinite(Type x) { template Type wrap_pi(Type x) { - if (!isfinite(x)) { + if (!is_finite(x)) { return x; } diff --git a/matrix/math.hpp b/matrix/math.hpp index 4a759efe63..b69d2e0eec 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -13,4 +13,3 @@ #include "Scalar.hpp" #include "Quaternion.hpp" #include "AxisAngle.hpp" -#include "helper_functions.hpp" From 2283e6946a591e93f81df6678a0953baad1b9835 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 4 Feb 2017 10:42:10 +0100 Subject: [PATCH 208/388] Matrix inversion: Ensure that null check is done against the same type --- matrix/SquareMatrix.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ddb059840d..32fb43ca9b 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -142,12 +142,12 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) for (size_t n = 0; n < M; n++) { // if diagonal is zero, swap with row below - if (fabsf(U(n, n)) < 1e-8f) { + if (fabsf(static_cast(U(n, n))) < 1e-8f) { //printf("trying pivot for row %d\n",n); for (size_t i = n + 1; i < M; i++) { //printf("\ttrying row %d\n",i); - if (fabsf(U(i, n)) > 1e-8f) { + if (fabsf(static_cast(U(i, n))) > 1e-8f) { //printf("swapped %d\n",i); U.swapRows(i, n); P.swapRows(i, n); @@ -167,7 +167,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) #endif // failsafe, return zero matrix - if (fabsf(U(n, n)) < 1e-8f) { + if (fabsf(static_cast(U(n, n))) < 1e-8f) { return false; } From e2211c586714d0c3175d5d38c28d7f1f677d64a3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 15 Feb 2017 18:02:05 -0500 Subject: [PATCH 209/388] QuRT use __builtin_isfinite --- matrix/helper_functions.hpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 893f4da492..79d57504c7 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -15,8 +15,10 @@ namespace matrix template bool is_finite(Type x) { -#if defined (__PX4_NUTTX) || defined (__PX4_QURT) +#if defined (__PX4_NUTTX) return PX4_ISFINITE(x); +#elif defined (__PX4_QURT) + return __builtin_isfinite(x); #else return std::isfinite(x); #endif From 68c7cc5bfdb58b10486d0942e6c678f1a76208fd Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 11:08:39 -0500 Subject: [PATCH 210/388] Quaternion add copyTo --- .gitignore | 31 ++++++++++++++++++++++++++++++- matrix/Quaternion.hpp | 14 ++++++++++++++ test/attitude.cpp | 11 +++++++++++ 3 files changed, 55 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index 433da5d5ba..2cdd83e6be 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,33 @@ -build*/ *.orig *.swp +astyle/ +build*/ +cmake_install.cmake +CMakeCache.txt +CMakeFiles/ +CPackConfig.cmake +CPackSourceConfig.cmake +CTestTestfile.cmake +Makefile +test/attitude +test/cmake_install.cmake +test/CMakeFiles/ +test/CTestTestfile.cmake +test/filter +test/hatvee +test/helper +test/integration +test/inverse +test/Makefile +test/matrixAssignment +test/matrixMult +test/matrixScalarMult +test/setIdentity +test/slice +test/squareMatrix +test/transpose +test/vector +test/vector2 +test/vector3 +test/vectorAssignment Testing/ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a06165fb72..c7a5f2bda3 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -253,6 +253,20 @@ public: q = q * scalar; } + /** + * Copy quaternion to a float array + * + * @param dst array of 4 floats + */ + void copyTo(float (&dst)[4]) + { + const Quaternion &q = *this; + dst[0] = q(0); + dst[1] = q(1); + dst[2] = q(2); + dst[3] = q(3); + } + /** * Computes the derivative of q_12 when * rotated with angular velocity expressed in frame 2 diff --git a/test/attitude.cpp b/test/attitude.cpp index bb5baa42d8..460a3c10b5 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -343,6 +343,17 @@ int main() q = Quatf(0,0,0,1); // 180 degree rotation around the z axis R = Dcmf(q); TEST(isEqual(q, Quatf(R))); + + + // Quaternion copyTo + q = Quatf(1, 2, 3, 4); + float dst[4] = {}; + q.copyTo(dst); + TEST(fabsf(q(0) - dst[0]) < eps); + TEST(fabsf(q(1) - dst[1]) < eps); + TEST(fabsf(q(2) - dst[2]) < eps); + TEST(fabsf(q(3) - dst[3]) < eps); + } /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From f00edc944220d8a305b51e20203b73ccb93da149 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 11:10:19 -0500 Subject: [PATCH 211/388] update to astyle 2.06 and fix formatting --- CMakeLists.txt | 2 +- matrix/Matrix.hpp | 16 ++++++++-------- test/inverse.cpp | 6 +++--- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ab4e2a0a3f..e08762f53e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,7 +75,7 @@ endif() if(FORMAT) set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) add_custom_command(OUTPUT ${astyle_exe} - COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.05.1/astyle_2.05.1_linux.tar.gz -O /tmp/astyle.tar.gz + COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.06/astyle_2.06_linux.tar.gz -O /tmp/astyle.tar.gz COMMAND tar -xvf /tmp/astyle.tar.gz COMMAND cd astyle/src && make -f ../build/gcc/Makefile WORKING_DIRECTORY ${CMAKE_BINARY_DIR} diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 9082d6b6a2..dab1b65d30 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -119,7 +119,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j)*other(i, j); + res(i, j) = self(i, j)*other(i, j); } } @@ -133,7 +133,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j)/other(i, j); + res(i, j) = self(i, j)/other(i, j); } } @@ -147,7 +147,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) + other(i, j); + res(i, j) = self(i, j) + other(i, j); } } @@ -161,7 +161,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) - other(i, j); + res(i, j) = self(i, j) - other(i, j); } } @@ -176,7 +176,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = -self(i, j); + res(i, j) = -self(i, j); } } @@ -213,7 +213,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) * scalar; + res(i, j) = self(i, j) * scalar; } } @@ -232,7 +232,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - res(i , j) = self(i, j) + scalar; + res(i, j) = self(i, j) + scalar; } } @@ -491,7 +491,7 @@ bool isEqual(const Matrix &x, for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - if (fabs(x(i , j) - y(i, j)) > eps) { + if (fabs(x(i, j) - y(i, j)) > eps) { equal = false; break; } diff --git a/test/inverse.cpp b/test/inverse.cpp index 98f0c92d8f..69808b4af1 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -55,8 +55,8 @@ int main() }; float data2_check[81] = { - 6, -4, 3, -3 , -9, -8, -10, 8, 14, - -2, -7, -5, -3 , -2, -2, -16, -5, 8, + 6, -4, 3, -3, -9, -8, -10, 8, 14, + -2, -7, -5, -3, -2, -2, -16, -5, 8, -2, 0, -23, 7, -24, -5, -28, -14, 9, 3, -7, 2, -5, -4, -6, -13, 4, 13, -1, 4, -8, 5, -8, 0, -3, -5, -2, @@ -115,7 +115,7 @@ int main() float data4_cholesky[9] = { 1.15529921f, 0.f, 0.f, - 0.6487213f , 0.80892311f, 0.f, + 0.6487213f, 0.80892311f, 0.f, -0.04602089f, 0.13625271f, 0.99774847f }; SquareMatrix A4_cholesky_check(data4_cholesky); From fb87165051aa5942f5cef2bb26652d5b3fcbbced Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 11:14:25 -0500 Subject: [PATCH 212/388] cmake add check --- .travis.yml | 4 +--- CMakeLists.txt | 5 +++++ 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index 6afc49c8f9..e92e7a7613 100644 --- a/.travis.yml +++ b/.travis.yml @@ -4,9 +4,7 @@ install: - pip install --user cpp-coveralls script: - cmake -DCMAKE_BUILD_TYPE=Profile -DTESTING=ON -DFORMAT=ON . - - make - - make check_format - - ctest -V + - make check after_success: - cpp-coveralls -i matrix env: diff --git a/CMakeLists.txt b/CMakeLists.txt index e08762f53e..f21b56fe09 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -96,6 +96,11 @@ if(FORMAT) ) endif() +if(TESTING AND FORMAT) + add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) + add_dependencies(check test_build check_format) +endif() + set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) From 5f2f6f0308e726bc77f5f25c19f08b3ec8cc21ac Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 11:37:03 -0500 Subject: [PATCH 213/388] rename cmake "Profile" to "Coverage" and add builds --- .gitignore | 4 ++ .travis.yml | 41 ++++++++++++++----- CMakeLists.txt | 96 +++++++++++++++++++++++++-------------------- test/CMakeLists.txt | 2 +- 4 files changed, 90 insertions(+), 53 deletions(-) diff --git a/.gitignore b/.gitignore index 2cdd83e6be..8efccc5293 100644 --- a/.gitignore +++ b/.gitignore @@ -1,10 +1,12 @@ *.orig *.swp +*~ astyle/ build*/ cmake_install.cmake CMakeCache.txt CMakeFiles/ +compile_commands.json CPackConfig.cmake CPackSourceConfig.cmake CTestTestfile.cmake @@ -12,6 +14,7 @@ Makefile test/attitude test/cmake_install.cmake test/CMakeFiles/ +test/coverage.info test/CTestTestfile.cmake test/filter test/hatvee @@ -22,6 +25,7 @@ test/Makefile test/matrixAssignment test/matrixMult test/matrixScalarMult +test/out/ test/setIdentity test/slice test/squareMatrix diff --git a/.travis.yml b/.travis.yml index e92e7a7613..790f6a2f40 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,17 +1,40 @@ language: c -sudo: false -install: - - pip install --user cpp-coveralls -script: - - cmake -DCMAKE_BUILD_TYPE=Profile -DTESTING=ON -DFORMAT=ON . - - make check -after_success: - - cpp-coveralls -i matrix + env: global: - export COVERALLS_SERVICE_NAME=travis-ci - secure: "dA+jGAR9O3f+xsh6h7e7coeM0dU1vHiiM7kIPh5TvbbifDQiF5s2uxFQziZVSnLuohRD9oNODiJFz077n+svp7S9t77sdks0+7r61pkD5LlVItZ6ol5jQCfiksyMw6q5ChEes9KSKEfdFRjuDvQUHwShgpsXVAurizA2Hs3MziWxfIlOPULY4UCCm5+TLoY+vXmfFc4bwk2knxpIP8pYRd+xKYAiN9QC1fJiglipuKHaYbo2+ZYrM92RD0Cl+BZdWyI7vD7zmeXV6mstzAFZ20c63NhNNCYRy0VIC3hLB8zKMuvCZdJnpmSRfFt5uJYJPNcORc1ypeY7/CGMm5Rq1lNwxehFO3/++/aHE8H7GR0cTiKndPO0jDu48j+GUB4k1HHSsVEpj7vO7F3FOO0619xxybDFk1zFjHw8KTbdSXmBERldYAKZOP0JKZxp6CU5DXOO2dunumZAzl6WHJjhRMPFqPheE4e+I2YOEHvXTwDcEO/lMwacr6nuaZZXxEh/TwEdqsIRd9bvsoG1zuVQnZm+atLp3oF4QW8nI5l6qe6R+3l5dEgJGtz5hOsiEpWrwWk6ub2VCdELcgpPZyZcdwu/bKvXx3ndW6LjqzcLxMGxM3rdxx6J+b7Es/vkmT1SXFcxiUjpKkUf04Bb8SmGdbJdAKRZuSRFtjqsU0tHPfo=" + +matrix: + fast_finish: true + include: + - os: linux + dist: trusty + compiler: gcc + env: CMAKE_BUILD_TYPE=Coverage + - os: linux + dist: trusty + compiler: clang + env: CMAKE_BUILD_TYPE=Release CC=clang CXX=clang++ + - os: osx + osx_image: xcode8 + env: CMAKE_BUILD_TYPE=Release + addons: apt: packages: - - cmake + - cmake + - gcc + - g++ + - clang + +install: + - pip install --user cpp-coveralls + +script: + - cmake -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DTESTING=ON -DFORMAT=ON . + - make check + +after_success: + - if [[ "${CMAKE_BUILD_TYPE}" = "Coverage" && "${TRAVIS_BRANCH}" == "master" ]]; then cpp-coveralls -i matrix; fi + diff --git a/CMakeLists.txt b/CMakeLists.txt index f21b56fe09..1dc32ced5d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -7,69 +7,82 @@ set(VERSION_PATCH "2") project(matrix CXX) if (NOT CMAKE_BUILD_TYPE) - set(CMAKE_BUILD_TYPE "Profile" CACHE STRING "Build type" FORCE) + set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() -set_property(CACHE CMAKE_BUILD_TYPE PROPERTY - STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Profile") +set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage") -option(SUPPORT_STDIOSTREAM - "If enabled provides support for << operator (as used with std::cout)" OFF) +option(SUPPORT_STDIOSTREAM "If enabled provides support for << operator (as used with std::cout)" OFF) option(TESTING "Enable testing" OFF) option(FORMAT "Enable formatting" OFF) option(COV_HTML "Display html for coverage" OFF) +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + +include_directories(${CMAKE_SOURCE_DIR}) + if(SUPPORT_STDIOSTREAM) add_definitions(-DSUPPORT_STDIOSTREAM) endif() -set(CMAKE_CXX_FLAGS_PROFILE - ${CMAKE_CXX_FLAGS_DEBUG} - --coverage - -fno-inline - -fno-inline-small-functions - -fno-default-inline - ) -string(REPLACE ";" " " CMAKE_CXX_FLAGS_PROFILE "${CMAKE_CXX_FLAGS_PROFILE}") +set(CMAKE_CXX_FLAGS_COVERAGE + "--coverage -fprofile-arcs -ftest-coverage -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors" + CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) +set(CMAKE_EXE_LINKER_FLAGS_COVERAGE + "--coverage -ftest-coverage -lgcov" + CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) +mark_as_advanced(CMAKE_CXX_FLAGS_COVERAGE CMAKE_C_FLAGS_COVERAGE CMAKE_EXE_LINKER_FLAGS_COVERAGE) -set(CMAKE_CXX_FLAGS - ${CMAKE_CXX_FLAGS} +add_compile_options( + -pedantic -Wall - -Wno-sign-compare - -Wextra - -Wshadow - -Wfloat-equal - -Wpointer-arith - -Wmissing-declarations - -Wno-unused-parameter - -Werror=format-security - -Werror=array-bounds - #-Wfatal-errors - -Werror=unused-variable - -Werror=reorder - -Werror=uninitialized - -Werror=init-self + -Warray-bounds + -Wcast-align -Wcast-qual -Wconversion - -Wcast-align + -Wctor-dtor-privacy + -Wdisabled-optimization -Werror - -pedantic -Wctor-dtor-privacy -Wdisabled-optimization -Wformat=2 - -Winit-self -Wlogical-op -Wmissing-declarations - -Wmissing-include-dirs -Wnoexcept -Wold-style-cast - -Woverloaded-virtual -Wredundant-decls -Wshadow -Wsign-conversion - -Wsign-promo -Wstrict-null-sentinel -Wstrict-overflow=5 - -Wswitch-default -Wundef -Werror -Wno-unused + -Wextra + -Wfloat-equal + -Wformat-security + -Wformat=2 + -Winit-self + -Wlogical-op + -Wmissing-declarations + -Wmissing-include-dirs + -Wno-sign-compare + -Wno-unused + -Wno-unused-parameter + -Wnoexcept + -Wold-style-cast + -Woverloaded-virtual + -Wpointer-arith + -Wredundant-decls + -Wreorder + -Wshadow + -Wsign-conversion + -Wsign-promo + -Wstrict-null-sentinel + -Wstrict-overflow=5 + -Wswitch-default + -Wundef + -Wuninitialized + -Wunused-variable ) -string(REPLACE ";" " " CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") -include_directories(${CMAKE_SOURCE_DIR}) +# clang tolerate unknown gcc options +if ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + add_compile_options(-Wno-error=unused-command-line-argument-hard-error-in-future -Wno-unknown-warning-option) +endif() -file(GLOB_RECURSE COV_SRCS matrix/*.hpp matrix/*.cpp) +add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) if(TESTING) enable_testing() add_subdirectory(test) + add_dependencies(check test_build) endif() if(FORMAT) @@ -94,11 +107,8 @@ if(FORMAT) VERBATIM DEPENDS ${astyle_exe} ) -endif() -if(TESTING AND FORMAT) - add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) - add_dependencies(check test_build check_format) + add_dependencies(check check_format) endif() set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index da5e6316b2..2c7d42981f 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -26,7 +26,7 @@ foreach(test_name ${tests}) add_dependencies(test_build ${test_name}) endforeach() -if (${CMAKE_BUILD_TYPE} STREQUAL "Profile") +if (${CMAKE_BUILD_TYPE} STREQUAL "Coverage") add_custom_target(coverage_build COMMAND ${CMAKE_CTEST_COMMAND} From cfa68c21967a39c4ed0b403d801e6a81f3fbecf3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 13:10:52 -0500 Subject: [PATCH 214/388] clang-tidy trivial cleanup --- .clang-tidy | 9 ++++++++ CMakeLists.txt | 16 +++++++++++-- matrix/AxisAngle.hpp | 2 +- matrix/Dcm.hpp | 2 -- matrix/Matrix.hpp | 26 +++++++++------------ matrix/Scalar.hpp | 6 ----- matrix/SquareMatrix.hpp | 6 ----- matrix/Vector.hpp | 2 +- matrix/helper_functions.hpp | 7 ------ test/attitude.cpp | 45 +++++++++++++++++++------------------ test/filter.cpp | 10 +++++---- test/hatvee.cpp | 9 ++++---- test/helper.cpp | 10 ++++----- test/integration.cpp | 12 +++++----- test/inverse.cpp | 10 +++------ test/matrixAssignment.cpp | 24 +++++++++++--------- test/matrixMult.cpp | 7 +++--- test/matrixScalarMult.cpp | 7 +++--- test/setIdentity.cpp | 15 ++++++------- test/slice.cpp | 7 +++--- test/squareMatrix.cpp | 6 ++--- test/transpose.cpp | 9 +++----- test/vector.cpp | 8 +++---- test/vector2.cpp | 25 ++++++++++----------- test/vector3.cpp | 31 +++++++++++++------------ test/vectorAssignment.cpp | 23 +++++++++---------- 26 files changed, 157 insertions(+), 177 deletions(-) create mode 100644 .clang-tidy diff --git a/.clang-tidy b/.clang-tidy new file mode 100644 index 0000000000..2878339187 --- /dev/null +++ b/.clang-tidy @@ -0,0 +1,9 @@ +Checks: 'clang-diagnostic-*,clang-analyzer-*,*, + ,-cppcoreguidelines-pro-type-vararg + ,-cppcoreguidelines-pro-bounds-array-to-pointer-decay + ,-cppcoreguidelines-pro-bounds-constant-array-index + ,-cppcoreguidelines-pro-bounds-pointer-arithmetic + ' +WarningsAsErrors: '*' +HeaderFilterRegex: '*.h, *.hpp, *.hh, *.hxx' + diff --git a/CMakeLists.txt b/CMakeLists.txt index 1dc32ced5d..788988e6c0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,6 +6,9 @@ set(VERSION_PATCH "2") project(matrix CXX) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + if (NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") @@ -65,7 +68,6 @@ add_compile_options( -Wsign-conversion -Wsign-promo -Wstrict-null-sentinel - -Wstrict-overflow=5 -Wswitch-default -Wundef -Wuninitialized @@ -74,7 +76,14 @@ add_compile_options( # clang tolerate unknown gcc options if ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") - add_compile_options(-Wno-error=unused-command-line-argument-hard-error-in-future -Wno-unknown-warning-option) + add_compile_options( + -Wno-error=unused-command-line-argument-hard-error-in-future + -Wno-unknown-warning-option + ) +else() + add_compile_options( + -Wstrict-overflow=5 + ) endif() add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) @@ -83,6 +92,9 @@ if(TESTING) enable_testing() add_subdirectory(test) add_dependencies(check test_build) + + add_custom_target(clang-tidy COMMAND clang-tidy -p . ${CMAKE_SOURCE_DIR}/test/*.cpp) + add_dependencies(clang-tidy test_build) endif() if(FORMAT) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index ab945379d6..5a6cc4af9f 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -31,7 +31,7 @@ template class AxisAngle : public Vector { public: - virtual ~AxisAngle() {}; + ~AxisAngle() override = default; typedef Matrix Matrix31; diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index ba61d66a54..c418a8a30b 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -17,7 +17,6 @@ #include "math.hpp" - namespace matrix { @@ -30,7 +29,6 @@ class Euler; template class AxisAngle; - /** * Direction cosine matrix class * diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index dab1b65d30..0d3fd48e38 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -8,11 +8,10 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include + #if defined(SUPPORT_STDIOSTREAM) #include #include @@ -36,25 +35,20 @@ public: virtual ~Matrix() {}; - Matrix() : - _data() - { - } + // Constructors + Matrix() : _data() {} - Matrix(const Type data_[][N]) : - _data() + Matrix(const Type data_[][N]) : _data() { memcpy(_data, data_, sizeof(_data)); } - Matrix(const Type *data_) : - _data() + Matrix(const Type *data_) : _data() { memcpy(_data, data_, sizeof(_data)); } - Matrix(const Matrix &other) : - _data() + Matrix(const Matrix &other) : _data() { memcpy(_data, other._data, sizeof(_data)); } @@ -519,7 +513,7 @@ bool isEqualF(Type x, bool equal = true; - if (fabsf(x - y) > eps) { + if (fabs(x - y) > eps) { equal = false; } diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 86025dfc0f..ca3743d328 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -8,12 +8,6 @@ #pragma once -#include -#include -#include -#include -#include - #include "math.hpp" namespace matrix diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 32fb43ca9b..f1a5a9b134 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -8,12 +8,6 @@ #pragma once -#include -#include -#include -#include -#include - #include "math.hpp" #include "helper_functions.hpp" diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 61382d7548..9265b2a223 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -22,7 +22,7 @@ template class Vector : public Matrix { public: - virtual ~Vector() {}; + ~Vector() override = default; typedef Matrix MatrixM1; diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 79d57504c7..f501598f9b 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -1,14 +1,7 @@ #pragma once #include "math.hpp" - -// grody hack - this should go once C++11 is supported -// on all platforms. -#if defined (__PX4_NUTTX) || defined (__PX4_QURT) -#include -#else #include -#endif namespace matrix { diff --git a/test/attitude.cpp b/test/attitude.cpp index 460a3c10b5..49b47b3807 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -1,21 +1,20 @@ -#include -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; - -// important to list all classes here for coverage -template class Quaternion; -template class Euler; -template class Dcm; -template class AxisAngle; -template class Scalar; -template class SquareMatrix; -template class Vector; -template class Vector2; -template class Vector3; +using matrix::AxisAnglef; +using matrix::Dcm; +using matrix::Dcmf; +using matrix::Euler; +using matrix::Eulerf; +using matrix::eye; +using matrix::isEqualF; +using matrix::Matrix; +using matrix::Quaternion; +using matrix::Quatf; +using matrix::SquareMatrix; +using matrix::Vector3f; +using matrix::Vector; +using matrix::zeros; int main() { @@ -51,10 +50,10 @@ int main() // quaternion ctor Quatf q0(1, 2, 3, 4); Quatf q(q0); - TEST(fabs(q(0) - 1) < eps); - TEST(fabs(q(1) - 2) < eps); - TEST(fabs(q(2) - 3) < eps); - TEST(fabs(q(3) - 4) < eps); + TEST(fabsf(q(0) - 1) < eps); + TEST(fabsf(q(1) - 2) < eps); + TEST(fabsf(q(2) - 3) < eps); + TEST(fabsf(q(3) - 4) < eps); // quat normalization q.normalize(); @@ -102,10 +101,12 @@ int main() for (size_t i = 0; i < 1000; i++) { A = R * A; } + A.renormalize(); float err = 0.0f; - for (size_t row = 0; row < 3; row++) { - matrix::Vector3f rvec(A._data[row]); + + for (auto & row : A._data) { + Vector3f rvec(row); err += fabsf(1.0f - rvec.length()); } TEST(err < eps); diff --git a/test/filter.cpp b/test/filter.cpp index 368b788f7b..c5e6d2ca77 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -1,9 +1,11 @@ -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; +using matrix::Matrix; +using matrix::kalman_correct; +using matrix::eye; +using matrix::SquareMatrix; +using matrix::Vector; int main() { diff --git a/test/hatvee.cpp b/test/hatvee.cpp index c79a2b4184..6250621a24 100644 --- a/test/hatvee.cpp +++ b/test/hatvee.cpp @@ -1,11 +1,10 @@ -#include #include "test_macros.hpp" - #include -using namespace matrix; - -template class SquareMatrix; +using matrix::Dcm; +using matrix::Euler; +using matrix::isEqual; +using matrix::Vector3; int main() { diff --git a/test/helper.cpp b/test/helper.cpp index e4787fc3a2..e280f5238f 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -1,10 +1,10 @@ -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; - +using matrix::isEqual; +using matrix::isEqualF; +using matrix::Vector3f; +using matrix::wrap_pi; int main() { diff --git a/test/integration.cpp b/test/integration.cpp index abbfe885b3..ec4cf80230 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -1,13 +1,13 @@ -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; +using matrix::Matrix; +using matrix::ones; +using matrix::Vector; -Vector f(float t, const Matrix & y, const Matrix & u); +Vector f(float t, const Matrix & /*y*/, const Matrix & /*u*/); -Vector f(float t, const Matrix & y, const Matrix & u) { +Vector f(float t, const Matrix & /*y*/, const Matrix & /*u*/) { float v = -sinf(t); return v*ones(); } diff --git a/test/inverse.cpp b/test/inverse.cpp index 69808b4af1..92aaa70a03 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -1,15 +1,11 @@ -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; +using matrix::SquareMatrix; +using matrix::zeros; static const size_t n_large = 50; -template class SquareMatrix; -template class SquareMatrix; - int main() { float data[9] = {0, 2, 3, diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 1cba50f097..6f18d36ee7 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -1,9 +1,11 @@ -#include #include "test_macros.hpp" +#include -using namespace matrix; - -template class Matrix; +using matrix::Matrix; +using matrix::Matrix3f; +using matrix::Scalar; +using matrix::Vector; +using matrix::Vector2f; int main() { @@ -24,7 +26,7 @@ int main() Matrix3f m2(data); for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabsf(data[i] - m2.data()[i]) < 1e-6f); } float data2d[3][3] = { @@ -34,7 +36,7 @@ int main() }; m2 = Matrix3f(data2d); for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabsf(data[i] - m2.data()[i]) < 1e-6f); } float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; @@ -96,17 +98,17 @@ int main() m4.swapCols(2, 2); TEST(isEqual(m4, Matrix3f(data))); - TEST(fabs(m4.min() - 1) < 1e-5); - TEST(fabs((-m4).min() + 9) < 1e-5); + TEST(fabsf(m4.min() - 1) < 1e-5); + TEST(fabsf((-m4).min() + 9) < 1e-5); Scalar s; s = 1; const Vector & s_vect = s; - TEST(fabs(s - 1) < 1e-5); - TEST(fabs(s_vect(0) - 1.0f) < 1e-5); + TEST(fabsf(s - 1) < 1e-5); + TEST(fabsf(s_vect(0) - 1.0f) < 1e-5); Matrix m5 = s; - TEST(fabs(m5(0,0) - s) < 1e-5); + TEST(fabsf(m5(0,0) - s) < 1e-5); Matrix m6; m6.setRow(0, Vector2f(1, 2)); diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index ecf9d9b3af..97caa1532d 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -1,9 +1,8 @@ -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; +using matrix::Matrix3f; +using matrix::eye; int main() { diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index 147459d42b..925dbd95a6 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -1,9 +1,8 @@ -#include - -#include #include "test_macros.hpp" -using namespace matrix; +#include + +using matrix::Matrix3f; int main() { diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index f266d62732..fc48ed41a2 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -1,9 +1,7 @@ -#include #include "test_macros.hpp" +#include -using namespace matrix; - -template class Matrix; +using matrix::Matrix3f; int main() { @@ -13,10 +11,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST( fabs(A(i, j) - 1) < 1e-7); + TEST(fabsf(A(i, j) - 1) < 1e-7); } else { - TEST( fabs(A(i, j) - 0) < 1e-7); + TEST(fabsf(A(i, j) - 0) < 1e-7); } } } @@ -27,13 +25,14 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST( fabs(B(i, j) - 1) < 1e-7); + TEST(fabsf(B(i, j) - 1) < 1e-7); } else { - TEST( fabs(B(i, j) - 0) < 1e-7); + TEST(fabsf(B(i, j) - 0) < 1e-7); } } } + return 0; } diff --git a/test/slice.cpp b/test/slice.cpp index 36f13f504b..ba44980f1c 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -1,9 +1,8 @@ -#include - -#include #include "test_macros.hpp" +#include -using namespace matrix; +using matrix::Matrix; +using matrix::SquareMatrix; int main() { diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index ff87a3b8be..0ecb26874b 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -1,11 +1,9 @@ -#include #include "test_macros.hpp" #include -using namespace matrix; - -template class SquareMatrix; +using matrix::SquareMatrix; +using matrix::Vector3; int main() { diff --git a/test/transpose.cpp b/test/transpose.cpp index 9da5e32d98..350c626070 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -1,12 +1,8 @@ -#include - -#include #include "test_macros.hpp" -using namespace matrix; +#include -template class Matrix; -template class Matrix; +using matrix::Matrix; int main() { @@ -16,6 +12,7 @@ int main() float data_check[6] = {1, 4, 2, 5, 3, 6}; Matrix A_T_check(data_check); TEST(isEqual(A_T, A_T_check)); + return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index 66aa109e2e..8bb71c997e 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -1,11 +1,9 @@ -#include - -#include #include "test_macros.hpp" -using namespace matrix; +#include -template class Vector; +using matrix::Vector; +using matrix::isEqualF; int main() { diff --git a/test/vector2.cpp b/test/vector2.cpp index a0625a7ee7..399b301456 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -1,35 +1,34 @@ -#include + #include #include "test_macros.hpp" -using namespace matrix; - -template class Vector; +using matrix::Vector2f; +using matrix::Matrix; int main() { Vector2f a(1, 0); Vector2f b(0, 1); - TEST(fabs(a % b - 1.0f) < 1e-5); + TEST(fabsf(a % b - 1.0f) < 1e-5); Vector2f c; - TEST(fabs(c(0) - 0) < 1e-5); - TEST(fabs(c(1) - 0) < 1e-5); + TEST(fabsf(c(0) - 0) < 1e-5); + TEST(fabsf(c(1) - 0) < 1e-5); Matrix d(a); - TEST(fabs(d(0,0) - 1) < 1e-5); - TEST(fabs(d(1,0) - 0) < 1e-5); + TEST(fabsf(d(0,0) - 1) < 1e-5); + TEST(fabsf(d(1,0) - 0) < 1e-5); Vector2f e(d); - TEST(fabs(e(0) - 1) < 1e-5); - TEST(fabs(e(1) - 0) < 1e-5); + TEST(fabsf(e(0) - 1) < 1e-5); + TEST(fabsf(e(1) - 0) < 1e-5); float data[] = {4,5}; Vector2f f(data); - TEST(fabs(f(0) - 4) < 1e-5); - TEST(fabs(f(1) - 5) < 1e-5); + TEST(fabsf(f(0) - 4) < 1e-5); + TEST(fabsf(f(1) - 5) < 1e-5); return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index 611eef9887..8bb76a978d 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -1,34 +1,33 @@ -#include - -#include #include "test_macros.hpp" -using namespace matrix; +#include -template class Vector; +using matrix::Vector3f; +using matrix::Matrix; int main() { Vector3f a(1, 0, 0); Vector3f b(0, 1, 0); Vector3f c = a.cross(b); - TEST(isEqual(c, Vector3f(0,0,1))); + TEST(matrix::isEqual(c, Vector3f(0,0,1))); c = a % b; - TEST (isEqual(c, Vector3f(0,0,1))); + TEST(matrix::isEqual(c, Vector3f(0,0,1))); Matrix d(c); Vector3f e(d); - TEST (isEqual(e, d)); + TEST (matrix::isEqual(e, d)); float data[] = {4, 5, 6}; Vector3f f(data); - TEST(isEqual(f, Vector3f(4, 5, 6))); + TEST(matrix::isEqual(f, Vector3f(4, 5, 6))); + + TEST(matrix::isEqual(a + b, Vector3f(1, 1, 0))); + TEST(matrix::isEqual(a - b, Vector3f(1, -1, 0))); + TEST(matrix::isEqualF(a * b, 0.0f)); + TEST(matrix::isEqual(-a, Vector3f(-1, 0, 0))); + TEST(matrix::isEqual(a.unit(), a)); + TEST(matrix::isEqual(a.unit(), a.normalized())); + TEST(matrix::isEqual(a*2.0, Vector3f(2, 0, 0))); - TEST(isEqual(a + b, Vector3f(1, 1, 0))); - TEST(isEqual(a - b, Vector3f(1, -1, 0))); - TEST(isEqualF(a * b, 0.0f)); - TEST(isEqual(-a, Vector3f(-1, 0, 0))); - TEST(isEqual(a.unit(), a)); - TEST(isEqual(a.unit(), a.normalized())); - TEST(isEqual(a*2.0, Vector3f(2, 0, 0))); return 0; } diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 215ba0a62b..1f78211965 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -2,9 +2,8 @@ #include "test_macros.hpp" -using namespace matrix; - -template class Vector; +using matrix::SquareMatrix; +using matrix::Vector3f; int main() { @@ -15,20 +14,20 @@ int main() static const float eps = 1e-7f; - TEST(fabs(v(0) - 1) < eps); - TEST(fabs(v(1) - 2) < eps); - TEST(fabs(v(2) - 3) < eps); + TEST(fabsf(v(0) - 1) < eps); + TEST(fabsf(v(1) - 2) < eps); + TEST(fabsf(v(2) - 3) < eps); Vector3f v2(4, 5, 6); - TEST(fabs(v2(0) - 4) < eps); - TEST(fabs(v2(1) - 5) < eps); - TEST(fabs(v2(2) - 6) < eps); + TEST(fabsf(v2(0) - 4) < eps); + TEST(fabsf(v2(1) - 5) < eps); + TEST(fabsf(v2(2) - 6) < eps); SquareMatrix m = diag(Vector3f(1,2,3)); - TEST(fabs(m(0, 0) - 1) < eps); - TEST(fabs(m(1, 1) - 2) < eps); - TEST(fabs(m(2, 2) - 3) < eps); + TEST(fabsf(m(0, 0) - 1) < eps); + TEST(fabsf(m(1, 1) - 2) < eps); + TEST(fabsf(m(2, 2) - 3) < eps); return 0; } From de3517a5c73ec70774dd1f8833129095e8d4e367 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 13:47:40 -0500 Subject: [PATCH 215/388] cmake add asan and ubsan --- CMakeLists.txt | 36 +++++++++++++++++++++++++++++++++++- 1 file changed, 35 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 788988e6c0..e9baaa2b4c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,6 +20,8 @@ option(SUPPORT_STDIOSTREAM "If enabled provides support for << operator (as used option(TESTING "Enable testing" OFF) option(FORMAT "Enable formatting" OFF) option(COV_HTML "Display html for coverage" OFF) +option(ASAN "Enable address sanitizer" OFF) +option(UBSAN "Enable undefined behaviour sanitizer" OFF) set(CMAKE_EXPORT_COMPILE_COMMANDS ON) @@ -75,7 +77,7 @@ add_compile_options( ) # clang tolerate unknown gcc options -if ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") +if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") add_compile_options( -Wno-error=unused-command-line-argument-hard-error-in-future -Wno-unknown-warning-option @@ -86,6 +88,38 @@ else() ) endif() +# santiziers (ASAN, UBSAN) +if(ASAN) + message(STATUS "address sanitizer enabled") + + # environment variables + # ASAN_OPTIONS=detect_stack_use_after_return=1 + # ASAN_OPTIONS=check_initialization_order=1 + + add_compile_options( + -fsanitize=address + -g3 + -O1 + -fno-omit-frame-pointer + ) + + set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=address) + +elseif(UBSAN) + message(STATUS "undefined behaviour sanitizer enabled") + + add_compile_options( + -fsanitize=undefined + -fsanitize=integer + -g3 + -O1 + -fno-omit-frame-pointer + ) + + set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=undefined) +endif() + + add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) if(TESTING) From d81ddb0f376c78ca51cedf1f92dc041bab38a047 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 13:49:28 -0500 Subject: [PATCH 216/388] travis-ci only check formatting once --- .travis.yml | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/.travis.yml b/.travis.yml index 790f6a2f40..692a570bd3 100644 --- a/.travis.yml +++ b/.travis.yml @@ -11,30 +11,30 @@ matrix: - os: linux dist: trusty compiler: gcc - env: CMAKE_BUILD_TYPE=Coverage + env: CMAKE_BUILD_TYPE=Coverage FORMAT=ON - os: linux dist: trusty compiler: clang - env: CMAKE_BUILD_TYPE=Release CC=clang CXX=clang++ + env: CMAKE_BUILD_TYPE=Release CC=clang CXX=clang++ FORMAT=OFF - os: osx osx_image: xcode8 - env: CMAKE_BUILD_TYPE=Release + env: CMAKE_BUILD_TYPE=Release FORMAT=OFF addons: apt: packages: - - cmake - - gcc - - g++ - clang + - cmake + - g++ + - gcc install: - - pip install --user cpp-coveralls + - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then pip install --user cpp-coveralls; fi script: - - cmake -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DTESTING=ON -DFORMAT=ON . + - cmake -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DTESTING=ON -DFORMAT=${FORMAT} . - make check after_success: - - if [[ "${CMAKE_BUILD_TYPE}" = "Coverage" && "${TRAVIS_BRANCH}" == "master" ]]; then cpp-coveralls -i matrix; fi + - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then cpp-coveralls -i matrix; fi From cf924956d7d62ce18bfc4f8441e9177ddb69c0dc Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 24 Feb 2017 16:10:02 -0500 Subject: [PATCH 217/388] test vector3 using matrix::isEqual --- test/vector.cpp | 2 +- test/vector2.cpp | 2 +- test/vector3.cpp | 26 ++++++++++++++------------ 3 files changed, 16 insertions(+), 14 deletions(-) diff --git a/test/vector.cpp b/test/vector.cpp index 8bb71c997e..7a1aa863f1 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -2,8 +2,8 @@ #include -using matrix::Vector; using matrix::isEqualF; +using matrix::Vector; int main() { diff --git a/test/vector2.cpp b/test/vector2.cpp index 399b301456..4e93282217 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -4,8 +4,8 @@ #include "test_macros.hpp" -using matrix::Vector2f; using matrix::Matrix; +using matrix::Vector2f; int main() { diff --git a/test/vector3.cpp b/test/vector3.cpp index 8bb76a978d..f603eced66 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -2,31 +2,33 @@ #include -using matrix::Vector3f; +using matrix::isEqual; +using matrix::isEqualF; using matrix::Matrix; +using matrix::Vector3f; int main() { Vector3f a(1, 0, 0); Vector3f b(0, 1, 0); Vector3f c = a.cross(b); - TEST(matrix::isEqual(c, Vector3f(0,0,1))); + TEST(isEqual(c, Vector3f(0,0,1))); c = a % b; - TEST(matrix::isEqual(c, Vector3f(0,0,1))); + TEST(isEqual(c, Vector3f(0,0,1))); Matrix d(c); Vector3f e(d); - TEST (matrix::isEqual(e, d)); + TEST(isEqual(e, d)); float data[] = {4, 5, 6}; Vector3f f(data); - TEST(matrix::isEqual(f, Vector3f(4, 5, 6))); + TEST(isEqual(f, Vector3f(4, 5, 6))); - TEST(matrix::isEqual(a + b, Vector3f(1, 1, 0))); - TEST(matrix::isEqual(a - b, Vector3f(1, -1, 0))); - TEST(matrix::isEqualF(a * b, 0.0f)); - TEST(matrix::isEqual(-a, Vector3f(-1, 0, 0))); - TEST(matrix::isEqual(a.unit(), a)); - TEST(matrix::isEqual(a.unit(), a.normalized())); - TEST(matrix::isEqual(a*2.0, Vector3f(2, 0, 0))); + TEST(isEqual(a + b, Vector3f(1, 1, 0))); + TEST(isEqual(a - b, Vector3f(1, -1, 0))); + TEST(isEqualF(a * b, 0.0f)); + TEST(isEqual(-a, Vector3f(-1, 0, 0))); + TEST(isEqual(a.unit(), a)); + TEST(isEqual(a.unit(), a.normalized())); + TEST(isEqual(a*2.0, Vector3f(2, 0, 0))); return 0; } From 8af7b8c13019a8aadeec28bf26da87e585e324cd Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:08:07 +0300 Subject: [PATCH 218/388] Poisoned the C library identifiers --- test/test_macros.hpp | 35 +++++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/test/test_macros.hpp b/test/test_macros.hpp index 998264db82..28b2a32070 100644 --- a/test/test_macros.hpp +++ b/test/test_macros.hpp @@ -4,9 +4,44 @@ * Helps with cmake testing. * * @author James Goppert + * Pavel Kirienko */ #pragma once #include +#include // cmath has to be introduced BEFORE we poison the C library identifiers #define TEST(X) if(!(X)) { fprintf(stderr, "test failed on %s:%d\n", __FILE__, __LINE__); return -1;} + +/** + * This construct is needed to catch any unintended use of the C standard library. + * Feel free to extend the list of poisoned identifiers with as many C functions as possible. + * The current list was constructed by means of automated parsing of http://en.cppreference.com/w/c/numeric/math + */ +#ifdef __GNUC__ + +// float functions +# pragma GCC poison fabsf fmodf +# pragma GCC poison remainderf remquof fmaf fmaxf fminf fdimf fnanf expf +# pragma GCC poison exp2f expm1f logf log10f log2f log1pf powf sqrtf cbrtf +# pragma GCC poison hypotf sinf cosf tanf asinf acosf atanf atan2f sinhf +# pragma GCC poison coshf tanhf asinhf acoshf atanhf erff erfcf tgammaf +# pragma GCC poison lgammaf ceilf floorf truncf roundf nearbyintf rintf +# pragma GCC poison frexpf ldexpf modff scalbnf ilogbf logbf nextafterf +# pragma GCC poison copysignf + +// double functions +// this list is scarce because otherwise most functions from std:: would be also poisoned, which we don't want +# pragma GCC poison fabs + +// long double functions +# pragma GCC poison fabsl fabsl fabsl fmodl +# pragma GCC poison remainderl remquol fmal fmaxl fminl fdiml fnanl expl +# pragma GCC poison exp2l expm1l logl log10l log2l log1pl powl sqrtl cbrtl +# pragma GCC poison hypotl sinl cosl tanl asinl acosl atanl atan2l sinhl +# pragma GCC poison coshl tanhl asinhl acoshl atanhl erfl erfcl tgammal +# pragma GCC poison lgammal ceill floorl truncl roundl nearbyintl rintl +# pragma GCC poison frexpl ldexpl modfl scalbnl ilogbl logbl nextafterl +# pragma GCC poison copysignl + +#endif From b74749fb61da466094a0fd7c34893af6d9a75f01 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:30:17 +0300 Subject: [PATCH 219/388] Un-poisoned fabs --- test/test_macros.hpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/test/test_macros.hpp b/test/test_macros.hpp index 28b2a32070..d6ca2d2fb1 100644 --- a/test/test_macros.hpp +++ b/test/test_macros.hpp @@ -30,9 +30,8 @@ # pragma GCC poison frexpf ldexpf modff scalbnf ilogbf logbf nextafterf # pragma GCC poison copysignf -// double functions -// this list is scarce because otherwise most functions from std:: would be also poisoned, which we don't want -# pragma GCC poison fabs +// the list of double functions is missing because otherwise most functions from std:: would be also poisoned, +// which we don't want // long double functions # pragma GCC poison fabsl fabsl fabsl fmodl From 552dad40a10b2240f24fa04c53e00aa78818c81d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:31:05 +0300 Subject: [PATCH 220/388] Fixed inclusions in matrix/ --- matrix/Matrix.hpp | 1 - matrix/Vector.hpp | 2 - matrix/helper_functions.hpp | 1 - matrix/math.hpp | 1 + matrix/stdlib_imports.hpp | 90 +++++++++++++++++++++++++++++++++++++ 5 files changed, 91 insertions(+), 4 deletions(-) create mode 100644 matrix/stdlib_imports.hpp diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 0d3fd48e38..976ca83f71 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -8,7 +8,6 @@ #pragma once -#include #include #include diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 9265b2a223..2fa0363400 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -8,8 +8,6 @@ #pragma once -#include - #include "math.hpp" namespace matrix diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index f501598f9b..e8cc0dcb80 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -1,7 +1,6 @@ #pragma once #include "math.hpp" -#include namespace matrix { diff --git a/matrix/math.hpp b/matrix/math.hpp index b69d2e0eec..342ae5e612 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -1,5 +1,6 @@ #pragma once +#include "stdlib_imports.hpp" #ifdef __PX4_QURT #include "dspal_math.h" #endif diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp new file mode 100644 index 0000000000..c72b1fc3d5 --- /dev/null +++ b/matrix/stdlib_imports.hpp @@ -0,0 +1,90 @@ +/** + * @file stdlib_imports.hpp + * + * @author Pavel Kirienko + */ + +#pragma once + +#include +#include +#include + +namespace matrix { + +using std::abs; +using std::div; +using std::fabs; +using std::fmod; +using std::exp; +using std::log; +using std::log10; +using std::pow; +using std::sqrt; +using std::sin; +using std::cos; +using std::tan; +using std::asin; +using std::acos; +using std::atan; +using std::atan2; +using std::sinh; +using std::cosh; +using std::tanh; +using std::ceil; +using std::floor; +using std::frexp; +using std::ldexp; +using std::modf; +using std::fpclassify; +using std::isfinite; +using std::isinf; +using std::isnan; +using std::isnormal; +using std::signbit; +using std::isgreater; +using std::isgreaterequal; +using std::isless; +using std::islessequal; +using std::islessgreater; +using std::isunordered; + +#if __cplusplus >= 201103L + +using std::imaxabs; +using std::imaxdiv; +using std::remainder; +using std::remquo; +using std::fma; +using std::fmax; +using std::fmin; +using std::fdim; +using std::nan; +using std::nanf; +using std::nanl; +using std::exp2; +using std::expm1; +using std::log2; +using std::log1p; +using std::cbrt; +using std::hypot; +using std::asinh; +using std::acosh; +using std::atanh; +using std::erf; +using std::erfc; +using std::tgamma; +using std::lgamma; +using std::trunc; +using std::round; +using std::nearbyint; +using std::rint; +using std::scalbn; +using std::ilogb; +using std::logb; +using std::nextafter; +using std::copysign; + +#endif + +} From 9ebf5f89dbc2f15ab0c4bc288fc3108549aa07d6 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:34:41 +0300 Subject: [PATCH 221/388] Removed all use of C library from the matrix namespace --- matrix/AxisAngle.hpp | 6 +++--- matrix/Quaternion.hpp | 18 +++++++++--------- matrix/SquareMatrix.hpp | 10 +++++----- 3 files changed, 17 insertions(+), 17 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 5a6cc4af9f..b281138e0e 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -76,9 +76,9 @@ public: Vector() { AxisAngle &v = *this; - Type ang = Type(2.0f)*acosf(q(0)); - Type mag = sinf(ang/2.0f); - if (fabsf(mag) > 0) { + Type ang = Type(2.0f)*acos(q(0)); + Type mag = sin(ang/2.0f); + if (fabs(mag) > 0) { v(0) = ang*q(1)/mag; v(1) = ang*q(2)/mag; v(2) = ang*q(3)/mag; diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index c7a5f2bda3..0873c8757c 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -97,28 +97,28 @@ public: Quaternion &q = *this; Type t = R.trace(); if (t > Type(0)) { - t = sqrtf(Type(1) + t); + t = sqrt(Type(1) + t); q(0) = Type(0.5) * t; t = Type(0.5) / t; q(1) = (R(2,1) - R(1,2)) * t; q(2) = (R(0,2) - R(2,0)) * t; q(3) = (R(1,0) - R(0,1)) * t; } else if (R(0,0) > R(1,1) && R(0,0) > R(2,2)) { - t = sqrtf(Type(1) + R(0,0) - R(1,1) - R(2,2)); + t = sqrt(Type(1) + R(0,0) - R(1,1) - R(2,2)); q(1) = Type(0.5) * t; t = Type(0.5) / t; q(0) = (R(2,1) - R(1,2)) * t; q(2) = (R(1,0) + R(0,1)) * t; q(3) = (R(0,2) + R(2,0)) * t; } else if (R(1,1) > R(2,2)) { - t = sqrtf(Type(1) - R(0,0) + R(1,1) - R(2,2)); + t = sqrt(Type(1) - R(0,0) + R(1,1) - R(2,2)); q(2) = Type(0.5) * t; t = Type(0.5) / t; q(0) = (R(0,2) - R(2,0)) * t; q(1) = (R(1,0) + R(0,1)) * t; q(3) = (R(2,1) + R(1,2)) * t; } else { - t = sqrtf(Type(1) - R(0,0) - R(1,1) + R(2,2)); + t = sqrt(Type(1) - R(0,0) - R(1,1) + R(2,2)); q(3) = Type(0.5) * t; t = Type(0.5) / t; q(0) = (R(1,0) - R(0,1)) * t; @@ -171,8 +171,8 @@ public: q(0) = Type(1.0); q(1) = q(2) = q(3) = 0; } else { - Type magnitude = sinf(angle / 2.0f); - q(0) = cosf(angle / 2.0f); + Type magnitude = sin(angle / 2.0f); + q(0) = cos(angle / 2.0f); q(1) = axis(0) * magnitude; q(2) = axis(1) * magnitude; q(3) = axis(2) * magnitude; @@ -389,9 +389,9 @@ public: q(1) = q(2) = q(3) = 0; } - Type magnitude = sinf(theta / 2.0f); + Type magnitude = sin(theta / 2.0f); - q(0) = cosf(theta / 2.0f); + q(0) = cos(theta / 2.0f); q(1) = axis(0) * magnitude; q(2) = axis(1) * magnitude; q(3) = axis(2) * magnitude; @@ -418,7 +418,7 @@ public: if (axis_magnitude >= Type(1e-10)) { vec = vec / axis_magnitude; - vec = vec * wrap_pi(Type(2.0) * atan2f(axis_magnitude, q(0))); + vec = vec * wrap_pi(Type(2.0) * atan2(axis_magnitude, q(0))); } return vec; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index f1a5a9b134..5b2560dc71 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -136,12 +136,12 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) for (size_t n = 0; n < M; n++) { // if diagonal is zero, swap with row below - if (fabsf(static_cast(U(n, n))) < 1e-8f) { + if (fabs(static_cast(U(n, n))) < 1e-8f) { //printf("trying pivot for row %d\n",n); for (size_t i = n + 1; i < M; i++) { //printf("\ttrying row %d\n",i); - if (fabsf(static_cast(U(i, n))) > 1e-8f) { + if (fabs(static_cast(U(i, n))) > 1e-8f) { //printf("swapped %d\n",i); U.swapRows(i, n); P.swapRows(i, n); @@ -157,11 +157,11 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) //printf("U:\n"); U.print(); //printf("P:\n"); P.print(); //fflush(stdout); - //ASSERT(fabsf(U(n, n)) > 1e-8f); + //ASSERT(fabs(U(n, n)) > 1e-8f); #endif // failsafe, return zero matrix - if (fabsf(static_cast(U(n, n))) < 1e-8f) { + if (fabs(static_cast(U(n, n))) < 1e-8f) { return false; } @@ -280,7 +280,7 @@ SquareMatrix cholesky(const SquareMatrix & A) if (res <= 0) { L(j, j) = 0; } else { - L(j, j) = sqrtf(res); + L(j, j) = sqrt(res); } } else { float sum = 0; From e09cf12e2eaaa61ed5f21d8701c96a457117683b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:38:48 +0300 Subject: [PATCH 222/388] Removed all uses of C library from tests --- test/attitude.cpp | 93 +++++++++++++++++---------------------- test/filter.cpp | 6 +-- test/hatvee.cpp | 5 +-- test/helper.cpp | 5 +-- test/integration.cpp | 8 ++-- test/inverse.cpp | 3 +- test/matrixAssignment.cpp | 20 ++++----- test/matrixMult.cpp | 3 +- test/matrixScalarMult.cpp | 2 +- test/setIdentity.cpp | 10 ++--- test/slice.cpp | 3 +- test/squareMatrix.cpp | 3 +- test/transpose.cpp | 2 +- test/vector.cpp | 3 +- test/vector2.cpp | 21 +++++---- test/vector3.cpp | 5 +-- test/vectorAssignment.cpp | 21 +++++---- 17 files changed, 87 insertions(+), 126 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 49b47b3807..406a56f373 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -1,20 +1,7 @@ #include "test_macros.hpp" #include -using matrix::AxisAnglef; -using matrix::Dcm; -using matrix::Dcmf; -using matrix::Euler; -using matrix::Eulerf; -using matrix::eye; -using matrix::isEqualF; -using matrix::Matrix; -using matrix::Quaternion; -using matrix::Quatf; -using matrix::SquareMatrix; -using matrix::Vector3f; -using matrix::Vector; -using matrix::zeros; +using namespace matrix; int main() { @@ -50,10 +37,10 @@ int main() // quaternion ctor Quatf q0(1, 2, 3, 4); Quatf q(q0); - TEST(fabsf(q(0) - 1) < eps); - TEST(fabsf(q(1) - 2) < eps); - TEST(fabsf(q(2) - 3) < eps); - TEST(fabsf(q(3) - 4) < eps); + TEST(fabs(q(0) - 1) < eps); + TEST(fabs(q(1) - 2) < eps); + TEST(fabs(q(2) - 3) < eps); + TEST(fabs(q(3) - 4) < eps); // quat normalization q.normalize(); @@ -107,7 +94,7 @@ int main() for (auto & row : A._data) { Vector3f rvec(row); - err += fabsf(1.0f - rvec.length()); + err += fabs(1.0f - rvec.length()); } TEST(err < eps); @@ -215,17 +202,17 @@ int main() // quaternion inverse q = q_check.inversed(); - TEST(fabsf(q_check(0) - q(0)) < eps); - TEST(fabsf(q_check(1) + q(1)) < eps); - TEST(fabsf(q_check(2) + q(2)) < eps); - TEST(fabsf(q_check(3) + q(3)) < eps); + TEST(fabs(q_check(0) - q(0)) < eps); + TEST(fabs(q_check(1) + q(1)) < eps); + TEST(fabs(q_check(2) + q(2)) < eps); + TEST(fabs(q_check(3) + q(3)) < eps); q = q_check; q.invert(); - TEST(fabsf(q_check(0) - q(0)) < eps); - TEST(fabsf(q_check(1) + q(1)) < eps); - TEST(fabsf(q_check(2) + q(2)) < eps); - TEST(fabsf(q_check(3) + q(3)) < eps); + TEST(fabs(q_check(0) - q(0)) < eps); + TEST(fabs(q_check(1) + q(1)) < eps); + TEST(fabs(q_check(2) + q(2)) < eps); + TEST(fabs(q_check(3) + q(3)) < eps); // non-unit quaternion invese Quatf qI(1.0f, 0.0f, 0.0f, 0.0f); @@ -237,52 +224,52 @@ int main() rot(0) = 1.0f; rot(1) = rot(2) = 0.0f; qI.rotate(rot); - Quatf q_true(cosf(1.0f / 2), sinf(1.0f / 2), 0.0f, 0.0f); - TEST(fabsf(qI(0) - q_true(0)) < eps); - TEST(fabsf(qI(1) - q_true(1)) < eps); - TEST(fabsf(qI(2) - q_true(2)) < eps); - TEST(fabsf(qI(3) - q_true(3)) < eps); + Quatf q_true(cos(1.0f / 2), sin(1.0f / 2), 0.0f, 0.0f); + TEST(fabs(qI(0) - q_true(0)) < eps); + TEST(fabs(qI(1) - q_true(1)) < eps); + TEST(fabs(qI(2) - q_true(2)) < eps); + TEST(fabs(qI(3) - q_true(3)) < eps); // rotate quaternion (zero rotation) qI = Quatf(1.0f, 0.0f, 0.0f, 0.0f); rot(0) = 0.0f; rot(1) = rot(2) = 0.0f; qI.rotate(rot); - q_true = Quatf(cosf(0.0f), sinf(0.0f), 0.0f, 0.0f); - TEST(fabsf(qI(0) - q_true(0)) < eps); - TEST(fabsf(qI(1) - q_true(1)) < eps); - TEST(fabsf(qI(2) - q_true(2)) < eps); - TEST(fabsf(qI(3) - q_true(3)) < eps); + q_true = Quatf(cos(0.0f), sin(0.0f), 0.0f, 0.0f); + TEST(fabs(qI(0) - q_true(0)) < eps); + TEST(fabs(qI(1) - q_true(1)) < eps); + TEST(fabs(qI(2) - q_true(2)) < eps); + TEST(fabs(qI(3) - q_true(3)) < eps); // get rotation axis from quaternion (nonzero rotation) - q = Quatf(cosf(1.0f / 2), 0.0f, sinf(1.0f / 2), 0.0f); + q = Quatf(cos(1.0f / 2), 0.0f, sin(1.0f / 2), 0.0f); rot = q.to_axis_angle(); - TEST(fabsf(rot(0)) < eps); - TEST(fabsf(rot(1) - 1.0f) < eps); - TEST(fabsf(rot(2)) < eps); + TEST(fabs(rot(0)) < eps); + TEST(fabs(rot(1) - 1.0f) < eps); + TEST(fabs(rot(2)) < eps); // get rotation axis from quaternion (zero rotation) q = Quatf(1.0f, 0.0f, 0.0f, 0.0f); rot = q.to_axis_angle(); - TEST(fabsf(rot(0)) < eps); - TEST(fabsf(rot(1)) < eps); - TEST(fabsf(rot(2)) < eps); + TEST(fabs(rot(0)) < eps); + TEST(fabs(rot(1)) < eps); + TEST(fabs(rot(2)) < eps); // from axis angle (zero rotation) rot(0) = rot(1) = rot(2) = 0.0f; q.from_axis_angle(rot, 0.0f); q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f); - TEST(fabsf(q(0) - q_true(0)) < eps); - TEST(fabsf(q(1) - q_true(1)) < eps); - TEST(fabsf(q(2) - q_true(2)) < eps); - TEST(fabsf(q(3) - q_true(3)) < eps); + TEST(fabs(q(0) - q_true(0)) < eps); + TEST(fabs(q(1) - q_true(1)) < eps); + TEST(fabs(q(2) - q_true(2)) < eps); + TEST(fabs(q(3) - q_true(3)) < eps); // Quaternion initialisation per array float q_array[] = {0.9833f, -0.0343f, -0.1060f, -0.1436f}; Quaternionq_from_array(q_array); for (size_t i = 0; i < 4; i++) { - TEST(fabsf(q_from_array(i) - q_array[i]) < eps); + TEST(fabs(q_from_array(i) - q_array[i]) < eps); } // axis angle @@ -350,10 +337,10 @@ int main() q = Quatf(1, 2, 3, 4); float dst[4] = {}; q.copyTo(dst); - TEST(fabsf(q(0) - dst[0]) < eps); - TEST(fabsf(q(1) - dst[1]) < eps); - TEST(fabsf(q(2) - dst[2]) < eps); - TEST(fabsf(q(3) - dst[3]) < eps); + TEST(fabs(q(0) - dst[0]) < eps); + TEST(fabs(q(1) - dst[1]) < eps); + TEST(fabs(q(2) - dst[2]) < eps); + TEST(fabs(q(3) - dst[3]) < eps); } diff --git a/test/filter.cpp b/test/filter.cpp index c5e6d2ca77..342da22824 100644 --- a/test/filter.cpp +++ b/test/filter.cpp @@ -1,11 +1,7 @@ #include "test_macros.hpp" #include -using matrix::Matrix; -using matrix::kalman_correct; -using matrix::eye; -using matrix::SquareMatrix; -using matrix::Vector; +using namespace matrix; int main() { diff --git a/test/hatvee.cpp b/test/hatvee.cpp index 6250621a24..aa2c2cf90e 100644 --- a/test/hatvee.cpp +++ b/test/hatvee.cpp @@ -1,10 +1,7 @@ #include "test_macros.hpp" #include -using matrix::Dcm; -using matrix::Euler; -using matrix::isEqual; -using matrix::Vector3; +using namespace matrix; int main() { diff --git a/test/helper.cpp b/test/helper.cpp index e280f5238f..cfc1aeb3ef 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -1,10 +1,7 @@ #include "test_macros.hpp" #include -using matrix::isEqual; -using matrix::isEqualF; -using matrix::Vector3f; -using matrix::wrap_pi; +using namespace matrix; int main() { diff --git a/test/integration.cpp b/test/integration.cpp index ec4cf80230..6dbd807205 100644 --- a/test/integration.cpp +++ b/test/integration.cpp @@ -1,14 +1,12 @@ #include "test_macros.hpp" #include -using matrix::Matrix; -using matrix::ones; -using matrix::Vector; +using namespace matrix; Vector f(float t, const Matrix & /*y*/, const Matrix & /*u*/); Vector f(float t, const Matrix & /*y*/, const Matrix & /*u*/) { - float v = -sinf(t); + float v = -sin(t); return v*ones(); } @@ -20,7 +18,7 @@ int main() float tf = 2; float h = 0.001f; integrate_rk4(f, y, u, t0, tf, h, y); - float v = 1 + cosf(tf) - cosf(t0); + float v = 1 + cos(tf) - cos(t0); TEST(isEqual(y, (ones()*v))); return 0; } diff --git a/test/inverse.cpp b/test/inverse.cpp index 92aaa70a03..20d69c4282 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -1,8 +1,7 @@ #include "test_macros.hpp" #include -using matrix::SquareMatrix; -using matrix::zeros; +using namespace matrix; static const size_t n_large = 50; diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 6f18d36ee7..91b4cc02b0 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -1,11 +1,7 @@ #include "test_macros.hpp" #include -using matrix::Matrix; -using matrix::Matrix3f; -using matrix::Scalar; -using matrix::Vector; -using matrix::Vector2f; +using namespace matrix; int main() { @@ -26,7 +22,7 @@ int main() Matrix3f m2(data); for(int i=0; i<9; i++) { - TEST(fabsf(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); } float data2d[3][3] = { @@ -36,7 +32,7 @@ int main() }; m2 = Matrix3f(data2d); for(int i=0; i<9; i++) { - TEST(fabsf(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); } float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; @@ -98,17 +94,17 @@ int main() m4.swapCols(2, 2); TEST(isEqual(m4, Matrix3f(data))); - TEST(fabsf(m4.min() - 1) < 1e-5); - TEST(fabsf((-m4).min() + 9) < 1e-5); + TEST(fabs(m4.min() - 1) < 1e-5); + TEST(fabs((-m4).min() + 9) < 1e-5); Scalar s; s = 1; const Vector & s_vect = s; - TEST(fabsf(s - 1) < 1e-5); - TEST(fabsf(s_vect(0) - 1.0f) < 1e-5); + TEST(fabs(s - 1) < 1e-5); + TEST(fabs(s_vect(0) - 1.0f) < 1e-5); Matrix m5 = s; - TEST(fabsf(m5(0,0) - s) < 1e-5); + TEST(fabs(m5(0,0) - s) < 1e-5); Matrix m6; m6.setRow(0, Vector2f(1, 2)); diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 97caa1532d..65623260dc 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -1,8 +1,7 @@ #include "test_macros.hpp" #include -using matrix::Matrix3f; -using matrix::eye; +using namespace matrix; int main() { diff --git a/test/matrixScalarMult.cpp b/test/matrixScalarMult.cpp index 925dbd95a6..320f0c8b58 100644 --- a/test/matrixScalarMult.cpp +++ b/test/matrixScalarMult.cpp @@ -2,7 +2,7 @@ #include -using matrix::Matrix3f; +using namespace matrix; int main() { diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index fc48ed41a2..9e1009548b 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -1,7 +1,7 @@ #include "test_macros.hpp" #include -using matrix::Matrix3f; +using namespace matrix; int main() { @@ -11,10 +11,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST(fabsf(A(i, j) - 1) < 1e-7); + TEST(fabs(A(i, j) - 1) < 1e-7); } else { - TEST(fabsf(A(i, j) - 0) < 1e-7); + TEST(fabs(A(i, j) - 0) < 1e-7); } } } @@ -25,10 +25,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST(fabsf(B(i, j) - 1) < 1e-7); + TEST(fabs(B(i, j) - 1) < 1e-7); } else { - TEST(fabsf(B(i, j) - 0) < 1e-7); + TEST(fabs(B(i, j) - 0) < 1e-7); } } } diff --git a/test/slice.cpp b/test/slice.cpp index ba44980f1c..4c43e93c0a 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -1,8 +1,7 @@ #include "test_macros.hpp" #include -using matrix::Matrix; -using matrix::SquareMatrix; +using namespace matrix; int main() { diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 0ecb26874b..2c668e4abf 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -2,8 +2,7 @@ #include -using matrix::SquareMatrix; -using matrix::Vector3; +using namespace matrix; int main() { diff --git a/test/transpose.cpp b/test/transpose.cpp index 350c626070..41627a6b0c 100644 --- a/test/transpose.cpp +++ b/test/transpose.cpp @@ -2,7 +2,7 @@ #include -using matrix::Matrix; +using namespace matrix; int main() { diff --git a/test/vector.cpp b/test/vector.cpp index 7a1aa863f1..21c41e8bff 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -2,8 +2,7 @@ #include -using matrix::isEqualF; -using matrix::Vector; +using namespace matrix; int main() { diff --git a/test/vector2.cpp b/test/vector2.cpp index 4e93282217..a8838d9b4e 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -4,31 +4,30 @@ #include "test_macros.hpp" -using matrix::Matrix; -using matrix::Vector2f; +using namespace matrix; int main() { Vector2f a(1, 0); Vector2f b(0, 1); - TEST(fabsf(a % b - 1.0f) < 1e-5); + TEST(fabs(a % b - 1.0f) < 1e-5); Vector2f c; - TEST(fabsf(c(0) - 0) < 1e-5); - TEST(fabsf(c(1) - 0) < 1e-5); + TEST(fabs(c(0) - 0) < 1e-5); + TEST(fabs(c(1) - 0) < 1e-5); Matrix d(a); - TEST(fabsf(d(0,0) - 1) < 1e-5); - TEST(fabsf(d(1,0) - 0) < 1e-5); + TEST(fabs(d(0,0) - 1) < 1e-5); + TEST(fabs(d(1,0) - 0) < 1e-5); Vector2f e(d); - TEST(fabsf(e(0) - 1) < 1e-5); - TEST(fabsf(e(1) - 0) < 1e-5); + TEST(fabs(e(0) - 1) < 1e-5); + TEST(fabs(e(1) - 0) < 1e-5); float data[] = {4,5}; Vector2f f(data); - TEST(fabsf(f(0) - 4) < 1e-5); - TEST(fabsf(f(1) - 5) < 1e-5); + TEST(fabs(f(0) - 4) < 1e-5); + TEST(fabs(f(1) - 5) < 1e-5); return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index f603eced66..ebe8a2ca6f 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -2,10 +2,7 @@ #include -using matrix::isEqual; -using matrix::isEqualF; -using matrix::Matrix; -using matrix::Vector3f; +using namespace matrix; int main() { diff --git a/test/vectorAssignment.cpp b/test/vectorAssignment.cpp index 1f78211965..e8e63462a2 100644 --- a/test/vectorAssignment.cpp +++ b/test/vectorAssignment.cpp @@ -2,8 +2,7 @@ #include "test_macros.hpp" -using matrix::SquareMatrix; -using matrix::Vector3f; +using namespace matrix; int main() { @@ -14,20 +13,20 @@ int main() static const float eps = 1e-7f; - TEST(fabsf(v(0) - 1) < eps); - TEST(fabsf(v(1) - 2) < eps); - TEST(fabsf(v(2) - 3) < eps); + TEST(fabs(v(0) - 1) < eps); + TEST(fabs(v(1) - 2) < eps); + TEST(fabs(v(2) - 3) < eps); Vector3f v2(4, 5, 6); - TEST(fabsf(v2(0) - 4) < eps); - TEST(fabsf(v2(1) - 5) < eps); - TEST(fabsf(v2(2) - 6) < eps); + TEST(fabs(v2(0) - 4) < eps); + TEST(fabs(v2(1) - 5) < eps); + TEST(fabs(v2(2) - 6) < eps); SquareMatrix m = diag(Vector3f(1,2,3)); - TEST(fabsf(m(0, 0) - 1) < eps); - TEST(fabsf(m(1, 1) - 2) < eps); - TEST(fabsf(m(2, 2) - 3) < eps); + TEST(fabs(m(0, 0) - 1) < eps); + TEST(fabs(m(1, 1) - 2) < eps); + TEST(fabs(m(2, 2) - 3) < eps); return 0; } From 23def31d214f984eb6d6bf832ccfc6dc77f7a103 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:47:51 +0300 Subject: [PATCH 223/388] Fixed stdlib imports --- matrix/stdlib_imports.hpp | 27 +++++++++++++++------------ 1 file changed, 15 insertions(+), 12 deletions(-) diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index c72b1fc3d5..2667a10b1c 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -1,6 +1,9 @@ /** * @file stdlib_imports.hpp * + * This file is needed to shadow the C standard library math functions with ones provided by the C++ standard library. + * This way we can guarantee that unwanted functions from the C library will never creep back in unexpectedly. + * * @author Pavel Kirienko */ @@ -36,18 +39,6 @@ using std::floor; using std::frexp; using std::ldexp; using std::modf; -using std::fpclassify; -using std::isfinite; -using std::isinf; -using std::isnan; -using std::isnormal; -using std::signbit; -using std::isgreater; -using std::isgreaterequal; -using std::isless; -using std::islessequal; -using std::islessgreater; -using std::isunordered; #if __cplusplus >= 201103L @@ -84,6 +75,18 @@ using std::ilogb; using std::logb; using std::nextafter; using std::copysign; +using std::fpclassify; +using std::isfinite; +using std::isinf; +using std::isnan; +using std::isnormal; +using std::signbit; +using std::isgreater; +using std::isgreaterequal; +using std::isless; +using std::islessequal; +using std::islessgreater; +using std::isunordered; #endif From 8dbe4a753172ddf0ac1b4124b0b49871ec681aa6 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 13:57:09 +0300 Subject: [PATCH 224/388] NuttX workaround --- matrix/stdlib_imports.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index 2667a10b1c..4d24b814cf 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -40,7 +40,7 @@ using std::frexp; using std::ldexp; using std::modf; -#if __cplusplus >= 201103L +#if (__cplusplus >= 201103L) && !defined(__PX4_NUTTX) using std::imaxabs; using std::imaxdiv; From 99b44c02422e2baa423071724714b58c46ae60a3 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 14:44:57 +0300 Subject: [PATCH 225/388] NuttX math lib workaround --- matrix/stdlib_imports.hpp | 39 ++++++++++++++++++++++++++++++++++++++- 1 file changed, 38 insertions(+), 1 deletion(-) diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index 4d24b814cf..efeba31322 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -15,6 +15,42 @@ namespace matrix { +#if defined(__PX4_NUTTX) +/* + * NuttX has no usable C++ math library, so we need to provide the needed definitions here manually. + */ +#define MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(name) \ + inline float name(float x) { return ::name##f(x); } \ + inline double name(double x) { return ::name(x); } \ + inline long double name(long double x) { return ::name##l(x); } + +#define MATRIX_NUTTX_WRAP_MATH_FUN_BINARY(name) \ + inline float name(float x, float y) { return ::name##f(x, y); } \ + inline double name(double x, double y) { return ::name(x, y); } \ + inline long double name(long double x, long double y) { return ::name##l(x, y); } + +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(fabs) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(log) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(log10) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(exp) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(sqrt) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(sin) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(cos) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(tan) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(asin) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(acos) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(atan) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(sinh) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(cosh) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(tanh) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(ceil) +MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(floor) + +MATRIX_NUTTX_WRAP_MATH_FUN_BINARY(pow) +MATRIX_NUTTX_WRAP_MATH_FUN_BINARY(atan2) + +#else // Not NuttX, using the C++ standard library + using std::abs; using std::div; using std::fabs; @@ -40,7 +76,7 @@ using std::frexp; using std::ldexp; using std::modf; -#if (__cplusplus >= 201103L) && !defined(__PX4_NUTTX) +# if (__cplusplus >= 201103L) using std::imaxabs; using std::imaxdiv; @@ -88,6 +124,7 @@ using std::islessequal; using std::islessgreater; using std::isunordered; +# endif #endif } From 499b897e5f270c3207a0e88d2f7239c5885d1681 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 17 Mar 2017 15:02:21 +0300 Subject: [PATCH 226/388] Style fix --- matrix/stdlib_imports.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index efeba31322..1d23c5c93e 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -22,12 +22,12 @@ namespace matrix { #define MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(name) \ inline float name(float x) { return ::name##f(x); } \ inline double name(double x) { return ::name(x); } \ - inline long double name(long double x) { return ::name##l(x); } + inline long double name(long double x) { return ::name##l(x); } #define MATRIX_NUTTX_WRAP_MATH_FUN_BINARY(name) \ inline float name(float x, float y) { return ::name##f(x, y); } \ inline double name(double x, double y) { return ::name(x, y); } \ - inline long double name(long double x, long double y) { return ::name##l(x, y); } + inline long double name(long double x, long double y) { return ::name##l(x, y); } MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(fabs) MATRIX_NUTTX_WRAP_MATH_FUN_UNARY(log) From 66e1b406b8a68422135c365d42b987a64c9ddf8d Mon Sep 17 00:00:00 2001 From: Nate Weibley Date: Thu, 23 Mar 2017 16:24:11 -0400 Subject: [PATCH 227/388] Remove artifical need to virtualize dtors --- matrix/AxisAngle.hpp | 2 -- matrix/Dcm.hpp | 2 -- matrix/Euler.hpp | 2 -- matrix/Matrix.hpp | 2 -- matrix/Quaternion.hpp | 2 -- matrix/Scalar.hpp | 2 -- matrix/Vector.hpp | 2 -- matrix/Vector2.hpp | 2 -- matrix/Vector3.hpp | 2 -- 9 files changed, 18 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index b281138e0e..e1275c3f1d 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -31,8 +31,6 @@ template class AxisAngle : public Vector { public: - ~AxisAngle() override = default; - typedef Matrix Matrix31; /** diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index c418a8a30b..834daf0845 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -39,8 +39,6 @@ template class Dcm : public SquareMatrix { public: - virtual ~Dcm() {}; - typedef Matrix Vector3; /** diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 7c320eb1f6..e308a2f3f5 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -40,8 +40,6 @@ template class Euler : public Vector { public: - virtual ~Euler() {}; - /** * Standard constructor */ diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 976ca83f71..5959e4f119 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -32,8 +32,6 @@ public: Type _data[M][N]; - virtual ~Matrix() {}; - // Constructors Matrix() : _data() {} diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 0873c8757c..120f9ad733 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -45,8 +45,6 @@ template class Quaternion : public Vector { public: - virtual ~Quaternion() {}; - typedef Matrix Matrix41; typedef Matrix Matrix31; diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index ca3743d328..302cd70c87 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -17,8 +17,6 @@ template class Scalar { public: - virtual ~Scalar() {}; - Scalar() : _value() { } diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 2fa0363400..b0e01f5555 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -20,8 +20,6 @@ template class Vector : public Matrix { public: - ~Vector() override = default; - typedef Matrix MatrixM1; Vector() : MatrixM1() diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index 50e9855c9f..7badf94b12 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -23,8 +23,6 @@ public: typedef Matrix Matrix21; - virtual ~Vector2() {}; - Vector2() : Vector() { diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 272d5d7712..3dbaa26c23 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -29,8 +29,6 @@ public: typedef Matrix Matrix31; - virtual ~Vector3() {}; - Vector3() : Vector() { From 2ad3ec46b93df01c5c5a298b720e9cf86c2b2d41 Mon Sep 17 00:00:00 2001 From: Nate Weibley Date: Thu, 23 Mar 2017 16:37:52 -0400 Subject: [PATCH 228/388] Mark simple min, max, abs methods as const --- matrix/Matrix.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 5959e4f119..5223a8acc4 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -413,7 +413,7 @@ public: } } - Matrix abs() + Matrix abs() const { Matrix r; for (size_t i=0; i Date: Thu, 23 Mar 2017 16:38:08 -0400 Subject: [PATCH 229/388] Provide const dataptr access --- matrix/Matrix.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 5223a8acc4..26fd13153f 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -59,6 +59,11 @@ public: return _data[0]; } + const Type *data() const + { + return _data[0]; + } + inline Type operator()(size_t i, size_t j) const { return _data[i][j]; From e595ebb9a704c24aeae990dac768d26949fcaee0 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 3 Feb 2017 16:38:39 -0500 Subject: [PATCH 230/388] Switch to Hamilton quaternions and add Cholesky decomposition. --- matrix/Quaternion.hpp | 23 ++++++++++++++++------- test/attitude.cpp | 10 +++++----- 2 files changed, 21 insertions(+), 12 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 120f9ad733..8a85e57579 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -4,11 +4,20 @@ * All rotations and axis systems follow the right-hand rule. * The Hamilton quaternion product definition is used. * - * In order to rotate a vector v by a righthand rotation defined by the quaternion q + * In order to rotate a vector in frame b (v_b) to frame n by a righthand + * rotation defined by the quaternion q_nb (from frame b to n) * one can use the following operation: - * v_rotated = q^(-1) * [0;v] * q - * where q^(-1) represents the inverse of the quaternion q. - * The product z of two quaternions z = q1 * q2 represents an intrinsic rotation + * v_n = q_nb * [0;v_b] * q_nb^-1 + * + * Just like DCM's: v_n = C_nb * v_b (vector rotation) + * M_n = C_nb * M_b * C_nb^(-1) (matrix rotation) + * + * or similarly + * v_b = q_nb^1 * [0;v_n] * q_nb + * + * where q_nb^(-1) represents the inverse of the quaternion q_nb = q_bn + * + * The product z of two quaternions z = q2 * q1 represents an intrinsic rotation * in the order of first q1 followed by q2. * The first element of the quaternion * represents the real part, thus, a quaternion representing a zero-rotation @@ -211,9 +220,9 @@ public: const Quaternion &p = *this; Quaternion r; r(0) = p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3); - r(1) = p(0) * q(1) + p(1) * q(0) - p(2) * q(3) + p(3) * q(2); - r(2) = p(0) * q(2) + p(1) * q(3) + p(2) * q(0) - p(3) * q(1); - r(3) = p(0) * q(3) - p(1) * q(2) + p(2) * q(1) + p(3) * q(0); + r(1) = p(0) * q(1) + p(1) * q(0) + p(2) * q(3) - p(3) * q(2); + r(2) = p(0) * q(2) - p(1) * q(3) + p(2) * q(0) + p(3) * q(1); + r(3) = p(0) * q(3) + p(1) * q(2) - p(2) * q(1) + p(3) * q(0); return r; } diff --git a/test/attitude.cpp b/test/attitude.cpp index 406a56f373..8042bc1a2b 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -170,13 +170,13 @@ int main() // quaternion derivative in frame 1 Quatf q1(0, 1, 0, 0); Vector q1_dot1 = q1.derivative1(Vector3f(1, 2, 3)); - float data_q_dot1_check[] = { -0.5f, 0.0f, 1.5f, -1.0f}; + float data_q_dot1_check[] = { -0.5f, 0.0f, -1.5f, 1.0f}; Vector q1_dot1_check(data_q_dot1_check); TEST(isEqual(q1_dot1, q1_dot1_check)); // quaternion derivative in frame 2 Vector q1_dot2 = q1.derivative2(Vector3f(1, 2, 3)); - float data_q_dot2_check[] = { -0.5f, 0.0f, -1.5f, 1.0f}; + float data_q_dot2_check[] = { -0.5f, 0.0f, 1.5f, -1.0f}; Vector q1_dot2_check(data_q_dot2_check); TEST(isEqual(q1_dot2, q1_dot2_check)); @@ -296,8 +296,8 @@ int main() // conjugate Vector3f v1(1.5f, 2.2f, 3.2f); - TEST(isEqual(q.conjugate_inversed(v1), Dcmf(q)*v1)); - TEST(isEqual(q.conjugate(v1), Dcmf(q).T()*v1)); + TEST(isEqual(q.conjugate_inversed(v1), Dcmf(q).T()*v1)); + TEST(isEqual(q.conjugate(v1), Dcmf(q)*v1)); AxisAnglef aa_q_init(q); TEST(isEqual(aa_q_init, AxisAnglef(1.0f, 2.0f, 3.0f))); @@ -319,7 +319,7 @@ int main() Dcmf dcm3(Eulerf(1, 2, 3)); Dcmf dcm4(Eulerf(4, 5, 6)); Dcmf dcm34 = dcm3 * dcm4; - TEST(isEqual(Eulerf(Quatf(dcm4)*Quatf(dcm3)), Eulerf(dcm34))); + TEST(isEqual(Eulerf(Quatf(dcm3)*Quatf(dcm4)), Eulerf(dcm34))); // check corner cases of matrix to quaternion conversion q = Quatf(0,1,0,0); // 180 degree rotation around the x axis From baf54ad29fdc3bcd5a6ecc2aef278a6a607395d9 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 25 Sep 2017 13:08:05 +0200 Subject: [PATCH 231/388] quaternion: correcting comments ^(-1) went missing and some phrase was inprecise --- matrix/Quaternion.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 8a85e57579..38eed54374 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -2,20 +2,20 @@ * @file Quaternion.hpp * * All rotations and axis systems follow the right-hand rule. - * The Hamilton quaternion product definition is used. + * The Hamilton quaternion convention including its product definition is used. * * In order to rotate a vector in frame b (v_b) to frame n by a righthand * rotation defined by the quaternion q_nb (from frame b to n) * one can use the following operation: - * v_n = q_nb * [0;v_b] * q_nb^-1 + * v_n = q_nb * [0;v_b] * q_nb^(-1) * * Just like DCM's: v_n = C_nb * v_b (vector rotation) * M_n = C_nb * M_b * C_nb^(-1) (matrix rotation) * - * or similarly - * v_b = q_nb^1 * [0;v_n] * q_nb + * or similarly the reverse operation + * v_b = q_nb^(-1) * [0;v_n] * q_nb * - * where q_nb^(-1) represents the inverse of the quaternion q_nb = q_bn + * where q_nb^(-1) represents the inverse of the quaternion q_nb^(-1) = q_bn * * The product z of two quaternions z = q2 * q1 represents an intrinsic rotation * in the order of first q1 followed by q2. From 976461eb0f3954e999099d1d141d1192259e6442 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 25 Sep 2017 13:12:41 +0200 Subject: [PATCH 232/388] Dcm: more efficient conversion from quaternion, extend reuse of multiplications --- matrix/Dcm.hpp | 40 +++++++++++++++++++++++----------------- 1 file changed, 23 insertions(+), 17 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 834daf0845..3f0d969402 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -80,23 +80,29 @@ public: Dcm(const Quaternion &q) { Dcm &dcm = *this; - Type a = q(0); - Type b = q(1); - Type c = q(2); - Type d = q(3); - Type aSq = a * a; - Type bSq = b * b; - Type cSq = c * c; - Type dSq = d * d; - dcm(0, 0) = aSq + bSq - cSq - dSq; - dcm(0, 1) = 2 * (b * c - a * d); - dcm(0, 2) = 2 * (a * c + b * d); - dcm(1, 0) = 2 * (b * c + a * d); - dcm(1, 1) = aSq - bSq + cSq - dSq; - dcm(1, 2) = 2 * (c * d - a * b); - dcm(2, 0) = 2 * (b * d - a * c); - dcm(2, 1) = 2 * (a * b + c * d); - dcm(2, 2) = aSq - bSq - cSq + dSq; + const Type a = q(0); + const Type b = q(1); + const Type c = q(2); + const Type d = q(3); + const Type aa = a * a; + const Type ab = a * b; + const Type ac = a * c; + const Type ad = a * d; + const Type bb = b * b; + const Type bc = b * c; + const Type bd = b * d; + const Type cc = c * c; + const Type cd = c * d; + const Type dd = d * d; + dcm(0, 0) = aa + bb - cc - dd; + dcm(0, 1) = 2 * (bc - ad); + dcm(0, 2) = 2 * (ac + bd); + dcm(1, 0) = 2 * (bc + ad); + dcm(1, 1) = aa - bb + cc - dd; + dcm(1, 2) = 2 * (cd - ab); + dcm(2, 0) = 2 * (bd - ac); + dcm(2, 1) = 2 * (ab + cd); + dcm(2, 2) = aa - bb - cc + dd; } /** From 0a772f59ddf4470067749f82cea4e4abedbb1007 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 26 Sep 2017 11:12:56 +0200 Subject: [PATCH 233/388] Quaternion: added direct efficient body z-axis calculation with test --- matrix/Quaternion.hpp | 21 +++++++++++++++++++++ test/attitude.cpp | 4 ++++ 2 files changed, 25 insertions(+) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 38eed54374..75484e939d 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -440,6 +440,27 @@ public: return Vector3(q(1), q(2), q(3)); } + /** + * Corresponding body z-axis to an attitude quaternion / + * last orthogonal unit basis vector + * + * == last column of the equivalent rotation matrix + * but calculated more efficiently than a full conversion + */ + Vector3 dcm_z() + { + Quaternion &q = *this; + Vector3 R_z; + const Type a = q(0); + const Type b = q(1); + const Type c = q(2); + const Type d = q(3); + R_z(0) = 2 * (a * c + b * d); + R_z(1) = 2 * (c * d - a * b); + R_z(2) = a * a - b * b - c * c + d * d; + return R_z; + } + /** * XXX DEPRECATED, can use assignment or ctor */ diff --git a/test/attitude.cpp b/test/attitude.cpp index 8042bc1a2b..49e59b257b 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -68,6 +68,10 @@ int main() // quaternion to dcm Dcmf dcm1(q_check); TEST(isEqual(dcm1, dcm_check)); + // quaternion z-axis unit base vector + Vector3f q_z = q_check.dcm_z(); + Vector3f R_z(dcm_check(0, 2), dcm_check(1, 2), dcm_check(2, 2)); + TEST(isEqual(q_z, R_z)); // dcm default ctor Dcmf dcm2; From 0527471a527945157154b21f82203460a50dea3f Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 16 Oct 2017 19:14:31 +0200 Subject: [PATCH 234/388] Matrix: adjust buffer size calculation to account for additional characters Note: If the buffer is too small there's no memory corruption because of the snprintf limit but part of the output gets missing. --- matrix/Matrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 26fd13153f..2428f9d246 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -286,7 +286,7 @@ public: void print() const { - static const size_t n = 10*N*M; + static const size_t n = 11*N*M + M; // for every entry a tab and 10 digits, for every row a newline char * buf = new char[n]; write_string(buf, n); printf("%s\n", buf); From 6b1fea76d0213236b7c10759c13b165f763c0e8b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 16 Oct 2017 19:16:05 +0200 Subject: [PATCH 235/388] Quaternion: added and adjusted comments to further explain conjugation and derivative functionality --- matrix/Quaternion.hpp | 22 +++++++++++++++++++--- 1 file changed, 19 insertions(+), 3 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 75484e939d..4e5d2ad11f 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -276,11 +276,11 @@ public: /** * Computes the derivative of q_12 when - * rotated with angular velocity expressed in frame 2 + * rotated with angular velocity expressed in frame 1 * v_2 = q_12 * v_1 * q_12^-1 * d/dt q_12 = 0.5 * q_12 * omega_12_2 * - * @param w angular rate in frame 2 + * @param w angular rate in frame 1 (typically body frame) */ Matrix41 derivative1(const Matrix31 &w) const { @@ -295,7 +295,7 @@ public: * v_2 = q_12 * v_1 * q_12^-1 * d/dt q_12 = 0.5 * omega_12_1 * q_12 * - * @param w angular rate in frame (typically reference frame) + * @param w angular rate in frame 2 (typically reference frame) */ Matrix41 derivative2(const Matrix31 &w) const { @@ -341,6 +341,14 @@ public: (*this) = (*this) * res; } + /** + * Rotates vector v_1 in frame 1 to vector r_2 in frame 2 + * using the rotation quaternion q_12 + * v_2 = q_12 * v_1 * q_12^-1 + * + * @param vec vector to rotate in frame 1 (typically body frame) + * @return rotated vector in frame 2 (typically reference frame) + */ Vector3f conjugate(const Vector3f &vec) { Quaternion q = *this; Quaternion v(0, vec(0), vec(1), vec(2)); @@ -348,6 +356,14 @@ public: return Vector3f(res(1), res(2), res(3)); } + /** + * Rotates vector v_2 in frame 2 to vector r_1 in frame 1 + * using the rotation quaternion q_12 + * v_1 = q_12^-1 * v_1 * q_12 + * + * @param vec vector to rotate in frame 2 (typically reference frame) + * @return rotated vector in frame 1 (typically body frame) + */ Vector3f conjugate_inversed(const Vector3f &vec) { Quaternion q = *this; Quaternion v(0, vec(0), vec(1), vec(2)); From b241cf5c95d1113e4afef42e5e47801a91b1da2b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 16 Oct 2017 19:18:56 +0200 Subject: [PATCH 236/388] Quaternion: Adjusted rotate() to the Hamilton convention (which we switched to) Note: This error was not caught by a test because the test included only trivial cases which do not explore non-commuting quaternions. --- matrix/Quaternion.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 4e5d2ad11f..f4a859fca9 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -338,7 +338,7 @@ public: { Quaternion res; res.from_axis_angle(vec); - (*this) = (*this) * res; + (*this) = res * (*this); } /** From ee2219b8368992eb04b314066c616d311c2b312f Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Oct 2017 08:14:02 +0200 Subject: [PATCH 237/388] Quaternion: replace conversion in rotate() with AxisAngle call --- matrix/Quaternion.hpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index f4a859fca9..d98051375c 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -330,14 +330,12 @@ public: /** * Rotate quaternion from rotation vector - * TODO replace with AxisAngle call * * @param vec rotation vector */ - void rotate(const Vector &vec) + void rotate(const AxisAngle &vec) { - Quaternion res; - res.from_axis_angle(vec); + Quaternion res(vec); (*this) = res * (*this); } From d259ab2108bba93003f9fd15a220a6541fa083c4 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Oct 2017 08:14:51 +0200 Subject: [PATCH 238/388] Test: add Quaternion rotate() test that catches non-commutating rotations --- test/attitude.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 49e59b257b..25bdefa489 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -229,10 +229,7 @@ int main() rot(1) = rot(2) = 0.0f; qI.rotate(rot); Quatf q_true(cos(1.0f / 2), sin(1.0f / 2), 0.0f, 0.0f); - TEST(fabs(qI(0) - q_true(0)) < eps); - TEST(fabs(qI(1) - q_true(1)) < eps); - TEST(fabs(qI(2) - q_true(2)) < eps); - TEST(fabs(qI(3) - q_true(3)) < eps); + TEST(isEqual(qI, q_true)); // rotate quaternion (zero rotation) qI = Quatf(1.0f, 0.0f, 0.0f, 0.0f); @@ -240,10 +237,14 @@ int main() rot(1) = rot(2) = 0.0f; qI.rotate(rot); q_true = Quatf(cos(0.0f), sin(0.0f), 0.0f, 0.0f); - TEST(fabs(qI(0) - q_true(0)) < eps); - TEST(fabs(qI(1) - q_true(1)) < eps); - TEST(fabs(qI(2) - q_true(2)) < eps); - TEST(fabs(qI(3) - q_true(3)) < eps); + TEST(isEqual(qI, q_true)); + + // rotate quaternion (random non-commutating rotation) + q = Quatf(AxisAnglef(5.1f, 3.2f, 8.4f)); + rot = Vector3f(1.1f, 2.5f, 3.8f); + q.rotate(rot); + q_true = Quatf(0.3019f, 0.2645f, 0.2268f, 0.8874f); + TEST(isEqual(q, q_true)); // get rotation axis from quaternion (nonzero rotation) q = Quatf(cos(1.0f / 2), 0.0f, sin(1.0f / 2), 0.0f); @@ -263,10 +264,7 @@ int main() rot(0) = rot(1) = rot(2) = 0.0f; q.from_axis_angle(rot, 0.0f); q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f); - TEST(fabs(q(0) - q_true(0)) < eps); - TEST(fabs(q(1) - q_true(1)) < eps); - TEST(fabs(q(2) - q_true(2)) < eps); - TEST(fabs(q(3) - q_true(3)) < eps); + TEST(isEqual(q, q_true)); // Quaternion initialisation per array float q_array[] = {0.9833f, -0.0343f, -0.1060f, -0.1436f}; @@ -346,6 +344,7 @@ int main() TEST(fabs(q(2) - dst[2]) < eps); TEST(fabs(q(3) - dst[3]) < eps); + return 0; } /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From f4243160e2c77eb8034a35fe42924d59a39319da Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Oct 2017 16:24:02 +0200 Subject: [PATCH 239/388] Quaternion: changed comments because of typos and unclear inconsistent indexing --- matrix/Quaternion.hpp | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index d98051375c..bd8cd9955e 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -275,10 +275,10 @@ public: } /** - * Computes the derivative of q_12 when + * Computes the derivative of q_21 when * rotated with angular velocity expressed in frame 1 - * v_2 = q_12 * v_1 * q_12^-1 - * d/dt q_12 = 0.5 * q_12 * omega_12_2 + * v_2 = q_21 * v_1 * q_21^-1 + * d/dt q_21 = 0.5 * q_21 * omega_2 * * @param w angular rate in frame 1 (typically body frame) */ @@ -290,10 +290,10 @@ public: } /** - * Computes the derivative of q_12 when + * Computes the derivative of q_21 when * rotated with angular velocity expressed in frame 2 - * v_2 = q_12 * v_1 * q_12^-1 - * d/dt q_12 = 0.5 * omega_12_1 * q_12 + * v_2 = q_21 * v_1 * q_21^-1 + * d/dt q_21 = 0.5 * omega_1 * q_21 * * @param w angular rate in frame 2 (typically reference frame) */ @@ -340,9 +340,10 @@ public: } /** - * Rotates vector v_1 in frame 1 to vector r_2 in frame 2 - * using the rotation quaternion q_12 - * v_2 = q_12 * v_1 * q_12^-1 + * Rotates vector v_1 in frame 1 to vector v_2 in frame 2 + * using the rotation quaternion q_21 + * describing the rotation from frame 1 to 2 + * v_2 = q_21 * v_1 * q_21^-1 * * @param vec vector to rotate in frame 1 (typically body frame) * @return rotated vector in frame 2 (typically reference frame) @@ -355,9 +356,10 @@ public: } /** - * Rotates vector v_2 in frame 2 to vector r_1 in frame 1 - * using the rotation quaternion q_12 - * v_1 = q_12^-1 * v_1 * q_12 + * Rotates vector v_2 in frame 2 to vector v_1 in frame 1 + * using the rotation quaternion q_21 + * describing the rotation from frame 1 to 2 + * v_1 = q_21^-1 * v_1 * q_21 * * @param vec vector to rotate in frame 2 (typically reference frame) * @return rotated vector in frame 1 (typically body frame) From 9e59691e43583835062745e438695bc666b316aa Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 6 Nov 2017 10:45:27 +0100 Subject: [PATCH 240/388] Vector: Additional normalization with check for zero norm because it occurs so many times in applications --- matrix/Vector.hpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index b0e01f5555..3d19e1dac0 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -83,6 +83,14 @@ public: return (*this) / norm(); } + Vector unit_or_zero(const Type eps = 1e-5f) { + const Type n = norm(); + if (n > eps) { + return (*this) / n; + } + return Vector(); + } + inline Vector normalized() const { return unit(); } From 3bd94fcd6f65f2d55c3bbce410657eeba5577336 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Sun, 5 Nov 2017 12:14:37 +0100 Subject: [PATCH 241/388] Test vector: structured & commented, added normalize and unit_or_zero tests, removed duplicate data preparation --- test/vector.cpp | 27 ++++++++++++++++++--------- 1 file changed, 18 insertions(+), 9 deletions(-) diff --git a/test/vector.cpp b/test/vector.cpp index 21c41e8bff..bfebe6414a 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -6,25 +6,34 @@ using namespace matrix; int main() { + // test data float data1[] = {1,2,3,4,5}; float data2[] = {6,7,8,9,10}; Vector v1(data1); - TEST(isEqualF(v1.norm(), 7.416198487095663f)); - TEST(isEqualF(v1.norm(), v1.length())); Vector v2(data2); - TEST(isEqualF(v1.dot(v2), 130.0f)); - v2.normalize(); + + // copy constructor Vector v3(v2); TEST(isEqual(v2, v3)); + + // norm, dot product + TEST(isEqualF(v1.norm(), 7.416198487095663f)); + TEST(isEqualF(v1.norm(), v1.length())); + TEST(isEqualF(v1.dot(v2), 130.0f)); + TEST(isEqualF(v1.dot(v2), v1 * v2)); + + // unit, unit_zero, normalize + TEST(isEqualF(v2.unit().norm(), 1.f)); + TEST(isEqualF(v2.unit_or_zero().norm(), 1.f)); + TEST(isEqualF(Vector().unit_or_zero().norm(), 0.f)); + v2.normalize(); + TEST(isEqualF(v2.norm(), 1.f)); + + // power float data1_sq[] = {1,4,9,16,25}; Vector v4(data1_sq); TEST(isEqual(v1, v4.pow(0.5))); - // dot product operator - v1 = Vector(data1); - v2 = Vector(data2); - float dprod = v1 * v2; - TEST(isEqualF(dprod, 130.0f)); return 0; } From 1dffd5930bfec53879e467294eb323b63efc500c Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 15 Nov 2017 22:15:13 +0100 Subject: [PATCH 242/388] Matrix: add copyTo copying data to an array and copyToColumnMajor which does the same but with column-major order same functionality explicitly for quaternions can be deleted --- matrix/Matrix.hpp | 16 ++++++++++++++++ matrix/Quaternion.hpp | 14 -------------- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 2428f9d246..559a8d804d 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -82,6 +82,22 @@ public: return (*this); } + void copyTo(Type (&dst)[M*N]) const + { + memcpy(dst, _data, sizeof(dst)); + } + + void copyToColumnMajor(Type (&dst)[M*N]) const + { + const Matrix &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + dst[i+(j*M)] = self(i, j); + } + } + } + /** * Matrix Operations */ diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index bd8cd9955e..ea24e1fc6e 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -260,20 +260,6 @@ public: q = q * scalar; } - /** - * Copy quaternion to a float array - * - * @param dst array of 4 floats - */ - void copyTo(float (&dst)[4]) - { - const Quaternion &q = *this; - dst[0] = q(0); - dst[1] = q(1); - dst[2] = q(2); - dst[3] = q(3); - } - /** * Computes the derivative of q_21 when * rotated with angular velocity expressed in frame 1 From 308a6c91cbce698c5602296eb5b69a755e47b0df Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 15 Nov 2017 22:44:03 +0100 Subject: [PATCH 243/388] Test: added copyTo tests for Vector3, Quaternion and Matrix including clolumn-major order --- .gitignore | 1 + test/CMakeLists.txt | 1 + test/attitude.cpp | 10 --------- test/copyto.cpp | 51 +++++++++++++++++++++++++++++++++++++++++++++ 4 files changed, 53 insertions(+), 10 deletions(-) create mode 100644 test/copyto.cpp diff --git a/.gitignore b/.gitignore index 8efccc5293..09e562fc8c 100644 --- a/.gitignore +++ b/.gitignore @@ -14,6 +14,7 @@ Makefile test/attitude test/cmake_install.cmake test/CMakeFiles/ +test/copyto test/coverage.info test/CTestTestfile.cmake test/filter diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 2c7d42981f..77284c0170 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -16,6 +16,7 @@ set(tests squareMatrix helper hatvee + copyto ) add_custom_target(test_build) diff --git a/test/attitude.cpp b/test/attitude.cpp index 25bdefa489..7972aedb9e 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -334,16 +334,6 @@ int main() R = Dcmf(q); TEST(isEqual(q, Quatf(R))); - - // Quaternion copyTo - q = Quatf(1, 2, 3, 4); - float dst[4] = {}; - q.copyTo(dst); - TEST(fabs(q(0) - dst[0]) < eps); - TEST(fabs(q(1) - dst[1]) < eps); - TEST(fabs(q(2) - dst[2]) < eps); - TEST(fabs(q(3) - dst[3]) < eps); - return 0; } diff --git a/test/copyto.cpp b/test/copyto.cpp new file mode 100644 index 0000000000..0a9ccb20f7 --- /dev/null +++ b/test/copyto.cpp @@ -0,0 +1,51 @@ +#include "test_macros.hpp" +#include + +using namespace matrix; + +int main() +{ + float eps = 1e-6f; + + // Vector3 copyTo + Vector3f v(1, 2, 3); + float dst3[3] = {}; + v.copyTo(dst3); + for (size_t i = 0; i < 3; i++) { + TEST(fabs(v(i) - dst3[i]) < eps); + } + + // Quaternion copyTo + Quatf q(1, 2, 3, 4); + float dst4[4] = {}; + q.copyTo(dst4); + for (size_t i = 0; i < 4; i++) { + TEST(fabs(q(i) - dst4[i]) < eps); + } + + // Matrix copyTo + Matrix A; + A(0,0) = 1; + A(0,1) = 2; + A(0,2) = 3; + A(1,0) = 4; + A(1,1) = 5; + A(1,2) = 6; + float array_A[6] = {}; + A.copyTo(array_A); + float array_row[6] = {1, 2, 3, 4, 5, 6}; + for (size_t i = 0; i < 6; i++) { + TEST(fabs(array_A[i] - array_row[i]) < eps); + } + + // Matrix copyToColumnMajor + A.copyToColumnMajor(array_A); + float array_column[6] = {1, 4, 2, 5, 3, 6}; + for (size_t i = 0; i < 6; i++) { + TEST(fabs(array_A[i] - array_column[i]) < eps); + } + + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 41ad2bdea52771a8f486a0be6098e6e45786bdcd Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 16 Nov 2017 17:51:16 +0100 Subject: [PATCH 244/388] Matrix: added copyToRaw method to allow copying to a pointer because most uORB messages still contain all components of a vector one by one after each other --- matrix/Matrix.hpp | 5 +++++ test/copyto.cpp | 7 +++++++ 2 files changed, 12 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 559a8d804d..30b7fa929e 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -87,6 +87,11 @@ public: memcpy(dst, _data, sizeof(dst)); } + void copyToRaw(Type *dst) const + { + memcpy(dst, _data, sizeof(_data)); + } + void copyToColumnMajor(Type (&dst)[M*N]) const { const Matrix &self = *this; diff --git a/test/copyto.cpp b/test/copyto.cpp index 0a9ccb20f7..fe35cff672 100644 --- a/test/copyto.cpp +++ b/test/copyto.cpp @@ -38,6 +38,13 @@ int main() TEST(fabs(array_A[i] - array_row[i]) < eps); } + // Matrix copyTo with a pointer + A.copyToRaw(static_cast (array_A)); + float array_row_p[6] = {1, 2, 3, 4, 5, 6}; + for (size_t i = 0; i < 6; i++) { + TEST(fabs(array_A[i] - array_row_p[i]) < eps); + } + // Matrix copyToColumnMajor A.copyToColumnMajor(array_A); float array_column[6] = {1, 4, 2, 5, 3, 6}; From 5130da206a1d02eb2466e8ce23f3c1f1cc0b8414 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 13 Nov 2017 16:23:33 +0100 Subject: [PATCH 245/388] Vector: added norm_squared() because sometimes you can safe the sqrt operation --- matrix/Vector.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 3d19e1dac0..fc937c2a42 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -71,6 +71,11 @@ public: return Type(sqrt(a.dot(a))); } + Type norm_squared() const { + const Vector &a(*this); + return Type(a.dot(a)); + } + inline Type length() const { return norm(); } From d513c94f85f0946f2bbd5034476da09f8d4aaebb Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 13 Nov 2017 16:24:33 +0100 Subject: [PATCH 246/388] Test: added check for Vector.norm_squared() --- test/vector.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/test/vector.cpp b/test/vector.cpp index bfebe6414a..7cf24a07e4 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -18,6 +18,7 @@ int main() // norm, dot product TEST(isEqualF(v1.norm(), 7.416198487095663f)); + TEST(isEqualF(v1.norm_squared(), v1.norm() * v1.norm())); TEST(isEqualF(v1.norm(), v1.length())); TEST(isEqualF(v1.dot(v2), 130.0f)); TEST(isEqualF(v1.dot(v2), v1 * v2)); From 84cd7483ae3a8f27861e3738f1643585f144b827 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 13 Nov 2017 16:35:33 +0100 Subject: [PATCH 247/388] Quaternion: added constructor which generates the shortest rotation that maps one vector to another including tedious corner case handling for parallel vectors with 180 degree rotations --- matrix/Quaternion.hpp | 41 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 41 insertions(+) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index ea24e1fc6e..891835f1f1 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -186,6 +186,47 @@ public: } } + /** + * Quaternion from two vectors + * Generates shortest rotation from source to destination vector + * Default destination if not specified is [0,0,1] + * + * @param dst destination vector (no need to normalize) + * @param src source vector (no need to normalize) + * @param eps epsilon threshold which decides if a value is considered zero + */ + Quaternion(const Vector3 &src, const Vector dst = Vector3(0, 0, 1), const Type eps = 1e-5f) : + Vector() + { + Quaternion &q = *this; + Vector3 cr = src.cross(dst); + float dt = src.dot(dst); + if (cr.norm() < eps && dt < 0) { + cr = src.abs(); + if (cr(0) < cr(1)) { + if (cr(0) < cr(2)) { + cr = Vector3(1, 0, 0); + } else { + cr = Vector3(0, 0, 1); + } + } else { + if (cr(1) < cr(2)) { + cr = Vector3(0, 1, 0); + } else { + cr = Vector3(0, 0, 1); + } + } + q(0) = Type(0); + cr = src.cross(cr); + } else { + q(0) = src.dot(dst) + sqrt(src.norm_squared() * dst.norm_squared()); + } + q(1) = cr(0); + q(2) = cr(1); + q(3) = cr(2); + q.normalize(); + } + /** * Constructor from quaternion values From af2610ec04cf0ccd194d406c30fcabc0d4127b6f Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 13 Nov 2017 17:29:49 +0100 Subject: [PATCH 248/388] Test: added check for quaternion vector to vector rotation constructor including all the parallel vector corner cases --- test/attitude.cpp | 34 +++++++++++++++++++++++++++++----- 1 file changed, 29 insertions(+), 5 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 7972aedb9e..7758ac3717 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -27,10 +27,7 @@ int main() TEST(isEqual(e, e)); // euler vector ctor - Vector v; - v(0) = 0.1f; - v(1) = 0.2f; - v(2) = 0.3f; + Vector3f v(0.1f, 0.2f, 0.3f); Eulerf euler_copy(v); TEST(isEqual(euler_copy, euler_check)); @@ -42,6 +39,33 @@ int main() TEST(fabs(q(2) - 3) < eps); TEST(fabs(q(3) - 4) < eps); + // quaternion ctor: vector to vector + Vector3f v1(0.f, 0.f, 1.f); + // identity & default destination vector test + Quatf quat_v(v1); + TEST(isEqual(quat_v.conjugate(v1), v1)); + // random test (vector norm can not be preserved with a pure rotation) + v1 = Vector3f(-80.1f, 1.5f, -6.89f); + quat_v = Quatf(v1, v); + TEST(isEqual(quat_v.conjugate(v1).normalized() * v.norm(), v)); + // special 180 degree case 1 + v1 = Vector3f(0.f, 1.f, 1.f); + quat_v = Quatf(v1, -v1); + TEST(isEqual(quat_v.conjugate(v1), -v1)); + // special 180 degree case 2 + v1 = Vector3f(1.f, 2.f, 0.f); + quat_v = Quatf(v1, -v1); + TEST(isEqual(quat_v.conjugate(v1), -v1)); + // special 180 degree case 3 + v1 = Vector3f(0.f, 0.f, 1.f); + quat_v = Quatf(v1, -v1); + TEST(isEqual(quat_v.conjugate(v1), -v1)); + // special 180 degree case 4 + v1 = Vector3f(1.f, 1.f, 1.f); + quat_v = Quatf(v1, -v1); + TEST(isEqual(quat_v.conjugate(v1), -v1)); + + // quat normalization q.normalize(); TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, @@ -297,7 +321,7 @@ int main() TEST(isEqual(Dcmf(q), q.to_dcm())); // conjugate - Vector3f v1(1.5f, 2.2f, 3.2f); + v = Vector3f(1.5f, 2.2f, 3.2f); TEST(isEqual(q.conjugate_inversed(v1), Dcmf(q).T()*v1)); TEST(isEqual(q.conjugate(v1), Dcmf(q)*v1)); From f835d390171ae61de977d00cdaf5ed16e5361e4e Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 4 Dec 2017 13:27:58 +0100 Subject: [PATCH 249/388] Quaternion/Vector: Small refactor for review: put more comments, switched type conversions, took out default destination vector because confusing --- matrix/Quaternion.hpp | 6 ++++-- matrix/Vector.hpp | 4 ++-- test/attitude.cpp | 9 ++++----- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 891835f1f1..4961fab5ee 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -189,18 +189,19 @@ public: /** * Quaternion from two vectors * Generates shortest rotation from source to destination vector - * Default destination if not specified is [0,0,1] * * @param dst destination vector (no need to normalize) * @param src source vector (no need to normalize) * @param eps epsilon threshold which decides if a value is considered zero */ - Quaternion(const Vector3 &src, const Vector dst = Vector3(0, 0, 1), const Type eps = 1e-5f) : + Quaternion(const Vector3 &src, const Vector3 &dst, const Type eps = Type(1e-5)) : Vector() { Quaternion &q = *this; Vector3 cr = src.cross(dst); float dt = src.dot(dst); + /* If the two vectors are parallel, cross product is zero + * If they point opposite, the dot product is negative */ if (cr.norm() < eps && dt < 0) { cr = src.abs(); if (cr(0) < cr(1)) { @@ -219,6 +220,7 @@ public: q(0) = Type(0); cr = src.cross(cr); } else { + /* Half-Way Quaternion Solution */ q(0) = src.dot(dst) + sqrt(src.norm_squared() * dst.norm_squared()); } q(1) = cr(0); diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index fc937c2a42..a1058f2361 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -73,7 +73,7 @@ public: Type norm_squared() const { const Vector &a(*this); - return Type(a.dot(a)); + return a.dot(a); } inline Type length() const { @@ -88,7 +88,7 @@ public: return (*this) / norm(); } - Vector unit_or_zero(const Type eps = 1e-5f) { + Vector unit_or_zero(const Type eps = Type(1e-5)) { const Type n = norm(); if (n > eps) { return (*this) / n; diff --git a/test/attitude.cpp b/test/attitude.cpp index 7758ac3717..6cb1d8dd70 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -40,12 +40,11 @@ int main() TEST(fabs(q(3) - 4) < eps); // quaternion ctor: vector to vector - Vector3f v1(0.f, 0.f, 1.f); - // identity & default destination vector test - Quatf quat_v(v1); - TEST(isEqual(quat_v.conjugate(v1), v1)); + // identity test + Quatf quat_v(v,v); + TEST(isEqual(quat_v.conjugate(v), v)); // random test (vector norm can not be preserved with a pure rotation) - v1 = Vector3f(-80.1f, 1.5f, -6.89f); + Vector3f v1(-80.1f, 1.5f, -6.89f); quat_v = Quatf(v1, v); TEST(isEqual(quat_v.conjugate(v1).normalized() * v.norm(), v)); // special 180 degree case 1 From 41a1cc7583253f3063ab4c626c40e7bc2a0bc868 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 4 Dec 2017 14:07:47 -0500 Subject: [PATCH 250/388] LICENSE minor changes to template --- LICENSE | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/LICENSE b/LICENSE index a8b6be7e12..cc64b5a484 100644 --- a/LICENSE +++ b/LICENSE @@ -1,6 +1,6 @@ -The Matrix library is licensed under a permissive 3-clause BSD license. Contributions must be made under the same license. +BSD 3-Clause License -Copyright (c) 2015, Matrix Development Team. +Copyright (c) 2015, PX4 Pro Drone Autopilot All rights reserved. Redistribution and use in source and binary forms, with or without @@ -13,7 +13,7 @@ modification, are permitted provided that the following conditions are met: this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. -* Neither the name of matrix nor the names of its +* Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. @@ -27,4 +27,3 @@ SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - From 61af508755c59d177c4e61a35cbfa270b06d9684 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 19 Mar 2018 02:19:34 -0400 Subject: [PATCH 251/388] helper_functions include required px4_defines header --- matrix/helper_functions.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index e8cc0dcb80..dffd9e0020 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -2,6 +2,10 @@ #include "math.hpp" +#if defined (__PX4_NUTTX) || defined (__PX4_QURT) +#include +#endif + namespace matrix { From 50446a55c83fd4bcc1cc4666cf2801cb5c5c9ba0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 18 Mar 2018 19:52:31 -0400 Subject: [PATCH 252/388] Matrix add == and != operators --- matrix/Matrix.hpp | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 30b7fa929e..4d4c238711 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -288,6 +288,29 @@ public: *this = (*this) - scalar; } + bool operator==(const Matrix &other) const + { + const Matrix &self = *this; + + // TODO: set this based on Type + static constexpr float eps = 1e-4f; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + if (fabs(self(i, j) - other(i, j) > eps) ) { + return false; + } + } + } + + return true; + } + + bool operator!=(const Matrix &other) const + { + const Matrix &self = *this; + return !(self == other); + } /** * Misc. Functions From d142ac234c4d08f83954751df901e6c18139fbed Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 27 Mar 2018 17:39:40 -0400 Subject: [PATCH 253/388] Fix coverage and bug in matrix equal test. --- .travis.yml | 3 ++- matrix/Matrix.hpp | 2 +- test/attitude.cpp | 58 +++++++++++++++++++++++++++++++++------------ test/matrixMult.cpp | 11 ++++++++- 4 files changed, 56 insertions(+), 18 deletions(-) diff --git a/.travis.yml b/.travis.yml index 692a570bd3..741c121ab9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -27,12 +27,13 @@ addons: - cmake - g++ - gcc + - lcov install: - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then pip install --user cpp-coveralls; fi script: - - cmake -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DTESTING=ON -DFORMAT=${FORMAT} . + - cmake -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DSUPPORT_STDIOSTREAM=ON -DTESTING=ON -DFORMAT=${FORMAT} . - make check after_success: diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 4d4c238711..f4972d6834 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -297,7 +297,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - if (fabs(self(i, j) - other(i, j) > eps) ) { + if (fabs(self(i, j) - other(i, j)) > eps) { return false; } } diff --git a/test/attitude.cpp b/test/attitude.cpp index 6cb1d8dd70..3f1c132277 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -1,11 +1,28 @@ #include "test_macros.hpp" #include +#include using namespace matrix; +namespace matrix { + +// manually instantiated all files we intend to test +// so that coverage works correctly +// doesn't matter what test this is in +template class Matrix; +template class Vector3; +template class Vector2; +template class Vector; +template class Quaternion; +template class AxisAngle; +template class Scalar; +template class SquareMatrix; + +} + int main() { - double eps = 1e-6; + // check data Eulerf euler_check(0.1f, 0.2f, 0.3f); @@ -34,6 +51,7 @@ int main() // quaternion ctor Quatf q0(1, 2, 3, 4); Quatf q(q0); + double eps = 1e-6; TEST(fabs(q(0) - 1) < eps); TEST(fabs(q(1) - 2) < eps); TEST(fabs(q(2) - 3) < eps); @@ -64,7 +82,6 @@ int main() quat_v = Quatf(v1, -v1); TEST(isEqual(quat_v.conjugate(v1), -v1)); - // quat normalization q.normalize(); TEST(isEqual(q, Quatf(0.18257419f, 0.36514837f, @@ -130,18 +147,18 @@ int main() double rad2deg = 180.0 / M_PI; // euler dcm round trip check - for (int roll = -90; roll <= 90; roll += 90) { - for (int pitch = -90; pitch <= 90; pitch += 90) { - for (int yaw = -179; yaw <= 180; yaw += 90) { + for (double roll = -90; roll <= 90; roll += 90) { + for (double pitch = -90; pitch <= 90; pitch += 90) { + for (double yaw = -179; yaw <= 180; yaw += 90) { // note if theta = pi/2, then roll is set to zero - int roll_expected = roll; - int yaw_expected = yaw; + double roll_expected = roll; + double yaw_expected = yaw; - if (pitch == 90) { + if (fabs(pitch -90) < eps) { roll_expected = 0; yaw_expected = yaw - roll; - } else if (pitch == -90) { + } else if (fabs(pitch + 90) < eps) { roll_expected = 0; yaw_expected = yaw + roll; } @@ -156,13 +173,13 @@ int main() //printf("roll:%d pitch:%d yaw:%d\n", roll, pitch, yaw); Euler euler_expected( - deg2rad * double(roll_expected), - deg2rad * double(pitch), - deg2rad * double(yaw_expected)); + deg2rad * roll_expected, + deg2rad * pitch, + deg2rad * yaw_expected); Euler euler( - deg2rad * double(roll), - deg2rad * double(pitch), - deg2rad * double(yaw)); + deg2rad * roll, + deg2rad * pitch, + deg2rad * yaw); Dcm dcm_from_euler(euler); //dcm_from_euler.print(); Euler euler_out(dcm_from_euler); @@ -289,6 +306,13 @@ int main() q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f); TEST(isEqual(q, q_true)); + // from axis angle, with length of vector the rotation + float n = float(sqrt(4*M_PI*M_PI/3)); + q.from_axis_angle(Vector3f(n, n, n)); + TEST(isEqual(q, Quatf(-1, 0, 0, 0))); + q.from_axis_angle(Vector3f(0, 0, 0)); + TEST(isEqual(q, Quatf(1, 0, 0, 0))); + // Quaternion initialisation per array float q_array[] = {0.9833f, -0.0343f, -0.1060f, -0.1436f}; Quaternionq_from_array(q_array); @@ -340,6 +364,7 @@ int main() TEST(isEqual(Quatf((AxisAnglef(Vector3f(0.0f, 0.0f, 1.0f), 0.0f))), Quatf(1.0f, 0.0f, 0.0f, 0.0f))); + // check consistentcy of quaternion and dcm product Dcmf dcm3(Eulerf(1, 2, 3)); Dcmf dcm4(Eulerf(4, 5, 6)); @@ -357,6 +382,9 @@ int main() R = Dcmf(q); TEST(isEqual(q, Quatf(R))); +#if defined(SUPPORT_STDIOSTREAM) + std::cout << "q:" << q; +#endif return 0; } diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 65623260dc..1699d3f3c8 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -7,6 +7,14 @@ int main() { float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; Matrix3f A(data); + + const Matrix3f Const(data); + const float * raw_data = Const.data(); + const float eps = 1e-4f; + for (int i=0; i<9; i++) { + TEST(fabs(raw_data[i] - data[i]) < eps); + } + float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; Matrix3f A_I(data_check); Matrix3f I; @@ -18,7 +26,8 @@ int main() R2 *= A_I; TEST(isEqual(R2, I)); - + TEST(R2==I); + TEST(A!=A_I); Matrix3f A2 = eye()*2; Matrix3f B = A2.emult(A2); Matrix3f B_check = eye()*4; From e7c95fa027675f38f14b06344bf9855883013727 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 27 Mar 2018 20:02:48 -0400 Subject: [PATCH 254/388] Fix README/cmake format. --- CMakeLists.txt | 190 ++++++++++++++++++++++---------------------- README.md | 143 ++++++++++++++++----------------- scripts/format.sh | 26 +++--- test/CMakeLists.txt | 90 +++++++++++---------- 4 files changed, 227 insertions(+), 222 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e9baaa2b4c..5fae908d9a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,8 +10,8 @@ set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_STANDARD_REQUIRED ON) if (NOT CMAKE_BUILD_TYPE) - set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) - message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") + set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) + message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage") @@ -28,133 +28,133 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS ON) include_directories(${CMAKE_SOURCE_DIR}) if(SUPPORT_STDIOSTREAM) - add_definitions(-DSUPPORT_STDIOSTREAM) + add_definitions(-DSUPPORT_STDIOSTREAM) endif() set(CMAKE_CXX_FLAGS_COVERAGE - "--coverage -fprofile-arcs -ftest-coverage -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors" - CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) + "--coverage -fprofile-arcs -ftest-coverage -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors" + CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) set(CMAKE_EXE_LINKER_FLAGS_COVERAGE - "--coverage -ftest-coverage -lgcov" - CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) + "--coverage -ftest-coverage -lgcov" + CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) mark_as_advanced(CMAKE_CXX_FLAGS_COVERAGE CMAKE_C_FLAGS_COVERAGE CMAKE_EXE_LINKER_FLAGS_COVERAGE) add_compile_options( - -pedantic - -Wall - -Warray-bounds - -Wcast-align - -Wcast-qual - -Wconversion - -Wctor-dtor-privacy - -Wdisabled-optimization - -Werror - -Wextra - -Wfloat-equal - -Wformat-security - -Wformat=2 - -Winit-self - -Wlogical-op - -Wmissing-declarations - -Wmissing-include-dirs - -Wno-sign-compare - -Wno-unused - -Wno-unused-parameter - -Wnoexcept - -Wold-style-cast - -Woverloaded-virtual - -Wpointer-arith - -Wredundant-decls - -Wreorder - -Wshadow - -Wsign-conversion - -Wsign-promo - -Wstrict-null-sentinel - -Wswitch-default - -Wundef - -Wuninitialized - -Wunused-variable - ) + -pedantic + -Wall + -Warray-bounds + -Wcast-align + -Wcast-qual + -Wconversion + -Wctor-dtor-privacy + -Wdisabled-optimization + -Werror + -Wextra + -Wfloat-equal + -Wformat-security + -Wformat=2 + -Winit-self + -Wlogical-op + -Wmissing-declarations + -Wmissing-include-dirs + -Wno-sign-compare + -Wno-unused + -Wno-unused-parameter + -Wnoexcept + -Wold-style-cast + -Woverloaded-virtual + -Wpointer-arith + -Wredundant-decls + -Wreorder + -Wshadow + -Wsign-conversion + -Wsign-promo + -Wstrict-null-sentinel + -Wswitch-default + -Wundef + -Wuninitialized + -Wunused-variable + ) # clang tolerate unknown gcc options if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") - add_compile_options( - -Wno-error=unused-command-line-argument-hard-error-in-future - -Wno-unknown-warning-option - ) + add_compile_options( + -Wno-error=unused-command-line-argument-hard-error-in-future + -Wno-unknown-warning-option + ) else() - add_compile_options( - -Wstrict-overflow=5 - ) + add_compile_options( + -Wstrict-overflow=5 + ) endif() # santiziers (ASAN, UBSAN) if(ASAN) - message(STATUS "address sanitizer enabled") + message(STATUS "address sanitizer enabled") - # environment variables - # ASAN_OPTIONS=detect_stack_use_after_return=1 - # ASAN_OPTIONS=check_initialization_order=1 + # environment variables + # ASAN_OPTIONS=detect_stack_use_after_return=1 + # ASAN_OPTIONS=check_initialization_order=1 - add_compile_options( - -fsanitize=address - -g3 - -O1 - -fno-omit-frame-pointer - ) + add_compile_options( + -fsanitize=address + -g3 + -O1 + -fno-omit-frame-pointer + ) - set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=address) + set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=address) elseif(UBSAN) - message(STATUS "undefined behaviour sanitizer enabled") + message(STATUS "undefined behaviour sanitizer enabled") - add_compile_options( - -fsanitize=undefined - -fsanitize=integer - -g3 - -O1 - -fno-omit-frame-pointer - ) + add_compile_options( + -fsanitize=undefined + -fsanitize=integer + -g3 + -O1 + -fno-omit-frame-pointer + ) - set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=undefined) + set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=undefined) endif() add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure) if(TESTING) - enable_testing() - add_subdirectory(test) - add_dependencies(check test_build) + enable_testing() + add_subdirectory(test) + add_dependencies(check test_build) - add_custom_target(clang-tidy COMMAND clang-tidy -p . ${CMAKE_SOURCE_DIR}/test/*.cpp) - add_dependencies(clang-tidy test_build) + add_custom_target(clang-tidy COMMAND clang-tidy -p . ${CMAKE_SOURCE_DIR}/test/*.cpp) + add_dependencies(clang-tidy test_build) endif() if(FORMAT) - set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) - add_custom_command(OUTPUT ${astyle_exe} - COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.06/astyle_2.06_linux.tar.gz -O /tmp/astyle.tar.gz - COMMAND tar -xvf /tmp/astyle.tar.gz - COMMAND cd astyle/src && make -f ../build/gcc/Makefile - WORKING_DIRECTORY ${CMAKE_BINARY_DIR} - ) + set(astyle_exe ${CMAKE_BINARY_DIR}/astyle/src/bin/astyle) + add_custom_command(OUTPUT ${astyle_exe} + COMMAND wget http://sourceforge.net/projects/astyle/files/astyle/astyle%202.06/astyle_2.06_linux.tar.gz -O /tmp/astyle.tar.gz + COMMAND tar -xvf /tmp/astyle.tar.gz + COMMAND cd astyle/src && make -f ../build/gcc/Makefile + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + ) - add_custom_target(check_format - COMMAND scripts/format.sh ${astyle_exe} 0 - WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} - DEPENDS ${astyle_exe} - VERBATIM - ) + add_custom_target(check_format + COMMAND scripts/format.sh ${astyle_exe} 0 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + DEPENDS ${astyle_exe} + VERBATIM + ) - add_custom_target(format - COMMAND scripts/format.sh ${astyle_exe} 1 - WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} - VERBATIM - DEPENDS ${astyle_exe} - ) + add_custom_target(format + COMMAND scripts/format.sh ${astyle_exe} 1 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + VERBATIM + DEPENDS ${astyle_exe} + ) - add_dependencies(check check_format) + add_dependencies(check check_format) endif() set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) @@ -163,4 +163,4 @@ set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com") include(CPack) -# vim: set noet fenc=utf-8 ft=cmake ff=unix sts=0 sw=4 ts=4 : +# vim: set et fenc=utf-8 ft=cmake ff=unix sts=0 sw=4 ts=4 : diff --git a/README.md b/README.md index 0b2ba53175..5cc19294d2 100644 --- a/README.md +++ b/README.md @@ -16,111 +16,112 @@ A simple and efficient template based matrix library. ## Library Overview * matrix/math.hpp : Provides matrix math routines. - * Matrix (MxN) - * Square Matrix (MxM, has inverse) - * Vector (Mx1) - * Scalar (1x1) - * Quaternion - * Dcm - * Euler (Body 321) - * Axis Angle + * Matrix (MxN) + * Square Matrix (MxM, has inverse) + * Vector (Mx1) + * Scalar (1x1) + * Quaternion + * Dcm + * Euler (Body 321) + * Axis Angle * matrix/filter.hpp : Provides filtering routines. - * kalman_correct + * kalman_correct * matrix/integrate.hpp : Provides integration routines. - * integrate_rk4 (Runge-Kutta 4th order) + * integrate_rk4 (Runge-Kutta 4th order) ## Example See the test directory for detailed examples. Some simple examples are included below: ```c++ - // define an euler angle (Body 3(yaw)-2(pitch)-1(roll) rotation) - float roll = 0.1f; - float pitch = 0.2f; - float yaw = 0.3f; - Eulerf euler(roll, pitch, yaw); + // define an euler angle (Body 3(yaw)-2(pitch)-1(roll) rotation) + float roll = 0.1f; + float pitch = 0.2f; + float yaw = 0.3f; + Eulerf euler(roll, pitch, yaw); - // convert to quaternion from euler - Quatf q_nb(euler); + // convert to quaternion from euler + Quatf q_nb(euler); - // convert to DCM from quaternion - Dcmf dcm(q_nb); + // convert to DCM from quaternion + Dcmf dcm(q_nb); - // you can assign a rotation instance that already exist to another rotation instance, e.g. - dcm = euler; + // you can assign a rotation instance that already exist to another rotation instance, e.g. + dcm = euler; - // you can also directly create a DCM instance from euler angles like this - dcm = Eulerf(roll, pitch, yaw); + // you can also directly create a DCM instance from euler angles like this + dcm = Eulerf(roll, pitch, yaw); - // create an axis angle representation from euler angles - AxisAngle axis_angle = euler; + // create an axis angle representation from euler angles + AxisAngle axis_angle = euler; - // use axis angle to initialize a DCM - Dcmf dcm2(AxisAngle(1, 2, 3)); - - // use axis angle with axis/angle separated to init DCM - Dcmf dcm3(AxisAngle(Vector3f(1, 0, 0), 0.2)); + // use axis angle to initialize a DCM + Dcmf dcm2(AxisAngle(1, 2, 3)); + + // use axis angle with axis/angle separated to init DCM + Dcmf dcm3(AxisAngle(Vector3f(1, 0, 0), 0.2)); - // do some kalman filtering - const size_t n_x = 5; - const size_t n_y = 3; + // do some kalman filtering + const size_t n_x = 5; + const size_t n_y = 3; - // define matrix sizes - SquareMatrix P; - Vector x; - Vector y; - Matrix C; - SquareMatrix R; - SquareMatrix S; - Matrix K; + // define matrix sizes + SquareMatrix P; + Vector x; + Vector y; + Matrix C; + SquareMatrix R; + SquareMatrix S; + Matrix K; - // define measurement matrix - C = zero(); // or C.setZero() - C(0,0) = 1; - C(1,1) = 2; - C(2,2) = 3; + // define measurement matrix + C = zero(); // or C.setZero() + C(0,0) = 1; + C(1,1) = 2; + C(2,2) = 3; - // set x to zero - x = zero(); // or x.setZero() + // set x to zero + x = zero(); // or x.setZero() - // set P to identity * 0.01 - P = eye()*0.01; + // set P to identity * 0.01 + P = eye()*0.01; - // set R to identity * 0.1 - R = eye()*0.1; + // set R to identity * 0.1 + R = eye()*0.1; - // measurement - y(0) = 1; - y(1) = 2; - y(2) = 3; + // measurement + y(0) = 1; + y(1) = 2; + y(2) = 3; - // innovation - r = y - C*x; + // innovation + r = y - C*x; - // innovations variance - S = C*P*C.T() + R; + // innovations variance + S = C*P*C.T() + R; - // Kalman gain matrix - K = P*C.T()*S.I(); - // S.I() is the inverse, defined for SquareMatrix + // Kalman gain matrix + K = P*C.T()*S.I(); + // S.I() is the inverse, defined for SquareMatrix - // correction - x += K*r; + // correction + x += K*r; - // slicing + // slicing float data[9] = {0, 2, 3, 4, 5, 6, 7, 8, 10 }; SquareMatrix A(data); - // Slice a 3,3 matrix starting at row 1, col 0, - // with size 2 x 3, warning, no size checking + // Slice a 3,3 matrix starting at row 1, col 0, + // with size 2 x 3, warning, no size checking Matrix B(A.slice<2, 3>(1, 0)); - // this results in: - // 4, 5, 6 - // 7, 8, 10 + // this results in: + // 4, 5, 6 + // 7, 8, 10 ``` + diff --git a/scripts/format.sh b/scripts/format.sh index 3e1a23f4b3..feee98a76c 100755 --- a/scripts/format.sh +++ b/scripts/format.sh @@ -12,17 +12,19 @@ format_wildcards=""" if [[ $format -eq 1 ]] then - echo formatting - $astyle ${format_wildcards} + echo formatting + $astyle ${format_wildcards} else - echo checking format... - $astyle --dry-run ${format_wildcards} | grep Formatted &>/dev/null - if [[ $? -eq 0 ]] - then - echo Error: need to format - echo "From cmake build directory run: 'make format'" - exit 1 - fi - echo no formatting needed - exit 0 + echo checking format... + $astyle --dry-run ${format_wildcards} | grep Formatted &>/dev/null + if [[ $? -eq 0 ]] + then + echo Error: need to format + echo "From cmake build directory run: 'make format'" + exit 1 + fi + echo no formatting needed + exit 0 fi + +# vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 77284c0170..f6c56af60e 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,57 +1,59 @@ set(tests - setIdentity - inverse - slice - matrixMult - vectorAssignment - matrixAssignment - matrixScalarMult - transpose - vector - vector2 - vector3 - attitude - filter - integration - squareMatrix - helper - hatvee - copyto - ) + setIdentity + inverse + slice + matrixMult + vectorAssignment + matrixAssignment + matrixScalarMult + transpose + vector + vector2 + vector3 + attitude + filter + integration + squareMatrix + helper + hatvee + copyto + ) add_custom_target(test_build) foreach(test_name ${tests}) - add_executable(${test_name} - ${test_name}.cpp) - add_test(test_${test_name} ${test_name}) - add_dependencies(test_build ${test_name}) + add_executable(${test_name} + ${test_name}.cpp) + add_test(test_${test_name} ${test_name}) + add_dependencies(test_build ${test_name}) endforeach() if (${CMAKE_BUILD_TYPE} STREQUAL "Coverage") - add_custom_target(coverage_build - COMMAND ${CMAKE_CTEST_COMMAND} - COMMAND lcov --capture --directory . --output-file coverage.info - COMMAND lcov --summary coverage.info - WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS test_build - ) + add_custom_target(coverage_build + COMMAND ${CMAKE_CTEST_COMMAND} + COMMAND lcov --capture --directory . --output-file coverage.info + COMMAND lcov --summary coverage.info + WORKING_DIRECTORY ${CMAKE_BUILD_DIR} + DEPENDS test_build + ) - add_custom_target(coverage_html - COMMAND genhtml coverage.info --output-directory out - COMMAND x-www-browser out/index.html - WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS coverage_build - ) + add_custom_target(coverage_html + COMMAND genhtml coverage.info --output-directory out + COMMAND x-www-browser out/index.html + WORKING_DIRECTORY ${CMAKE_BUILD_DIR} + DEPENDS coverage_build + ) - set(coverage_deps - coverage_build) + set(coverage_deps + coverage_build) - if (COV_HTML) - list(APPEND coverage_deps coverage_html) - endif() + if (COV_HTML) + list(APPEND coverage_deps coverage_html) + endif() - add_custom_target(coverage - DEPENDS ${coverage_deps} - ) + add_custom_target(coverage + DEPENDS ${coverage_deps} + ) endif() + +# vim: set et fenc=utf-8 ft=cmake ff=unix sts=0 sw=4 ts=4 : From 21d47424c6050bb94da5de3f7580a8df66b6fcc7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 31 Mar 2018 16:59:03 -0400 Subject: [PATCH 255/388] Quaternion mark const helpers const --- matrix/Quaternion.hpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 4961fab5ee..87bea23d2c 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -346,9 +346,9 @@ public: * * @return inverted quaternion */ - Quaternion inversed() + Quaternion inversed() const { - Quaternion &q = *this; + const Quaternion &q = *this; Type normSq = q.dot(q); return Quaternion( q(0)/normSq, @@ -393,7 +393,8 @@ public: * @param vec vector to rotate in frame 2 (typically reference frame) * @return rotated vector in frame 1 (typically body frame) */ - Vector3f conjugate_inversed(const Vector3f &vec) { + Vector3f conjugate_inversed(const Vector3f &vec) const + { Quaternion q = *this; Quaternion v(0, vec(0), vec(1), vec(2)); Quaternion res = q.inversed()*v*q; @@ -459,9 +460,9 @@ public: * * @return vector, direction representing rotation axis and norm representing angle */ - Vector to_axis_angle() + Vector to_axis_angle() const { - Quaternion &q = *this; + const Quaternion &q = *this; Type axis_magnitude = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); Vector vec; vec(0) = q(1); @@ -479,9 +480,9 @@ public: /** * Imaginary components of quaternion */ - Vector3 imag() + Vector3 imag() const { - Quaternion &q = *this; + const Quaternion &q = *this; return Vector3(q(1), q(2), q(3)); } @@ -492,9 +493,9 @@ public: * == last column of the equivalent rotation matrix * but calculated more efficiently than a full conversion */ - Vector3 dcm_z() + Vector3 dcm_z() const { - Quaternion &q = *this; + const Quaternion &q = *this; Vector3 R_z; const Type a = q(0); const Type b = q(1); From abc8f82d49e1a871b9294b1ddca49514ab2c9569 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 9 Jun 2018 21:08:56 -0400 Subject: [PATCH 256/388] travis-ci add codecov.io (#69) --- .travis.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.travis.yml b/.travis.yml index 741c121ab9..ad0668aa60 100644 --- a/.travis.yml +++ b/.travis.yml @@ -38,4 +38,5 @@ script: after_success: - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then cpp-coveralls -i matrix; fi + - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then bash <(curl -s https://codecov.io/bash) -F matrix_tests; fi From 03a3e3ad46d21bb90e78f8cedd3526d24617df5f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 9 Jun 2018 16:58:25 -0400 Subject: [PATCH 257/388] helper_functions add wrap_2pi --- matrix/helper_functions.hpp | 49 ++++++++++++++++++++++++++++++++++--- test/helper.cpp | 8 ++++++ 2 files changed, 53 insertions(+), 4 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index dffd9e0020..ce8ba11456 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -6,6 +6,8 @@ #include #endif +#include + namespace matrix { @@ -27,18 +29,57 @@ Type wrap_pi(Type x) return x; } - while (x >= Type(M_PI)) { - x -= Type(2.0 * M_PI); + int c = 0; + while (x >= Type(M_PI)) { + x -= Type(2 * M_PI); + + if (c++ > 100) { + return std::numeric_limits::quiet_NaN(); + } } - while (x < Type(-M_PI)) { - x += Type(2.0 * M_PI); + c = 0; + while (x < Type(-M_PI)) { + x += Type(2 * M_PI); + + if (c++ > 100) { + return std::numeric_limits::quiet_NaN(); + } } return x; } +template +Type wrap_2pi(Type x) +{ + if (!is_finite(x)) { + return x; + } + + int c = 0; + + while (x >= Type(2 * M_PI)) { + x -= Type(2 * M_PI); + + if (c++ > 100) { + return std::numeric_limits::quiet_NaN(); + } + } + + c = 0; + + while (x < Type(0)) { + x += Type(2 * M_PI); + + if (c++ > 100) { + return std::numeric_limits::quiet_NaN(); + } + } + + return x; +} } diff --git a/test/helper.cpp b/test/helper.cpp index cfc1aeb3ef..fb1e779a72 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -8,8 +8,16 @@ int main() TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5); TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); TEST(fabs(wrap_pi(3.0) - (3.0)) < 1e-3); + TEST(!is_finite(wrap_pi(1000.0f))); + TEST(!is_finite(wrap_pi(-1000.0f))); wrap_pi(NAN); + TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); + TEST(fabs(wrap_2pi(3.0) - (3.0)) < 1e-3); + TEST(!is_finite(wrap_2pi(1000.0f))); + TEST(!is_finite(wrap_2pi(-1000.0f))); + wrap_2pi(NAN); + Vector3f a(1, 2, 3); Vector3f b(4, 5, 6); a.T().print(); From b815fc97c4e686a93a8074f27d1830a031b0d38d Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 12 Jun 2018 18:24:51 +0200 Subject: [PATCH 258/388] replace quiet_NaN() with INFINITY (#70) - solves undefined symbols for QURT Signed-off-by: Roman --- matrix/helper_functions.hpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index ce8ba11456..43c28d571d 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -6,8 +6,6 @@ #include #endif -#include - namespace matrix { @@ -35,7 +33,7 @@ Type wrap_pi(Type x) x -= Type(2 * M_PI); if (c++ > 100) { - return std::numeric_limits::quiet_NaN(); + return INFINITY; } } @@ -45,7 +43,7 @@ Type wrap_pi(Type x) x += Type(2 * M_PI); if (c++ > 100) { - return std::numeric_limits::quiet_NaN(); + return INFINITY; } } @@ -65,7 +63,7 @@ Type wrap_2pi(Type x) x -= Type(2 * M_PI); if (c++ > 100) { - return std::numeric_limits::quiet_NaN(); + return INFINITY; } } @@ -75,7 +73,7 @@ Type wrap_2pi(Type x) x += Type(2 * M_PI); if (c++ > 100) { - return std::numeric_limits::quiet_NaN(); + return INFINITY; } } From 1bcf48bd82559369e1eeac3578d0a073fec2e434 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 30 Aug 2018 11:49:40 -0400 Subject: [PATCH 259/388] Quaternion from_dcm don't pass by value --- matrix/Quaternion.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 87bea23d2c..a17205fc12 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -510,7 +510,7 @@ public: /** * XXX DEPRECATED, can use assignment or ctor */ - Quaternion from_dcm(Matrix dcm) { + Quaternion from_dcm(const Matrix& dcm) { return Quaternion(Dcmf(dcm)); } From f1bee775a0d4781ebc3590890f65c57cf435fe84 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 27 Aug 2018 14:05:55 -0400 Subject: [PATCH 260/388] use default constructors and skip unnecessary initialization --- matrix/AxisAngle.hpp | 20 ++++++-------------- matrix/Dcm.hpp | 2 +- matrix/Euler.hpp | 9 +++------ matrix/Matrix.hpp | 10 +++++----- matrix/Quaternion.hpp | 18 ++++++------------ matrix/Scalar.hpp | 17 +++++++---------- matrix/SquareMatrix.hpp | 5 +---- matrix/Vector.hpp | 4 +--- matrix/Vector2.hpp | 9 +++------ matrix/Vector3.hpp | 10 +++------- test/matrixAssignment.cpp | 3 +-- 11 files changed, 37 insertions(+), 70 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index e1275c3f1d..51d6a3e26a 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -46,10 +46,7 @@ public: /** * Standard constructor */ - AxisAngle() : - Vector() - { - } + AxisAngle() = default; /** * Constructor from Matrix31 @@ -70,8 +67,7 @@ public: * * @param q quaternion */ - AxisAngle(const Quaternion &q) : - Vector() + AxisAngle(const Quaternion &q) { AxisAngle &v = *this; Type ang = Type(2.0f)*acos(q(0)); @@ -95,8 +91,7 @@ public: * * @param dcm dcm to set quaternion to */ - AxisAngle(const Dcm &dcm) : - Vector() + AxisAngle(const Dcm &dcm) { AxisAngle &v = *this; v = Quaternion(dcm); @@ -111,8 +106,7 @@ public: * * @param euler euler angle instance */ - AxisAngle(const Euler &euler) : - Vector() + AxisAngle(const Euler &euler) { AxisAngle &v = *this; v = Quaternion(euler); @@ -125,8 +119,7 @@ public: * @param y r_y*angle * @param z r_z*angle */ - AxisAngle(Type x, Type y, Type z) : - Vector() + AxisAngle(Type x, Type y, Type z) { AxisAngle &v = *this; v(0) = x; @@ -140,8 +133,7 @@ public: * @param axis An axis of rotation, normalized if not unit length * @param angle The amount to rotate */ - AxisAngle(const Matrix31 & axis_, Type angle_) : - Vector() + AxisAngle(const Matrix31 & axis_, Type angle_) { AxisAngle &v = *this; // make sure axis is a unit vector diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 3f0d969402..43d3cee1d3 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -46,7 +46,7 @@ public: * * Initializes to identity */ - Dcm() : SquareMatrix() + Dcm() { (*this) = eye(); } diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index e308a2f3f5..d16d307ed1 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -43,9 +43,7 @@ public: /** * Standard constructor */ - Euler() : Vector() - { - } + Euler() = default; /** * Copy constructor @@ -95,7 +93,7 @@ public: * * @param dcm Direction cosine matrix */ - Euler(const Dcm &dcm) : Vector() + Euler(const Dcm &dcm) { Type phi_val = Type(atan2(dcm(2, 1), dcm(2, 2))); Type theta_val = Type(asin(-dcm(2, 0))); @@ -126,8 +124,7 @@ public: * * @param q quaternion */ - Euler(const Quaternion &q) : - Vector() + Euler(const Quaternion &q) { *this = Euler(Dcm(q)); } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index f4972d6834..151b337884 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -30,22 +30,22 @@ class Matrix public: - Type _data[M][N]; + Type _data[M][N] {}; // Constructors - Matrix() : _data() {} + Matrix() = default; - Matrix(const Type data_[][N]) : _data() + Matrix(const Type data_[][N]) { memcpy(_data, data_, sizeof(_data)); } - Matrix(const Type *data_) : _data() + Matrix(const Type *data_) { memcpy(_data, data_, sizeof(_data)); } - Matrix(const Matrix &other) : _data() + Matrix(const Matrix &other) { memcpy(_data, other._data, sizeof(_data)); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a17205fc12..cbf2c2b85a 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -70,8 +70,7 @@ public: /** * Standard constructor */ - Quaternion() : - Vector() + Quaternion() { Quaternion &q = *this; q(0) = 1; @@ -98,8 +97,7 @@ public: * * @param dcm dcm to set quaternion to */ - Quaternion(const Dcm &R) : - Vector() + Quaternion(const Dcm &R) { Quaternion &q = *this; Type t = R.trace(); @@ -143,8 +141,7 @@ public: * * @param euler euler angle instance */ - Quaternion(const Euler &euler) : - Vector() + Quaternion(const Euler &euler) { Quaternion &q = *this; Type cosPhi_2 = Type(cos(euler.phi() / Type(2.0))); @@ -168,8 +165,7 @@ public: * * @param aa axis-angle vector */ - Quaternion(const AxisAngle &aa) : - Vector() + Quaternion(const AxisAngle &aa) { Quaternion &q = *this; Type angle = aa.norm(); @@ -194,8 +190,7 @@ public: * @param src source vector (no need to normalize) * @param eps epsilon threshold which decides if a value is considered zero */ - Quaternion(const Vector3 &src, const Vector3 &dst, const Type eps = Type(1e-5)) : - Vector() + Quaternion(const Vector3 &src, const Vector3 &dst, const Type eps = Type(1e-5)) { Quaternion &q = *this; Vector3 cr = src.cross(dst); @@ -242,8 +237,7 @@ public: * @param c set quaternion value 2 * @param d set quaternion value 3 */ - Quaternion(Type a, Type b, Type c, Type d) : - Vector() + Quaternion(Type a, Type b, Type c, Type d) { Quaternion &q = *this; q(0) = a; diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index 302cd70c87..c9765028c3 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -17,21 +17,18 @@ template class Scalar { public: - Scalar() : _value() + Scalar() = delete; + + Scalar(const Matrix & other) : + _value{other(0,0)} { } - Scalar(const Matrix & other) + Scalar(Type other) : _value(other) { - _value = other(0,0); } - Scalar(Type other) - { - _value = other; - } - - operator Type &() + operator const Type &() { return _value; } @@ -49,7 +46,7 @@ public: } private: - Type _value; + const Type _value; }; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 5b2560dc71..2e348137b1 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -24,10 +24,7 @@ template class SquareMatrix : public Matrix { public: - SquareMatrix() : - Matrix() - { - } + SquareMatrix() = default; SquareMatrix(const Type *data_) : Matrix(data_) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index a1058f2361..7ea2d0caee 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -22,9 +22,7 @@ class Vector : public Matrix public: typedef Matrix MatrixM1; - Vector() : MatrixM1() - { - } + Vector() = default; Vector(const MatrixM1 & other) : MatrixM1(other) diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index 7badf94b12..7aeeb1d927 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -23,10 +23,7 @@ public: typedef Matrix Matrix21; - Vector2() : - Vector() - { - } + Vector2() = default; Vector2(const Matrix21 & other) : Vector(other) @@ -38,14 +35,14 @@ public: { } - Vector2(Type x, Type y) : Vector() + Vector2(Type x, Type y) { Vector2 &v(*this); v(0) = x; v(1) = y; } - Type cross(const Matrix21 & b) const { + Type cross(const Matrix21 & b) const { const Vector2 &a(*this); return a(0)*b(1, 0) - a(1)*b(0, 0); } diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 3dbaa26c23..989e247032 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -29,10 +29,7 @@ public: typedef Matrix Matrix31; - Vector3() : - Vector() - { - } + Vector3() = default; Vector3(const Matrix31 & other) : Vector(other) @@ -44,15 +41,14 @@ public: { } - Vector3(Type x, Type y, Type z) : Vector() - { + Vector3(Type x, Type y, Type z) { Vector3 &v(*this); v(0) = x; v(1) = y; v(2) = z; } - Vector3 cross(const Matrix31 & b) const { + Vector3 cross(const Matrix31 & b) const { const Vector3 &a(*this); Vector3 c; c(0) = a(1)*b(2,0) - a(2)*b(1,0); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 91b4cc02b0..5ad7de6779 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -97,8 +97,7 @@ int main() TEST(fabs(m4.min() - 1) < 1e-5); TEST(fabs((-m4).min() + 9) < 1e-5); - Scalar s; - s = 1; + Scalar s = 1; const Vector & s_vect = s; TEST(fabs(s - 1) < 1e-5); TEST(fabs(s_vect(0) - 1.0f) < 1e-5); From dc3af8097798881b9b2e72a029a3c6c10abd059b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 27 Aug 2018 15:39:29 -0400 Subject: [PATCH 261/388] constructors use array size rather than pointers --- matrix/AxisAngle.hpp | 2 +- matrix/Matrix.hpp | 6 +++--- matrix/Quaternion.hpp | 2 +- matrix/SquareMatrix.hpp | 2 +- matrix/Vector.hpp | 2 +- matrix/Vector2.hpp | 2 +- matrix/Vector3.hpp | 2 +- 7 files changed, 9 insertions(+), 9 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 51d6a3e26a..339651fe0a 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -38,7 +38,7 @@ public: * * @param data_ array */ - AxisAngle(const Type *data_) : + AxisAngle(const Type data_[3]) : Vector(data_) { } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 151b337884..ea2f8330d9 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -24,7 +24,7 @@ namespace matrix template class Vector; -template +template class Matrix { @@ -35,12 +35,12 @@ public: // Constructors Matrix() = default; - Matrix(const Type data_[][N]) + Matrix(const Type data_[M*N]) { memcpy(_data, data_, sizeof(_data)); } - Matrix(const Type *data_) + Matrix(const Type data_[M][N]) { memcpy(_data, data_, sizeof(_data)); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index cbf2c2b85a..180bbd57cc 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -62,7 +62,7 @@ public: * * @param data_ array */ - Quaternion(const Type *data_) : + Quaternion(const Type data_[4]) : Vector(data_) { } diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 2e348137b1..5421dbab20 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -26,7 +26,7 @@ class SquareMatrix : public Matrix public: SquareMatrix() = default; - SquareMatrix(const Type *data_) : + SquareMatrix(const Type data_[M][M]) : Matrix(data_) { } diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 7ea2d0caee..4c5bd915f8 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -29,7 +29,7 @@ public: { } - Vector(const Type *data_) : + Vector(const Type data_[M]) : MatrixM1(data_) { } diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index 7aeeb1d927..f6577e255e 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -30,7 +30,7 @@ public: { } - Vector2(const Type *data_) : + Vector2(const Type data_[2]) : Vector(data_) { } diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 989e247032..dea65de5f4 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -36,7 +36,7 @@ public: { } - Vector3(const Type *data_) : + Vector3(const Type data_[3]) : Vector(data_) { } From 0009328257625159f4b4b19d334f9c5fba13b13e Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Sun, 9 Sep 2018 12:48:33 +0200 Subject: [PATCH 262/388] least squares solver for MxN matrices using QR householder algorithm --- matrix/LeastSquaresSolver.hpp | 145 ++++++++++++++++++++++++++++++++++ matrix/math.hpp | 1 + test/CMakeLists.txt | 1 + test/least_squares.cpp | 69 ++++++++++++++++ test/test_data.py | 22 ++++++ 5 files changed, 238 insertions(+) create mode 100644 matrix/LeastSquaresSolver.hpp create mode 100644 test/least_squares.cpp diff --git a/matrix/LeastSquaresSolver.hpp b/matrix/LeastSquaresSolver.hpp new file mode 100644 index 0000000000..08d7df11de --- /dev/null +++ b/matrix/LeastSquaresSolver.hpp @@ -0,0 +1,145 @@ +/** + * @file LeastSquaresSolver.hpp + * + * Least Squares Solver using QR householder decomposition. + * It calculates x for Ax = b. + * A = Q*R + * where R is an upper triangular matrix. + * + * R*x = Q^T*b + * This is efficiently solved for x because of the upper triangular property of R. + * + * @author Bart Slinger + */ + +#pragma once + +#include "math.hpp" + +namespace matrix { + +template +class LeastSquaresSolver +{ +public: + + /** + * @brief Class calculates QR decomposition which can be used for linear + * least squares + * @param A Matrix of size MxN + * + * Initialize the class with a MxN matrix. The constructor starts the + * QR decomposition. This class does not check the rank of the matrix. + * The user needs to make sure that rank(A) = N and N >= M. + */ + LeastSquaresSolver(Matrix A) + { + if (M < N) { + return; + } + // Copy contentents of matrix A + memcpy(_data, A._data, sizeof(_data)); + + for (size_t j = 0; j < N; j++) { + float normx = 0.0f; + for (size_t i = j; i < M; i++) { + normx += _data[i][j] * _data[i][j]; + } + normx = sqrt(normx); + float s = _data[j][j] > 0 ? -1.0f : 1.0f; + float u1 = _data[j][j] - s*normx; + // prevent divide by zero + // also covers u1. normx is never negative + if (normx < 1e-8f) { + return; + } + float w[M] = {}; + w[0] = 1.0f; + for (size_t i = j+1; i < M; i++) { + w[i-j] = _data[i][j] / u1; + _data[i][j] = w[i-j]; + } + _data[j][j] = s*normx; + _tau[j] = -s*u1/normx; + + for (size_t k = j+1; k < N; k++) { + float tmp = 0.0f; + for (size_t i = j; i < M; i++) { + tmp += w[i-j] * _data[i][k]; + } + for (size_t i = j; i < M; i++) { + _data[i][k] -= _tau[j] * w[i-j] * tmp; + } + } + + } + } + + /** + * @brief qtb Calculate Q^T * b + * @param b + * @return Q^T*b + * + * This function calculates Q^T * b. This is useful for the solver + * because R*x = Q^T*b. + */ + Vector qtb(Vector b) { + Vector qtbv = b; + + for (size_t j = 0; j < N; j++) { + float w[M]; + w[0] = 1.0f; + // fill vector w + for (size_t i = j+1; i < M; i++) { + w[i-j] = _data[i][j]; + } + float tmp = 0.0f; + for (size_t i = j; i < M; i++) { + tmp += w[i-j] * qtbv(i); + } + + for (size_t i = j; i < M; i++) { + qtbv(i) -= _tau[j] * w[i-j] * tmp; + } + } + return qtbv; + } + + /** + * @brief Solve Ax=b for x + * @param b + * @return Vector x + * + * Find x in the equation Ax = b. + * A is provided in the initializer of the class. + */ + Vector solve(Vector b) { + Vector qtbv = qtb(b); + Vector x; + + for (size_t l = N; l > 0 ; l--) { + size_t i = l - 1; + x(i) = qtbv(i); + for (size_t r = i+1; r < N; r++) { + x(i) -= _data[i][r] * x(r); + } + // divide by zero, return vector of zeros + if (fabs(_data[i][i]) < 1e-8f) { + for (size_t z = 0; z < N; z++) { + x(z) = 0.0f; + } + } + x(i) = x(i) / _data[i][i]; + } + return x; + } + +private: + Type _data[M][N] {}; + Type _tau[N] {}; + +}; + +} // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/math.hpp b/matrix/math.hpp index 342ae5e612..30479f26e0 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -14,3 +14,4 @@ #include "Scalar.hpp" #include "Quaternion.hpp" #include "AxisAngle.hpp" +#include "LeastSquaresSolver.hpp" diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index f6c56af60e..43fa7e12dc 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -17,6 +17,7 @@ set(tests helper hatvee copyto + least_squares ) add_custom_target(test_build) diff --git a/test/least_squares.cpp b/test/least_squares.cpp new file mode 100644 index 0000000000..57c7064662 --- /dev/null +++ b/test/least_squares.cpp @@ -0,0 +1,69 @@ +#include "test_macros.hpp" +#include + +using namespace matrix; + +int test_4x3(void); +int test_4x4(void); + +int main() +{ + int ret; + + ret = test_4x4(); + if (ret != 0) return ret; + + ret = test_4x3(); + if (ret != 0) return ret; + + return 0; +} + +int test_4x3() { + // Start with an (m x n) A matrix + float data[12] = {20.f , -10.f , -13.f , + 17.f , 16.f , -18.f , + 0.7f, -0.8f, 0.9f, + -1.f , -1.1f, -1.2f}; + Matrix A(data); + + float b_data[4] = {2.0, 3.0, 4.0, 5.0}; + Vector b(b_data); + + float x_check_data[3] = {-0.69168233f, + -0.26227593f, + -1.03767522f}; + Vector x_check(x_check_data); + + LeastSquaresSolver qrd = LeastSquaresSolver(A); + + Vector x = qrd.solve(b); + TEST(isEqual(x, x_check)); + return 0; +} + +int test_4x4() { + // Start with an (m x n) A matrix + float data[16] = { 20.f , -10.f , -13.f , 21.f , + 17.f , 16.f , -18.f , -14.f , + 0.7f, -0.8f, 0.9f, -0.5f, + -1.f , -1.1f, -1.2f, -1.3f}; + Matrix A(data); + + float b_data[4] = {2.0, 3.0, 4.0, 5.0}; + Vector b(b_data); + + float x_check_data[4] = { 0.97893433f, + -2.80798701f, + -0.03175765f, + -2.19387649f}; + Vector x_check(x_check_data); + + LeastSquaresSolver qrd = LeastSquaresSolver(A); + + Vector x = qrd.solve(b); + TEST(isEqual(x, x_check)); + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/test/test_data.py b/test/test_data.py index 0ae4e958ae..94eed5e278 100644 --- a/test/test_data.py +++ b/test/test_data.py @@ -124,4 +124,26 @@ for i in range(1,3): A_pow = A_pow.dot(A) print(eA_approx) +print('\nqr decomposition 4x4') +A = array([[20.0, -10.0, -13.0, 21.0], [ 17.0, 16.0, -18.0, -14], [0.7, -0.8, 0.9, -0.5], [-1.0, -1.1, -1.2, -1.3]]) +b = array([[2.], [3.], [4.], [5.]]) +x = scipy.linalg.lstsq(A,b)[0] +print('A:') +pprint(A) +print('b:') +pprint(b) +print('x:') +pprint(scipy.linalg.lstsq(A,b)[0]) + +print('\nqr decomposition 4x3') +A = array([[20.0, -10.0, -13.0], [ 17.0, 16.0, -18.0], [0.7, -0.8, 0.9], [-1.0, -1.1, -1.2]]) +b = array([[2.], [3.], [4.], [5.]]) +x = scipy.linalg.lstsq(A,b)[0] +print('A:') +pprint(A) +print('b:') +pprint(b) +print('x:') +pprint(x) + # vim: set et ft=python fenc=utf-8 ff=unix sts=4 sw=4 ts=8 : From 98b8e2d43b3296c59ad7ad83d108f30d2e2af5dc Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Wed, 12 Sep 2018 20:27:08 +0200 Subject: [PATCH 263/388] formatting --- test/least_squares.cpp | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/test/least_squares.cpp b/test/least_squares.cpp index 57c7064662..46042f2d96 100644 --- a/test/least_squares.cpp +++ b/test/least_squares.cpp @@ -21,10 +21,11 @@ int main() int test_4x3() { // Start with an (m x n) A matrix - float data[12] = {20.f , -10.f , -13.f , - 17.f , 16.f , -18.f , - 0.7f, -0.8f, 0.9f, - -1.f , -1.1f, -1.2f}; + float data[12] = {20.f, -10.f, -13.f, + 17.f, 16.f, -18.f, + 0.7f, -0.8f, 0.9f, + -1.f, -1.1f, -1.2f + }; Matrix A(data); float b_data[4] = {2.0, 3.0, 4.0, 5.0}; @@ -32,7 +33,8 @@ int test_4x3() { float x_check_data[3] = {-0.69168233f, -0.26227593f, - -1.03767522f}; + -1.03767522f + }; Vector x_check(x_check_data); LeastSquaresSolver qrd = LeastSquaresSolver(A); @@ -44,19 +46,21 @@ int test_4x3() { int test_4x4() { // Start with an (m x n) A matrix - float data[16] = { 20.f , -10.f , -13.f , 21.f , - 17.f , 16.f , -18.f , -14.f , - 0.7f, -0.8f, 0.9f, -0.5f, - -1.f , -1.1f, -1.2f, -1.3f}; + float data[16] = { 20.f, -10.f, -13.f, 21.f, + 17.f, 16.f, -18.f, -14.f, + 0.7f, -0.8f, 0.9f, -0.5f, + -1.f, -1.1f, -1.2f, -1.3f + }; Matrix A(data); float b_data[4] = {2.0, 3.0, 4.0, 5.0}; Vector b(b_data); float x_check_data[4] = { 0.97893433f, - -2.80798701f, - -0.03175765f, - -2.19387649f}; + -2.80798701f, + -0.03175765f, + -2.19387649f + }; Vector x_check(x_check_data); LeastSquaresSolver qrd = LeastSquaresSolver(A); From 983a3f02123c4baa222c9c1b98d809e6954709b4 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Wed, 12 Sep 2018 20:42:45 +0200 Subject: [PATCH 264/388] use Matrix and Vector class for A and tau --- matrix/LeastSquaresSolver.hpp | 34 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/matrix/LeastSquaresSolver.hpp b/matrix/LeastSquaresSolver.hpp index 08d7df11de..880a7c9481 100644 --- a/matrix/LeastSquaresSolver.hpp +++ b/matrix/LeastSquaresSolver.hpp @@ -38,16 +38,16 @@ public: return; } // Copy contentents of matrix A - memcpy(_data, A._data, sizeof(_data)); + _A = A; for (size_t j = 0; j < N; j++) { float normx = 0.0f; for (size_t i = j; i < M; i++) { - normx += _data[i][j] * _data[i][j]; + normx += _A(i,j) * _A(i,j); } normx = sqrt(normx); - float s = _data[j][j] > 0 ? -1.0f : 1.0f; - float u1 = _data[j][j] - s*normx; + float s = _A(j,j) > 0 ? -1.0f : 1.0f; + float u1 = _A(j,j) - s*normx; // prevent divide by zero // also covers u1. normx is never negative if (normx < 1e-8f) { @@ -56,19 +56,19 @@ public: float w[M] = {}; w[0] = 1.0f; for (size_t i = j+1; i < M; i++) { - w[i-j] = _data[i][j] / u1; - _data[i][j] = w[i-j]; + w[i-j] = _A(i,j) / u1; + _A(i,j) = w[i-j]; } - _data[j][j] = s*normx; - _tau[j] = -s*u1/normx; + _A(j,j) = s*normx; + _tau(j) = -s*u1/normx; for (size_t k = j+1; k < N; k++) { float tmp = 0.0f; for (size_t i = j; i < M; i++) { - tmp += w[i-j] * _data[i][k]; + tmp += w[i-j] * _A(i,k); } for (size_t i = j; i < M; i++) { - _data[i][k] -= _tau[j] * w[i-j] * tmp; + _A(i,k) -= _tau(j) * w[i-j] * tmp; } } @@ -91,7 +91,7 @@ public: w[0] = 1.0f; // fill vector w for (size_t i = j+1; i < M; i++) { - w[i-j] = _data[i][j]; + w[i-j] = _A(i,j); } float tmp = 0.0f; for (size_t i = j; i < M; i++) { @@ -99,7 +99,7 @@ public: } for (size_t i = j; i < M; i++) { - qtbv(i) -= _tau[j] * w[i-j] * tmp; + qtbv(i) -= _tau(j) * w[i-j] * tmp; } } return qtbv; @@ -121,22 +121,22 @@ public: size_t i = l - 1; x(i) = qtbv(i); for (size_t r = i+1; r < N; r++) { - x(i) -= _data[i][r] * x(r); + x(i) -= _A(i,r) * x(r); } // divide by zero, return vector of zeros - if (fabs(_data[i][i]) < 1e-8f) { + if (fabs(_A(i,i)) < 1e-8f) { for (size_t z = 0; z < N; z++) { x(z) = 0.0f; } } - x(i) = x(i) / _data[i][i]; + x(i) = x(i) / _A(i,i); } return x; } private: - Type _data[M][N] {}; - Type _tau[N] {}; + Matrix _A; + Vector _tau; }; From 3f2d3cf58ddcb3c0f349307a54d80b843ef316b9 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Wed, 12 Sep 2018 20:49:48 +0200 Subject: [PATCH 265/388] fix a div/0 condition --- matrix/LeastSquaresSolver.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/matrix/LeastSquaresSolver.hpp b/matrix/LeastSquaresSolver.hpp index 880a7c9481..266e2ebe40 100644 --- a/matrix/LeastSquaresSolver.hpp +++ b/matrix/LeastSquaresSolver.hpp @@ -51,7 +51,7 @@ public: // prevent divide by zero // also covers u1. normx is never negative if (normx < 1e-8f) { - return; + break; } float w[M] = {}; w[0] = 1.0f; @@ -128,6 +128,7 @@ public: for (size_t z = 0; z < N; z++) { x(z) = 0.0f; } + break; } x(i) = x(i) / _A(i,i); } From 74957943865b2e8db8c48885c55fa010ba2af1e9 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Wed, 12 Sep 2018 21:06:17 +0200 Subject: [PATCH 266/388] test zero divisions --- test/least_squares.cpp | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/test/least_squares.cpp b/test/least_squares.cpp index 46042f2d96..14868218f7 100644 --- a/test/least_squares.cpp +++ b/test/least_squares.cpp @@ -5,6 +5,7 @@ using namespace matrix; int test_4x3(void); int test_4x4(void); +int test_div_zero(void); int main() { @@ -16,6 +17,9 @@ int main() ret = test_4x3(); if (ret != 0) return ret; + ret = test_div_zero(); + if (ret != 0) return ret; + return 0; } @@ -70,4 +74,22 @@ int test_4x4() { return 0; } +int test_div_zero() { + float data[4] = {0.0f, 0.0f, 0.0f, 0.0f}; + Matrix A(data); + + float b_data[2] = {1.0, 1.0}; + Vector b(b_data); + + // Implement such that x returns zeros if it reaches div by zero + float x_check_data[2] = {0.0f, 0.0f}; + Vector x_check(x_check_data); + + LeastSquaresSolver qrd = LeastSquaresSolver(A); + + Vector x = qrd.solve(b); + TEST(isEqual(x, x_check)); + return 0; +} + /* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From 480c5f1f8ef0811fc88e782d68561e7566b7ad87 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Thu, 13 Sep 2018 10:53:13 +0200 Subject: [PATCH 267/388] static assert M>=N. floats to Type, arguments as const reference --- matrix/LeastSquaresSolver.hpp | 37 +++++++++++++++++------------------ test/least_squares.cpp | 29 +++++++++++++++++++++++++++ 2 files changed, 47 insertions(+), 19 deletions(-) diff --git a/matrix/LeastSquaresSolver.hpp b/matrix/LeastSquaresSolver.hpp index 266e2ebe40..f594e16e9d 100644 --- a/matrix/LeastSquaresSolver.hpp +++ b/matrix/LeastSquaresSolver.hpp @@ -30,31 +30,30 @@ public: * * Initialize the class with a MxN matrix. The constructor starts the * QR decomposition. This class does not check the rank of the matrix. - * The user needs to make sure that rank(A) = N and N >= M. + * The user needs to make sure that rank(A) = N and M >= N. */ - LeastSquaresSolver(Matrix A) + LeastSquaresSolver(const Matrix &A) { - if (M < N) { - return; - } + static_assert(M >= N, "Matrix dimension should be M >= N"); + // Copy contentents of matrix A _A = A; for (size_t j = 0; j < N; j++) { - float normx = 0.0f; + Type normx = 0.; for (size_t i = j; i < M; i++) { normx += _A(i,j) * _A(i,j); } normx = sqrt(normx); - float s = _A(j,j) > 0 ? -1.0f : 1.0f; - float u1 = _A(j,j) - s*normx; + Type s = _A(j,j) > 0 ? -1. : 1.; + Type u1 = _A(j,j) - s*normx; // prevent divide by zero // also covers u1. normx is never negative - if (normx < 1e-8f) { + if (normx < 1e-8) { break; } - float w[M] = {}; - w[0] = 1.0f; + Type w[M] = {}; + w[0] = 1.; for (size_t i = j+1; i < M; i++) { w[i-j] = _A(i,j) / u1; _A(i,j) = w[i-j]; @@ -63,7 +62,7 @@ public: _tau(j) = -s*u1/normx; for (size_t k = j+1; k < N; k++) { - float tmp = 0.0f; + Type tmp = 0.; for (size_t i = j; i < M; i++) { tmp += w[i-j] * _A(i,k); } @@ -83,17 +82,17 @@ public: * This function calculates Q^T * b. This is useful for the solver * because R*x = Q^T*b. */ - Vector qtb(Vector b) { + Vector qtb(const Vector &b) { Vector qtbv = b; for (size_t j = 0; j < N; j++) { - float w[M]; - w[0] = 1.0f; + Type w[M]; + w[0] = 1.; // fill vector w for (size_t i = j+1; i < M; i++) { w[i-j] = _A(i,j); } - float tmp = 0.0f; + Type tmp = 0.; for (size_t i = j; i < M; i++) { tmp += w[i-j] * qtbv(i); } @@ -113,7 +112,7 @@ public: * Find x in the equation Ax = b. * A is provided in the initializer of the class. */ - Vector solve(Vector b) { + Vector solve(const Vector &b) { Vector qtbv = qtb(b); Vector x; @@ -124,9 +123,9 @@ public: x(i) -= _A(i,r) * x(r); } // divide by zero, return vector of zeros - if (fabs(_A(i,i)) < 1e-8f) { + if (fabs(_A(i,i)) < 1e-8) { for (size_t z = 0; z < N; z++) { - x(z) = 0.0f; + x(z) = 0.; } break; } diff --git a/test/least_squares.cpp b/test/least_squares.cpp index 14868218f7..f9cae89cd6 100644 --- a/test/least_squares.cpp +++ b/test/least_squares.cpp @@ -5,6 +5,7 @@ using namespace matrix; int test_4x3(void); int test_4x4(void); +int test_4x4_type_double(void); int test_div_zero(void); int main() @@ -17,6 +18,8 @@ int main() ret = test_4x3(); if (ret != 0) return ret; + ret = test_4x4_type_double(); + ret = test_div_zero(); if (ret != 0) return ret; @@ -74,6 +77,32 @@ int test_4x4() { return 0; } +int test_4x4_type_double() { + // Start with an (m x n) A matrix + double data[16] = { 20., -10., -13., 21., + 17., 16., -18., -14., + 0.7, -0.8, 0.9, -0.5, + -1., -1.1, -1.2, -1.3 + }; + Matrix A(data); + + double b_data[4] = {2.0, 3.0, 4.0, 5.0}; + Vector b(b_data); + + double x_check_data[4] = { 0.97893433, + -2.80798701, + -0.03175765, + -2.19387649 + }; + Vector x_check(x_check_data); + + LeastSquaresSolver qrd = LeastSquaresSolver(A); + + Vector x = qrd.solve(b); + TEST(isEqual(x, x_check)); + return 0; +} + int test_div_zero() { float data[4] = {0.0f, 0.0f, 0.0f, 0.0f}; Matrix A(data); From 707e28801928f98b3f9ffb5e09463da0cbad7d15 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Thu, 13 Sep 2018 14:22:47 +0200 Subject: [PATCH 268/388] explicit casting --- matrix/LeastSquaresSolver.hpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/matrix/LeastSquaresSolver.hpp b/matrix/LeastSquaresSolver.hpp index f594e16e9d..2d812d7fda 100644 --- a/matrix/LeastSquaresSolver.hpp +++ b/matrix/LeastSquaresSolver.hpp @@ -40,20 +40,20 @@ public: _A = A; for (size_t j = 0; j < N; j++) { - Type normx = 0.; + Type normx = Type(0); for (size_t i = j; i < M; i++) { normx += _A(i,j) * _A(i,j); } normx = sqrt(normx); - Type s = _A(j,j) > 0 ? -1. : 1.; + Type s = _A(j,j) > 0 ? Type(-1) : Type(1); Type u1 = _A(j,j) - s*normx; // prevent divide by zero // also covers u1. normx is never negative - if (normx < 1e-8) { + if (normx < Type(1e-8)) { break; } Type w[M] = {}; - w[0] = 1.; + w[0] = Type(1); for (size_t i = j+1; i < M; i++) { w[i-j] = _A(i,j) / u1; _A(i,j) = w[i-j]; @@ -62,7 +62,7 @@ public: _tau(j) = -s*u1/normx; for (size_t k = j+1; k < N; k++) { - Type tmp = 0.; + Type tmp = Type(0); for (size_t i = j; i < M; i++) { tmp += w[i-j] * _A(i,k); } @@ -87,12 +87,12 @@ public: for (size_t j = 0; j < N; j++) { Type w[M]; - w[0] = 1.; + w[0] = Type(1); // fill vector w for (size_t i = j+1; i < M; i++) { w[i-j] = _A(i,j); } - Type tmp = 0.; + Type tmp = Type(0); for (size_t i = j; i < M; i++) { tmp += w[i-j] * qtbv(i); } @@ -123,9 +123,9 @@ public: x(i) -= _A(i,r) * x(r); } // divide by zero, return vector of zeros - if (fabs(_A(i,i)) < 1e-8) { + if (fabs(_A(i,i)) < Type(1e-8)) { for (size_t z = 0; z < N; z++) { - x(z) = 0.; + x(z) = Type(0); } break; } From 30d5a794326f41286b387581f7c21f4bdb8fa696 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Fri, 14 Sep 2018 13:15:52 +0200 Subject: [PATCH 269/388] testing float/double with Type template --- test/least_squares.cpp | 72 ++++++++++++++---------------------------- 1 file changed, 24 insertions(+), 48 deletions(-) diff --git a/test/least_squares.cpp b/test/least_squares.cpp index f9cae89cd6..573715caa2 100644 --- a/test/least_squares.cpp +++ b/test/least_squares.cpp @@ -4,7 +4,7 @@ using namespace matrix; int test_4x3(void); -int test_4x4(void); +template int test_4x4(void); int test_4x4_type_double(void); int test_div_zero(void); @@ -12,14 +12,15 @@ int main() { int ret; - ret = test_4x4(); + ret = test_4x4(); + if (ret != 0) return ret; + + ret = test_4x4(); if (ret != 0) return ret; ret = test_4x3(); if (ret != 0) return ret; - ret = test_4x4_type_double(); - ret = test_div_zero(); if (ret != 0) return ret; @@ -35,7 +36,7 @@ int test_4x3() { }; Matrix A(data); - float b_data[4] = {2.0, 3.0, 4.0, 5.0}; + float b_data[4] = {2.0f, 3.0f, 4.0f, 5.0f}; Vector b(b_data); float x_check_data[3] = {-0.69168233f, @@ -51,54 +52,29 @@ int test_4x3() { return 0; } +template int test_4x4() { // Start with an (m x n) A matrix - float data[16] = { 20.f, -10.f, -13.f, 21.f, - 17.f, 16.f, -18.f, -14.f, - 0.7f, -0.8f, 0.9f, -0.5f, - -1.f, -1.1f, -1.2f, -1.3f - }; - Matrix A(data); + const Type data[16] = { 20.f, -10.f, -13.f, 21.f, + 17.f, 16.f, -18.f, -14.f, + 0.7f, -0.8f, 0.9f, -0.5f, + -1.f, -1.1f, -1.2f, -1.3f + }; + Matrix A(data); - float b_data[4] = {2.0, 3.0, 4.0, 5.0}; - Vector b(b_data); + Type b_data[4] = {2.0f, 3.0f, 4.0f, 5.0f}; + Vector b(b_data); - float x_check_data[4] = { 0.97893433f, - -2.80798701f, - -0.03175765f, - -2.19387649f - }; - Vector x_check(x_check_data); + Type x_check_data[4] = { 0.97893433f, + -2.80798701f, + -0.03175765f, + -2.19387649f + }; + Vector x_check(x_check_data); - LeastSquaresSolver qrd = LeastSquaresSolver(A); + LeastSquaresSolver qrd = LeastSquaresSolver(A); - Vector x = qrd.solve(b); - TEST(isEqual(x, x_check)); - return 0; -} - -int test_4x4_type_double() { - // Start with an (m x n) A matrix - double data[16] = { 20., -10., -13., 21., - 17., 16., -18., -14., - 0.7, -0.8, 0.9, -0.5, - -1., -1.1, -1.2, -1.3 - }; - Matrix A(data); - - double b_data[4] = {2.0, 3.0, 4.0, 5.0}; - Vector b(b_data); - - double x_check_data[4] = { 0.97893433, - -2.80798701, - -0.03175765, - -2.19387649 - }; - Vector x_check(x_check_data); - - LeastSquaresSolver qrd = LeastSquaresSolver(A); - - Vector x = qrd.solve(b); + Vector x = qrd.solve(b); TEST(isEqual(x, x_check)); return 0; } @@ -107,7 +83,7 @@ int test_div_zero() { float data[4] = {0.0f, 0.0f, 0.0f, 0.0f}; Matrix A(data); - float b_data[2] = {1.0, 1.0}; + float b_data[2] = {1.0f, 1.0f}; Vector b(b_data); // Implement such that x returns zeros if it reaches div by zero From 807472bfd79e31f36bd5e57d8163d0f67c7be71b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 1 Oct 2018 09:16:02 +0200 Subject: [PATCH 270/388] README: document how to run tests --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/README.md b/README.md index 5cc19294d2..72f553665b 100644 --- a/README.md +++ b/README.md @@ -31,6 +31,15 @@ A simple and efficient template based matrix library. * matrix/integrate.hpp : Provides integration routines. * integrate_rk4 (Runge-Kutta 4th order) +## Testing +The tests can be executed as following: +``` +mkdir build +cd build +cmake -DTESTING=ON .. +make check +``` + ## Example See the test directory for detailed examples. Some simple examples are included below: From 0d3bff5e006cfaa358b51e3a6d11984e3782a90e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 1 Oct 2018 09:16:45 +0200 Subject: [PATCH 271/388] Vector2: add explicit constructor for Vector3 Initialize from the first 2 elements. --- matrix/Vector2.hpp | 8 ++++++++ test/vector2.cpp | 5 +++++ 2 files changed, 13 insertions(+) diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index f6577e255e..dc42c5d5e9 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -22,6 +22,7 @@ class Vector2 : public Vector public: typedef Matrix Matrix21; + typedef Vector Vector3; Vector2() = default; @@ -42,6 +43,13 @@ public: v(1) = y; } + explicit Vector2(const Vector3 & other) + { + Vector2 &v(*this); + v(0) = other(0); + v(1) = other(1); + } + Type cross(const Matrix21 & b) const { const Vector2 &a(*this); return a(0)*b(1, 0) - a(1)*b(0, 0); diff --git a/test/vector2.cpp b/test/vector2.cpp index a8838d9b4e..f46f59fe29 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -29,6 +29,11 @@ int main() TEST(fabs(f(0) - 4) < 1e-5); TEST(fabs(f(1) - 5) < 1e-5); + Vector3f g(1.23f, 423.4f, 3221.f); + Vector2f h(g); + TEST(fabs(h(0) - 1.23f) < 1e-5); + TEST(fabs(h(1) - 423.4f) < 1e-5); + return 0; } From 9c0acfba36a928b7b002eea3a9dca54a5a0c1250 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 20 Nov 2018 17:33:30 +0100 Subject: [PATCH 272/388] Matrix: remove unsafe copyToRaw method It used a pointer and could therefore not do correct type checking for index out of bound or struct memebr order. Has to be considered unsafe and bad practise. We should switch to arrays as representation for vectors inside the messages instead of foo_x, foo_y, foo_z fields. --- matrix/Matrix.hpp | 5 ----- test/copyto.cpp | 7 ------- 2 files changed, 12 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index ea2f8330d9..f097301611 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -87,11 +87,6 @@ public: memcpy(dst, _data, sizeof(dst)); } - void copyToRaw(Type *dst) const - { - memcpy(dst, _data, sizeof(_data)); - } - void copyToColumnMajor(Type (&dst)[M*N]) const { const Matrix &self = *this; diff --git a/test/copyto.cpp b/test/copyto.cpp index fe35cff672..0a9ccb20f7 100644 --- a/test/copyto.cpp +++ b/test/copyto.cpp @@ -38,13 +38,6 @@ int main() TEST(fabs(array_A[i] - array_row[i]) < eps); } - // Matrix copyTo with a pointer - A.copyToRaw(static_cast (array_A)); - float array_row_p[6] = {1, 2, 3, 4, 5, 6}; - for (size_t i = 0; i < 6; i++) { - TEST(fabs(array_A[i] - array_row_p[i]) < eps); - } - // Matrix copyToColumnMajor A.copyToColumnMajor(array_A); float array_column[6] = {1, 4, 2, 5, 3, 6}; From a4f39c0f890ff0dbe68a84179dcf7d238e00eb91 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Sun, 16 Dec 2018 17:59:44 +0000 Subject: [PATCH 273/388] quaternion: reuse existing dot product --- matrix/Quaternion.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 180bbd57cc..18fc2d68c5 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -194,7 +194,7 @@ public: { Quaternion &q = *this; Vector3 cr = src.cross(dst); - float dt = src.dot(dst); + const float dt = src.dot(dst); /* If the two vectors are parallel, cross product is zero * If they point opposite, the dot product is negative */ if (cr.norm() < eps && dt < 0) { @@ -216,7 +216,7 @@ public: cr = src.cross(cr); } else { /* Half-Way Quaternion Solution */ - q(0) = src.dot(dst) + sqrt(src.norm_squared() * dst.norm_squared()); + q(0) = dt + sqrt(src.norm_squared() * dst.norm_squared()); } q(1) = cr(0); q(2) = cr(1); From 18fba8221cc1840964c43f04d8c2aa21857e1b9b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Sun, 16 Dec 2018 18:00:02 +0000 Subject: [PATCH 274/388] quaternion: improve comments --- matrix/Quaternion.hpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 18fc2d68c5..29e711dc46 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -195,9 +195,10 @@ public: Quaternion &q = *this; Vector3 cr = src.cross(dst); const float dt = src.dot(dst); - /* If the two vectors are parallel, cross product is zero - * If they point opposite, the dot product is negative */ if (cr.norm() < eps && dt < 0) { + // handle corner cases with 180 degree rotations + // if the two vectors are parallel, cross product is zero + // if they point opposite, the dot product is negative cr = src.abs(); if (cr(0) < cr(1)) { if (cr(0) < cr(2)) { @@ -215,7 +216,7 @@ public: q(0) = Type(0); cr = src.cross(cr); } else { - /* Half-Way Quaternion Solution */ + // normal case, do half-way quaternion solution q(0) = dt + sqrt(src.norm_squared() * dst.norm_squared()); } q(1) = cr(0); From 6b0777d815cd64902eb0575d56ec52f53aebb4a0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 21 Jan 2019 09:12:36 -0500 Subject: [PATCH 275/388] stdlib_imports cinttypes currently unavailable in NuttX toolchain (#79) --- matrix/stdlib_imports.hpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index 1d23c5c93e..1f6b88b9c9 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -11,7 +11,7 @@ #include #include -#include +#include namespace matrix { @@ -78,8 +78,6 @@ using std::modf; # if (__cplusplus >= 201103L) -using std::imaxabs; -using std::imaxdiv; using std::remainder; using std::remquo; using std::fma; From 96cb9ab14638b5dba974b06eaad2d7b2e906465a Mon Sep 17 00:00:00 2001 From: TSC21 Date: Sun, 17 Feb 2019 16:54:25 +0000 Subject: [PATCH 276/388] add NaN value set for Matrix; add return of URT of a matrix --- matrix/Matrix.hpp | 12 ++++++++++++ matrix/SquareMatrix.hpp | 18 +++++++++++++++++- 2 files changed, 29 insertions(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index f097301611..7cbc5ea753 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -412,6 +412,11 @@ public: setAll(1); } + inline void setNaN() + { + setAll(NAN); + } + void setIdentity() { setZero(); @@ -512,6 +517,13 @@ Matrix ones() { return m; } +template +Matrix nans() { + Matrix m; + m.setNaN(); + return m; +} + template Matrix operator*(Type scalar, const Matrix &other) { diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 5421dbab20..21cf40cf96 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -48,7 +48,6 @@ public: } } - // inverse alias inline bool I(SquareMatrix &i) const { @@ -67,6 +66,23 @@ public: return res; } + // get matrix upper right triangle + Vector urt() const + { + Vector res; + const SquareMatrix &self = *this; + + unsigned idx = 0; + for (size_t x = 0; x < M; x++) { + for (size_t y = x; y < M; y++) { + res(idx) = self(x, y); + ++idx; + } + } + + return res; + } + Type trace() const { Type res = 0; From 210c76c04b8a10ea273318316467d28b2128885c Mon Sep 17 00:00:00 2001 From: TSC21 Date: Sun, 17 Feb 2019 18:04:41 +0000 Subject: [PATCH 277/388] add test to setNaN() --- test/matrixAssignment.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 5ad7de6779..60b7c55d4d 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -25,6 +25,12 @@ int main() TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); } + Matrix3f m_nan; + m_nan.setNaN(); + for(int i=0; i<9; i++) { + TEST(isnan(m_nan.data()[i])); + } + float data2d[3][3] = { {1, 2, 3}, {4, 5, 6}, From 707967d117ab15bb8deac5ef3556df9795ce2884 Mon Sep 17 00:00:00 2001 From: TSC21 Date: Sun, 17 Feb 2019 18:18:26 +0000 Subject: [PATCH 278/388] add test to .urt() --- test/CMakeLists.txt | 1 + test/urt.cpp | 24 ++++++++++++++++++++++++ 2 files changed, 25 insertions(+) create mode 100644 test/urt.cpp diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 43fa7e12dc..2453f70899 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -18,6 +18,7 @@ set(tests hatvee copyto least_squares + urt ) add_custom_target(test_build) diff --git a/test/urt.cpp b/test/urt.cpp new file mode 100644 index 0000000000..6699caa661 --- /dev/null +++ b/test/urt.cpp @@ -0,0 +1,24 @@ +#include "test_macros.hpp" +#include "float.h" +#include + +using namespace matrix; + +int main() +{ + float data[9] = {1, 2, 3, + 4, 5, 6, + 7, 8, 10 + }; + float urt[6] = {1, 2, 3, 5, 6, 10}; + + SquareMatrix A(data); + + for(int i=0; i Date: Sun, 17 Feb 2019 18:25:54 +0000 Subject: [PATCH 279/388] Travis CI: update MacOS version to use --- .travis.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index ad0668aa60..98e0bbdd62 100644 --- a/.travis.yml +++ b/.travis.yml @@ -17,7 +17,7 @@ matrix: compiler: clang env: CMAKE_BUILD_TYPE=Release CC=clang CXX=clang++ FORMAT=OFF - os: osx - osx_image: xcode8 + osx_image: xcode10.1 env: CMAKE_BUILD_TYPE=Release FORMAT=OFF addons: @@ -39,4 +39,3 @@ script: after_success: - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then cpp-coveralls -i matrix; fi - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then bash <(curl -s https://codecov.io/bash) -F matrix_tests; fi - From 7ab2b24e6557cea839d6716964100bd6c9937e2e Mon Sep 17 00:00:00 2001 From: TSC21 Date: Sun, 17 Feb 2019 18:29:43 +0000 Subject: [PATCH 280/388] tests: urt: refactor --- test/urt.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/test/urt.cpp b/test/urt.cpp index 6699caa661..41a772e72d 100644 --- a/test/urt.cpp +++ b/test/urt.cpp @@ -1,5 +1,4 @@ #include "test_macros.hpp" -#include "float.h" #include using namespace matrix; @@ -14,8 +13,8 @@ int main() SquareMatrix A(data); - for(int i=0; i Date: Sun, 17 Feb 2019 18:51:13 +0000 Subject: [PATCH 281/388] tests: use __FLT_EPSILON__ in comparisons --- matrix/SquareMatrix.hpp | 4 ++-- test/helper.cpp | 10 +++++----- test/inverse.cpp | 4 ++-- test/matrixAssignment.cpp | 14 +++++++------- test/setIdentity.cpp | 8 ++++---- test/squareMatrix.cpp | 4 ++-- test/test_data.py | 10 +++++----- test/test_macros.hpp | 1 + test/urt.cpp | 2 +- test/vector2.cpp | 22 +++++++++++----------- 10 files changed, 40 insertions(+), 39 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 21cf40cf96..dbcb307b16 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -149,7 +149,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) for (size_t n = 0; n < M; n++) { // if diagonal is zero, swap with row below - if (fabs(static_cast(U(n, n))) < 1e-8f) { + if (fabs(static_cast(U(n, n))) < __FLT_EPSILON__) { //printf("trying pivot for row %d\n",n); for (size_t i = n + 1; i < M; i++) { @@ -174,7 +174,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) #endif // failsafe, return zero matrix - if (fabs(static_cast(U(n, n))) < 1e-8f) { + if (fabs(static_cast(U(n, n))) < __FLT_EPSILON__) { return false; } diff --git a/test/helper.cpp b/test/helper.cpp index fb1e779a72..dda3c90df6 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -5,15 +5,15 @@ using namespace matrix; int main() { - TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < 1e-5); - TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); - TEST(fabs(wrap_pi(3.0) - (3.0)) < 1e-3); + TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < __FLT_EPSILON__); + TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < __FLT_EPSILON__); + TEST(fabs(wrap_pi(3.0) - (3.0)) < __FLT_EPSILON__); TEST(!is_finite(wrap_pi(1000.0f))); TEST(!is_finite(wrap_pi(-1000.0f))); wrap_pi(NAN); - TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < 1e-5); - TEST(fabs(wrap_2pi(3.0) - (3.0)) < 1e-3); + TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < __FLT_EPSILON__); + TEST(fabs(wrap_2pi(3.0) - (3.0)) < __FLT_EPSILON__); TEST(!is_finite(wrap_2pi(1000.0f))); TEST(!is_finite(wrap_2pi(-1000.0f))); wrap_2pi(NAN); diff --git a/test/inverse.cpp b/test/inverse.cpp index 20d69c4282..d5f75296c4 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -20,7 +20,7 @@ int main() SquareMatrix A(data); SquareMatrix A_I = inv(A); SquareMatrix A_I_check(data_check); - TEST((A_I - A_I_check).abs().max() < 1e-5); + TEST((A_I - A_I_check).abs().max() < 1e-6f); // stess test SquareMatrix A_large; @@ -63,7 +63,7 @@ int main() SquareMatrix A2(data2); SquareMatrix A2_I = inv(A2); SquareMatrix A2_I_check(data2_check); - TEST((A2_I - A2_I_check).abs().max() < 1e-3); + TEST((A2_I - A2_I_check).abs().max() < 1e-3f); float data3[9] = { 0, 1, 2, 3, 4, 5, diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 60b7c55d4d..81e34120dc 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -22,7 +22,7 @@ int main() Matrix3f m2(data); for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabs(data[i] - m2.data()[i]) < __FLT_EPSILON__); } Matrix3f m_nan; @@ -38,7 +38,7 @@ int main() }; m2 = Matrix3f(data2d); for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < 1e-6f); + TEST(fabs(data[i] - m2.data()[i]) < __FLT_EPSILON__); } float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; @@ -100,16 +100,16 @@ int main() m4.swapCols(2, 2); TEST(isEqual(m4, Matrix3f(data))); - TEST(fabs(m4.min() - 1) < 1e-5); - TEST(fabs((-m4).min() + 9) < 1e-5); + TEST(fabs(m4.min() - 1) < __FLT_EPSILON__); + TEST(fabs((-m4).min() + 9) < __FLT_EPSILON__); Scalar s = 1; const Vector & s_vect = s; - TEST(fabs(s - 1) < 1e-5); - TEST(fabs(s_vect(0) - 1.0f) < 1e-5); + TEST(fabs(s - 1) < __FLT_EPSILON__); + TEST(fabs(s_vect(0) - 1.0f) < __FLT_EPSILON__); Matrix m5 = s; - TEST(fabs(m5(0,0) - s) < 1e-5); + TEST(fabs(m5(0,0) - s) < __FLT_EPSILON__); Matrix m6; m6.setRow(0, Vector2f(1, 2)); diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index 9e1009548b..fd96791a39 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -11,10 +11,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST(fabs(A(i, j) - 1) < 1e-7); + TEST(fabs(A(i, j) - 1) < __FLT_EPSILON__); } else { - TEST(fabs(A(i, j) - 0) < 1e-7); + TEST(fabs(A(i, j) - 0) < __FLT_EPSILON__); } } } @@ -25,10 +25,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST(fabs(B(i, j) - 1) < 1e-7); + TEST(fabs(B(i, j) - 1) < __FLT_EPSILON__); } else { - TEST(fabs(B(i, j) - 0) < 1e-7); + TEST(fabs(B(i, j) - 0) < __FLT_EPSILON__); } } } diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 2c668e4abf..1fc4bed1f7 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -14,7 +14,7 @@ int main() Vector3 diag_check(1, 5, 10); TEST(isEqual(A.diag(), diag_check)); - TEST(A.trace() - 16 < 1e-3); + TEST(A.trace() - 16 < __FLT_EPSILON__); float data_check[9] = { 1.01158503f, 0.02190432f, 0.03238144f, @@ -25,7 +25,7 @@ int main() float dt = 0.01f; SquareMatrix eA = expm(SquareMatrix(A*dt), 5); SquareMatrix eA_check(data_check); - TEST((eA - eA_check).abs().max() < 1e-3); + TEST((eA - eA_check).abs().max() < 1e-3f); return 0; } diff --git a/test/test_data.py b/test/test_data.py index 94eed5e278..85fa79c5e8 100644 --- a/test/test_data.py +++ b/test/test_data.py @@ -75,9 +75,9 @@ psi = 0.3 print('euler', phi, theta, psi) q = euler_to_quat(phi, theta, psi) -assert(abs(norm(q) - 1) < 1e-10) -assert(abs(norm(q) - 1) < 1e-10) -assert(norm(array(quat_to_euler(q)) - array([phi, theta, psi])) < 1e-10) +assert(abs(norm(q) - 1) < __FLT_EPSILON__) +assert(abs(norm(q) - 1) < __FLT_EPSILON__) +assert(norm(array(quat_to_euler(q)) - array([phi, theta, psi])) < __FLT_EPSILON__) print('\nq:') pprint(q) @@ -85,8 +85,8 @@ dcm = euler_to_dcm(phi, theta, psi) assert(norm(dcm[:,0]) == 1) assert(norm(dcm[:,1]) == 1) assert(norm(dcm[:,2]) == 1) -assert(abs(dcm[:,0].dot(dcm[:,1])) < 1e-10) -assert(abs(dcm[:,0].dot(dcm[:,2])) < 1e-10) +assert(abs(dcm[:,0].dot(dcm[:,1])) < __FLT_EPSILON__) +assert(abs(dcm[:,0].dot(dcm[:,2])) < __FLT_EPSILON__) print('\ndcm:') pprint(dcm) diff --git a/test/test_macros.hpp b/test/test_macros.hpp index d6ca2d2fb1..f21c5a66a8 100644 --- a/test/test_macros.hpp +++ b/test/test_macros.hpp @@ -10,6 +10,7 @@ #include #include // cmath has to be introduced BEFORE we poison the C library identifiers +#include "float.h" #define TEST(X) if(!(X)) { fprintf(stderr, "test failed on %s:%d\n", __FILE__, __LINE__); return -1;} diff --git a/test/urt.cpp b/test/urt.cpp index 41a772e72d..7b54d0583f 100644 --- a/test/urt.cpp +++ b/test/urt.cpp @@ -14,7 +14,7 @@ int main() SquareMatrix A(data); for(int i=0; i<6; i++) { - TEST(fabs(urt[i] - A.urt().data()[i]) < 1e-6f); + TEST(fabs(urt[i] - A.urt().data()[i]) < __FLT_EPSILON__); } return 0; diff --git a/test/vector2.cpp b/test/vector2.cpp index f46f59fe29..d5bf782241 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -10,29 +10,29 @@ int main() { Vector2f a(1, 0); Vector2f b(0, 1); - TEST(fabs(a % b - 1.0f) < 1e-5); + TEST(fabs(a % b - 1.0f) < __FLT_EPSILON__); Vector2f c; - TEST(fabs(c(0) - 0) < 1e-5); - TEST(fabs(c(1) - 0) < 1e-5); + TEST(fabs(c(0) - 0) < __FLT_EPSILON__); + TEST(fabs(c(1) - 0) < __FLT_EPSILON__); Matrix d(a); - TEST(fabs(d(0,0) - 1) < 1e-5); - TEST(fabs(d(1,0) - 0) < 1e-5); + TEST(fabs(d(0,0) - 1) < __FLT_EPSILON__); + TEST(fabs(d(1,0) - 0) < __FLT_EPSILON__); Vector2f e(d); - TEST(fabs(e(0) - 1) < 1e-5); - TEST(fabs(e(1) - 0) < 1e-5); + TEST(fabs(e(0) - 1) < __FLT_EPSILON__); + TEST(fabs(e(1) - 0) < __FLT_EPSILON__); float data[] = {4,5}; Vector2f f(data); - TEST(fabs(f(0) - 4) < 1e-5); - TEST(fabs(f(1) - 5) < 1e-5); + TEST(fabs(f(0) - 4) < __FLT_EPSILON__); + TEST(fabs(f(1) - 5) < __FLT_EPSILON__); Vector3f g(1.23f, 423.4f, 3221.f); Vector2f h(g); - TEST(fabs(h(0) - 1.23f) < 1e-5); - TEST(fabs(h(1) - 423.4f) < 1e-5); + TEST(fabs(h(0) - 1.23f) < __FLT_EPSILON__); + TEST(fabs(h(1) - 423.4f) < __FLT_EPSILON__); return 0; } From ec436d5aeec888128b6918b18e44dd697e79d1e5 Mon Sep 17 00:00:00 2001 From: TSC21 Date: Tue, 19 Feb 2019 14:44:46 +0000 Subject: [PATCH 282/388] define FLT_EPSILON; be descriptive about upper_right_triangle() method --- matrix/SquareMatrix.hpp | 8 ++++---- matrix/stdlib_imports.hpp | 4 ++++ test/CMakeLists.txt | 2 +- test/helper.cpp | 10 +++++----- test/matrixAssignment.cpp | 14 +++++++------- test/setIdentity.cpp | 8 ++++---- test/squareMatrix.cpp | 2 +- test/test_data.py | 10 +++++----- test/test_macros.hpp | 1 - test/{urt.cpp => upperRightTriangle.cpp} | 2 +- test/vector2.cpp | 22 +++++++++++----------- 11 files changed, 43 insertions(+), 40 deletions(-) rename test/{urt.cpp => upperRightTriangle.cpp} (83%) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index dbcb307b16..3063051145 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -66,8 +66,8 @@ public: return res; } - // get matrix upper right triangle - Vector urt() const + // get matrix upper right triangle in a row-major vector format + Vector upper_right_triangle() const { Vector res; const SquareMatrix &self = *this; @@ -149,7 +149,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) for (size_t n = 0; n < M; n++) { // if diagonal is zero, swap with row below - if (fabs(static_cast(U(n, n))) < __FLT_EPSILON__) { + if (fabs(static_cast(U(n, n))) < FLT_EPSILON) { //printf("trying pivot for row %d\n",n); for (size_t i = n + 1; i < M; i++) { @@ -174,7 +174,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) #endif // failsafe, return zero matrix - if (fabs(static_cast(U(n, n))) < __FLT_EPSILON__) { + if (fabs(static_cast(U(n, n))) < FLT_EPSILON) { return false; } diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index 1f6b88b9c9..6e98a0da7c 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -15,6 +15,10 @@ namespace matrix { +#if !defined(FLT_EPSILON) +#define FLT_EPSILON __FLT_EPSILON__ +#endif + #if defined(__PX4_NUTTX) /* * NuttX has no usable C++ math library, so we need to provide the needed definitions here manually. diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 2453f70899..0dc8480731 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -18,7 +18,7 @@ set(tests hatvee copyto least_squares - urt + upperRightTriangle ) add_custom_target(test_build) diff --git a/test/helper.cpp b/test/helper.cpp index dda3c90df6..a21c90a76c 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -5,15 +5,15 @@ using namespace matrix; int main() { - TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < __FLT_EPSILON__); - TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < __FLT_EPSILON__); - TEST(fabs(wrap_pi(3.0) - (3.0)) < __FLT_EPSILON__); + TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(3.0) - (3.0)) < FLT_EPSILON); TEST(!is_finite(wrap_pi(1000.0f))); TEST(!is_finite(wrap_pi(-1000.0f))); wrap_pi(NAN); - TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < __FLT_EPSILON__); - TEST(fabs(wrap_2pi(3.0) - (3.0)) < __FLT_EPSILON__); + TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < FLT_EPSILON); + TEST(fabs(wrap_2pi(3.0) - (3.0)) < FLT_EPSILON); TEST(!is_finite(wrap_2pi(1000.0f))); TEST(!is_finite(wrap_2pi(-1000.0f))); wrap_2pi(NAN); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 81e34120dc..994af85c9a 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -22,7 +22,7 @@ int main() Matrix3f m2(data); for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < __FLT_EPSILON__); + TEST(fabs(data[i] - m2.data()[i]) < FLT_EPSILON); } Matrix3f m_nan; @@ -38,7 +38,7 @@ int main() }; m2 = Matrix3f(data2d); for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < __FLT_EPSILON__); + TEST(fabs(data[i] - m2.data()[i]) < FLT_EPSILON); } float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; @@ -100,16 +100,16 @@ int main() m4.swapCols(2, 2); TEST(isEqual(m4, Matrix3f(data))); - TEST(fabs(m4.min() - 1) < __FLT_EPSILON__); - TEST(fabs((-m4).min() + 9) < __FLT_EPSILON__); + TEST(fabs(m4.min() - 1) < FLT_EPSILON); + TEST(fabs((-m4).min() + 9) < FLT_EPSILON); Scalar s = 1; const Vector & s_vect = s; - TEST(fabs(s - 1) < __FLT_EPSILON__); - TEST(fabs(s_vect(0) - 1.0f) < __FLT_EPSILON__); + TEST(fabs(s - 1) < FLT_EPSILON); + TEST(fabs(s_vect(0) - 1.0f) < FLT_EPSILON); Matrix m5 = s; - TEST(fabs(m5(0,0) - s) < __FLT_EPSILON__); + TEST(fabs(m5(0,0) - s) < FLT_EPSILON); Matrix m6; m6.setRow(0, Vector2f(1, 2)); diff --git a/test/setIdentity.cpp b/test/setIdentity.cpp index fd96791a39..289e286464 100644 --- a/test/setIdentity.cpp +++ b/test/setIdentity.cpp @@ -11,10 +11,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST(fabs(A(i, j) - 1) < __FLT_EPSILON__); + TEST(fabs(A(i, j) - 1) < FLT_EPSILON); } else { - TEST(fabs(A(i, j) - 0) < __FLT_EPSILON__); + TEST(fabs(A(i, j) - 0) < FLT_EPSILON); } } } @@ -25,10 +25,10 @@ int main() for (size_t i = 0; i < 3; i++) { for (size_t j = 0; j < 3; j++) { if (i == j) { - TEST(fabs(B(i, j) - 1) < __FLT_EPSILON__); + TEST(fabs(B(i, j) - 1) < FLT_EPSILON); } else { - TEST(fabs(B(i, j) - 0) < __FLT_EPSILON__); + TEST(fabs(B(i, j) - 0) < FLT_EPSILON); } } } diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 1fc4bed1f7..861139ecc0 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -14,7 +14,7 @@ int main() Vector3 diag_check(1, 5, 10); TEST(isEqual(A.diag(), diag_check)); - TEST(A.trace() - 16 < __FLT_EPSILON__); + TEST(A.trace() - 16 < FLT_EPSILON); float data_check[9] = { 1.01158503f, 0.02190432f, 0.03238144f, diff --git a/test/test_data.py b/test/test_data.py index 85fa79c5e8..61ef1d0964 100644 --- a/test/test_data.py +++ b/test/test_data.py @@ -75,9 +75,9 @@ psi = 0.3 print('euler', phi, theta, psi) q = euler_to_quat(phi, theta, psi) -assert(abs(norm(q) - 1) < __FLT_EPSILON__) -assert(abs(norm(q) - 1) < __FLT_EPSILON__) -assert(norm(array(quat_to_euler(q)) - array([phi, theta, psi])) < __FLT_EPSILON__) +assert(abs(norm(q) - 1) < FLT_EPSILON) +assert(abs(norm(q) - 1) < FLT_EPSILON) +assert(norm(array(quat_to_euler(q)) - array([phi, theta, psi])) < FLT_EPSILON) print('\nq:') pprint(q) @@ -85,8 +85,8 @@ dcm = euler_to_dcm(phi, theta, psi) assert(norm(dcm[:,0]) == 1) assert(norm(dcm[:,1]) == 1) assert(norm(dcm[:,2]) == 1) -assert(abs(dcm[:,0].dot(dcm[:,1])) < __FLT_EPSILON__) -assert(abs(dcm[:,0].dot(dcm[:,2])) < __FLT_EPSILON__) +assert(abs(dcm[:,0].dot(dcm[:,1])) < FLT_EPSILON) +assert(abs(dcm[:,0].dot(dcm[:,2])) < FLT_EPSILON) print('\ndcm:') pprint(dcm) diff --git a/test/test_macros.hpp b/test/test_macros.hpp index f21c5a66a8..d6ca2d2fb1 100644 --- a/test/test_macros.hpp +++ b/test/test_macros.hpp @@ -10,7 +10,6 @@ #include #include // cmath has to be introduced BEFORE we poison the C library identifiers -#include "float.h" #define TEST(X) if(!(X)) { fprintf(stderr, "test failed on %s:%d\n", __FILE__, __LINE__); return -1;} diff --git a/test/urt.cpp b/test/upperRightTriangle.cpp similarity index 83% rename from test/urt.cpp rename to test/upperRightTriangle.cpp index 7b54d0583f..9807365003 100644 --- a/test/urt.cpp +++ b/test/upperRightTriangle.cpp @@ -14,7 +14,7 @@ int main() SquareMatrix A(data); for(int i=0; i<6; i++) { - TEST(fabs(urt[i] - A.urt().data()[i]) < __FLT_EPSILON__); + TEST(fabs(urt[i] - A.upper_right_triangle().data()[i]) < FLT_EPSILON); } return 0; diff --git a/test/vector2.cpp b/test/vector2.cpp index d5bf782241..1ea88fc933 100644 --- a/test/vector2.cpp +++ b/test/vector2.cpp @@ -10,29 +10,29 @@ int main() { Vector2f a(1, 0); Vector2f b(0, 1); - TEST(fabs(a % b - 1.0f) < __FLT_EPSILON__); + TEST(fabs(a % b - 1.0f) < FLT_EPSILON); Vector2f c; - TEST(fabs(c(0) - 0) < __FLT_EPSILON__); - TEST(fabs(c(1) - 0) < __FLT_EPSILON__); + TEST(fabs(c(0) - 0) < FLT_EPSILON); + TEST(fabs(c(1) - 0) < FLT_EPSILON); Matrix d(a); - TEST(fabs(d(0,0) - 1) < __FLT_EPSILON__); - TEST(fabs(d(1,0) - 0) < __FLT_EPSILON__); + TEST(fabs(d(0,0) - 1) < FLT_EPSILON); + TEST(fabs(d(1,0) - 0) < FLT_EPSILON); Vector2f e(d); - TEST(fabs(e(0) - 1) < __FLT_EPSILON__); - TEST(fabs(e(1) - 0) < __FLT_EPSILON__); + TEST(fabs(e(0) - 1) < FLT_EPSILON); + TEST(fabs(e(1) - 0) < FLT_EPSILON); float data[] = {4,5}; Vector2f f(data); - TEST(fabs(f(0) - 4) < __FLT_EPSILON__); - TEST(fabs(f(1) - 5) < __FLT_EPSILON__); + TEST(fabs(f(0) - 4) < FLT_EPSILON); + TEST(fabs(f(1) - 5) < FLT_EPSILON); Vector3f g(1.23f, 423.4f, 3221.f); Vector2f h(g); - TEST(fabs(h(0) - 1.23f) < __FLT_EPSILON__); - TEST(fabs(h(1) - 423.4f) < __FLT_EPSILON__); + TEST(fabs(h(0) - 1.23f) < FLT_EPSILON); + TEST(fabs(h(1) - 423.4f) < FLT_EPSILON); return 0; } From 5872bbc28cb60811b1527db042b4ede69f6880ed Mon Sep 17 00:00:00 2001 From: Oskar Weigl Date: Sun, 28 Oct 2018 16:00:25 -0700 Subject: [PATCH 283/388] Add slicing tests that are not pure row slicing I had a look at the implementation of `slice`, and I found it odd that it doesn't have a copy loop. The current implementation does a raw memcpy of the underlying contiguous row-major data. As far as I can tell, this could only slice along rows. Interestingly, I found that the tests only tested for slicing along rows, so this bug would go unnoticed. I added some tests that checks slicing along columns also. I have a feeling this would break, and we need to fix the implementation of `slice`. However I could be wrong, and hence I'm submitting these tests first to verify. --- test/slice.cpp | 32 +++++++++++++++++++++++++++----- 1 file changed, 27 insertions(+), 5 deletions(-) diff --git a/test/slice.cpp b/test/slice.cpp index 4c43e93c0a..ee1da077d5 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -9,15 +9,37 @@ int main() 4, 5, 6, 7, 8, 10 }; - float data_check[6] = { + SquareMatrix A(data); + + // Test row slicing + Matrix B_rowslice(A.slice<2, 3>(1, 0)); + float data_check_rowslice[6] = { 4, 5, 6, 7, 8, 10 }; - SquareMatrix A(data); - Matrix B_check(data_check); - Matrix B(A.slice<2, 3>(1, 0)); - TEST(isEqual(B, B_check)); + Matrix B_check_rowslice(data_check_rowslice); + TEST(isEqual(B_rowslice, B_check_rowslice)); + + // Test column slicing + Matrix B_colslice(A.slice<3, 2>(0, 1)); + float data_check_colslice[6] = { + 2, 3, + 5, 6, + 8, 10 + }; + Matrix B_check_colslice(data_check_colslice); + TEST(isEqual(B_colslice, B_check_colslice)); + // Test slicing both + Matrix B_bothslice(A.slice<2, 2>(1, 1)); + float data_check_bothslice[4] = { + 5, 6, + 8, 10 + }; + Matrix B_check_bothslice(data_check_bothslice); + TEST(isEqual(B_bothslice, B_check_bothslice)); + + //Test block writing float data_2[4] = { 11, 12, 13, 14 From 93375fbd3cf328755074463d84bd381d99670591 Mon Sep 17 00:00:00 2001 From: Oskar Weigl Date: Sun, 28 Oct 2018 16:04:37 -0700 Subject: [PATCH 284/388] Fix copy-paste error --- test/slice.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/slice.cpp b/test/slice.cpp index ee1da077d5..55d43f4036 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -31,7 +31,7 @@ int main() TEST(isEqual(B_colslice, B_check_colslice)); // Test slicing both - Matrix B_bothslice(A.slice<2, 2>(1, 1)); + Matrix B_bothslice(A.slice<2, 2>(1, 1)); float data_check_bothslice[4] = { 5, 6, 8, 10 From eea6b59973df774a7d7fe6e8ce27bba47c304217 Mon Sep 17 00:00:00 2001 From: Oskar Weigl Date: Mon, 4 Mar 2019 21:32:26 -0800 Subject: [PATCH 285/388] Implement slice as copy loop --- matrix/Matrix.hpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 7cbc5ea753..70bcea5ef7 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -355,7 +355,13 @@ public: template Matrix slice(size_t x0, size_t y0) const { - Matrix res(&(_data[x0][y0])); + Matrix &self = *this; + Matrix res; //default constructed + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + res(i, j) = self(i + x0, j + y0); + } + } return res; } From 5ccfa74c7260be13f964bb9632f7b4edec3e1f4b Mon Sep 17 00:00:00 2001 From: Oskar Weigl Date: Mon, 4 Mar 2019 21:37:28 -0800 Subject: [PATCH 286/388] Fix const error --- matrix/Matrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 70bcea5ef7..b9c3895197 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -355,7 +355,7 @@ public: template Matrix slice(size_t x0, size_t y0) const { - Matrix &self = *this; + const Matrix &self = *this; Matrix res; //default constructed for (size_t i = 0; i < P; i++) { for (size_t j = 0; j < Q; j++) { From 56b069956da141da244926ed7000e89b2ba6c731 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 8 Mar 2019 20:20:08 +0100 Subject: [PATCH 287/388] slice test: fix trailing whitespace style --- test/slice.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test/slice.cpp b/test/slice.cpp index 55d43f4036..f1b422064c 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -10,7 +10,7 @@ int main() 7, 8, 10 }; SquareMatrix A(data); - + // Test row slicing Matrix B_rowslice(A.slice<2, 3>(1, 0)); float data_check_rowslice[6] = { @@ -19,7 +19,7 @@ int main() }; Matrix B_check_rowslice(data_check_rowslice); TEST(isEqual(B_rowslice, B_check_rowslice)); - + // Test column slicing Matrix B_colslice(A.slice<3, 2>(0, 1)); float data_check_colslice[6] = { From 84b3da227cda0b66a2c8ebaa99aeddedf8858b02 Mon Sep 17 00:00:00 2001 From: kritz Date: Thu, 22 Aug 2019 15:05:14 +0200 Subject: [PATCH 288/388] Canonical Quaternion with tests (#81) --- matrix/Quaternion.hpp | 24 ++++++++++++++++++++++++ test/attitude.cpp | 11 +++++++++++ 2 files changed, 35 insertions(+) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 29e711dc46..f543a1b929 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -352,6 +352,30 @@ public: -q(3)/normSq); } + /** + * Bring quaternion to canonical form + */ + void canonicalize() + { + *this = this->canonical(); + } + + + /** + * Return canonical form of the quaternion + * + * @return quaternion in canonical from + */ + Quaternion canonical() const + { + const Quaternion &q = *this; + if(q(0) Date: Mon, 26 Aug 2019 19:27:58 +0200 Subject: [PATCH 289/388] matrix: add method to check all values are nan (#82) --- matrix/Matrix.hpp | 11 +++++++++++ test/matrixAssignment.cpp | 2 ++ 2 files changed, 13 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index b9c3895197..1026874637 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -507,6 +507,17 @@ public: return min_val; } + bool isAllNan() const { + const Matrix &self = *this; + bool result = true; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + result = result && isnan(self(i, j)); + } + } + return result; + } + }; template diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 994af85c9a..96bda28aeb 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -30,6 +30,7 @@ int main() for(int i=0; i<9; i++) { TEST(isnan(m_nan.data()[i])); } + TEST(m_nan.isAllNan()); float data2d[3][3] = { {1, 2, 3}, @@ -40,6 +41,7 @@ int main() for(int i=0; i<9; i++) { TEST(fabs(data[i] - m2.data()[i]) < FLT_EPSILON); } + TEST(!m2.isAllNan()); float data_times_2[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; Matrix3f m3(data_times_2); From 007c7c58c4565c6c86aa1344bb975ebe338d937a Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 4 Sep 2019 23:42:58 +0200 Subject: [PATCH 290/388] fix math defines to have M_PI and M_TWOPI --- matrix/Euler.hpp | 4 ---- matrix/stdlib_imports.hpp | 7 +++++++ 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index d16d307ed1..ec82cf1314 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -17,10 +17,6 @@ #include "math.hpp" -#ifndef M_PI -#define M_PI (3.14159265358979323846f) -#endif - namespace matrix { diff --git a/matrix/stdlib_imports.hpp b/matrix/stdlib_imports.hpp index 6e98a0da7c..547b5fed75 100644 --- a/matrix/stdlib_imports.hpp +++ b/matrix/stdlib_imports.hpp @@ -13,6 +13,13 @@ #include #include +#ifndef M_PI +#define M_PI 3.14159265358979323846 +#endif +#ifndef M_TWOPI +#define M_TWOPI (M_PI * 2.0) +#endif + namespace matrix { #if !defined(FLT_EPSILON) From 315010bae1c34c8557d62092f0d17b6196fbb5cc Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 4 Sep 2019 23:43:57 +0200 Subject: [PATCH 291/388] helper_functions: generalize wrap function to any range --- matrix/helper_functions.hpp | 93 +++++++++++++++++-------------------- 1 file changed, 43 insertions(+), 50 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 43c28d571d..e13b1f297d 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -20,64 +20,57 @@ bool is_finite(Type x) { #endif } +/** + * Wrap value to stay in range [low, high) + * + * @param x input possibly outside of the range + * @param low lower limit of the allowed range + * @param high upper limit of the allowed range + * @return wrapped value inside the range + */ +template +Type wrap(Type x, Type low, Type high) { + // already in range + if (low < x && x < high) { + return x; + } + + // close to range + Type range = high - low; + if ((high <= x) && (x < high + (range*100))) { + while (high <= x) { + x -= range; + } + return x; + } + + if ((low - (range*100) <= x) && (x < low)) { + while (x < low) { + x += range; + } + return x; + } + + // very far from the range -> something went terribly wrong + return NAN; +} + +/** + * Wrap value in range [-π, π) + */ template Type wrap_pi(Type x) { - if (!is_finite(x)) { - return x; - } - - int c = 0; - - while (x >= Type(M_PI)) { - x -= Type(2 * M_PI); - - if (c++ > 100) { - return INFINITY; - } - } - - c = 0; - - while (x < Type(-M_PI)) { - x += Type(2 * M_PI); - - if (c++ > 100) { - return INFINITY; - } - } - - return x; + return wrap(x, Type(-M_PI), Type(M_PI)); } +/** + * Wrap value in range [0, 2π) + */ template Type wrap_2pi(Type x) { - if (!is_finite(x)) { - return x; - } - - int c = 0; - - while (x >= Type(2 * M_PI)) { - x -= Type(2 * M_PI); - - if (c++ > 100) { - return INFINITY; - } - } - - c = 0; - - while (x < Type(0)) { - x += Type(2 * M_PI); - - if (c++ > 100) { - return INFINITY; - } - } - - return x; + return wrap(x, Type(0), Type(M_TWOPI)); } } From 938274fce5ea93743f0c11fd7622089b3ee39281 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 4 Sep 2019 23:45:09 +0200 Subject: [PATCH 292/388] helper test: add extensive wrap tests --- test/helper.cpp | 33 +++++++++++++++++++++++---------- 1 file changed, 23 insertions(+), 10 deletions(-) diff --git a/test/helper.cpp b/test/helper.cpp index a21c90a76c..7fe23820ef 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -5,22 +5,35 @@ using namespace matrix; int main() { - TEST(fabs(wrap_pi(4.0) - (4.0 - 2*M_PI)) < FLT_EPSILON); - TEST(fabs(wrap_pi(-4.0) - (-4.0 + 2*M_PI)) < FLT_EPSILON); - TEST(fabs(wrap_pi(3.0) - (3.0)) < FLT_EPSILON); - TEST(!is_finite(wrap_pi(1000.0f))); - TEST(!is_finite(wrap_pi(-1000.0f))); - wrap_pi(NAN); + // general wraps + TEST(fabs(wrap(4.0, 0.0, 10.0) - 4.0) < FLT_EPSILON); + TEST(fabs(wrap(4.0, 0.0, 1.0)) < FLT_EPSILON); + TEST(fabs(wrap(-4.0, 0.0, 10.0) - 6.0) < FLT_EPSILON); + TEST(fabs(wrap(-18.0, 0.0, 10.0) - 2.0) < FLT_EPSILON); + TEST(fabs(wrap(-1.5, 3.0, 5.0) - 4.5) < FLT_EPSILON); + TEST(fabs(wrap(15.5, 3.0, 5.0) - 3.5) < FLT_EPSILON); + TEST(fabs(wrap(-1.0, 30.0, 40.0) - 39.0) < FLT_EPSILON); + TEST(fabs(wrap(-8000.0, -555.0, 1.0) - (-216.0)) < FLT_EPSILON); + TEST(!is_finite(wrap(1000.,0.,.01))); + // wrap pi + TEST(fabs(wrap_pi(4.0) - (4.0 - M_TWOPI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(-4.0) - (-4.0 + M_TWOPI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(3.0) - (3.0)) < FLT_EPSILON); + TEST(fabs(wrap_pi(100.0f) - (100.0f - 32 * float(M_PI))) < 10e-5); + TEST(fabs(wrap_pi(-100.0f) - (-100.0f + 32 * float(M_PI))) < 10e-5); + TEST(fabs(wrap_pi(-101.0f) - (-101.0f + 32 * float(M_PI))) < 10e-5); + TEST(!is_finite(wrap_pi(NAN))); + + // wrap 2pi TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < FLT_EPSILON); TEST(fabs(wrap_2pi(3.0) - (3.0)) < FLT_EPSILON); - TEST(!is_finite(wrap_2pi(1000.0f))); - TEST(!is_finite(wrap_2pi(-1000.0f))); - wrap_2pi(NAN); + TEST(fabs(wrap_2pi(200.0f) - (200.0f - 31 * float(M_TWOPI))) < 10e-5); + TEST(fabs(wrap_2pi(-201.0f) - (-201.0f + 32 * float(M_TWOPI))) < 10e-5); + TEST(!is_finite(wrap_2pi(NAN))); Vector3f a(1, 2, 3); Vector3f b(4, 5, 6); - a.T().print(); TEST(!isEqual(a, b)); TEST(isEqual(a, a)); From 31450c407c338e7afe9961b1b76afec326369b0a Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 4 Sep 2019 23:46:06 +0200 Subject: [PATCH 293/388] Matrix: use existing print() if isEqual test fails --- matrix/Matrix.hpp | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 1026874637..ea78147a8c 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -550,7 +550,6 @@ Matrix operator*(Type scalar, const Matrix &other) template bool isEqual(const Matrix &x, const Matrix &y, const Type eps=1e-4f) { - bool equal = true; for (size_t i = 0; i < M; i++) { @@ -563,16 +562,13 @@ bool isEqual(const Matrix &x, if (equal == false) break; } - if (!equal) { - static const size_t n = 10*N*M; - char * buf = new char[n]; - x.write_string(buf, n); - printf("not equal\nx:\n%s\n", buf); - y.write_string(buf, n); - printf("y:\n%s\n", buf); - delete[] buf; + printf("not equal\nx:\n"); + x.print(); + printf("y:\n"); + y.print(); } + return equal; } From 4a4309327ad7b7c306c2c82fbc88157d4635f123 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Thu, 5 Sep 2019 10:12:45 +0200 Subject: [PATCH 294/388] better API comment Co-Authored-By: Julian Oes --- matrix/helper_functions.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index e13b1f297d..eee74ebeec 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -26,7 +26,7 @@ bool is_finite(Type x) { * @param x input possibly outside of the range * @param low lower limit of the allowed range * @param high upper limit of the allowed range - * @return wrapped value inside the range + * @return wrapped value inside the range, or NAN if value is too far away from range. */ template Type wrap(Type x, Type low, Type high) { From 26fd962cbe669bc5cb5ebeb59ba92d8b4f597edf Mon Sep 17 00:00:00 2001 From: Tanja Baumann Date: Thu, 5 Sep 2019 11:21:41 +0200 Subject: [PATCH 295/388] fix bug in matrix wrap function (#83) --- matrix/helper_functions.hpp | 2 +- test/helper.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index eee74ebeec..029272ce29 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -31,7 +31,7 @@ bool is_finite(Type x) { template Type wrap(Type x, Type low, Type high) { // already in range - if (low < x && x < high) { + if (low <= x && x < high) { return x; } diff --git a/test/helper.cpp b/test/helper.cpp index 7fe23820ef..4f855e0210 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -14,6 +14,7 @@ int main() TEST(fabs(wrap(15.5, 3.0, 5.0) - 3.5) < FLT_EPSILON); TEST(fabs(wrap(-1.0, 30.0, 40.0) - 39.0) < FLT_EPSILON); TEST(fabs(wrap(-8000.0, -555.0, 1.0) - (-216.0)) < FLT_EPSILON); + TEST(fabs(wrap(0.0, 0.0, 360.0)) < FLT_EPSILON); TEST(!is_finite(wrap(1000.,0.,.01))); // wrap pi @@ -30,6 +31,7 @@ int main() TEST(fabs(wrap_2pi(3.0) - (3.0)) < FLT_EPSILON); TEST(fabs(wrap_2pi(200.0f) - (200.0f - 31 * float(M_TWOPI))) < 10e-5); TEST(fabs(wrap_2pi(-201.0f) - (-201.0f + 32 * float(M_TWOPI))) < 10e-5); + TEST(fabs(wrap_2pi(0.0f)) < FLT_EPSILON); TEST(!is_finite(wrap_2pi(NAN))); Vector3f a(1, 2, 3); From 74ace7d1d55edf87c8a02a1ec5a8d7a564d036cd Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 5 Sep 2019 18:02:33 +0200 Subject: [PATCH 296/388] helper test: cover wrap close to limits cases (#84) --- test/helper.cpp | 52 +++++++++++++++++++++++++++---------------------- 1 file changed, 29 insertions(+), 23 deletions(-) diff --git a/test/helper.cpp b/test/helper.cpp index 4f855e0210..bfaa87a596 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -6,32 +6,38 @@ using namespace matrix; int main() { // general wraps - TEST(fabs(wrap(4.0, 0.0, 10.0) - 4.0) < FLT_EPSILON); - TEST(fabs(wrap(4.0, 0.0, 1.0)) < FLT_EPSILON); - TEST(fabs(wrap(-4.0, 0.0, 10.0) - 6.0) < FLT_EPSILON); - TEST(fabs(wrap(-18.0, 0.0, 10.0) - 2.0) < FLT_EPSILON); - TEST(fabs(wrap(-1.5, 3.0, 5.0) - 4.5) < FLT_EPSILON); - TEST(fabs(wrap(15.5, 3.0, 5.0) - 3.5) < FLT_EPSILON); - TEST(fabs(wrap(-1.0, 30.0, 40.0) - 39.0) < FLT_EPSILON); - TEST(fabs(wrap(-8000.0, -555.0, 1.0) - (-216.0)) < FLT_EPSILON); - TEST(fabs(wrap(0.0, 0.0, 360.0)) < FLT_EPSILON); - TEST(!is_finite(wrap(1000.,0.,.01))); + TEST(fabs(wrap(4., 0., 10.) - 4.) < FLT_EPSILON); + TEST(fabs(wrap(4., 0., 1.)) < FLT_EPSILON); + TEST(fabs(wrap(-4., 0., 10.) - 6.) < FLT_EPSILON); + TEST(fabs(wrap(-18., 0., 10.) - 2.) < FLT_EPSILON); + TEST(fabs(wrap(-1.5, 3., 5.) - 4.5) < FLT_EPSILON); + TEST(fabs(wrap(15.5, 3., 5.) - 3.5) < FLT_EPSILON); + TEST(fabs(wrap(-1., 30., 40.) - 39.) < FLT_EPSILON); + TEST(fabs(wrap(-8000., -555., 1.) - (-216.)) < FLT_EPSILON); + TEST(fabs(wrap(0., 0., 360.)) < FLT_EPSILON); + TEST(fabs(wrap(0. - FLT_EPSILON, 0., 360.) - (360. - FLT_EPSILON)) < FLT_EPSILON); + TEST(fabs(wrap(0. + FLT_EPSILON, 0., 360.) - FLT_EPSILON) < FLT_EPSILON); + TEST(fabs(wrap(360., 0., 360.)) < FLT_EPSILON); + TEST(fabs(wrap(360. - FLT_EPSILON, 0., 360.) - (360. - FLT_EPSILON)) < FLT_EPSILON); + TEST(fabs(wrap(360. + FLT_EPSILON, 0., 360.) - FLT_EPSILON) < FLT_EPSILON); + TEST(!is_finite(wrap(1000., 0., .01))); // wrap pi - TEST(fabs(wrap_pi(4.0) - (4.0 - M_TWOPI)) < FLT_EPSILON); - TEST(fabs(wrap_pi(-4.0) - (-4.0 + M_TWOPI)) < FLT_EPSILON); - TEST(fabs(wrap_pi(3.0) - (3.0)) < FLT_EPSILON); - TEST(fabs(wrap_pi(100.0f) - (100.0f - 32 * float(M_PI))) < 10e-5); - TEST(fabs(wrap_pi(-100.0f) - (-100.0f + 32 * float(M_PI))) < 10e-5); - TEST(fabs(wrap_pi(-101.0f) - (-101.0f + 32 * float(M_PI))) < 10e-5); + TEST(fabs(wrap_pi(0.)) < FLT_EPSILON); + TEST(fabs(wrap_pi(4.) - (4. - M_TWOPI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(-4.) - (-4. + M_TWOPI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(3.) - (3.)) < FLT_EPSILON); + TEST(fabs(wrap_pi(100.) - (100. - 32. * M_PI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(-100.) - (-100. + 32. * M_PI)) < FLT_EPSILON); + TEST(fabs(wrap_pi(-101.) - (-101. + 32. * M_PI)) < FLT_EPSILON); TEST(!is_finite(wrap_pi(NAN))); // wrap 2pi - TEST(fabs(wrap_2pi(-4.0) - (-4.0 + 2*M_PI)) < FLT_EPSILON); - TEST(fabs(wrap_2pi(3.0) - (3.0)) < FLT_EPSILON); - TEST(fabs(wrap_2pi(200.0f) - (200.0f - 31 * float(M_TWOPI))) < 10e-5); - TEST(fabs(wrap_2pi(-201.0f) - (-201.0f + 32 * float(M_TWOPI))) < 10e-5); - TEST(fabs(wrap_2pi(0.0f)) < FLT_EPSILON); + TEST(fabs(wrap_2pi(0.)) < FLT_EPSILON); + TEST(fabs(wrap_2pi(-4.) - (-4. + 2. * M_PI)) < FLT_EPSILON); + TEST(fabs(wrap_2pi(3.) - (3.)) < FLT_EPSILON); + TEST(fabs(wrap_2pi(200.) - (200. - 31. * M_TWOPI)) < FLT_EPSILON); + TEST(fabs(wrap_2pi(-201.) - (-201. + 32. * M_TWOPI)) < FLT_EPSILON); TEST(!is_finite(wrap_2pi(NAN))); Vector3f a(1, 2, 3); @@ -39,8 +45,8 @@ int main() TEST(!isEqual(a, b)); TEST(isEqual(a, a)); - TEST(isEqualF(1.0f, 1.0f)); - TEST(!isEqualF(1.0f, 2.0f)); + TEST(isEqualF(1., 1.)); + TEST(!isEqualF(1., 2.)); return 0; } From 22bf63cb714156eafd8a6d3822b903eba4980a8a Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Thu, 5 Sep 2019 17:34:29 +0200 Subject: [PATCH 297/388] A smaller codesize wrap, since it gets inlined in many places --- matrix/helper_functions.hpp | 24 +++++------------------- test/helper.cpp | 1 - 2 files changed, 5 insertions(+), 20 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 029272ce29..88fc56ab8f 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -26,7 +26,7 @@ bool is_finite(Type x) { * @param x input possibly outside of the range * @param low lower limit of the allowed range * @param high upper limit of the allowed range - * @return wrapped value inside the range, or NAN if value is too far away from range. + * @return wrapped value inside the range */ template Type wrap(Type x, Type low, Type high) { @@ -35,24 +35,10 @@ Type wrap(Type x, Type low, Type high) { return x; } - // close to range - Type range = high - low; - if ((high <= x) && (x < high + (range*100))) { - while (high <= x) { - x -= range; - } - return x; - } - - if ((low - (range*100) <= x) && (x < low)) { - while (x < low) { - x += range; - } - return x; - } - - // very far from the range -> something went terribly wrong - return NAN; + const Type range = high - low; + const Type inv_range = Type(1) / range; // should evaluate at compile time, multiplies below at runtime + const Type num_wraps = floor((x - low) * inv_range); + return x - range * num_wraps; } /** diff --git a/test/helper.cpp b/test/helper.cpp index bfaa87a596..91935eaffd 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -20,7 +20,6 @@ int main() TEST(fabs(wrap(360., 0., 360.)) < FLT_EPSILON); TEST(fabs(wrap(360. - FLT_EPSILON, 0., 360.) - (360. - FLT_EPSILON)) < FLT_EPSILON); TEST(fabs(wrap(360. + FLT_EPSILON, 0., 360.) - FLT_EPSILON) < FLT_EPSILON); - TEST(!is_finite(wrap(1000., 0., .01))); // wrap pi TEST(fabs(wrap_pi(0.)) < FLT_EPSILON); From 03ffd696a690e3d1c8f41040579650363f7aa471 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 9 Sep 2019 09:37:43 +0200 Subject: [PATCH 298/388] Replace pow with sqrt --- matrix/Vector.hpp | 6 +++--- test/vector.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 4c5bd915f8..09ad18ca69 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -66,7 +66,7 @@ public: Type norm() const { const Vector &a(*this); - return Type(sqrt(a.dot(a))); + return Type(::sqrt(a.dot(a))); } Type norm_squared() const { @@ -98,11 +98,11 @@ public: return unit(); } - Vector pow(Type v) const { + Vector sqrt() const { const Vector &a(*this); Vector r; for (size_t i = 0; i v4(data1_sq); - TEST(isEqual(v1, v4.pow(0.5))); + TEST(isEqual(v1, v4.sqrt())); return 0; } From 15865b741ccc49322a8ffd445d9814eba9f94710 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 9 Sep 2019 19:53:50 +0200 Subject: [PATCH 299/388] Help compiler with name resolution to avoid overload mixups --- matrix/Vector.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 09ad18ca69..c6f0c24698 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -66,7 +66,7 @@ public: Type norm() const { const Vector &a(*this); - return Type(::sqrt(a.dot(a))); + return Type(matrix::sqrt(a.dot(a))); } Type norm_squared() const { @@ -102,7 +102,7 @@ public: const Vector &a(*this); Vector r; for (size_t i = 0; i Date: Mon, 16 Sep 2019 15:53:15 +0200 Subject: [PATCH 300/388] Add Slice class --- matrix/Slice.hpp | 81 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 81 insertions(+) create mode 100644 matrix/Slice.hpp diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp new file mode 100644 index 0000000000..cff1521690 --- /dev/null +++ b/matrix/Slice.hpp @@ -0,0 +1,81 @@ +/** + * @file Slice.hpp + * + * A simple matrix template library. + * + * @author Julian Kent < julian@auterion.com > + */ + +#pragma once + +#include "math.hpp" + + +namespace matrix { + +template +class Matrix; + +template +class Vector; + +template +class Slice { +public: + Slice(size_t x0, size_t y0, const Matrix* data) : + _x0(x0), + _y0(y0), + _data(const_cast*>(data)) { + static_assert(P <= M, "Slice rows bigger than backing matrix"); + static_assert(Q <= N, "Slice cols bigger than backing matrix"); + } + + Type operator()(size_t i, size_t j) const + { + return (*_data)(_x0 + i, _y0 + j); + } + + Type &operator()(size_t i, size_t j) + { + return (*_data)(_x0 + i, _y0 + j); + } + + template + Slice& operator=(const Slice& in_matrix) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) = in_matrix(i, j); + } + } + return self; + } + + Slice& operator=(const Matrix& in_matrix) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) = in_matrix(i, j); + } + } + return self; + } + + // allow assigning vectors to a slice that are in the axis + Slice& operator=(const Vector& in_vector) + { + Slice& self = *this; + for (size_t j = 0; j < Q; j++) { + self(0, j) = in_vector(j); + } + return self; + } + +private: + size_t _x0, _y0; + Matrix* _data; +}; + +} From 82d565f4d9e5628214fa63807079c3f73ae41056 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 16 Sep 2019 15:55:06 +0200 Subject: [PATCH 301/388] Add support for Slice to Matrix, SquareMatrix, Vector --- matrix/Matrix.hpp | 38 +++++++++++++++++++++----------------- matrix/SquareMatrix.hpp | 22 +++++++++++++++++++++- matrix/Vector.hpp | 6 ++++++ matrix/Vector2.hpp | 5 +++++ matrix/Vector3.hpp | 10 +++++++++- matrix/math.hpp | 1 + test/slice.cpp | 2 +- test/squareMatrix.cpp | 13 +++++++++++++ 8 files changed, 77 insertions(+), 20 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index ea78147a8c..7170f31f82 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -24,6 +24,12 @@ namespace matrix template class Vector; +template +class Matrix; + +template +class Slice; + template class Matrix { @@ -50,6 +56,17 @@ public: memcpy(_data, other._data, sizeof(_data)); } + template + Matrix(const Slice& in_slice) + { + Matrix& self = *this; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) = in_slice(i, j); + } + } + } + /** * Accessors/ Assignment etc. */ @@ -353,27 +370,15 @@ public: } template - Matrix slice(size_t x0, size_t y0) const + const Slice slice(size_t x0, size_t y0) const { - const Matrix &self = *this; - Matrix res; //default constructed - for (size_t i = 0; i < P; i++) { - for (size_t j = 0; j < Q; j++) { - res(i, j) = self(i + x0, j + y0); - } - } - return res; + return Slice(x0, y0, this); } template - void set(const Matrix &m, size_t x0, size_t y0) + Slice slice(size_t x0, size_t y0) { - Matrix &self = *this; - for (size_t i = 0; i < P; i++) { - for (size_t j = 0; j < Q; j++) { - self(i + x0, j + y0) = m(i, j); - } - } + return Slice(x0, y0, this); } void setRow(size_t i, const Matrix &row) @@ -517,7 +522,6 @@ public: } return result; } - }; template diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 3063051145..7b0a46023f 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -20,6 +20,9 @@ class Matrix; template class Vector; +template +class Slice; + template class SquareMatrix : public Matrix { @@ -36,6 +39,24 @@ public: { } + template + SquareMatrix(const Slice& in_slice) : Matrix(in_slice) + { + } + + SquareMatrix& operator=(const Matrix& other) + { + Matrix::operator=(other); + return *this; + } + + template + SquareMatrix & operator=(const Slice& in_slice) + { + Matrix::operator=(in_slice); + return *this; + } + // inverse alias inline SquareMatrix I() const { @@ -93,7 +114,6 @@ public: } return res; } - }; typedef SquareMatrix SquareMatrix3f; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index c6f0c24698..edac621ca6 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -34,6 +34,12 @@ public: { } + template + Vector(const Slice& slice_in) : + Matrix(slice_in) + { + } + inline Type operator()(size_t i) const { const MatrixM1 &v = *this; diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index dc42c5d5e9..5e209bbbf2 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -43,6 +43,11 @@ public: v(1) = y; } + template + Vector2(const Slice& slice_in) : Vector(slice_in) + { + } + explicit Vector2(const Vector3 & other) { Vector2 &v(*this); diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index dea65de5f4..71e20cfb06 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -19,9 +19,12 @@ class Matrix; template class Vector; -template +template class Dcm; +template +class Vector2; + template class Vector3 : public Vector { @@ -48,6 +51,11 @@ public: v(2) = z; } + template + Vector3(const Slice& slice_in) : Vector(slice_in) + { + } + Vector3 cross(const Matrix31 & b) const { const Vector3 &a(*this); Vector3 c; diff --git a/matrix/math.hpp b/matrix/math.hpp index 30479f26e0..9626b78d08 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -6,6 +6,7 @@ #endif #include "Matrix.hpp" #include "SquareMatrix.hpp" +#include "Slice.hpp" #include "Vector.hpp" #include "Vector2.hpp" #include "Vector3.hpp" diff --git a/test/slice.cpp b/test/slice.cpp index f1b422064c..0c7c35d386 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -46,7 +46,7 @@ int main() }; Matrix C(data_2); - A.set(C, 1, 1); + A.slice<2, 2>(1, 1) = C; float data_2_check[9] = { 0, 2, 3, diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 861139ecc0..3ad6b1a832 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -26,6 +26,19 @@ int main() SquareMatrix eA = expm(SquareMatrix(A*dt), 5); SquareMatrix eA_check(data_check); TEST((eA - eA_check).abs().max() < 1e-3f); + + SquareMatrix A_bottomright = A.slice<2,2>(1,1); + SquareMatrix A_bottomright2; + A_bottomright2 = A.slice<2,2>(1,1); + + float data_bottomright[4] = {5, 6, + 8, 10 + }; + SquareMatrix bottomright_check(data_bottomright); + TEST(isEqual(A_bottomright, bottomright_check)); + TEST(isEqual(A_bottomright2, bottomright_check)); + + return 0; } From b817e8677d4a7683da2a3f97dbfee1b476ba0618 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 16 Sep 2019 15:55:51 +0200 Subject: [PATCH 302/388] Add helpers based on Slice: row(), col(), xy() --- matrix/Dcm.hpp | 6 +++--- matrix/Matrix.hpp | 35 +++++++++++++++++++++++++---------- matrix/Vector3.hpp | 10 ++++++++++ test/slice.cpp | 41 +++++++++++++++++++++++++++++++++++++++++ test/vector3.cpp | 23 +++++++++++++++++++++++ 5 files changed, 102 insertions(+), 13 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 43d3cee1d3..31ea35da5c 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -166,9 +166,9 @@ public: void renormalize() { /* renormalize rows */ - for (size_t row = 0; row < 3; row++) { - matrix::Vector3f rvec(this->_data[row]); - this->setRow(row, rvec.normalized()); + for (size_t r = 0; r < 3; r++) { + matrix::Vector3 rvec(Matrix(this->Matrix::row(r)).transpose()); + this->Matrix::row(r) = rvec.normalized(); } } }; diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 7170f31f82..b6a9322c46 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -381,20 +381,35 @@ public: return Slice(x0, y0, this); } - void setRow(size_t i, const Matrix &row) + const Slice row(size_t i) const { - Matrix &self = *this; - for (size_t j = 0; j < N; j++) { - self(i, j) = row(j, 0); - } + return slice<1, N>(i,0); } - void setCol(size_t j, const Matrix &col) + Slice row(size_t i) { - Matrix &self = *this; - for (size_t i = 0; i < M; i++) { - self(i, j) = col(i, 0); - } + return slice<1, N>(i,0); + } + + const Slice col(size_t j) const + { + return slice(0,j); + } + + Slice col(size_t j) + { + return slice(0,j); + } + + void setRow(size_t i, const Matrix &row_in) + { + slice<1,N>(i,0) = row_in.transpose(); + } + + + void setCol(size_t j, const Matrix &column) + { + slice(0,j) = column; } void setZero() diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 71e20cfb06..4f2de37f0b 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -109,6 +109,16 @@ public: return unit(); } + const Slice xy() const + { + return Slice(0, 0, this); + } + + Slice xy() + { + return Slice(0, 0, this); + } + Dcm hat() const { // inverse to Dcm.vee() operation const Vector3 &v(*this); diff --git a/test/slice.cpp b/test/slice.cpp index 0c7c35d386..f92fef99df 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -56,6 +56,47 @@ int main() Matrix D(data_2_check); TEST(isEqual(A, D)); + //Test writing to slices + Matrix E; + E(0,0) = -1; + E(1,0) = 1; + E(2,0) = 3; + + Matrix F; + F(0,0) = 9; + F(1,0) = 11; + + E.slice<2,1>(0,0) = F; + + float data_3_check[3] = {9, 11, 3}; + Matrix G (data_3_check); + TEST(isEqual(E, G)); + TEST(isEqual(E, Matrix(E.slice<3,1>(0,0)))); + + Matrix H = E.slice<2,1>(0,0); + TEST(isEqual(H,F)); + + float data_4_check[5] = {3, 11, 9, 0, 0}; + { // assigning row slices to each other + const Matrix J (data_3_check); + Matrix K; + K.row(2) = J.row(0); + K.row(1) = J.row(1); + K.row(0) = J.row(2); + + Matrix K_check(data_4_check); + TEST(isEqual(K, K_check)); + } + { // assigning col slices to each other + const Matrix J (data_3_check); + Matrix K; + K.col(2) = J.col(0); + K.col(1) = J.col(1); + K.col(0) = J.col(2); + + Matrix K_check(data_4_check); + TEST(isEqual(K, K_check)); + } return 0; } diff --git a/test/vector3.cpp b/test/vector3.cpp index ebe8a2ca6f..b5cef674b9 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -27,6 +27,29 @@ int main() TEST(isEqual(a.unit(), a.normalized())); TEST(isEqual(a*2.0, Vector3f(2, 0, 0))); + Vector2f g2(1,3); + Vector3f g3(7, 11, 17); + g3.xy() = g2; + TEST(isEqual(g3, Vector3f(1, 3, 17))); + + const Vector3f g4(g3); + Vector2f g5 = g4.xy(); + TEST(isEqual(g5,g2)); + TEST(isEqual(g2,Vector2f(g4.xy()))); + + Vector3f h; + TEST(isEqual(h,Vector3f(0,0,0))); + + Vector j; + j(0) = 1; + j(1) = 2; + j(2) = 3; + j(3) = 4; + + Vector3f k = j.slice<3,1>(0,0); + Vector3f k_test(1,2,3); + TEST(isEqual(k,k_test)); + return 0; } From 18218c8f9c86474c76c5a9cc0aea3df47ed18dd6 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 16 Sep 2019 17:40:25 +0200 Subject: [PATCH 303/388] Test non-square matrix multiplication (#91) * Test non-square matrix multiplication --- test/matrixMult.cpp | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 1699d3f3c8..fa97f95106 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -35,6 +35,31 @@ int main() TEST(isEqual(B, B_check)); Matrix3f C = B_check.edivide(C_check); TEST(isEqual(C, C_check)); + + // Test non-square matrix + float data_43[12] = {1,3,2, + 2,2,1, + 5,2,1, + 2,3,4 + }; + float data_32[6] = {2,3, + 1,7, + 5,4 + }; + + Matrix m43(data_43); + Matrix m32(data_32); + + Matrix m42 = m43 * m32; + + float data_42[8] = {15,32, + 11,24, + 17,33, + 27,43 + }; + Matrix m42_check(data_42); + TEST(isEqual(m42, m42_check)) + return 0; } From 51d2f9f0dcb3c47ca2ee4a8216ed5cde08b0b76e Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 16 Sep 2019 10:29:48 +0200 Subject: [PATCH 304/388] Remove direct access to internal data --- matrix/Matrix.hpp | 13 ++----------- test/attitude.cpp | 4 ++-- test/matrixAssignment.cpp | 18 ++++++++++++------ test/matrixMult.cpp | 7 ------- test/upperRightTriangle.cpp | 4 ++-- 5 files changed, 18 insertions(+), 28 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index b6a9322c46..15548a1c3f 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -34,10 +34,10 @@ template class Matrix { -public: - Type _data[M][N] {}; +public: + // Constructors Matrix() = default; @@ -71,15 +71,6 @@ public: * Accessors/ Assignment etc. */ - Type *data() - { - return _data[0]; - } - - const Type *data() const - { - return _data[0]; - } inline Type operator()(size_t i, size_t j) const { diff --git a/test/attitude.cpp b/test/attitude.cpp index 525bbd06be..becb39602f 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -136,8 +136,8 @@ int main() A.renormalize(); float err = 0.0f; - for (auto & row : A._data) { - Vector3f rvec(row); + for (size_t r = 0; r < 3; r++) { + Vector3f rvec(matrix::Matrix(A.row(r)).transpose()); err += fabs(1.0f - rvec.length()); } TEST(err < eps); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 96bda28aeb..6e744265cc 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -21,14 +21,18 @@ int main() float data[9] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; Matrix3f m2(data); - for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < FLT_EPSILON); + for(size_t i=0; i<3; i++) { + for (size_t j = 0; j < 3; j++) { + TEST(fabs(data[i*3 + j] - m2(i,j)) < FLT_EPSILON); + } } Matrix3f m_nan; m_nan.setNaN(); - for(int i=0; i<9; i++) { - TEST(isnan(m_nan.data()[i])); + for(size_t i=0; i<3; i++) { + for (size_t j = 0; j < 3; j++) { + TEST(isnan(m_nan(i,j))); + } } TEST(m_nan.isAllNan()); @@ -38,8 +42,10 @@ int main() {7, 8, 9} }; m2 = Matrix3f(data2d); - for(int i=0; i<9; i++) { - TEST(fabs(data[i] - m2.data()[i]) < FLT_EPSILON); + for(size_t i=0; i<3; i++) { + for (size_t j = 0; j < 3; j++) { + TEST(fabs(data[i*3 + j] - m2(i,j)) < FLT_EPSILON); + } } TEST(!m2.isAllNan()); diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index fa97f95106..5dd0d329ff 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -8,13 +8,6 @@ int main() float data[9] = {1, 0, 0, 0, 1, 0, 1, 0, 1}; Matrix3f A(data); - const Matrix3f Const(data); - const float * raw_data = Const.data(); - const float eps = 1e-4f; - for (int i=0; i<9; i++) { - TEST(fabs(raw_data[i] - data[i]) < eps); - } - float data_check[9] = {1, 0, 0, 0, 1, 0, -1, 0, 1}; Matrix3f A_I(data_check); Matrix3f I; diff --git a/test/upperRightTriangle.cpp b/test/upperRightTriangle.cpp index 9807365003..1db52d936c 100644 --- a/test/upperRightTriangle.cpp +++ b/test/upperRightTriangle.cpp @@ -13,8 +13,8 @@ int main() SquareMatrix A(data); - for(int i=0; i<6; i++) { - TEST(fabs(urt[i] - A.upper_right_triangle().data()[i]) < FLT_EPSILON); + for(size_t i=0; i<6; i++) { + TEST(fabs(urt[i] - A.upper_right_triangle()(i)) < FLT_EPSILON); } return 0; From b4714e2ed29ca0a4a010c27fe85883224123fc12 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Tue, 17 Sep 2019 12:21:20 +0200 Subject: [PATCH 305/388] Don't lose array sizes in copyTo --- matrix/Matrix.hpp | 4 ++-- test/copyto.cpp | 9 ++++++++- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 15548a1c3f..6ef16e3f20 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -90,9 +90,9 @@ public: return (*this); } - void copyTo(Type (&dst)[M*N]) const + void copyTo(Type dst [M*N]) const { - memcpy(dst, _data, sizeof(dst)); + memcpy(dst, _data, sizeof(Type)*M*N); } void copyToColumnMajor(Type (&dst)[M*N]) const diff --git a/test/copyto.cpp b/test/copyto.cpp index 0a9ccb20f7..47a209edc6 100644 --- a/test/copyto.cpp +++ b/test/copyto.cpp @@ -3,6 +3,13 @@ using namespace matrix; +namespace { +void doTheCopy(const Matrix& A, float array_A[6]) +{ + A.copyTo(array_A); +} +} + int main() { float eps = 1e-6f; @@ -32,7 +39,7 @@ int main() A(1,1) = 5; A(1,2) = 6; float array_A[6] = {}; - A.copyTo(array_A); + doTheCopy(A, array_A); float array_row[6] = {1, 2, 3, 4, 5, 6}; for (size_t i = 0; i < 6; i++) { TEST(fabs(array_A[i] - array_row[i]) < eps); From 60c9c99dcc44ea12bed0c3f9b95d01e2aa6d7d9e Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 17 Sep 2019 09:46:55 -0400 Subject: [PATCH 306/388] Fix type for division. --- matrix/Matrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 6ef16e3f20..79887eff63 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -278,7 +278,7 @@ public: void operator/=(Type scalar) { Matrix &self = *this; - self = self * (1.0f / scalar); + self = self * (Type(1.0f) / scalar); } inline void operator+=(Type scalar) From a374f37a548308c15e2bdde6d065ea9503ce0463 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 16 Sep 2019 15:30:37 +0200 Subject: [PATCH 307/388] Include helper_functions like all other library components --- matrix/AxisAngle.hpp | 1 - matrix/Quaternion.hpp | 1 - matrix/SquareMatrix.hpp | 1 - matrix/math.hpp | 1 + test/helper.cpp | 2 +- 5 files changed, 2 insertions(+), 4 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 339651fe0a..c2aec911e1 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -7,7 +7,6 @@ #pragma once #include "math.hpp" -#include "helper_functions.hpp" namespace matrix { diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index f543a1b929..2110ded9e3 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -29,7 +29,6 @@ #pragma once #include "math.hpp" -#include "helper_functions.hpp" namespace matrix { diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 7b0a46023f..6a8ed55606 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -9,7 +9,6 @@ #pragma once #include "math.hpp" -#include "helper_functions.hpp" namespace matrix { diff --git a/matrix/math.hpp b/matrix/math.hpp index 9626b78d08..83da08c1fd 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -4,6 +4,7 @@ #ifdef __PX4_QURT #include "dspal_math.h" #endif +#include "helper_functions.hpp" #include "Matrix.hpp" #include "SquareMatrix.hpp" #include "Slice.hpp" diff --git a/test/helper.cpp b/test/helper.cpp index 91935eaffd..9883e72d77 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -1,5 +1,5 @@ #include "test_macros.hpp" -#include +#include using namespace matrix; From 1e80807e8ebf812da28e9932e328457a780685a0 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 16 Sep 2019 15:54:55 +0200 Subject: [PATCH 308/388] test: Add uncovered equality checks with NAN and INFINITE --- test/helper.cpp | 18 ++++++++++++++++-- test/matrixAssignment.cpp | 3 +++ 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/test/helper.cpp b/test/helper.cpp index 9883e72d77..7dd1fb94b8 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -39,13 +39,27 @@ int main() TEST(fabs(wrap_2pi(-201.) - (-201. + 32. * M_TWOPI)) < FLT_EPSILON); TEST(!is_finite(wrap_2pi(NAN))); + // Equality checks + TEST(isEqualF(1., 1.)); + TEST(!isEqualF(1., 2.)); + TEST(!isEqualF(NAN, 1.f)); + TEST(!isEqualF(1.f, NAN)); + TEST(!isEqualF(INFINITY, 1.f)); + TEST(!isEqualF(1.f, INFINITY)); + TEST(!isEqualF(NAN, NAN)); + TEST(!isEqualF(INFINITY, INFINITY)); + Vector3f a(1, 2, 3); Vector3f b(4, 5, 6); TEST(!isEqual(a, b)); TEST(isEqual(a, a)); - TEST(isEqualF(1., 1.)); - TEST(!isEqualF(1., 2.)); + Vector3f c(1, 2, 3); + Vector3f d(1, 2, NAN); + TEST(!isEqual(c, d)); + TEST(isEqual(c, c)); + TEST(!isEqual(d, d)); + return 0; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 6e744265cc..b4bb637111 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -129,6 +129,9 @@ int main() Matrix m8(m8_array); TEST(isEqual(m6, m8)); + m7.setNaN(); + TEST(m7 != m8); + return 0; } From 5844b0e46eb6d2d8e027eab4c33a24a3e7ae61cd Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 16 Sep 2019 16:07:50 +0200 Subject: [PATCH 309/388] Implement one float equality check and use it everywhere --- matrix/Matrix.hpp | 43 ++----------------------------------- matrix/helper_functions.hpp | 17 +++++++++++++++ 2 files changed, 19 insertions(+), 41 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 79887eff63..d2eb7b0cb7 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -295,12 +295,9 @@ public: { const Matrix &self = *this; - // TODO: set this based on Type - static constexpr float eps = 1e-4f; - for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - if (fabs(self(i, j) - other(i, j)) > eps) { + if (!isEqualF(self(i, j), other(i, j))) { return false; } } @@ -560,43 +557,7 @@ Matrix operator*(Type scalar, const Matrix &other) template bool isEqual(const Matrix &x, const Matrix &y, const Type eps=1e-4f) { - bool equal = true; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - if (fabs(x(i, j) - y(i, j)) > eps) { - equal = false; - break; - } - } - if (equal == false) break; - } - - if (!equal) { - printf("not equal\nx:\n"); - x.print(); - printf("y:\n"); - y.print(); - } - - return equal; -} - - -template -bool isEqualF(Type x, - Type y, Type eps=1e-4f) { - - bool equal = true; - - if (fabs(x - y) > eps) { - equal = false; - } - - if (!equal) { - printf("not equal\nx:\n%g\ny:\n%g\n", double(x), double(y)); - } - return equal; + return x == y; } #if defined(SUPPORT_STDIOSTREAM) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 88fc56ab8f..4ddeabf922 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -20,6 +20,23 @@ bool is_finite(Type x) { #endif } +/** + * Compare if two floating point numbers are equal + * + * Note: Smaller or EQUAL than is important to correctly + * handle the comparison to infinite or nan. + * + * @param x right side of equality check + * @param y left side of equality check + * @param eps numerical tolerance of the check + * @return true if the two values are considered equal, false otherwise + */ +template +bool isEqualF(const Type x, const Type y, const Type eps = 1e-4f) +{ + return matrix::fabs(x - y) <= eps; +} + /** * Wrap value to stay in range [low, high) * From 374723272485ed065464c816772dbd672f3a2a1e Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Sep 2019 06:49:36 +0200 Subject: [PATCH 310/388] LeastSquaresSolver: Fix nasty GCC compile optimization error The original implementation with no wrapping on size_t is more readable but the compiler errors with: internal compiler error: in trunc_int_for_mode, at explow.c:55 I read up and it's apparently a loop optimization problem. Inspired by https://stackoverflow.com/a/27224697/6326048 I used a far less readable implementation that works fine and wrote a comment to explain it. --- matrix/LeastSquaresSolver.hpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/matrix/LeastSquaresSolver.hpp b/matrix/LeastSquaresSolver.hpp index 2d812d7fda..1f518b4d69 100644 --- a/matrix/LeastSquaresSolver.hpp +++ b/matrix/LeastSquaresSolver.hpp @@ -116,20 +116,21 @@ public: Vector qtbv = qtb(b); Vector x; - for (size_t l = N; l > 0 ; l--) { - size_t i = l - 1; + // size_t is unsigned and wraps i = 0 - 1 to i > N + for (size_t i = N - 1; i < N; i--) { + printf("i %d\n", static_cast(i)); x(i) = qtbv(i); for (size_t r = i+1; r < N; r++) { x(i) -= _A(i,r) * x(r); } // divide by zero, return vector of zeros - if (fabs(_A(i,i)) < Type(1e-8)) { + if (isEqualF(_A(i,i), Type(0), Type(1e-8))) { for (size_t z = 0; z < N; z++) { x(z) = Type(0); } break; } - x(i) = x(i) / _A(i,i); + x(i) /= _A(i,i); } return x; } From b0b7d7229aadd4ce3fd5b2e5c4e92fac96ede109 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Sep 2019 07:41:49 +0200 Subject: [PATCH 311/388] Multiplication test: fix division resulting in NAN --- test/matrixMult.cpp | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 5dd0d329ff..660db72f95 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -27,7 +27,17 @@ int main() Matrix3f C_check = eye()*2; TEST(isEqual(B, B_check)); Matrix3f C = B_check.edivide(C_check); - TEST(isEqual(C, C_check)); + + // off diagonal are NANs because division by 0 + for (size_t i = 0; i < 3; i++) { + for (size_t j = 0; j < 3; j++) { + if (i == j) { + TEST(isEqualF(C(i,j), 2.f)); + } else { + TEST(isnan(C(i,j))); + } + } + } // Test non-square matrix float data_43[12] = {1,3,2, From 33a629105c266c8ed75ea5c78dcea850374d124c Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Sep 2019 17:37:41 +0200 Subject: [PATCH 312/388] Matrix: add proper print function testing Before the print function was just implicitly called somewhere and that's why we had 100% line coverage. With this we have actual testing of the functions. --- matrix/Matrix.hpp | 9 +++++---- test/matrixAssignment.cpp | 38 ++++++++++++++++++++++++++++++++++++++ 2 files changed, 43 insertions(+), 4 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index d2eb7b0cb7..3849f66ac3 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -322,18 +322,19 @@ public: const Matrix &self = *this; for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - snprintf(buf + strlen(buf), n - strlen(buf), "\t%8.2g", double(self(i, j))); // directly append to the string buffer + snprintf(buf + strlen(buf), n - strlen(buf), "\t%8.8g", double(self(i, j))); // directly append to the string buffer } snprintf(buf + strlen(buf), n - strlen(buf), "\n"); } } - void print() const + void print(FILE *stream = stdout) const { - static const size_t n = 11*N*M + M; // for every entry a tab and 10 digits, for every row a newline + // element: tab, point, 8 digits; row: newline; string: \0 end + static const size_t n = 10*N*M + M + 1; char * buf = new char[n]; write_string(buf, n); - printf("%s\n", buf); + fprintf(stream, "%s\n", buf); delete[] buf; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index b4bb637111..00b6e88ab1 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -132,6 +132,44 @@ int main() m7.setNaN(); TEST(m7 != m8); + // check write_string() + float comma[6] = { + 1.f, 12345.678f, + 12345.67891f, 12345.67891f, + 1112345.67891f, 12345.111111111f + }; + Matrix Comma(comma); + const size_t len = 10*2*3 + 2 + 1; + char buffer[len]; + Comma.write_string(buffer, len); + char output[] = "\t 1\t12345.678\n\t12345.679\t12345.679\n\t1112345.6\t12345.111\n"; + for (size_t i = 0; i < len; i++) { + TEST(buffer[i] == output[i]); + if (buffer[i] == '\0') { + break; + } + } + + // check print() + // write + FILE *fp = fopen("testoutput.txt", "w+"); + TEST(fp != nullptr); + Comma.print(fp); + TEST(!fclose(fp)); + // read + fp = fopen("testoutput.txt", "r"); + TEST(fp != nullptr); + TEST(!fseek(fp, 0, SEEK_SET)); + for (size_t i = 0; i < len; i++) { + char c = static_cast(fgetc(fp)); + if (c == '\n') { + break; + } + printf("%d %d %c\n", static_cast(i), c, c); + TEST(c == output[i]); + } + TEST(!fclose(fp)); + return 0; } From bbaa93880b2a9ea67621232d444ecdda4006bdf0 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Sep 2019 17:53:54 +0200 Subject: [PATCH 313/388] helper: consider NAN equal to NAN such that vectors can be compared exactly --- matrix/helper_functions.hpp | 4 +++- test/helper.cpp | 7 ++++--- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 4ddeabf922..81e6243733 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -34,7 +34,9 @@ bool is_finite(Type x) { template bool isEqualF(const Type x, const Type y, const Type eps = 1e-4f) { - return matrix::fabs(x - y) <= eps; + return (matrix::fabs(x - y) <= eps) + || (isnan(x) && isnan(y)) + || (isinf(x) && isinf(y)); } /** diff --git a/test/helper.cpp b/test/helper.cpp index 7dd1fb94b8..4bd13daaec 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -46,8 +46,9 @@ int main() TEST(!isEqualF(1.f, NAN)); TEST(!isEqualF(INFINITY, 1.f)); TEST(!isEqualF(1.f, INFINITY)); - TEST(!isEqualF(NAN, NAN)); - TEST(!isEqualF(INFINITY, INFINITY)); + TEST(isEqualF(NAN, NAN)); + TEST(isEqualF(NAN, -NAN)); + TEST(isEqualF(INFINITY, INFINITY)); Vector3f a(1, 2, 3); Vector3f b(4, 5, 6); @@ -58,7 +59,7 @@ int main() Vector3f d(1, 2, NAN); TEST(!isEqual(c, d)); TEST(isEqual(c, c)); - TEST(!isEqual(d, d)); + TEST(isEqual(d, d)); return 0; } From c34e8dc98fd05ea55dcd4c9fc551b11a3d23a601 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 17 Sep 2019 21:02:21 +0200 Subject: [PATCH 314/388] helper: consider matrices with the same NANs and INFINITYs equal to simplify bulk checks when these values are expected --- matrix/helper_functions.hpp | 6 +++--- test/helper.cpp | 4 ++++ test/matrixMult.cpp | 11 ++--------- 3 files changed, 9 insertions(+), 12 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 81e6243733..d3ecf841b1 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -23,8 +23,8 @@ bool is_finite(Type x) { /** * Compare if two floating point numbers are equal * - * Note: Smaller or EQUAL than is important to correctly - * handle the comparison to infinite or nan. + * NAN is considered equal to NAN and -NAN + * INFINITY is considered equal INFINITY but not -INFINITY * * @param x right side of equality check * @param y left side of equality check @@ -36,7 +36,7 @@ bool isEqualF(const Type x, const Type y, const Type eps = 1e-4f) { return (matrix::fabs(x - y) <= eps) || (isnan(x) && isnan(y)) - || (isinf(x) && isinf(y)); + || (isinf(x) && isinf(y) && isnan(x - y)); } /** diff --git a/test/helper.cpp b/test/helper.cpp index 4bd13daaec..c9f42cfdd5 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -48,7 +48,11 @@ int main() TEST(!isEqualF(1.f, INFINITY)); TEST(isEqualF(NAN, NAN)); TEST(isEqualF(NAN, -NAN)); + TEST(isEqualF(-NAN, NAN)); TEST(isEqualF(INFINITY, INFINITY)); + TEST(!isEqualF(INFINITY, -INFINITY)); + TEST(!isEqualF(-INFINITY, INFINITY)); + TEST(isEqualF(-INFINITY, -INFINITY)); Vector3f a(1, 2, 3); Vector3f b(4, 5, 6); diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 660db72f95..799ab1c009 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -28,16 +28,9 @@ int main() TEST(isEqual(B, B_check)); Matrix3f C = B_check.edivide(C_check); + float off_diagonal_nan[9] = {2, NAN, NAN, NAN, 2, NAN, NAN, NAN, 2}; // off diagonal are NANs because division by 0 - for (size_t i = 0; i < 3; i++) { - for (size_t j = 0; j < 3; j++) { - if (i == j) { - TEST(isEqualF(C(i,j), 2.f)); - } else { - TEST(isnan(C(i,j))); - } - } - } + TEST(C == Matrix3f(off_diagonal_nan)); // Test non-square matrix float data_43[12] = {1,3,2, From 973999a4d3c6d4d85bf0153230974fd9571f7846 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 23 Sep 2019 08:54:41 +0200 Subject: [PATCH 315/388] Fix some template type conversions and style --- matrix/AxisAngle.hpp | 2 +- matrix/Euler.hpp | 4 ++-- matrix/Matrix.hpp | 2 +- matrix/Quaternion.hpp | 26 +++++++++++++------------- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index c2aec911e1..b86a57930f 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -69,7 +69,7 @@ public: AxisAngle(const Quaternion &q) { AxisAngle &v = *this; - Type ang = Type(2.0f)*acos(q(0)); + Type ang = Type(2) * acos(q(0)); Type mag = sin(ang/2.0f); if (fabs(mag) > 0) { v(0) = ang*q(1)/mag; diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index ec82cf1314..a0b8226cbd 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -97,11 +97,11 @@ public: Type pi = Type(M_PI); if (Type(fabs(theta_val - pi / Type(2))) < Type(1.0e-3)) { - phi_val = Type(0.0); + phi_val = Type(0); psi_val = Type(atan2(dcm(1, 2), dcm(0, 2))); } else if (Type(fabs(theta_val + pi / Type(2))) < Type(1.0e-3)) { - phi_val = Type(0.0); + phi_val = Type(0); psi_val = Type(atan2(-dcm(1, 2), -dcm(0, 2))); } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 3849f66ac3..15d042e969 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -278,7 +278,7 @@ public: void operator/=(Type scalar) { Matrix &self = *this; - self = self * (Type(1.0f) / scalar); + self = self * (Type(1) / scalar); } inline void operator+=(Type scalar) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 2110ded9e3..ffa00b602b 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -143,12 +143,12 @@ public: Quaternion(const Euler &euler) { Quaternion &q = *this; - Type cosPhi_2 = Type(cos(euler.phi() / Type(2.0))); - Type cosTheta_2 = Type(cos(euler.theta() / Type(2.0))); - Type cosPsi_2 = Type(cos(euler.psi() / Type(2.0))); - Type sinPhi_2 = Type(sin(euler.phi() / Type(2.0))); - Type sinTheta_2 = Type(sin(euler.theta() / Type(2.0))); - Type sinPsi_2 = Type(sin(euler.psi() / Type(2.0))); + Type cosPhi_2 = Type(cos(euler.phi() / Type(2))); + Type cosTheta_2 = Type(cos(euler.theta() / Type(2))); + Type cosPsi_2 = Type(cos(euler.psi() / Type(2))); + Type sinPhi_2 = Type(sin(euler.phi() / Type(2))); + Type sinTheta_2 = Type(sin(euler.theta() / Type(2))); + Type sinPsi_2 = Type(sin(euler.psi() / Type(2))); q(0) = cosPhi_2 * cosTheta_2 * cosPsi_2 + sinPhi_2 * sinTheta_2 * sinPsi_2; q(1) = sinPhi_2 * cosTheta_2 * cosPsi_2 - @@ -170,10 +170,10 @@ public: Type angle = aa.norm(); Vector axis = aa.unit(); if (angle < Type(1e-10)) { - q(0) = Type(1.0); + q(0) = Type(1); q(1) = q(2) = q(3) = 0; } else { - Type magnitude = sin(angle / 2.0f); + Type magnitude = sin(angle / Type(2)); q(0) = cos(angle / 2.0f); q(1) = axis(0) * magnitude; q(2) = axis(1) * magnitude; @@ -368,7 +368,7 @@ public: Quaternion canonical() const { const Quaternion &q = *this; - if(q(0)= Type(1e-10)) { vec = vec / axis_magnitude; - vec = vec * wrap_pi(Type(2.0) * atan2(axis_magnitude, q(0))); + vec = vec * wrap_pi(Type(2) * atan2(axis_magnitude, q(0))); } return vec; From 7b34c1c51ddd272929706c854407a2153afa9a8f Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 30 Sep 2019 11:06:41 +0200 Subject: [PATCH 316/388] Enable branch coverage --- test/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 0dc8480731..e1f9d0ae9f 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -33,14 +33,14 @@ if (${CMAKE_BUILD_TYPE} STREQUAL "Coverage") add_custom_target(coverage_build COMMAND ${CMAKE_CTEST_COMMAND} - COMMAND lcov --capture --directory . --output-file coverage.info - COMMAND lcov --summary coverage.info + COMMAND lcov --capture --directory . --output-file coverage.info --rc lcov_branch_coverage=1 + COMMAND lcov --rc lcov_branch_coverage=1 --summary coverage.info WORKING_DIRECTORY ${CMAKE_BUILD_DIR} DEPENDS test_build ) add_custom_target(coverage_html - COMMAND genhtml coverage.info --output-directory out + COMMAND genhtml coverage.info --output-directory out --branch-coverage COMMAND x-www-browser out/index.html WORKING_DIRECTORY ${CMAKE_BUILD_DIR} DEPENDS coverage_build From 740324cf1ee2b2141c9bb00f2a61295753a88c82 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 3 Oct 2019 13:38:51 +0200 Subject: [PATCH 317/388] Make all array constructors explicit (#99) * Make all array constructors explicit to avoid accidental implicit casts like e.g. Vector3f v = 0; assigning nullpointer content. --- matrix/AxisAngle.hpp | 2 +- matrix/Dcm.hpp | 11 ++++++++++- matrix/Matrix.hpp | 4 ++-- matrix/Quaternion.hpp | 2 +- matrix/SquareMatrix.hpp | 7 ++++++- matrix/Vector.hpp | 2 +- matrix/Vector2.hpp | 2 +- matrix/Vector3.hpp | 2 +- test/attitude.cpp | 6 +----- 9 files changed, 24 insertions(+), 14 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index b86a57930f..e95c046514 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -37,7 +37,7 @@ public: * * @param data_ array */ - AxisAngle(const Type data_[3]) : + explicit AxisAngle(const Type data_[3]) : Vector(data_) { } diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 31ea35da5c..9a1c6524b2 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -56,7 +56,16 @@ public: * * @param _data pointer to array */ - Dcm(const Type *data_) : SquareMatrix(data_) + explicit Dcm(const Type data_[3][3]) : SquareMatrix(data_) + { + } + + /** + * Constructor from array + * + * @param _data pointer to array + */ + explicit Dcm(const Type data_[3*3]) : SquareMatrix(data_) { } diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 15d042e969..79831f7a7b 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -41,12 +41,12 @@ public: // Constructors Matrix() = default; - Matrix(const Type data_[M*N]) + explicit Matrix(const Type data_[M*N]) { memcpy(_data, data_, sizeof(_data)); } - Matrix(const Type data_[M][N]) + explicit Matrix(const Type data_[M][N]) { memcpy(_data, data_, sizeof(_data)); } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index ffa00b602b..a99a290f52 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -61,7 +61,7 @@ public: * * @param data_ array */ - Quaternion(const Type data_[4]) : + explicit Quaternion(const Type data_[4]) : Vector(data_) { } diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 6a8ed55606..aaface6627 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -28,7 +28,12 @@ class SquareMatrix : public Matrix public: SquareMatrix() = default; - SquareMatrix(const Type data_[M][M]) : + explicit SquareMatrix(const Type data_[M][M]) : + Matrix(data_) + { + } + + explicit SquareMatrix(const Type data_[M*M]) : Matrix(data_) { } diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index edac621ca6..e46247539f 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -29,7 +29,7 @@ public: { } - Vector(const Type data_[M]) : + explicit Vector(const Type data_[M]) : MatrixM1(data_) { } diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index 5e209bbbf2..4ca5023ad1 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -31,7 +31,7 @@ public: { } - Vector2(const Type data_[2]) : + explicit Vector2(const Type data_[2]) : Vector(data_) { } diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 4f2de37f0b..e449b2657f 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -39,7 +39,7 @@ public: { } - Vector3(const Type data_[3]) : + explicit Vector3(const Type data_[3]) : Vector(data_) { } diff --git a/test/attitude.cpp b/test/attitude.cpp index becb39602f..00f7a6fb6a 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -4,11 +4,10 @@ using namespace matrix; -namespace matrix { - // manually instantiated all files we intend to test // so that coverage works correctly // doesn't matter what test this is in +namespace matrix { template class Matrix; template class Vector3; template class Vector2; @@ -17,13 +16,10 @@ template class Quaternion; template class AxisAngle; template class Scalar; template class SquareMatrix; - } int main() { - - // check data Eulerf euler_check(0.1f, 0.2f, 0.3f); Quatf q_check(0.98334744f, 0.0342708f, 0.10602051f, .14357218f); From 92d1c8761ec8e5dbe9ba3f756cebd5e90956a1b2 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Thu, 3 Oct 2019 13:47:36 +0200 Subject: [PATCH 318/388] More features: longerThan, norm, copyTo and slice on a Slice (#97) * Allow slices of slices, add longerThan to Vector/Slice --- matrix/Matrix.hpp | 4 +-- matrix/Slice.hpp | 69 +++++++++++++++++++++++++++++++++++---- matrix/Vector.hpp | 5 +++ test/copyto.cpp | 14 ++++++++ test/matrixAssignment.cpp | 2 ++ test/slice.cpp | 28 ++++++++++++++++ test/vector.cpp | 7 ++++ 7 files changed, 121 insertions(+), 8 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 79831f7a7b..155ae0736e 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -90,12 +90,12 @@ public: return (*this); } - void copyTo(Type dst [M*N]) const + void copyTo(Type dst[M*N]) const { memcpy(dst, _data, sizeof(Type)*M*N); } - void copyToColumnMajor(Type (&dst)[M*N]) const + void copyToColumnMajor(Type dst[M*N]) const { const Matrix &self = *this; diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index cff1521690..3a1008c21a 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -41,38 +41,95 @@ public: } template - Slice& operator=(const Slice& in_matrix) + Slice& operator=(const Slice& other) { Slice& self = *this; for (size_t i = 0; i < P; i++) { for (size_t j = 0; j < Q; j++) { - self(i, j) = in_matrix(i, j); + self(i, j) = other(i, j); } } return self; } - Slice& operator=(const Matrix& in_matrix) + Slice& operator=(const Matrix& other) { Slice& self = *this; for (size_t i = 0; i < P; i++) { for (size_t j = 0; j < Q; j++) { - self(i, j) = in_matrix(i, j); + self(i, j) = other(i, j); } } return self; } // allow assigning vectors to a slice that are in the axis - Slice& operator=(const Vector& in_vector) + template // make this a template function since it only exists for some instantiations + Slice& operator=(const Vector& other) { Slice& self = *this; for (size_t j = 0; j < Q; j++) { - self(0, j) = in_vector(j); + self(0, j) = other(j); } return self; } + template + const Slice slice(size_t x0, size_t y0) const + { + return Slice(x0 + _x0, y0 + _y0, _data); + } + + template + Slice slice(size_t x0, size_t y0) + { + return Slice(x0 + _x0, y0 + _y0, _data); + } + + void copyTo(Type dst[M*N]) const + { + const Slice &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + dst[i*N+j] = self(i, j); + } + } + } + + void copyToColumnMajor(Type dst[M*N]) const + { + const Slice &self = *this; + + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + dst[i+(j*M)] = self(i, j); + } + } + } + + Type norm_squared() + { + Slice& self = *this; + Type accum(0); + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + accum += self(i, j)*self(i, j); + } + } + return accum; + } + + Type norm() + { + return matrix::sqrt(norm_squared()); + } + + bool longerThan(Type testVal) + { + return norm_squared() > testVal*testVal; + } + private: size_t _x0, _y0; Matrix* _data; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index e46247539f..d517db45f6 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -104,6 +104,11 @@ public: return unit(); } + bool longerThan(Type testVal) + { + return norm_squared() > testVal*testVal; + } + Vector sqrt() const { const Vector &a(*this); Vector r; diff --git a/test/copyto.cpp b/test/copyto.cpp index 47a209edc6..4989adb0f1 100644 --- a/test/copyto.cpp +++ b/test/copyto.cpp @@ -52,6 +52,20 @@ int main() TEST(fabs(array_A[i] - array_column[i]) < eps); } + // Slice copyTo + float dst5[2] = {}; + v.slice<2,1>(0,0).copyTo(dst5); + for (size_t i = 0; i < 2; i++) { + TEST(fabs(v(i) - dst5[i]) < eps); + } + + float subarray_A[4] = {}; + A.slice<2,2>(0,0).copyToColumnMajor(subarray_A); + float subarray_column[4] = {1,4,2,5}; + for (size_t i = 0; i < 4; i++) { + TEST(fabs(subarray_A[i] - subarray_column[i]) < eps); + } + return 0; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 00b6e88ab1..070d1f1840 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -3,6 +3,8 @@ using namespace matrix; +template class matrix::Matrix; + int main() { Matrix3f m; diff --git a/test/slice.cpp b/test/slice.cpp index f92fef99df..36c252a742 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -3,6 +3,9 @@ using namespace matrix; +template class matrix::Slice; // so that we get full coverage results + + int main() { float data[9] = {0, 2, 3, @@ -97,6 +100,31 @@ int main() Matrix K_check(data_4_check); TEST(isEqual(K, K_check)); } + + // check that slice of a slice works for reading + const Matrix cm33(data); + Matrix topRight = cm33.slice<2,3>(0,0).slice<2,1>(0,2); + float top_right_check[2] = {3,6}; + TEST(isEqual(topRight, Matrix(top_right_check))); + + // check that slice of a slice works for writing + Matrix m33(data); + m33.slice<2,3>(0,0).slice<2,1>(0,2) = Matrix(); + const float data_check[9] = {0, 2, 0, + 4, 5, 0, + 7, 8, 10 + }; + TEST(isEqual(m33, Matrix(data_check))); + + // longerThan + Vector3f v5; + v5(0) = 3; + v5(1) = 4; + v5(2) = 9; + TEST(v5.xy().longerThan(4.99f)); + TEST(!v5.xy().longerThan(5.f)); + TEST(isEqualF(5.f, v5.xy().norm())); + return 0; } diff --git a/test/vector.cpp b/test/vector.cpp index c9463064b8..638ae1220f 100644 --- a/test/vector.cpp +++ b/test/vector.cpp @@ -35,6 +35,13 @@ int main() Vector v4(data1_sq); TEST(isEqual(v1, v4.sqrt())); + // longerThan + Vector v5; + v5(0) = 3; + v5(1) = 4; + TEST(v5.longerThan(4.99f)); + TEST(!v5.longerThan(5.f)); + return 0; } From 215203fc6fcb87d79a1ad8ef390fd243e6306d08 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Wed, 23 Oct 2019 12:07:51 +0200 Subject: [PATCH 319/388] Automatic Differentiation 'Dual' Type (#100) * Dual numbers initial implementation * Add test coverage, with partial derivative example * Add Jacobian test, fix small issues * Improve test to demonstrate non-square jacobian * Better naming for collectReals/Derivatives * Improve comments * Potential GCC 4.8 bug workaround * Add fallback workaround for non-IEEE float platforms --- matrix/Dual.hpp | 355 ++++++++++++++++++++++++++++++++++++++++++ matrix/Matrix.hpp | 26 +++- matrix/Quaternion.hpp | 16 +- matrix/Vector.hpp | 4 +- matrix/math.hpp | 1 + test/CMakeLists.txt | 1 + test/dual.cpp | 310 ++++++++++++++++++++++++++++++++++++ 7 files changed, 699 insertions(+), 14 deletions(-) create mode 100644 matrix/Dual.hpp create mode 100644 test/dual.cpp diff --git a/matrix/Dual.hpp b/matrix/Dual.hpp new file mode 100644 index 0000000000..8fbdcf157a --- /dev/null +++ b/matrix/Dual.hpp @@ -0,0 +1,355 @@ +/** + * @file Dual.hpp + * + * This is a dual number type for calculating automatic derivatives. + * + * Based roughly on the methods described in: + * Automatic Differentiation, C++ Templates and Photogrammetry, by Dan Piponi + * and + * Ceres Solver's excellent Jet.h + * + * @author Julian Kent + */ + +#pragma once + +#include "math.hpp" + +namespace matrix +{ + +template +class Vector; + +template +struct Dual +{ + static constexpr size_t WIDTH = N; + + Scalar value {}; + Vector derivative; + + Dual() = default; + + explicit Dual(Scalar v, size_t inputDimension = 65535) + { + value = v; + if (inputDimension < N) { + derivative(inputDimension) = Scalar(1); + } + } + + explicit Dual(Scalar v, const Vector& d) : + value(v), derivative(d) + {} + + Dual& operator=(const Scalar& a) + { + derivative.setZero(); + value = a; + return *this; + } + + Dual& operator +=(const Dual& a) + { + return (*this = *this + a); + } + + Dual& operator *=(const Dual& a) + { + return (*this = *this * a); + } + + Dual& operator -=(const Dual& a) + { + return (*this = *this - a); + } + + Dual& operator /=(const Dual& a) + { + return (*this = *this / a); + } + + Dual& operator +=(Scalar a) + { + return (*this = *this + a); + } + + Dual& operator -=(Scalar a) + { + return (*this = *this - a); + } + + Dual& operator *=(Scalar a) + { + return (*this = *this * a); + } + + Dual& operator /=(Scalar a) + { + return (*this = *this / a); + } + +}; + +// operators + +template +Dual operator+(const Dual& a) +{ + return a; +} + +template +Dual operator-(const Dual& a) +{ + return Dual(-a.value, -a.derivative); +} + +template +Dual operator+(const Dual& a, const Dual& b) +{ + return Dual(a.value + b.value, a.derivative + b.derivative); +} + +template +Dual operator-(const Dual& a, const Dual& b) +{ + return a + (-b); +} + +template +Dual operator+(const Dual& a, Scalar b) +{ + return Dual(a.value + b, a.derivative); +} + +template +Dual operator-(const Dual& a, Scalar b) +{ + return a + (-b); +} + +template +Dual operator+(Scalar a, const Dual& b) +{ + return Dual(a + b.value, b.derivative); +} + +template +Dual operator-(Scalar a, const Dual& b) +{ + return a + (-b); +} + +template +Dual operator*(const Dual& a, const Dual& b) +{ + return Dual(a.value * b.value, a.value * b.derivative + b.value * a.derivative); +} + +template +Dual operator*(const Dual& a, Scalar b) +{ + return Dual(a.value * b, a.derivative * b); +} + +template +Dual operator*(Scalar a, const Dual& b) +{ + return b * a; +} + +template +Dual operator/(const Dual& a, const Dual& b) +{ + const Scalar inv_b_real = Scalar(1) / b.value; + return Dual(a.value * inv_b_real, a.derivative * inv_b_real - + a.value * b.derivative * inv_b_real * inv_b_real); +} + +template +Dual operator/(const Dual& a, Scalar b) +{ + return a * (Scalar(1) / b); +} + +template +Dual operator/(Scalar a, const Dual& b) +{ + const Scalar inv_b_real = Scalar(1) / b.value; + return Dual(a * inv_b_real, (-inv_b_real * a * inv_b_real) * b.derivative); +} + +// basic math + +// sqrt +template +Dual sqrt(const Dual& a) +{ + Scalar real = sqrt(a.value); + return Dual(real, a.derivative * (Scalar(1) / (Scalar(2) * real))); +} + +// abs +template +Dual abs(const Dual& a) +{ + return a.value >= Scalar(0) ? a : -a; +} + +// ceil +template +Dual ceil(const Dual& a) +{ + return Dual(ceil(a.value)); +} + +// floor +template +Dual floor(const Dual& a) +{ + return Dual(floor(a.value)); +} + +// fmod +template +Dual fmod(const Dual& a, Scalar mod) +{ + return Dual(a.value - Scalar(size_t(a.value / mod)) * mod, a.derivative); +} + +// max +template +Dual max(const Dual& a, const Dual& b) +{ + return a.value >= b.value ? a : b; +} + +// min +template +Dual min(const Dual& a, const Dual& b) +{ + return a.value < b.value ? a : b; +} + +// isnan +template +bool isnan(const Dual& a) +{ + return isnan(a.value); +} + +// isfinite +template +bool isfinite(const Dual& a) +{ + return isfinite(a.value); +} + +// isinf +template +bool isinf(const Dual& a) +{ + return isinf(a.value); +} + +// trig + +// sin +template +Dual sin(const Dual& a) +{ + return Dual(sin(a.value), cos(a.value) * a.derivative); +} + +// cos +template +Dual cos(const Dual& a) +{ + return Dual(cos(a.value), -sin(a.value) * a.derivative); +} + +// tan +template +Dual tan(const Dual& a) +{ + Scalar real = tan(a.value); + return Dual(real, (Scalar(1) + real * real) * a.derivative); +} + +// asin +template +Dual asin(const Dual& a) +{ + Scalar asin_d = Scalar(1) / sqrt(Scalar(1) - a.value * a.value); + return Dual(asin(a.value), asin_d * a.derivative); +} + +// acos +template +Dual acos(const Dual& a) +{ + Scalar acos_d = -Scalar(1) / sqrt(Scalar(1) - a.value * a.value); + return Dual(acos(a.value), acos_d * a.derivative); +} + +// atan +template +Dual atan(const Dual& a) +{ + Scalar atan_d = Scalar(1) / (Scalar(1) + a.value * a.value); + return Dual(atan(a.value), atan_d * a.derivative); +} + +// atan2 +template +Dual atan2(const Dual& a, const Dual& b) +{ + // derivative is equal to that of atan(a/b), so substitute a/b into atan and simplify + Scalar atan_d = Scalar(1) / (a.value * a.value + b.value * b.value); + return Dual(atan2(a.value, b.value), (a.derivative * b.value - a.value * b.derivative) * atan_d); +} + +// retrieve the derivative elements of a vector of Duals into a matrix +template +Matrix collectDerivatives(const Matrix, M, 1>& input) +{ + Matrix jac; + for (size_t i = 0; i < M; i++) { + jac.row(i) = input(i, 0).derivative; + } + return jac; +} + +// retrieve the real (non-derivative) elements of a matrix of Duals into an equally sized matrix +template +Matrix collectReals(const Matrix, M, N>& input) +{ + Matrix r; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + r(i,j) = input(i,j).value; + } + } + return r; +} + +#if defined(SUPPORT_STDIOSTREAM) +template +std::ostream& operator<<(std::ostream& os, + const matrix::Dual& dual) +{ + os << "["; + os << std::setw(10) << dual.value << ";"; + for (size_t j = 0; j < N; ++j) { + os << "\t"; + os << std::setw(10) << static_cast(dual.derivative(j)); + } + os << "]"; + return os; +} +#endif // defined(SUPPORT_STDIOSTREAM) + +} + diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 155ae0736e..ff1f0541cc 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -34,12 +34,23 @@ template class Matrix { - Type _data[M][N] {}; + Type _data[M][N]; public: // Constructors - Matrix() = default; + Matrix() + { +#ifdef __STDC_IEC_559__ + memset(_data, 0, sizeof(_data)); //workaround for GCC 4.8 bug, don't use {} for array init +#else + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + _data[i][j] = Type{}; + } + } +#endif + } explicit Matrix(const Type data_[M*N]) { @@ -558,7 +569,14 @@ Matrix operator*(Type scalar, const Matrix &other) template bool isEqual(const Matrix &x, const Matrix &y, const Type eps=1e-4f) { - return x == y; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + if (!isEqualF(x(i,j), y(i,j), eps)) { + return false; + } + } + } + return true; } #if defined(SUPPORT_STDIOSTREAM) @@ -569,7 +587,7 @@ std::ostream& operator<<(std::ostream& os, for (size_t i = 0; i < M; ++i) { os << "["; for (size_t j = 0; j < N; ++j) { - os << std::setw(10) << static_cast(matrix(i, j)); + os << std::setw(10) << matrix(i, j); os << "\t"; } os << "]" << std::endl; diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index a99a290f52..f0a1d6c457 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -395,11 +395,11 @@ public: * @param vec vector to rotate in frame 1 (typically body frame) * @return rotated vector in frame 2 (typically reference frame) */ - Vector3f conjugate(const Vector3f &vec) { - Quaternion q = *this; - Quaternion v(0, vec(0), vec(1), vec(2)); + Vector3 conjugate(const Vector3 &vec) const { + const Quaternion& q = *this; + Quaternion v(Type(0), vec(0), vec(1), vec(2)); Quaternion res = q*v*q.inversed(); - return Vector3f(res(1), res(2), res(3)); + return Vector3(res(1), res(2), res(3)); } /** @@ -411,12 +411,12 @@ public: * @param vec vector to rotate in frame 2 (typically reference frame) * @return rotated vector in frame 1 (typically body frame) */ - Vector3f conjugate_inversed(const Vector3f &vec) const + Vector3 conjugate_inversed(const Vector3 &vec) const { - Quaternion q = *this; - Quaternion v(0, vec(0), vec(1), vec(2)); + const Quaternion& q = *this; + Quaternion v(Type(0), vec(0), vec(1), vec(2)); Quaternion res = q.inversed()*v*q; - return Vector3f(res(1), res(2), res(3)); + return Vector3(res(1), res(2), res(3)); } /** diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index d517db45f6..4af611542f 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -54,7 +54,7 @@ public: Type dot(const MatrixM1 & b) const { const Vector &a(*this); - Type r = 0; + Type r(0); for (size_t i = 0; i +#include + +using namespace matrix; + +template +bool isEqualAll(Dual a, Dual b) +{ + return isEqualF(a.value, b.value) && a.derivative == b.derivative; +} + +template +T testFunction(const Vector& point) { + // function is f(x,y,z) = x^2 + 2xy + 3y^2 + z + return point(0)*point(0) + + 2.f * point(0) * point(1) + + 3.f * point(1) * point(1) + + point(2); +} + +template +Vector positionError(const Vector& positionState, + const Vector& velocityStateBody, + const Quaternion& bodyOrientation, + const Vector& positionMeasurement, + Scalar dt + ) +{ + return positionMeasurement - (positionState + bodyOrientation.conjugate(velocityStateBody) * dt); +} + +int main() +{ + const Dual a(3,0); + const Dual b(6,0); + + { + TEST(isEqualF(a.value, 3.f)); + TEST(isEqualF(a.derivative(0), 1.f)); + } + + { + // addition + Dual c = a + b; + TEST(isEqualF(c.value, 9.f)); + TEST(isEqualF(c.derivative(0), 2.f)); + + Dual d = +a; + TEST(isEqualAll(d, a)); + d += b; + TEST(isEqualAll(d, c)); + + Dual e = a; + e += b.value; + TEST(isEqualF(e.value, c.value)); + TEST(isEqual(e.derivative, a.derivative)); + + Dual f = b.value + a; + TEST(isEqualAll(f, e)); + } + + { + // subtraction + Dual c = b - a; + TEST(isEqualF(c.value, 3.f)); + TEST(isEqualF(c.derivative(0), 0.f)); + + Dual d = b; + TEST(isEqualAll(d, b)); + d -= a; + TEST(isEqualAll(d, c)); + + Dual e = b; + e -= a.value; + TEST(isEqualF(e.value, c.value)); + TEST(isEqual(e.derivative, b.derivative)); + + Dual f = a.value - b; + TEST(isEqualAll(f, -e)); + } + + { + // multiplication + Dual c = a*b; + TEST(isEqualF(c.value, 18.f)); + TEST(isEqualF(c.derivative(0), 9.f)); + + Dual d = a; + TEST(isEqualAll(d, a)); + d *= b; + TEST(isEqualAll(d, c)); + + Dual e = a; + e *= b.value; + TEST(isEqualF(e.value, c.value)); + TEST(isEqual(e.derivative, a.derivative * b.value)); + + Dual f = b.value * a; + TEST(isEqualAll(f, e)); + } + + { + // division + Dual c = b/a; + TEST(isEqualF(c.value, 2.f)); + TEST(isEqualF(c.derivative(0), -1.f/3.f)); + + Dual d = b; + TEST(isEqualAll(d, b)); + d /= a; + TEST(isEqualAll(d, c)); + + Dual e = b; + e /= a.value; + TEST(isEqualF(e.value, c.value)); + TEST(isEqual(e.derivative, b.derivative / a.value)); + + Dual f = a.value / b; + TEST(isEqualAll(f, 1.f/e)); + } + + { + Dual blank; + TEST(isEqualF(blank.value, 0.f)); + TEST(isEqualF(blank.derivative(0), 0.f)); + } + + { + // sqrt + TEST(isEqualF(sqrt(a).value, sqrt(a.value))); + TEST(isEqualF(sqrt(a).derivative(0), 1.f/sqrt(12.f))); + } + + { + // abs + TEST(isEqualAll(a, abs(-a))); + TEST(!isEqualAll(-a, abs(a))); + TEST(isEqualAll(-a, -abs(a))); + } + + { + // ceil + Dual c(1.5,0); + TEST(isEqualF(ceil(c).value, ceil(c.value))); + TEST(isEqualF(ceil(c).derivative(0), 0.f)); + } + + { + // floor + Dual c(1.5,0); + TEST(isEqualF(floor(c).value, floor(c.value))); + TEST(isEqualF(floor(c).derivative(0), 0.f)); + } + + { + // fmod + TEST(isEqualF(fmod(a, 0.8f).value, fmod(a.value, 0.8f))); + TEST(isEqual(fmod(a, 0.8f).derivative, a.derivative)); + } + + { + // max/min + TEST(isEqualAll(b, max(a, b))); + TEST(isEqualAll(a, min(a, b))); + } + + { + // isnan + TEST(!isnan(a)); + Dual c(sqrt(-1.f),0); + TEST(isnan(c)); + } + + { + // isfinite/isinf + TEST(isfinite(a)); + TEST(!isinf(a)); + Dual c(sqrt(-1.f),0); + TEST(!isfinite(c)); + TEST(!isinf(c)); + Dual d(INFINITY,0); + TEST(!isfinite(d)); + TEST(isinf(d)); + } + + { + // sin/cos/tan + TEST(isEqualF(sin(a).value, sin(a.value))); + TEST(isEqualF(sin(a).derivative(0), cos(a.value))); // sin'(x) = cos(x) + + TEST(isEqualF(cos(a).value, cos(a.value))); + TEST(isEqualF(cos(a).derivative(0), -sin(a.value))); // cos'(x) = -sin(x) + + TEST(isEqualF(tan(a).value, tan(a.value))); + TEST(isEqualF(tan(a).derivative(0), 1.f + tan(a.value)*tan(a.value))); // tan'(x) = 1 + tan^2(x) + } + + { + // asin/acos/atan + Dual c(0.3f, 0); + TEST(isEqualF(asin(c).value, asin(c.value))); + TEST(isEqualF(asin(c).derivative(0), 1.f/sqrt(1.f - 0.3f*0.3f))); // asin'(x) = 1/sqrt(1-x^2) + + TEST(isEqualF(acos(c).value, acos(c.value))); + TEST(isEqualF(acos(c).derivative(0), -1.f/sqrt(1.f - 0.3f*0.3f))); // acos'(x) = -1/sqrt(1-x^2) + + TEST(isEqualF(atan(c).value, atan(c.value))); + TEST(isEqualF(atan(c).derivative(0), 1.f/(1.f + 0.3f*0.3f))); // tan'(x) = 1 + x^2 + } + + { + // atan2 + TEST(isEqualF(atan2(a, b).value, atan2(a.value, b.value))); + TEST(isEqualAll(atan2(a, Dual(b.value)), atan(a/b.value))); // atan2'(y, x) = atan'(y/x) + } + + { + // partial derivatives + // function is f(x,y,z) = x^2 + 2xy + 3y^2 + z, we need with respect to d/dx and d/dy at the point (0.5, -0.8, 2) + + using D = Dual; + + // set our starting point, requesting partial derivatives of x and y in column 0 and 1 + Vector3 dualPoint(D(0.5f, 0), D(-0.8f, 1), D(2.f)); + + Dual dualResult = testFunction(dualPoint); + + // compare to a numerical derivative: + Vector floatPoint = collectReals(dualPoint); + float floatResult = testFunction(floatPoint); + + float h = 0.0001f; + Vector floatPoint_plusDX = floatPoint; + floatPoint_plusDX(0) += h; + float floatResult_plusDX = testFunction(floatPoint_plusDX); + + Vector floatPoint_plusDY = floatPoint; + floatPoint_plusDY(1) += h; + float floatResult_plusDY = testFunction(floatPoint_plusDY); + + Vector2f numerical_derivative((floatResult_plusDX - floatResult)/h, + (floatResult_plusDY - floatResult)/h); + + TEST(isEqualF(dualResult.value, floatResult, 0.0f)); + TEST(isEqual(dualResult.derivative, numerical_derivative, 1e-2f)); + + } + + { + // jacobian + // get residual of x/y/z with partial derivatives of rotation + + Vector3f direct_error; + Matrix numerical_jacobian; + { + Vector3f positionState(5,6,7); + Vector3f velocityState(-1,0,1); + Quaternionf velocityOrientation(0.2f,-0.1f,0,1); + Vector3f positionMeasurement(4.5f, 6.2f, 7.9f); + float dt = 0.1f; + + direct_error = positionError(positionState, + velocityState, + velocityOrientation, + positionMeasurement, + dt); + float h = 0.001f; + for (size_t i = 0; i < 4; i++) + { + Quaternion h4 = velocityOrientation; + h4(i) += h; + numerical_jacobian.col(i) = (positionError(positionState, + velocityState, + h4, + positionMeasurement, + dt) + - direct_error)/h; + } + } + Vector3f auto_error; + Matrix auto_jacobian; + { + using D4 = Dual; + using Vector3d4 = Vector3; + Vector3d4 positionState(D4(5), D4(6), D4(7)); + Vector3d4 velocityState(D4(-1), D4(0), D4(1)); + + // request partial derivatives of velocity orientation + // by setting these variables' derivatives in corresponding columns [0...3] + Quaternion velocityOrientation(D4(0.2f, 0),D4(-0.1f, 1),D4(0, 2),D4(1, 3)); + + Vector3d4 positionMeasurement(D4(4.5f), D4(6.2f), D4(7.9f)); + D4 dt(0.1f); + + + Vector3d4 error = positionError(positionState, + velocityState, + velocityOrientation, + positionMeasurement, + dt); + auto_error = collectReals(error); + auto_jacobian = collectDerivatives(error); + } + TEST(isEqual(direct_error, auto_error, 0.0f)); + TEST(isEqual(numerical_jacobian, auto_jacobian, 1e-3f)); + + } + return 0; +} From 445f58d484f08822488243bcc1c279bb137bf524 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Fri, 1 Nov 2019 14:23:35 +0100 Subject: [PATCH 320/388] Fix weird C preprocessor conflicts (#101) --- matrix/Dual.hpp | 36 +++++++++++++++++++++++++++--------- test/dual.cpp | 16 ++++++++-------- 2 files changed, 35 insertions(+), 17 deletions(-) diff --git a/matrix/Dual.hpp b/matrix/Dual.hpp index 8fbdcf157a..da8eabf9e8 100644 --- a/matrix/Dual.hpp +++ b/matrix/Dual.hpp @@ -234,24 +234,42 @@ Dual min(const Dual& a, const Dual& b) } // isnan -template -bool isnan(const Dual& a) +template +bool IsNan(Scalar a) { - return isnan(a.value); + return isnan(a); +} + +template +bool IsNan(const Dual& a) +{ + return IsNan(a.value); } // isfinite -template -bool isfinite(const Dual& a) +template +bool IsFinite(Scalar a) { - return isfinite(a.value); + return isfinite(a); +} + +template +bool IsFinite(const Dual& a) +{ + return IsFinite(a.value); } // isinf -template -bool isinf(const Dual& a) +template +bool IsInf(Scalar a) { - return isinf(a.value); + return isinf(a); +} + +template +bool IsInf(const Dual& a) +{ + return IsInf(a.value); } // trig diff --git a/test/dual.cpp b/test/dual.cpp index cb6b7fc5c8..7d5fbb9db7 100644 --- a/test/dual.cpp +++ b/test/dual.cpp @@ -167,21 +167,21 @@ int main() { // isnan - TEST(!isnan(a)); + TEST(!IsNan(a)); Dual c(sqrt(-1.f),0); - TEST(isnan(c)); + TEST(IsNan(c)); } { // isfinite/isinf - TEST(isfinite(a)); - TEST(!isinf(a)); + TEST(IsFinite(a)); + TEST(!IsInf(a)); Dual c(sqrt(-1.f),0); - TEST(!isfinite(c)); - TEST(!isinf(c)); + TEST(!IsFinite(c)); + TEST(!IsInf(c)); Dual d(INFINITY,0); - TEST(!isfinite(d)); - TEST(isinf(d)); + TEST(!IsFinite(d)); + TEST(IsInf(d)); } { From 9f464839510a2779b9418ffbc2303a31f155e851 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 4 Nov 2019 10:25:21 +0100 Subject: [PATCH 321/388] Fix GCC-4.8 bug --- matrix/Matrix.hpp | 33 +++++++++++++++++---------------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index ff1f0541cc..1954934ffd 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -18,6 +18,14 @@ #include "math.hpp" +// There is a bug in GCC 4.8, which causes the compiler to segfault due to array {} constructors. +// Do for-loop constructors just for GCC 4.8 +#ifdef __GNUC__ +#define MATRIX_GCC_4_8_WORKAROUND (__GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 9)) +#else +#define MATRIX_GCC_4_8_WORKAROUND 0 +#endif + namespace matrix { @@ -33,24 +41,27 @@ class Slice; template class Matrix { - +#if MATRIX_GCC_4_8_WORKAROUND Type _data[M][N]; +#else + Type _data[M][N] {}; +#endif public: // Constructors +#if MATRIX_GCC_4_8_WORKAROUND Matrix() { -#ifdef __STDC_IEC_559__ - memset(_data, 0, sizeof(_data)); //workaround for GCC 4.8 bug, don't use {} for array init -#else for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { _data[i][j] = Type{}; } } -#endif } +#else + Matrix() = default; +#endif explicit Matrix(const Type data_[M*N]) { @@ -304,17 +315,7 @@ public: bool operator==(const Matrix &other) const { - const Matrix &self = *this; - - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - if (!isEqualF(self(i, j), other(i, j))) { - return false; - } - } - } - - return true; + return isEqual(*this, other); } bool operator!=(const Matrix &other) const From 93d42947b612733d2bd05e66ae093ada3e35ba12 Mon Sep 17 00:00:00 2001 From: kritz Date: Fri, 8 Nov 2019 17:27:33 +0100 Subject: [PATCH 322/388] Add test for setting Quaternion to Identity (#104) --- test/attitude.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/test/attitude.cpp b/test/attitude.cpp index 00f7a6fb6a..86ba63d894 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -265,6 +265,12 @@ int main() TEST(isEqual(q_non_canonical,q_canonical_ref)); TEST(isEqual(q_canonical,q_canonical_ref)); + // quaternion setIdentity + Quatf q_nonIdentity(-0.7f, 0.4f, 0.5f, -0.3f); + Quatf q_identity(1.0f, 0.0f, 0.0f, 0.0f); + q_nonIdentity.setIdentity(); + TEST(isEqual(q_nonIdentity, q_identity)); + // non-unit quaternion invese Quatf qI(1.0f, 0.0f, 0.0f, 0.0f); Quatf q_nonunit(0.1f, 0.2f, 0.3f, 0.4f); From 38e966cea1f745a25bf03783cf8028889a150a03 Mon Sep 17 00:00:00 2001 From: kritz Date: Tue, 12 Nov 2019 18:57:12 +0100 Subject: [PATCH 323/388] Add min, max, constrain function for Matrix (#105) * Add min, max, constrain function for Matrix * Set individual elements to nan in constrain * Deal with NANs --- matrix/Matrix.hpp | 122 ++++++++++++++++++++++++++++++++++++++ test/matrixAssignment.cpp | 54 +++++++++++++++++ 2 files changed, 176 insertions(+) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 1954934ffd..22d26a8018 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -580,6 +580,128 @@ bool isEqual(const Matrix &x, return true; } +namespace typeFunction +{ +template +Type min(const Type x, const Type y) { + bool x_is_nan = isnan(x); + bool y_is_nan = isnan(y); + // z > nan for z != nan is required by C the standard + if(x_is_nan || y_is_nan) { + if(x_is_nan && !y_is_nan) return y; + if(!x_is_nan && y_is_nan) return x; + return x; + } + return (x < y) ? x : y; +} +template +Type max(const Type x, const Type y) { + bool x_is_nan = isnan(x); + bool y_is_nan = isnan(y); + // z > nan for z != nan is required by C the standard + if(x_is_nan || y_is_nan) { + if(x_is_nan && !y_is_nan) return y; + if(!x_is_nan && y_is_nan) return x; + return x; + } + return (x > y) ? x : y; +} +template +Type constrain(const Type x, const Type lower_bound, const Type upper_bound) { + if(lower_bound > upper_bound) { + return NAN; + } else if(isnan(x)) { + return NAN; + } else { + return typeFunction::max(lower_bound, typeFunction::min(upper_bound, x)); + } +} +} + +template +Matrix min(const Matrix &x, const Type scalar_upper_bound) { + Matrix m; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + m(i,j) = typeFunction::min(x(i,j),scalar_upper_bound); + } + } + return m; +} + +template +Matrix min(const Type scalar_upper_bound, const Matrix &x) { + return min(x, scalar_upper_bound); +} + +template +Matrix min(const Matrix &x1, const Matrix &x2) { + Matrix m; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + m(i,j) = typeFunction::min(x1(i,j),x2(i,j)); + } + } + return m; +} + +template +Matrix max(const Matrix &x, const Type scalar_lower_bound) { + Matrix m; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + m(i,j) = typeFunction::max(x(i,j),scalar_lower_bound); + } + } + return m; +} + +template +Matrix max(const Type scalar_lower_bound, const Matrix &x) { + return max(x, scalar_lower_bound); +} + +template +Matrix max(const Matrix &x1, const Matrix &x2) { + Matrix m; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + m(i,j) = typeFunction::max(x1(i,j),x2(i,j)); + } + } + return m; +} + +template +Matrix constrain(const Matrix &x, + const Type scalar_lower_bound, + const Type scalar_upper_bound) { + Matrix m; + if(scalar_lower_bound > scalar_upper_bound) { + m.setNaN(); + } else { + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + m(i,j) = typeFunction::constrain(x(i,j), scalar_lower_bound, scalar_upper_bound); + } + } + } + return m; +} + +template +Matrix constrain(const Matrix &x, + const Matrix &x_lower_bound, + const Matrix &x_upper_bound) { + Matrix m; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + m(i,j) = typeFunction::constrain(x(i,j), x_lower_bound(i,j), x_upper_bound(i,j)); + } + } + return m; +} + #if defined(SUPPORT_STDIOSTREAM) template std::ostream& operator<<(std::ostream& os, diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 070d1f1840..8774cc38c7 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -134,6 +134,60 @@ int main() m7.setNaN(); TEST(m7 != m8); + // min, max, constrain matrix values with scalar + float data_m9[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; + float lower_bound = 7; + float upper_bound = 11; + float data_m9_lower_bounded[9] = {7, 7, 7, 8, 10, 12, 14, 16, 18}; + float data_m9_upper_bounded[9] = {2, 4, 6, 8, 10, 11, 11, 11, 11}; + float data_m9_lower_constrained[9] = {7, 7, 7, 8, 10, 11, 11, 11, 11}; + Matrix3f m9(data_m9); + Matrix3f m9_lower_bounded(data_m9_lower_bounded); + Matrix3f m9_upper_bounded(data_m9_upper_bounded); + Matrix3f m9_lower_upper_constrained(data_m9_lower_constrained); + TEST(isEqual(max(m9, lower_bound), m9_lower_bounded)); + TEST(isEqual(max(lower_bound, m9), m9_lower_bounded)); + TEST(isEqual(min(m9, upper_bound), m9_upper_bounded)); + TEST(isEqual(min(upper_bound, m9), m9_upper_bounded)); + TEST(isEqual(constrain(m9, lower_bound, upper_bound), m9_lower_upper_constrained)); + TEST(isEqual(constrain(m9, 8.0f, 7.0f), m_nan)); + + // min, max, constrain matrix values with matrix of same size + float data_m10[9] = {2, 4, 6, 8, 10, 12, 14, 16, 18}; + float data_m10_lower_bound[9] = {5, 7, 4, 8, 19, 10, 20, 16, 18}; + float data_m10_lower_bounded_ref[9] = {5, 7, 6, 8, 19, 12, 20, 16, 18}; + float data_m10_upper_bound[9] = {6, 4, 8, 18, 20, 11, 30, 16, 18}; + float data_m10_upper_bounded_ref[9] = {2, 4, 6, 8, 10, 11, 14, 16, 18}; + float data_m10_constrained_ref[9] = {5, NAN, 6, 8, 19, 11, 20, 16, 18}; + Matrix3f m10(data_m10); + Matrix3f m10_lower_bound(data_m10_lower_bound); + Matrix3f m10_lower_bounded_ref(data_m10_lower_bounded_ref); + Matrix3f m10_upper_bound(data_m10_upper_bound); + Matrix3f m10_upper_bounded_ref(data_m10_upper_bounded_ref); + Matrix3f m10_constrained_ref(data_m10_constrained_ref); + TEST(isEqual(max(m10, m10_lower_bound), m10_lower_bounded_ref)); + TEST(isEqual(max(m10_lower_bound, m10), m10_lower_bounded_ref)); + TEST(isEqual(min(m10, m10_upper_bound), m10_upper_bounded_ref)); + TEST(isEqual(min(m10_upper_bound, m9), m10_upper_bounded_ref)); + TEST(isEqual(constrain(m10, m10_lower_bound, m10_upper_bound), m10_constrained_ref)); + + // min, max, constrain with NAN + TEST(isEqualF(matrix::typeFunction::min(5.0f,NAN), 5.0f)); + TEST(isEqualF(matrix::typeFunction::min(NAN,5.0f), 5.0f)); + TEST(isEqualF(matrix::typeFunction::min(NAN,NAN), NAN)); + TEST(isEqualF(matrix::typeFunction::max(5.0f,NAN), 5.0f)); + TEST(isEqualF(matrix::typeFunction::max(NAN,5.0f), 5.0f)); + TEST(isEqualF(matrix::typeFunction::max(NAN,NAN), NAN)); + TEST(isEqualF(matrix::typeFunction::constrain(NAN,5.0f,6.0f), NAN)); + TEST(isEqualF(matrix::typeFunction::constrain(1.0f,5.0f,4.0f), NAN)); + TEST(isEqualF(matrix::typeFunction::constrain(6.0f,NAN,5.0f), 5.0f)); + TEST(isEqualF(matrix::typeFunction::constrain(1.0f,5.0f,NAN), 5.0f)); + Vector2f v1{NAN, 5.0f}; + Vector2f v1_min = min(v1,1.0f); + Matrix3f m11 = min(m10_constrained_ref,NAN); + TEST(isEqualF(fmin(NAN,1.0f), float(v1_min(0)))); + TEST(isEqual(m11, m10_constrained_ref)); + // check write_string() float comma[6] = { 1.f, 12345.678f, From cd185c995b6b28c12e06d20a2743a94bd68be7c2 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 13 Nov 2019 13:41:38 -0500 Subject: [PATCH 324/388] add braces around statements and cleanup formatting (#107) --- matrix/Matrix.hpp | 24 ++++++++++++++++-------- matrix/SquareMatrix.hpp | 4 ++-- 2 files changed, 18 insertions(+), 10 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 22d26a8018..0172669a5b 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -587,9 +587,13 @@ Type min(const Type x, const Type y) { bool x_is_nan = isnan(x); bool y_is_nan = isnan(y); // z > nan for z != nan is required by C the standard - if(x_is_nan || y_is_nan) { - if(x_is_nan && !y_is_nan) return y; - if(!x_is_nan && y_is_nan) return x; + if (x_is_nan || y_is_nan) { + if (x_is_nan && !y_is_nan) { + return y; + } + if (!x_is_nan && y_is_nan) { + return x; + } return x; } return (x < y) ? x : y; @@ -599,16 +603,20 @@ Type max(const Type x, const Type y) { bool x_is_nan = isnan(x); bool y_is_nan = isnan(y); // z > nan for z != nan is required by C the standard - if(x_is_nan || y_is_nan) { - if(x_is_nan && !y_is_nan) return y; - if(!x_is_nan && y_is_nan) return x; + if (x_is_nan || y_is_nan) { + if (x_is_nan && !y_is_nan) { + return y; + } + if (!x_is_nan && y_is_nan) { + return x; + } return x; } return (x > y) ? x : y; } template Type constrain(const Type x, const Type lower_bound, const Type upper_bound) { - if(lower_bound > upper_bound) { + if (lower_bound > upper_bound) { return NAN; } else if(isnan(x)) { return NAN; @@ -677,7 +685,7 @@ Matrix constrain(const Matrix &x, const Type scalar_lower_bound, const Type scalar_upper_bound) { Matrix m; - if(scalar_lower_bound > scalar_upper_bound) { + if (scalar_lower_bound > scalar_upper_bound) { m.setNaN(); } else { for (size_t i = 0; i < M; i++) { diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index aaface6627..175a3e40a7 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -65,7 +65,7 @@ public: inline SquareMatrix I() const { SquareMatrix i; - if(inv(*this, i)) { + if (inv(*this, i)) { return i; } else { i.setZero(); @@ -289,7 +289,7 @@ template SquareMatrix inv(const SquareMatrix & A) { SquareMatrix i; - if(inv(A, i)) { + if (inv(A, i)) { return i; } else { i.setZero(); From a172c3cdac9260369fb5805fcce19067121566e5 Mon Sep 17 00:00:00 2001 From: Julien Lecoeur Date: Mon, 18 Nov 2019 23:36:30 +0100 Subject: [PATCH 325/388] Add implementation of pseudo-inverse (#102) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Fix compilation error * Add implementation of pseudo-inverse The implementation is based on this publication: Courrieu, P. (2008). Fast Computation of Moore-Penrose Inverse Matrices, 8(2), 25–29. http://arxiv.org/abs/0804.4809 It is a fully templated implementation to guaranty type correctness. * Add tests for pseudoinverse * Apply suggestions from code review Co-Authored-By: Mathieu Bresciani * Adapt fullRankCholesky tolerance to type * Add pseudoinverse test with effectiveness matrix * Fix coverage * Fix rebase issue * Fix SquareMatrix test, add null Matrix test --- .gitignore | 1 + matrix/Dcm.hpp | 2 +- matrix/PseudoInverse.hpp | 56 ++++++++++++++++ matrix/PseudoInverse.hxx | 139 +++++++++++++++++++++++++++++++++++++++ matrix/math.hpp | 1 + test/CMakeLists.txt | 1 + test/pseudoInverse.cpp | 139 +++++++++++++++++++++++++++++++++++++++ 7 files changed, 338 insertions(+), 1 deletion(-) create mode 100644 matrix/PseudoInverse.hpp create mode 100644 matrix/PseudoInverse.hxx create mode 100644 test/pseudoInverse.cpp diff --git a/.gitignore b/.gitignore index 09e562fc8c..1edf5f525d 100644 --- a/.gitignore +++ b/.gitignore @@ -27,6 +27,7 @@ test/matrixAssignment test/matrixMult test/matrixScalarMult test/out/ +test/pseudoinverse test/setIdentity test/slice test/squareMatrix diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 9a1c6524b2..9b14868707 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -65,7 +65,7 @@ public: * * @param _data pointer to array */ - explicit Dcm(const Type data_[3*3]) : SquareMatrix(data_) + explicit Dcm(const Type data_[9]) : SquareMatrix(data_) { } diff --git a/matrix/PseudoInverse.hpp b/matrix/PseudoInverse.hpp new file mode 100644 index 0000000000..469e358100 --- /dev/null +++ b/matrix/PseudoInverse.hpp @@ -0,0 +1,56 @@ +/** + * @file PseudoInverse.hpp + * + * Implementation of matrix pseudo inverse + * + * @author Julien Lecoeur + */ + +#pragma once + +#include "math.hpp" + +namespace matrix +{ + +/** + * Full rank Cholesky factorization of A + */ +template +SquareMatrix fullRankCholesky(const SquareMatrix & A, size_t& rank); + +/** + * Geninv implementation detail + */ +template class GeninvImpl; + +/** + * Geninv + * Fast pseudoinverse based on full rank cholesky factorisation + * + * Courrieu, P. (2008). Fast Computation of Moore-Penrose Inverse Matrices, 8(2), 25–29. http://arxiv.org/abs/0804.4809 + */ +template +Matrix geninv(const Matrix & G) +{ + size_t rank; + if (M <= N) { + SquareMatrix A = G * G.transpose(); + SquareMatrix L = fullRankCholesky(A, rank); + + return GeninvImpl::genInvUnderdetermined(G, L, rank); + + } else { + SquareMatrix A = G.transpose() * G; + SquareMatrix L = fullRankCholesky(A, rank); + + return GeninvImpl::genInvOverdetermined(G, L, rank); + } +} + + +#include "PseudoInverse.hxx" + +} // namespace matrix + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ diff --git a/matrix/PseudoInverse.hxx b/matrix/PseudoInverse.hxx new file mode 100644 index 0000000000..99408f5e2f --- /dev/null +++ b/matrix/PseudoInverse.hxx @@ -0,0 +1,139 @@ +/** + * @file pseudoinverse.hxx + * + * Implementation of matrix pseudo inverse + * + * @author Julien Lecoeur + */ + + + +/** + * Full rank Cholesky factorization of A + */ +template +void fullRankCholeskyTolerance(Type &tol) +{ + tol /= 1000000000; +} + +template<> inline +void fullRankCholeskyTolerance(double &tol) +{ + tol /= 1000000000000000000.0; +} + +template +SquareMatrix fullRankCholesky(const SquareMatrix & A, + size_t& rank) +{ + // Compute + // dA = np.diag(A) + // tol = np.min(dA[dA > 0]) * 1e-9 + Vector d = A.diag(); + Type tol = d.max(); + for (size_t k = 0; k < N; k++) { + if ((d(k) > 0) && (d(k) < tol)) { + tol = d(k); + } + } + fullRankCholeskyTolerance(tol); + + Matrix L; + + size_t r = 0; + for (size_t k = 0; k < N; k++) { + + if (r == 0) { + for (size_t i = k; i < N; i++) { + L(i, r) = A(i, k); + } + + } else { + for (size_t i = k; i < N; i++) { + // Compute LL = L[k:n, :r] * L[k, :r].T + Type LL = Type(); + for (size_t j = 0; j < r; j++) { + LL += L(i, j) * L(k, j); + } + L(i, r) = A(i, k) - LL; + } + } + + if (L(k, r) > tol) { + L(k, r) = sqrt(L(k, r)); + + if (k < N - 1) { + for (size_t i = k + 1; i < N; i++) { + L(i, r) = L(i, r) / L(k, r); + } + } + + r = r + 1; + } + } + + // Return rank + rank = r; + + return L; +} + +template< typename Type, size_t M, size_t N, size_t R> +class GeninvImpl +{ +public: + static Matrix genInvUnderdetermined(const Matrix & G, const Matrix & L, size_t rank) + { + if (rank < R) { + // Recursive call + return GeninvImpl::genInvUnderdetermined(G, L, rank); + + } else if (rank > R) { + // Error + return Matrix(); + + } else { + // R == rank + Matrix LL = L. template slice(0, 0); + SquareMatrix X = inv(SquareMatrix(LL.transpose() * LL)); + return G.transpose() * LL * X * X * LL.transpose(); + + } + } + + static Matrix genInvOverdetermined(const Matrix & G, const Matrix & L, size_t rank) + { + if (rank < R) { + // Recursive call + return GeninvImpl::genInvOverdetermined(G, L, rank); + + } else if (rank > R) { + // Error + return Matrix(); + + } else { + // R == rank + Matrix LL = L. template slice(0, 0); + SquareMatrix X = inv(SquareMatrix(LL.transpose() * LL)); + return LL * X * X * LL.transpose() * G.transpose(); + + } + } +}; + +// Partial template specialisation for R==0, allows to stop recursion in genInvUnderdetermined and genInvOverdetermined +template< typename Type, size_t M, size_t N> +class GeninvImpl +{ +public: + static Matrix genInvUnderdetermined(const Matrix & G, const Matrix & L, size_t rank) + { + return Matrix(); + } + + static Matrix genInvOverdetermined(const Matrix & G, const Matrix & L, size_t rank) + { + return Matrix(); + } +}; diff --git a/matrix/math.hpp b/matrix/math.hpp index 1aa4b0ade4..1bb9d67243 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -18,3 +18,4 @@ #include "AxisAngle.hpp" #include "LeastSquaresSolver.hpp" #include "Dual.hpp" +#include "PseudoInverse.hpp" diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 8b0a0b3931..c1f8e7a024 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -20,6 +20,7 @@ set(tests least_squares upperRightTriangle dual + pseudoInverse ) add_custom_target(test_build) diff --git a/test/pseudoInverse.cpp b/test/pseudoInverse.cpp new file mode 100644 index 0000000000..476e45dd37 --- /dev/null +++ b/test/pseudoInverse.cpp @@ -0,0 +1,139 @@ +#include "test_macros.hpp" +#include + +using namespace matrix; + +static const size_t n_large = 20; + +int main() +{ + // 3x4 Matrix test + float data0[12] = { + 0.f, 1.f, 2.f, 3.f, + 4.f, 5.f, 6.f, 7.f, + 8.f, 9.f, 10.f, 11.f + }; + + float data0_check[12] = { + -0.3375f, -0.1f, 0.1375f, + -0.13333333f, -0.03333333f, 0.06666667f, + 0.07083333f, 0.03333333f, -0.00416667f, + 0.275f, 0.1f, -0.075f + }; + + Matrix A0(data0); + Matrix A0_I = geninv(A0); + Matrix A0_I_check(data0_check); + + TEST((A0_I - A0_I_check).abs().max() < 1e-5); + + // 4x3 Matrix test + float data1[12] = { + 0.f, 4.f, 8.f, + 1.f, 5.f, 9.f, + 2.f, 6.f, 10.f, + 3.f, 7.f, 11.f + }; + + float data1_check[12] = { + -0.3375f, -0.13333333f, 0.07083333f, 0.275f, + -0.1f, -0.03333333f, 0.03333333f, 0.1f, + 0.1375f, 0.06666667f, -0.00416667f, -0.075f + }; + + Matrix A1(data1); + Matrix A1_I = geninv(A1); + Matrix A1_I_check(data1_check); + + TEST((A1_I - A1_I_check).abs().max() < 1e-5); + + // Stess test + Matrix A_large; + A_large.setIdentity(); + Matrix A_large_I; + + for (size_t i = 0; i < n_large; i++) { + A_large_I = geninv(A_large); + TEST(isEqual(A_large, A_large_I.T())); + } + + // Square matrix test + float data2[9] = {0, 2, 3, + 4, 5, 6, + 7, 8, 10 + }; + float data2_check[9] = { + -0.4f, -0.8f, 0.6f, + -0.4f, 4.2f, -2.4f, + 0.6f, -2.8f, 1.6f + }; + + SquareMatrix A2(data2); + SquareMatrix A2_I = geninv(A2); + SquareMatrix A2_I_check(data2_check); + TEST((A2_I - A2_I_check).abs().max() < 1e-3); + + // Null matrix test + Matrix A3; + Matrix A3_I = geninv(A3); + Matrix A3_I_check; + TEST((A3_I - A3_I_check).abs().max() < 1e-5); + + // Mock-up effectiveness matrix + const float B_quad_w[6][16] = { + {-0.5717536f, 0.43756646f, 0.5717536f, -0.43756646f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f}, + { 0.35355328f, -0.35355328f, 0.35355328f, -0.35355328f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f}, + { 0.28323701f, 0.28323701f, -0.28323701f, -0.28323701f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f}, + { 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f}, + { 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f}, + {-0.25f, -0.25f, -0.25f, -0.25f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f} + }; + Matrix B = Matrix(B_quad_w); + const float A_quad_w[16][6] = { + { -0.495383f, 0.707107f, 0.765306f, 0.0f, 0.0f, -1.000000f }, + { 0.495383f, -0.707107f, 1.000000f, 0.0f, 0.0f, -1.000000f }, + { 0.495383f, 0.707107f, -0.765306f, 0.0f, 0.0f, -1.000000f }, + { -0.495383f, -0.707107f, -1.000000f, 0.0f, 0.0f, -1.000000f }, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f} + }; + Matrix A_check = Matrix(A_quad_w); + Matrix A = geninv(B); + TEST((A - A_check).abs().max() < 1e-5); + + // Test error case with erroneous rank in internal impl functions + Matrix L; + Matrix GM; + Matrix retM_check; + Matrix retM0 = GeninvImpl::genInvUnderdetermined(GM, L, 5); + Matrix GN; + Matrix retN_check; + Matrix retN0 = GeninvImpl::genInvOverdetermined(GN, L, 5); + TEST((retM0 - retM_check).abs().max() < 1e-5); + TEST((retN0 - retN_check).abs().max() < 1e-5); + + Matrix retM1 = GeninvImpl::genInvUnderdetermined(GM, L, 5); + Matrix retN1 = GeninvImpl::genInvOverdetermined(GN, L, 5); + TEST((retM1 - retM_check).abs().max() < 1e-5); + TEST((retN1 - retN_check).abs().max() < 1e-5); + + float float_scale = 1.f; + fullRankCholeskyTolerance(float_scale); + double double_scale = 1.; + fullRankCholeskyTolerance(double_scale); + TEST(static_cast(float_scale) > double_scale); + + return 0; +} + +/* vim: set et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : */ From de85dcff9760b77ad0d2cd06682f44b3f3c9716c Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 26 Nov 2019 13:46:45 +0100 Subject: [PATCH 326/388] Vector: switch read only functions to const (#108) --- matrix/Vector.hpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 4af611542f..fe83505af9 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -92,7 +92,7 @@ public: return (*this) / norm(); } - Vector unit_or_zero(const Type eps = Type(1e-5)) { + Vector unit_or_zero(const Type eps = Type(1e-5)) const { const Type n = norm(); if (n > eps) { return (*this) / n; @@ -104,8 +104,7 @@ public: return unit(); } - bool longerThan(Type testVal) - { + bool longerThan(Type testVal) const { return norm_squared() > testVal*testVal; } From dba84236cb55cf30a8730f77c71a000babf6d204 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 28 Nov 2019 04:36:13 -0500 Subject: [PATCH 327/388] Vector3f cross product directly return result (#109) --- matrix/Vector3.hpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index e449b2657f..70d503aafd 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -58,11 +58,7 @@ public: Vector3 cross(const Matrix31 & b) const { const Vector3 &a(*this); - Vector3 c; - c(0) = a(1)*b(2,0) - a(2)*b(1,0); - c(1) = -a(0)*b(2,0) + a(2)*b(0,0); - c(2) = a(0)*b(1,0) - a(1)*b(0,0); - return c; + return {a(1)*b(2,0) - a(2)*b(1,0), -a(0)*b(2,0) + a(2)*b(0,0), a(0)*b(1,0) - a(1)*b(0,0)}; } /** From a8009a36a3668da0cbab0cb028b6997cd8179dc1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 26 Nov 2019 12:03:15 -0500 Subject: [PATCH 328/388] Quaternion multiply inline return --- matrix/Quaternion.hpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index f0a1d6c457..9df08a9b3c 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -255,12 +255,11 @@ public: Quaternion operator*(const Quaternion &q) const { const Quaternion &p = *this; - Quaternion r; - r(0) = p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3); - r(1) = p(0) * q(1) + p(1) * q(0) + p(2) * q(3) - p(3) * q(2); - r(2) = p(0) * q(2) - p(1) * q(3) + p(2) * q(0) + p(3) * q(1); - r(3) = p(0) * q(3) + p(1) * q(2) - p(2) * q(1) + p(3) * q(0); - return r; + return { + p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3), + p(0) * q(1) + p(1) * q(0) + p(2) * q(3) - p(3) * q(2), + p(0) * q(2) - p(1) * q(3) + p(2) * q(0) + p(3) * q(1), + p(0) * q(3) + p(1) * q(2) - p(2) * q(1) + p(3) * q(0)}; } /** From de6a2d31ffcd1ce1adcc3e273dc6f6459b318f79 Mon Sep 17 00:00:00 2001 From: kritz Date: Wed, 4 Dec 2019 14:33:33 +0100 Subject: [PATCH 329/388] Slice assign value (#111) * Assign value to slice * Readme for formatting --- README.md | 10 ++++++++++ matrix/Slice.hpp | 11 +++++++++++ test/slice.cpp | 12 ++++++++++++ 3 files changed, 33 insertions(+) diff --git a/README.md b/README.md index 72f553665b..1cc31a5e2f 100644 --- a/README.md +++ b/README.md @@ -40,6 +40,16 @@ cmake -DTESTING=ON .. make check ``` +## Formatting +The format can be checked as following: +``` +mkdir build +cd build +cmake -DFORMAT=ON .. +make check_format +``` + + ## Example See the test directory for detailed examples. Some simple examples are included below: diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 3a1008c21a..fc5c942264 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -63,6 +63,17 @@ public: return self; } + Slice& operator=(const Type& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) = other; + } + } + return self; + } + // allow assigning vectors to a slice that are in the axis template // make this a template function since it only exists for some instantiations Slice& operator=(const Vector& other) diff --git a/test/slice.cpp b/test/slice.cpp index 36c252a742..2e2baab1b8 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -125,6 +125,18 @@ int main() TEST(!v5.xy().longerThan(5.f)); TEST(isEqualF(5.f, v5.xy().norm())); + // assign scalar value to slice + Matrix L; + L(0,0) = -1; + L(1,0) = 1; + L(2,0) = 3; + + L.slice<2,1>(0,0) = 0.0f; + + float data_5_check[3] = {0, 0, 3}; + Matrix M (data_5_check); + TEST(isEqual(L, M)); + return 0; } From ef442fab924bf5fd149811ac859c270532531598 Mon Sep 17 00:00:00 2001 From: kritz Date: Thu, 5 Dec 2019 11:39:21 +0100 Subject: [PATCH 330/388] Getter function for the diag elements of slice (#112) --- matrix/Slice.hpp | 10 ++++++++++ test/slice.cpp | 17 +++++++++++++++++ 2 files changed, 27 insertions(+) diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index fc5c942264..6fc3010b34 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -119,6 +119,16 @@ public: } } + Vector diag() + { + Slice& self = *this; + Vector res; + for (size_t j = 0; j < (P& self = *this; diff --git a/test/slice.cpp b/test/slice.cpp index 2e2baab1b8..2de317aa83 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -137,6 +137,23 @@ int main() Matrix M (data_5_check); TEST(isEqual(L, M)); + // return diagonal elements + float data_6[9] = {0, 2, 3, + 4, 5, 6, + 7, 8, 10 + }; + SquareMatrix N(data_6); + + Vector3f v6 = N.slice<3,3>(0,0).diag(); + Vector3f v6_check = {0, 5, 10}; + TEST(isEqual(v6,v6_check)); + Vector2f v7 = N.slice<2,3>(1,0).diag(); + Vector2f v7_check = {4, 8}; + TEST(isEqual(v7,v7_check)); + Vector2f v8 = N.slice<3,2>(0,1).diag(); + Vector2f v8_check = {2, 6}; + TEST(isEqual(v8,v8_check)); + return 0; } From 5cbcf6035ad6d1fa8a94fcbcc891c0e35709bb0f Mon Sep 17 00:00:00 2001 From: kritz Date: Thu, 5 Dec 2019 18:16:14 +0100 Subject: [PATCH 331/388] Set Matrix's col amd row to single value (#113) --- matrix/Matrix.hpp | 9 +++++++++ matrix/Slice.hpp | 4 ++-- matrix/SquareMatrix.hpp | 2 +- test/matrixAssignment.cpp | 22 ++++++++++++++++++++++ 4 files changed, 34 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 0172669a5b..c3b47ce839 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -407,12 +407,21 @@ public: slice<1,N>(i,0) = row_in.transpose(); } + void setRow(size_t i, Type val) + { + slice<1,N>(i,0) = val; + } void setCol(size_t j, const Matrix &column) { slice(0,j) = column; } + void setCol(size_t j, Type val) + { + slice(0,j) = val; + } + void setZero() { memset(_data, 0, sizeof(_data)); diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 6fc3010b34..21b2a4f09a 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -119,9 +119,9 @@ public: } } - Vector diag() + Vector diag() const { - Slice& self = *this; + const Slice& self = *this; Vector res; for (size_t j = 0; j < (P class Slice; -template +template class SquareMatrix : public Matrix { public: diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 8774cc38c7..b64a0e1b42 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -72,6 +72,28 @@ int main() TEST(isEqual(m3, m2)); + // set rows and columns to value + Matrix3f m2e(data2d); + + float data2e_check1[3][3] = { + {1, 11, 3}, + {4, 11, 6}, + {7, 11, 9} + }; + Matrix3f m2e_check1(data2e_check1); + + float data2e_check2[3][3] = { + {1, 11, 3}, + {4, 11, 6}, + {0, 0, 0} + }; + Matrix3f m2e_check2(data2e_check2); + + m2e.setCol(1, 11); + TEST(isEqual(m2e, m2e_check1)); + m2e.setRow(2, 0); + TEST(isEqual(m2e, m2e_check2)); + float data_row_02_swap[9] = { 7, 8, 9, 4, 5, 6, From 2f6398168d04451998cbb60b44d7f4898279caf0 Mon Sep 17 00:00:00 2001 From: kritz Date: Fri, 6 Dec 2019 12:03:26 +0100 Subject: [PATCH 332/388] Add several functions that are useful for coavriance matrices: (#114) * uncorrelateCovariance * uncorrelateCovarianceSetVariance * makeBlockSymmetric * makeRowColSymmetric * isBlockSymmetric * isRowColSymmetric --- matrix/SquareMatrix.hpp | 125 ++++++++++++++++++++++++++++++++++++++++ test/squareMatrix.cpp | 103 +++++++++++++++++++++++++++++++++ 2 files changed, 228 insertions(+) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 06415f1abd..fcb225d324 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -61,6 +61,18 @@ public: return *this; } + template + const Slice slice(size_t x0, size_t y0) const + { + return Slice(x0, y0, this); + } + + template + Slice slice(size_t x0, size_t y0) + { + return Slice(x0, y0, this); + } + // inverse alias inline SquareMatrix I() const { @@ -118,6 +130,119 @@ public: } return res; } + + // zero all offdiagonal elements and keep corresponding diagonal elements + template + void uncorrelateCovariance(size_t first) + { + SquareMatrix &self = *this; + Vector diag_elements = self.slice(first, first).diag(); + self.uncorrelateCovarianceSetVariance(first, diag_elements); + } + + template + void uncorrelateCovarianceSetVariance(size_t first, const Vector &vec) + { + SquareMatrix &self = *this; + // zero rows and columns + self.slice(first, 0) = 0; + self.slice(0, first) = 0; + + // set diagonals + unsigned vec_idx = 0; + for (size_t idx = first; idx < first+Width; idx++) { + self(idx,idx) = vec(vec_idx); + vec_idx ++; + } + } + + template + void uncorrelateCovarianceSetVariance(size_t first, Type val) + { + SquareMatrix &self = *this; + // zero rows and columns + self.slice(first, 0) = 0; + self.slice(0, first) = 0; + + // set diagonals + for (size_t idx = first; idx < first+Width; idx++) { + self(idx,idx) = val; + } + } + + // make block diagonal symmetric by taking the average of the two corresponding off diagonal values + template + void makeBlockSymmetric(size_t first) + { + SquareMatrix &self = *this; + if(Width>1) { + for (size_t row_idx = first+1; row_idx < first+Width; row_idx++) { + for (size_t col_idx = first; col_idx < row_idx; col_idx++) { + Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / 2; + self(row_idx,col_idx) = tmp; + self(col_idx,row_idx) = tmp; + } + } + } + } + + // make rows and columns symmetric by taking the average of the two corresponding off diagonal values + template + void makeRowColSymmetric(size_t first) + { + SquareMatrix &self = *this; + self.makeBlockSymmetric(first); + for (size_t row_idx = first; row_idx < first+Width; row_idx++) { + for (size_t col_idx = 0; col_idx < first; col_idx++) { + Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / 2; + self(row_idx,col_idx) = tmp; + self(col_idx,row_idx) = tmp; + } + for (size_t col_idx = first+Width; col_idx < M; col_idx++) { + Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / 2; + self(row_idx,col_idx) = tmp; + self(col_idx,row_idx) = tmp; + } + } + } + + // checks if block diagonal is symmetric + template + bool isBlockSymmetric(size_t first, const Type eps = 1e-8f) + { + SquareMatrix &self = *this; + if(Width>1) { + for (size_t row_idx = first+1; row_idx < first+Width; row_idx++) { + for (size_t col_idx = first; col_idx < row_idx; col_idx++) { + if(!isEqualF(self(row_idx,col_idx), self(col_idx,row_idx), eps)) { + return false; + } + } + } + } + return true; + } + + // checks if rows and columns are symmetric + template + bool isRowColSymmetric(size_t first, const Type eps = 1e-8f) + { + SquareMatrix &self = *this; + for (size_t row_idx = first; row_idx < first+Width; row_idx++) { + for (size_t col_idx = 0; col_idx < first; col_idx++) { + if(!isEqualF(self(row_idx,col_idx), self(col_idx,row_idx), eps)) { + return false; + } + } + for (size_t col_idx = first+Width; col_idx < M; col_idx++) { + if(!isEqualF(self(row_idx,col_idx), self(col_idx,row_idx), eps)) { + return false; + } + } + } + return self.isBlockSymmetric(first, eps); + } + }; typedef SquareMatrix SquareMatrix3f; diff --git a/test/squareMatrix.cpp b/test/squareMatrix.cpp index 3ad6b1a832..0c87debc0b 100644 --- a/test/squareMatrix.cpp +++ b/test/squareMatrix.cpp @@ -38,7 +38,110 @@ int main() TEST(isEqual(A_bottomright, bottomright_check)); TEST(isEqual(A_bottomright2, bottomright_check)); + // test diagonal functions + float data_4x4[16] = {1, 2, 3, 4, + 5, 6, 7, 8, + 9, 10, 11, 12, + 13, 14,15, 16 + }; + SquareMatrix B(data_4x4); + B.uncorrelateCovariance<1>(1); + float data_B_check[16] = {1, 0, 3, 4, + 0, 6, 0, 0, + 9, 0, 11, 12, + 13, 0,15, 16 + }; + SquareMatrix B_check(data_B_check); + TEST(isEqual(B, B_check)) + + SquareMatrix C(data_4x4); + C.uncorrelateCovariance<2>(1); + float data_C_check[16] = {1, 0, 0, 4, + 0, 6, 0, 0, + 0, 0, 11, 0, + 13, 0,0, 16 + }; + SquareMatrix C_check(data_C_check); + TEST(isEqual(C, C_check)) + + SquareMatrix D(data_4x4); + D.uncorrelateCovarianceSetVariance<2>(0, Vector2f{20,21}); + float data_D_check[16] = {20, 0, 0, 0, + 0, 21, 0, 0, + 0, 0, 11, 12, + 0, 0,15, 16 + }; + SquareMatrix D_check(data_D_check); + TEST(isEqual(D, D_check)) + + SquareMatrix E(data_4x4); + E.uncorrelateCovarianceSetVariance<3>(1, 33); + float data_E_check[16] = {1, 0, 0, 0, + 0, 33, 0, 0, + 0, 0, 33, 0, + 0, 0,0, 33 + }; + SquareMatrix E_check(data_E_check); + TEST(isEqual(E, E_check)) + + // test symmetric functions + SquareMatrix F(data_4x4); + F.makeBlockSymmetric<2>(1); + float data_F_check[16] = {1, 2, 3, 4, + 5, 6, 8.5, 8, + 9, 8.5, 11, 12, + 13, 14,15, 16 + }; + SquareMatrix F_check(data_F_check); + TEST(isEqual(F, F_check)) + TEST(F.isBlockSymmetric<2>(1)); + TEST(!F.isRowColSymmetric<2>(1)); + + SquareMatrix G(data_4x4); + G.makeRowColSymmetric<2>(1); + float data_G_check[16] = {1, 3.5, 6, 4, + 3.5, 6, 8.5, 11, + 6, 8.5, 11, 13.5, + 13, 11,13.5, 16 + }; + SquareMatrix G_check(data_G_check); + TEST(isEqual(G, G_check)); + TEST(G.isBlockSymmetric<2>(1)); + TEST(G.isRowColSymmetric<2>(1)); + + SquareMatrix H(data_4x4); + H.makeBlockSymmetric<1>(1); + float data_H_check[16] = {1, 2, 3, 4, + 5, 6, 7, 8, + 9, 10, 11, 12, + 13, 14,15, 16 + }; + SquareMatrix H_check(data_H_check); + TEST(isEqual(H, H_check)) + TEST(H.isBlockSymmetric<1>(1)); + TEST(!H.isRowColSymmetric<1>(1)); + + SquareMatrix J(data_4x4); + J.makeRowColSymmetric<1>(1); + float data_J_check[16] = {1, 3.5, 3, 4, + 3.5, 6, 8.5, 11, + 9, 8.5, 11, 12, + 13, 11,15, 16 + }; + SquareMatrix J_check(data_J_check); + TEST(isEqual(J, J_check)); + TEST(J.isBlockSymmetric<1>(1)); + TEST(J.isRowColSymmetric<1>(1)); + TEST(!J.isBlockSymmetric<3>(1)); + + float data_K[16] = {1, 2, 3, 4, + 2, 3, 4, 11, + 3, 4, 11, 12, + 4, 11,15, 16 + }; + SquareMatrix K(data_K); + TEST(!K.isRowColSymmetric<1>(2)); return 0; } From 4f3565da94d00c4cd1feb560f1f72a81296522f8 Mon Sep 17 00:00:00 2001 From: kritz Date: Mon, 9 Dec 2019 10:21:27 +0100 Subject: [PATCH 333/388] Add asserts (#115) * Add asserts * Type cast literals * asserts for indexing vectors * include assert * Fix accessing elements outside of slice --- CMakeLists.txt | 6 +++++- matrix/Matrix.hpp | 20 ++++++++++++++++++++ matrix/Slice.hpp | 27 +++++++++++++++++++++------ matrix/SquareMatrix.hpp | 40 ++++++++++++++++++++++++++++++++++------ matrix/Vector.hpp | 6 ++++++ matrix/math.hpp | 1 + 6 files changed, 87 insertions(+), 13 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5fae908d9a..909683df32 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,11 @@ set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_STANDARD_REQUIRED ON) if (NOT CMAKE_BUILD_TYPE) - set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) + if(TESTING) + set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) + else() + set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) + endif() message(STATUS "set build type to ${CMAKE_BUILD_TYPE}") endif() diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index c3b47ce839..188b5be619 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -96,11 +96,21 @@ public: inline Type operator()(size_t i, size_t j) const { + assert(i >= 0); + assert(i < M); + assert(j >= 0); + assert(j < N); + return _data[i][j]; } inline Type &operator()(size_t i, size_t j) { + assert(i >= 0); + assert(i < M); + assert(j >= 0); + assert(j < N); + return _data[i][j]; } @@ -470,6 +480,11 @@ public: inline void swapRows(size_t a, size_t b) { + assert(a >= 0); + assert(a < M); + assert(b >= 0); + assert(b < M); + if (a == b) { return; } @@ -485,6 +500,11 @@ public: inline void swapCols(size_t a, size_t b) { + assert(a >= 0); + assert(a < N); + assert(b >= 0); + assert(b < N); + if (a == b) { return; } diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 21b2a4f09a..f61a009054 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -28,15 +28,30 @@ public: _data(const_cast*>(data)) { static_assert(P <= M, "Slice rows bigger than backing matrix"); static_assert(Q <= N, "Slice cols bigger than backing matrix"); + assert(x0 >= 0); + assert(x0 + P <= M); + assert(y0 >= 0); + assert(y0 + Q <= N); } Type operator()(size_t i, size_t j) const { + assert(i >= 0); + assert(i < P); + assert(j >= 0); + assert(j < Q); + return (*_data)(_x0 + i, _y0 + j); } Type &operator()(size_t i, size_t j) + { + assert(i >= 0); + assert(i < P); + assert(j >= 0); + assert(j < Q); + return (*_data)(_x0 + i, _y0 + j); } @@ -97,23 +112,23 @@ public: return Slice(x0 + _x0, y0 + _y0, _data); } - void copyTo(Type dst[M*N]) const + void copyTo(Type dst[P*Q]) const { const Slice &self = *this; - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { dst[i*N+j] = self(i, j); } } } - void copyToColumnMajor(Type dst[M*N]) const + void copyToColumnMajor(Type dst[P*Q]) const { const Slice &self = *this; - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { dst[i+(j*M)] = self(i, j); } } diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index fcb225d324..d343bcfbfb 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -135,6 +135,10 @@ public: template void uncorrelateCovariance(size_t first) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; Vector diag_elements = self.slice(first, first).diag(); self.uncorrelateCovarianceSetVariance(first, diag_elements); @@ -143,10 +147,14 @@ public: template void uncorrelateCovarianceSetVariance(size_t first, const Vector &vec) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; // zero rows and columns - self.slice(first, 0) = 0; - self.slice(0, first) = 0; + self.slice(first, 0) = Type(0); + self.slice(0, first) = Type(0); // set diagonals unsigned vec_idx = 0; @@ -159,10 +167,14 @@ public: template void uncorrelateCovarianceSetVariance(size_t first, Type val) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; // zero rows and columns - self.slice(first, 0) = 0; - self.slice(0, first) = 0; + self.slice(first, 0) = Type(0); + self.slice(0, first) = Type(0); // set diagonals for (size_t idx = first; idx < first+Width; idx++) { @@ -174,11 +186,15 @@ public: template void makeBlockSymmetric(size_t first) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; if(Width>1) { for (size_t row_idx = first+1; row_idx < first+Width; row_idx++) { for (size_t col_idx = first; col_idx < row_idx; col_idx++) { - Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / 2; + Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / Type(2); self(row_idx,col_idx) = tmp; self(col_idx,row_idx) = tmp; } @@ -190,11 +206,15 @@ public: template void makeRowColSymmetric(size_t first) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; self.makeBlockSymmetric(first); for (size_t row_idx = first; row_idx < first+Width; row_idx++) { for (size_t col_idx = 0; col_idx < first; col_idx++) { - Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / 2; + Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / Type(2); self(row_idx,col_idx) = tmp; self(col_idx,row_idx) = tmp; } @@ -210,6 +230,10 @@ public: template bool isBlockSymmetric(size_t first, const Type eps = 1e-8f) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; if(Width>1) { for (size_t row_idx = first+1; row_idx < first+Width; row_idx++) { @@ -227,6 +251,10 @@ public: template bool isRowColSymmetric(size_t first, const Type eps = 1e-8f) { + static_assert(Width <= M, "Width bigger than matrix"); + assert(first >= 0); + assert(first + Width <= M); + SquareMatrix &self = *this; for (size_t row_idx = first; row_idx < first+Width; row_idx++) { for (size_t col_idx = 0; col_idx < first; col_idx++) { diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index fe83505af9..40803ba8cc 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -42,12 +42,18 @@ public: inline Type operator()(size_t i) const { + assert(i >= 0); + assert(i < M); + const MatrixM1 &v = *this; return v(i, 0); } inline Type &operator()(size_t i) { + assert(i >= 0); + assert(i < M); + MatrixM1 &v = *this; return v(i, 0); } diff --git a/matrix/math.hpp b/matrix/math.hpp index 1bb9d67243..edfc1591fc 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -1,5 +1,6 @@ #pragma once +#include #include "stdlib_imports.hpp" #ifdef __PX4_QURT #include "dspal_math.h" From e81483a808ce7b0217c11d3dc0fce90685f44353 Mon Sep 17 00:00:00 2001 From: kritz Date: Wed, 18 Dec 2019 14:12:47 +0100 Subject: [PATCH 334/388] Catch quaternion canonical corner cases (#116) --- matrix/Quaternion.hpp | 10 ++++--- matrix/helper_functions.hpp | 6 ++++ test/attitude.cpp | 58 +++++++++++++++++++++++++++++++------ test/copyto.cpp | 2 +- 4 files changed, 62 insertions(+), 14 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 9df08a9b3c..b05f063369 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -367,11 +367,13 @@ public: Quaternion canonical() const { const Quaternion &q = *this; - if (q(0) < Type(0)) { - return Quaternion(-q(0),-q(1),-q(2),-q(3)); - } else { - return Quaternion(q(0),q(1),q(2),q(3)); + + for (size_t i = 0; i < 4; i++) { + if (fabs(q(i)) > FLT_EPSILON) { + return q * Type(matrix::sign(q(i))); + } } + return q; } /** diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index d3ecf841b1..89f2dbffb9 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -78,4 +78,10 @@ Type wrap_2pi(Type x) return wrap(x, Type(0), Type(M_TWOPI)); } +template +int sign(T val) +{ + return (T(FLT_EPSILON) < val) - (val < T(FLT_EPSILON)); } + +} // namespace matrix diff --git a/test/attitude.cpp b/test/attitude.cpp index 86ba63d894..3acab686f5 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -255,15 +255,55 @@ int main() TEST(fabs(q_check(3) + q(3)) < eps); // quaternion canonical - Quatf q_non_canonical(-0.7f,0.4f, 0.3f, -0.3f); - Quatf q_canonical(0.7f,-0.4f, -0.3f, 0.3f); - Quatf q_canonical_ref(0.7f,-0.4f, -0.3f, 0.3f); - TEST(isEqual(q_non_canonical.canonical(),q_canonical_ref)); - TEST(isEqual(q_canonical.canonical(),q_canonical_ref)); - q_non_canonical.canonicalize(); - q_canonical.canonicalize(); - TEST(isEqual(q_non_canonical,q_canonical_ref)); - TEST(isEqual(q_canonical,q_canonical_ref)); + Quatf q_non_canonical_1(-0.7f,0.4f, 0.3f, -0.3f); + Quatf q_canonical_1(0.7f,-0.4f, -0.3f, 0.3f); + Quatf q_canonical_ref_1(0.7f,-0.4f, -0.3f, 0.3f); + TEST(isEqual(q_non_canonical_1.canonical(),q_canonical_ref_1)); + TEST(isEqual(q_canonical_1.canonical(),q_canonical_ref_1)); + q_non_canonical_1.canonicalize(); + q_canonical_1.canonicalize(); + TEST(isEqual(q_non_canonical_1,q_canonical_ref_1)); + TEST(isEqual(q_canonical_1,q_canonical_ref_1)); + + Quatf q_non_canonical_2(0.0f, -1.0f, 0.0f, 0.0f); + Quatf q_canonical_2(0.0f, 1.0f, 0.0f, 0.0f); + Quatf q_canonical_ref_2(0.0f, 1.0f, 0.0f, 0.0f); + TEST(isEqual(q_non_canonical_2.canonical(),q_canonical_ref_2)); + TEST(isEqual(q_canonical_2.canonical(),q_canonical_ref_2)); + q_non_canonical_2.canonicalize(); + q_canonical_2.canonicalize(); + TEST(isEqual(q_non_canonical_2,q_canonical_ref_2)); + TEST(isEqual(q_canonical_2,q_canonical_ref_2)); + + Quatf q_non_canonical_3(0.0f, 0.0f, -1.0f, 0.0f); + Quatf q_canonical_3(0.0f, 0.0f, 1.0f, 0.0f); + Quatf q_canonical_ref_3(0.0f, 0.0f, 1.0f, 0.0f); + TEST(isEqual(q_non_canonical_3.canonical(),q_canonical_ref_3)); + TEST(isEqual(q_canonical_3.canonical(),q_canonical_ref_3)); + q_non_canonical_3.canonicalize(); + q_canonical_3.canonicalize(); + TEST(isEqual(q_non_canonical_3,q_canonical_ref_3)); + TEST(isEqual(q_canonical_3,q_canonical_ref_3)); + + Quatf q_non_canonical_4(0.0f, 0.0f, 0.0f, -1.0f); + Quatf q_canonical_4(0.0f, 0.0f, 0.0f, 1.0f); + Quatf q_canonical_ref_4(0.0f, 0.0f, 0.0f, 1.0f); + TEST(isEqual(q_non_canonical_4.canonical(),q_canonical_ref_4)); + TEST(isEqual(q_canonical_4.canonical(),q_canonical_ref_4)); + q_non_canonical_4.canonicalize(); + q_canonical_4.canonicalize(); + TEST(isEqual(q_non_canonical_4,q_canonical_ref_4)); + TEST(isEqual(q_canonical_4,q_canonical_ref_4)); + + Quatf q_non_canonical_5(0.0f, 0.0f, 0.0f, 0.0f); + Quatf q_canonical_5(0.0f, 0.0f, 0.0f, 0.0f); + Quatf q_canonical_ref_5(0.0f, 0.0f, 0.0f, 0.0f); + TEST(isEqual(q_non_canonical_5.canonical(),q_canonical_ref_5)); + TEST(isEqual(q_canonical_5.canonical(),q_canonical_ref_5)); + q_non_canonical_5.canonicalize(); + q_canonical_5.canonicalize(); + TEST(isEqual(q_non_canonical_5,q_canonical_ref_5)); + TEST(isEqual(q_canonical_5,q_canonical_ref_5)); // quaternion setIdentity Quatf q_nonIdentity(-0.7f, 0.4f, 0.5f, -0.3f); diff --git a/test/copyto.cpp b/test/copyto.cpp index 4989adb0f1..4e72a1a91d 100644 --- a/test/copyto.cpp +++ b/test/copyto.cpp @@ -15,7 +15,7 @@ int main() float eps = 1e-6f; // Vector3 copyTo - Vector3f v(1, 2, 3); + const Vector3f v(1, 2, 3); float dst3[3] = {}; v.copyTo(dst3); for (size_t i = 0; i < 3; i++) { From d18be0d0fa17d9a0b60ab34bad3e33160f907b09 Mon Sep 17 00:00:00 2001 From: kritz Date: Sat, 28 Dec 2019 23:18:15 +0100 Subject: [PATCH 335/388] Fix AngleAxis constructors (#117) --- matrix/AxisAngle.hpp | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index e95c046514..98c89cd620 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -69,16 +69,11 @@ public: AxisAngle(const Quaternion &q) { AxisAngle &v = *this; - Type ang = Type(2) * acos(q(0)); - Type mag = sin(ang/2.0f); - if (fabs(mag) > 0) { - v(0) = ang*q(1)/mag; - v(1) = ang*q(2)/mag; - v(2) = ang*q(3)/mag; + Type mag = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); + if (fabs(mag) >= Type(1e-10)) { + v = q.imag() * Type(Type(2) * atan2(mag, q(0)) / mag); } else { - v(0) = 0; - v(1) = 0; - v(2) = 0; + v = q.imag() * Type(Type(2) * Type(sign(q(0)))); } } @@ -93,7 +88,7 @@ public: AxisAngle(const Dcm &dcm) { AxisAngle &v = *this; - v = Quaternion(dcm); + v = AxisAngle(Quaternion(dcm)); } /** @@ -108,7 +103,7 @@ public: AxisAngle(const Euler &euler) { AxisAngle &v = *this; - v = Quaternion(euler); + v = AxisAngle(Quaternion(euler)); } /** From 20a9e91d443ed14a19cd9817c7889fc95a4ea01c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 31 Dec 2019 15:54:31 +0100 Subject: [PATCH 336/388] Fix CMake configuration for coverage tests on Mac OS --- CMakeLists.txt | 21 +++++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 909683df32..cab5a889b9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -35,12 +35,21 @@ if(SUPPORT_STDIOSTREAM) add_definitions(-DSUPPORT_STDIOSTREAM) endif() -set(CMAKE_CXX_FLAGS_COVERAGE - "--coverage -fprofile-arcs -ftest-coverage -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors" - CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) -set(CMAKE_EXE_LINKER_FLAGS_COVERAGE - "--coverage -ftest-coverage -lgcov" - CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) +if (("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") OR ("${CMAKE_CXX_COMPILER_ID}" MATCHES "AppleClang")) + set(CMAKE_CXX_FLAGS_COVERAGE + "--coverage -ftest-coverage -fdiagnostics-absolute-paths -O0 -fprofile-arcs -fno-inline-functions -fno-elide-constructors" + CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) + set(CMAKE_EXE_LINKER_FLAGS_COVERAGE + "-ftest-coverage -fdiagnostics-absolute-paths" + CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) +else() + set(CMAKE_CXX_FLAGS_COVERAGE + "--coverage -fprofile-arcs -ftest-coverage -O0 -fno-default-inline -fprofile-abs-path -fno-inline -fno-inline-small-functions -fno-elide-constructors" + CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) + set(CMAKE_EXE_LINKER_FLAGS_COVERAGE + "--coverage -ftest-coverage -lgcov" + CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) +endif() mark_as_advanced(CMAKE_CXX_FLAGS_COVERAGE CMAKE_C_FLAGS_COVERAGE CMAKE_EXE_LINKER_FLAGS_COVERAGE) add_compile_options( From efa5580a673030a438dc117cd258f6db3dee18ae Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 1 Jan 2020 15:48:05 +0100 Subject: [PATCH 337/388] Update CMakeLists.txt Remove non-compatible compile option. --- CMakeLists.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index cab5a889b9..b37a1de914 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,7 +44,8 @@ if (("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") OR ("${CMAKE_CXX_COMPILER_ID}" CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) else() set(CMAKE_CXX_FLAGS_COVERAGE - "--coverage -fprofile-arcs -ftest-coverage -O0 -fno-default-inline -fprofile-abs-path -fno-inline -fno-inline-small-functions -fno-elide-constructors" + # Add when GCC 9 or later is available as part of the default toolchain: -fprofile-abs-path + "--coverage -fprofile-arcs -ftest-coverage -O0 -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors" CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) set(CMAKE_EXE_LINKER_FLAGS_COVERAGE "--coverage -ftest-coverage -lgcov" From 3b581fb5998c7a15b741947e6a139b9e3f99fe38 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 1 Jan 2020 15:49:56 +0100 Subject: [PATCH 338/388] Update .travis.yml Bring Ubuntu and Mac OS toolchains to latest. --- .travis.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index 98e0bbdd62..dab3adef51 100644 --- a/.travis.yml +++ b/.travis.yml @@ -9,15 +9,15 @@ matrix: fast_finish: true include: - os: linux - dist: trusty - compiler: gcc + dist: bionic + compiler: gcc-8 env: CMAKE_BUILD_TYPE=Coverage FORMAT=ON - os: linux - dist: trusty + dist: bionic compiler: clang env: CMAKE_BUILD_TYPE=Release CC=clang CXX=clang++ FORMAT=OFF - os: osx - osx_image: xcode10.1 + osx_image: xcode11.3 env: CMAKE_BUILD_TYPE=Release FORMAT=OFF addons: From a37b91c96a9726cd8336af2d3463e717007e60a5 Mon Sep 17 00:00:00 2001 From: kamilritz Date: Mon, 13 Jan 2020 12:12:55 +0100 Subject: [PATCH 339/388] Type cast remaining integer --- matrix/Dcm.hpp | 12 ++++++------ matrix/Quaternion.hpp | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 9b14868707..f4a4c3ca68 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -104,13 +104,13 @@ public: const Type cd = c * d; const Type dd = d * d; dcm(0, 0) = aa + bb - cc - dd; - dcm(0, 1) = 2 * (bc - ad); - dcm(0, 2) = 2 * (ac + bd); - dcm(1, 0) = 2 * (bc + ad); + dcm(0, 1) = Type(2) * (bc - ad); + dcm(0, 2) = Type(2) * (ac + bd); + dcm(1, 0) = Type(2) * (bc + ad); dcm(1, 1) = aa - bb + cc - dd; - dcm(1, 2) = 2 * (cd - ab); - dcm(2, 0) = 2 * (bd - ac); - dcm(2, 1) = 2 * (ab + cd); + dcm(1, 2) = Type(2) * (cd - ab); + dcm(2, 0) = Type(2) * (bd - ac); + dcm(2, 1) = Type(2) * (ab + cd); dcm(2, 2) = aa - bb - cc + dd; } diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index b05f063369..b93b038936 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -436,7 +436,7 @@ public: if (theta < Type(1e-10)) { q(0) = Type(1); - q(1) = q(2) = q(3) = 0; + q(1) = q(2) = q(3) = Type(0); return; } From 649c837b6b53fcc8b6fedb047dcc757b8cbaf44b Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 24 Feb 2020 13:35:34 +0100 Subject: [PATCH 340/388] Use faster but less accurate average --- matrix/SquareMatrix.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index d343bcfbfb..ba7510c068 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -194,7 +194,7 @@ public: if(Width>1) { for (size_t row_idx = first+1; row_idx < first+Width; row_idx++) { for (size_t col_idx = first; col_idx < row_idx; col_idx++) { - Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / Type(2); + Type tmp = (self(row_idx,col_idx) + self(col_idx,row_idx)) / Type(2); self(row_idx,col_idx) = tmp; self(col_idx,row_idx) = tmp; } @@ -214,12 +214,12 @@ public: self.makeBlockSymmetric(first); for (size_t row_idx = first; row_idx < first+Width; row_idx++) { for (size_t col_idx = 0; col_idx < first; col_idx++) { - Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / Type(2); + Type tmp = (self(row_idx,col_idx) + self(col_idx,row_idx)) / Type(2); self(row_idx,col_idx) = tmp; self(col_idx,row_idx) = tmp; } for (size_t col_idx = first+Width; col_idx < M; col_idx++) { - Type tmp = self(row_idx,col_idx) + (self(col_idx,row_idx) - self(row_idx,col_idx)) / 2; + Type tmp = (self(row_idx,col_idx) + self(col_idx,row_idx)) / Type(2); self(row_idx,col_idx) = tmp; self(col_idx,row_idx) = tmp; } From 4873dc1c1e74f492ec0fcd5b493c9b500f2784fa Mon Sep 17 00:00:00 2001 From: kritz Date: Wed, 4 Mar 2020 09:14:04 +0100 Subject: [PATCH 341/388] Analytic inverse implementation (#122) * Add analytic 2x2 matrix inverse * Add analytical 3x3 matrix inverse --- matrix/SquareMatrix.hpp | 41 +++++++++++++++++++++++++++++++++++++++++ test/inverse.cpp | 39 ++++++++++++++++++++++++++++++++++++++- 2 files changed, 79 insertions(+), 1 deletion(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ba7510c068..216ff172d8 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -435,6 +435,47 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) return true; } +template +bool inv(const SquareMatrix & A, SquareMatrix & inv) +{ + Type det = A(0, 0) * A(1, 1) - A(1, 0) * A(0, 1); + + if(fabs(static_cast(det)) < FLT_EPSILON || !is_finite(det)) { + return false; + } + + inv(0, 0) = A(1, 1); + inv(1, 0) = -A(1, 0); + inv(0, 1) = -A(0, 1); + inv(1, 1) = A(0, 0); + inv /= det; + return true; +} + +template +bool inv(const SquareMatrix & A, SquareMatrix & inv) +{ + Type det = A(0, 0) * (A(1, 1) * A(2, 2) - A(2, 1) * A(1, 2)) - + A(0, 1) * (A(1, 0) * A(2, 2) - A(1, 2) * A(2, 0)) + + A(0, 2) * (A(1, 0) * A(2, 1) - A(1, 1) * A(2, 0)); + + if(fabs(static_cast(det)) < FLT_EPSILON || !is_finite(det)) { + return false; + } + + inv(0, 0) = A(1, 1) * A(2, 2) - A(2, 1) * A(1, 2); + inv(0, 1) = A(0, 2) * A(2, 1) - A(0, 1) * A(2, 2); + inv(0, 2) = A(0, 1) * A(1, 2) - A(0, 2) * A(1, 1); + inv(1, 0) = A(1, 2) * A(2, 0) - A(1, 0) * A(2, 2); + inv(1, 1) = A(0, 0) * A(2, 2) - A(0, 2) * A(2, 0); + inv(1, 2) = A(1, 0) * A(0, 2) - A(0, 0) * A(1, 2); + inv(2, 0) = A(1, 0) * A(2, 1) - A(2, 0) * A(1, 1); + inv(2, 1) = A(2, 0) * A(0, 1) - A(0, 0) * A(2, 1); + inv(2, 2) = A(0, 0) * A(1, 1) - A(1, 0) * A(0, 1); + inv /= det; + return true; +} + /** * inverse based on LU factorization with partial pivotting */ diff --git a/test/inverse.cpp b/test/inverse.cpp index d5f75296c4..865c79db32 100644 --- a/test/inverse.cpp +++ b/test/inverse.cpp @@ -22,6 +22,27 @@ int main() SquareMatrix A_I_check(data_check); TEST((A_I - A_I_check).abs().max() < 1e-6f); + float data_2x2[4] = {12, 2, + -7, 5 + }; + float data_2x2_check[4] = { + 0.0675675675f, -0.02702702f, + 0.0945945945f, 0.162162162f + }; + + SquareMatrix A2x2(data_2x2); + SquareMatrix A2x2_I = inv(A2x2); + SquareMatrix A2x2_I_check(data_2x2_check); + TEST(isEqual(A2x2_I, A2x2_I_check)); + + SquareMatrix A2x2_sing = ones(); + SquareMatrix A2x2_sing_I; + TEST(inv(A2x2_sing, A2x2_sing_I) == false); + + SquareMatrix A3x3_sing = ones(); + SquareMatrix A3x3_sing_I; + TEST(inv(A3x3_sing, A3x3_sing_I) == false) + // stess test SquareMatrix A_large; A_large.setIdentity(); @@ -34,7 +55,7 @@ int main() } SquareMatrix zero_test = zeros(); - inv(zero_test); + TEST(isEqual(inv(zero_test), zeros())); // test pivotting float data2[81] = { @@ -64,6 +85,7 @@ int main() SquareMatrix A2_I = inv(A2); SquareMatrix A2_I_check(data2_check); TEST((A2_I - A2_I_check).abs().max() < 1e-3f); + float data3[9] = { 0, 1, 2, 3, 4, 5, @@ -93,6 +115,16 @@ int main() TEST(isEqual(A3_I, Z3)); TEST(isEqual(A3.I(), Z3)); + for(size_t i = 0; i < 9; i++) { + A2(0, i) = 0; + } + A2_I = inv(A2); + SquareMatrix Z9 = zeros(); + TEST(!A2.I(A2_I)); + TEST(!Z9.I(A2_I)); + TEST(isEqual(A2_I, Z9)); + TEST(isEqual(A2.I(), Z9)); + // cover NaN A3(0, 0) = NAN; A3(0, 1) = 0; @@ -101,6 +133,11 @@ int main() TEST(isEqual(A3_I, Z3)); TEST(isEqual(A3.I(), Z3)); + A2(0, 0) = NAN; + A2_I = inv(A2); + TEST(isEqual(A2_I, Z9)); + TEST(isEqual(A2.I(), Z9)); + float data4[9] = { 1.33471626f, 0.74946721f, -0.0531679f, 0.74946721f, 1.07519593f, 0.08036323f, From 2cca35c8fe6507ea7c3c7cbc70929fc0407e271b Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 12 Mar 2020 06:10:44 +0100 Subject: [PATCH 342/388] AxisAngle: call q.imag().norm() for conversion This is important depending on the platform because norm() calls matrix::squrt() which dispatches correctly to the implementation for the used type. Otherwise float squrt()s can get calculated as double. --- matrix/AxisAngle.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index 98c89cd620..d72de6269a 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -69,7 +69,7 @@ public: AxisAngle(const Quaternion &q) { AxisAngle &v = *this; - Type mag = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); + Type mag = q.imag().norm(); if (fabs(mag) >= Type(1e-10)) { v = q.imag() * Type(Type(2) * atan2(mag, q(0)) / mag); } else { From c6db357c92b1faa36de373ceae7642e55cf65461 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 12 Mar 2020 09:05:59 +0100 Subject: [PATCH 343/388] Matrix: correct print buffer size prediction Apparently printf of %8.8g can result in 8 significant digits + dot + scientific notation e.g. "e+12" = 14 bytes --- matrix/Matrix.hpp | 4 ++-- test/matrixAssignment.cpp | 16 +++++++++++----- 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 188b5be619..4af752bb3e 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -352,8 +352,8 @@ public: void print(FILE *stream = stdout) const { - // element: tab, point, 8 digits; row: newline; string: \0 end - static const size_t n = 10*N*M + M + 1; + // element: tab, point, 8 digits, 4 scientific notation chars; row: newline; string: \0 end + static const size_t n = 15*N*M + M + 1; char * buf = new char[n]; write_string(buf, n); fprintf(stream, "%s\n", buf); diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index b64a0e1b42..42523f4ca2 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -212,16 +212,22 @@ int main() // check write_string() float comma[6] = { - 1.f, 12345.678f, - 12345.67891f, 12345.67891f, - 1112345.67891f, 12345.111111111f + 1.f, 12345.123f, + 12345.1228f, .1234567891011f, + 12345678910.123456789f, 1234567891011.123456789101112f }; Matrix Comma(comma); - const size_t len = 10*2*3 + 2 + 1; + const size_t len = 15*2*3 + 2 + 1; char buffer[len]; + Comma.print(); // for debugging in case of failure Comma.write_string(buffer, len); - char output[] = "\t 1\t12345.678\n\t12345.679\t12345.679\n\t1112345.6\t12345.111\n"; + printf("%s\n", buffer); // for debugging in case of failure + char output[] = "\t 1\t12345.123\n\t12345.123\t0.12345679\n\t1.2345679e+10\t1.234568e+12\n"; + printf("%s\n", output); // for debugging in case of failure for (size_t i = 0; i < len; i++) { + if(buffer[i] != output[i]) { // for debugging in case of failure + printf("%d: \"%c\" != \"%c\"", int(i), buffer[i], output[i]); + } TEST(buffer[i] == output[i]); if (buffer[i] == '\0') { break; From a32892926c69ea0bad031fd9d7bfc915cc5e9b68 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 12 Mar 2020 12:47:25 +0100 Subject: [PATCH 344/388] Matrix: capture stdout for print() test I want to switch the print() function back to use printf() such that it's fully compatible with all (embedded) platforms. To still test the print function I'm capturing stdout into a file such that the print() function can stay unchanged and the result of the printf()s can be evaluated. --- matrix/Matrix.hpp | 4 ++-- test/matrixAssignment.cpp | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 4af752bb3e..93077a8182 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -350,13 +350,13 @@ public: } } - void print(FILE *stream = stdout) const + void print() const { // element: tab, point, 8 digits, 4 scientific notation chars; row: newline; string: \0 end static const size_t n = 15*N*M + M + 1; char * buf = new char[n]; write_string(buf, n); - fprintf(stream, "%s\n", buf); + printf("%s\n", buf); delete[] buf; } diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 42523f4ca2..052b8d6cc8 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -235,13 +235,13 @@ int main() } // check print() + // Redirect stdout + TEST(freopen("testoutput.txt", "w", stdout) != NULL); // write - FILE *fp = fopen("testoutput.txt", "w+"); - TEST(fp != nullptr); - Comma.print(fp); - TEST(!fclose(fp)); + Comma.print(); + fclose(stdout); // read - fp = fopen("testoutput.txt", "r"); + FILE *fp = fopen("testoutput.txt", "r"); TEST(fp != nullptr); TEST(!fseek(fp, 0, SEEK_SET)); for (size_t i = 0; i < len; i++) { @@ -249,7 +249,7 @@ int main() if (c == '\n') { break; } - printf("%d %d %c\n", static_cast(i), c, c); + printf("%d %d %d\n", static_cast(i), output[i], c); TEST(c == output[i]); } TEST(!fclose(fp)); From fa7153ecfbd18705f5cfbbdc316d693b943559e4 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Sat, 21 Mar 2020 15:22:11 +0100 Subject: [PATCH 345/388] Matrix: omit min max nan case with same result I observed this during review in https://github.com/PX4/Matrix/pull/105/files#r348386226 --- matrix/Matrix.hpp | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 93077a8182..4229bbb7eb 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -620,9 +620,7 @@ Type min(const Type x, const Type y) { if (x_is_nan && !y_is_nan) { return y; } - if (!x_is_nan && y_is_nan) { - return x; - } + // either !x_is_nan && y_is_nan or both are NAN anyways return x; } return (x < y) ? x : y; @@ -636,9 +634,7 @@ Type max(const Type x, const Type y) { if (x_is_nan && !y_is_nan) { return y; } - if (!x_is_nan && y_is_nan) { - return x; - } + // either !x_is_nan && y_is_nan or both are NAN anyways return x; } return (x > y) ? x : y; From 976ada411bf607136196c0d3e206f19eee153b56 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Sat, 21 Mar 2020 15:22:49 +0100 Subject: [PATCH 346/388] Matrix: min max comments and test style --- matrix/Matrix.hpp | 6 ++++-- test/matrixAssignment.cpp | 24 ++++++++++++------------ 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 4229bbb7eb..524ecee33a 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -615,7 +615,7 @@ template Type min(const Type x, const Type y) { bool x_is_nan = isnan(x); bool y_is_nan = isnan(y); - // z > nan for z != nan is required by C the standard + // take the non-nan value if there is one if (x_is_nan || y_is_nan) { if (x_is_nan && !y_is_nan) { return y; @@ -625,11 +625,12 @@ Type min(const Type x, const Type y) { } return (x < y) ? x : y; } + template Type max(const Type x, const Type y) { bool x_is_nan = isnan(x); bool y_is_nan = isnan(y); - // z > nan for z != nan is required by C the standard + // take the non-nan value if there is one if (x_is_nan || y_is_nan) { if (x_is_nan && !y_is_nan) { return y; @@ -639,6 +640,7 @@ Type max(const Type x, const Type y) { } return (x > y) ? x : y; } + template Type constrain(const Type x, const Type lower_bound, const Type upper_bound) { if (lower_bound > upper_bound) { diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index 052b8d6cc8..c3844c769e 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -194,20 +194,20 @@ int main() TEST(isEqual(constrain(m10, m10_lower_bound, m10_upper_bound), m10_constrained_ref)); // min, max, constrain with NAN - TEST(isEqualF(matrix::typeFunction::min(5.0f,NAN), 5.0f)); - TEST(isEqualF(matrix::typeFunction::min(NAN,5.0f), 5.0f)); - TEST(isEqualF(matrix::typeFunction::min(NAN,NAN), NAN)); - TEST(isEqualF(matrix::typeFunction::max(5.0f,NAN), 5.0f)); - TEST(isEqualF(matrix::typeFunction::max(NAN,5.0f), 5.0f)); - TEST(isEqualF(matrix::typeFunction::max(NAN,NAN), NAN)); - TEST(isEqualF(matrix::typeFunction::constrain(NAN,5.0f,6.0f), NAN)); - TEST(isEqualF(matrix::typeFunction::constrain(1.0f,5.0f,4.0f), NAN)); - TEST(isEqualF(matrix::typeFunction::constrain(6.0f,NAN,5.0f), 5.0f)); - TEST(isEqualF(matrix::typeFunction::constrain(1.0f,5.0f,NAN), 5.0f)); + TEST(isEqualF(matrix::typeFunction::min(5.f, NAN), 5.f)); + TEST(isEqualF(matrix::typeFunction::min(NAN, 5.f), 5.f)); + TEST(isEqualF(matrix::typeFunction::min(NAN, NAN), NAN)); + TEST(isEqualF(matrix::typeFunction::max(5.f, NAN), 5.f)); + TEST(isEqualF(matrix::typeFunction::max(NAN, 5.f), 5.f)); + TEST(isEqualF(matrix::typeFunction::max(NAN, NAN), NAN)); + TEST(isEqualF(matrix::typeFunction::constrain(NAN, 5.f, 6.f), NAN)); + TEST(isEqualF(matrix::typeFunction::constrain(1.f, 5.f, 4.f), NAN)); + TEST(isEqualF(matrix::typeFunction::constrain(6.f, NAN, 5.f), 5.f)); + TEST(isEqualF(matrix::typeFunction::constrain(1.f, 5.f, NAN), 5.f)); Vector2f v1{NAN, 5.0f}; - Vector2f v1_min = min(v1,1.0f); + Vector2f v1_min = min(v1, 1.f); Matrix3f m11 = min(m10_constrained_ref,NAN); - TEST(isEqualF(fmin(NAN,1.0f), float(v1_min(0)))); + TEST(isEqualF(fmin(NAN, 1.f), float(v1_min(0)))); TEST(isEqual(m11, m10_constrained_ref)); // check write_string() From d613055462bcbeacfd188cbd53de56c1dbc7b94d Mon Sep 17 00:00:00 2001 From: kamilritz Date: Mon, 6 Apr 2020 21:09:18 +0200 Subject: [PATCH 347/388] Add more assignment operators for slices --- matrix/Slice.hpp | 84 ++++++++++++++++++++++++++++++++++++++++++++++++ test/slice.cpp | 54 +++++++++++++++++++++++++++++++ 2 files changed, 138 insertions(+) diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index f61a009054..91cd7f7aea 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -100,6 +100,90 @@ public: return self; } + template + Slice& operator+=(const Slice& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) += other(i, j); + } + } + return self; + } + + Slice& operator+=(const Matrix& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) += other(i, j); + } + } + return self; + } + + Slice& operator+=(const Type& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) += other; + } + } + return self; + } + + template + Slice& operator-=(const Slice& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) -= other(i, j); + } + } + return self; + } + + Slice& operator-=(const Matrix& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) -= other(i, j); + } + } + return self; + } + + Slice& operator-=(const Type& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) -= other; + } + } + return self; + } + + Slice& operator*=(const Type& other) + { + Slice& self = *this; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + self(i, j) *= other; + } + } + return self; + } + + Slice& operator/=(const Type& other) + { + return operator*=(Type(1) / other); + } + template const Slice slice(size_t x0, size_t y0) const { diff --git a/test/slice.cpp b/test/slice.cpp index 2de317aa83..2987ba3ee4 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -154,6 +154,60 @@ int main() Vector2f v8_check = {2, 6}; TEST(isEqual(v8,v8_check)); + // Different assignment operators + SquareMatrix3f O(data); + float operand_data [4] = {2, 1, -3, -1}; + const SquareMatrix operand(operand_data); + + O.slice<2,2>(1,0) += operand; + float O_check_data_1 [9] = {0, 2, 3, 6, 6, 6, 4, 7, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_1))); + + O = SquareMatrix3f(data); + O.slice<2,1>(1,1) += operand.slice<2,1>(0,0); + float O_check_data_2 [9] = {0, 2, 3, 4, 7, 6, 7, 5, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_2))); + + O = SquareMatrix3f(data); + O.slice<3,3>(0,0) += -1; + float O_check_data_3 [9] = {-1, 1, 2, 3, 4, 5, 6, 7, 9}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_3))); + + O = SquareMatrix3f(data); + O.col(1) += Vector3f{1, -2, 3}; + float O_check_data_4 [9] = {0, 3, 3, 4, 3, 6, 7, 11, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_4))); + + O = SquareMatrix3f(data); + O.slice<2,2>(1,0) -= operand; + float O_check_data_5 [9] = {0, 2, 3, 2, 4, 6, 10, 9, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_5))); + + O = SquareMatrix3f(data); + O.slice<2,1>(1,1) -= operand.slice<2,1>(0,0); + float O_check_data_6 [9] = {0, 2, 3, 4, 3, 6, 7, 11, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_6))); + + O = SquareMatrix3f(data); + O.slice<3,3>(0,0) -= -1; + float O_check_data_7 [9] = {1, 3, 4, 5, 6, 7, 8, 9, 11}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_7))); + + O = SquareMatrix3f(data); + O.col(1) -= Vector3f{1, -2, 3}; + float O_check_data_8 [9] = {0, 1, 3, 4, 7, 6, 7, 5, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_8))); + + O = SquareMatrix3f(data); + O.slice<2,1>(1,1) *= 5.f; + float O_check_data_9 [9] = {0, 2, 3, 4, 25, 6, 7, 40, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_9))); + + O = SquareMatrix3f(data); + O.slice<2,1>(1,1) /= 2.f; + float O_check_data_10 [9] = {0, 2, 3, 4, 2.5, 6, 7, 4, 10}; + TEST(isEqual(O, SquareMatrix3f(O_check_data_10))); + return 0; } From 2bee0d078cb6b0e6205d17145899ccbb15dbe380 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 6 May 2020 09:57:34 +0200 Subject: [PATCH 348/388] Quaternion: refactor multiplication to matrix multiplication style MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Most often the multiplication in convention descriptions and papers is described in matrix multiplication style like this: q · p := Q(q)p Q(q) := [q0 −q1 −q2 −q3] [q1 q0 −q3 q2] [q2 q3 q0 −q1] [q3 −q2 q1 q0] I'm just rearanging the terms such that it's easily comparable with these definitions additional to it being clearly described by documenting we use the hamilton convention. --- matrix/Quaternion.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index b93b038936..db4eced28f 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -252,14 +252,14 @@ public: * @param q quaternion to multiply with * @return product */ - Quaternion operator*(const Quaternion &q) const + Quaternion operator*(const Quaternion &p) const { - const Quaternion &p = *this; + const Quaternion &q = *this; return { - p(0) * q(0) - p(1) * q(1) - p(2) * q(2) - p(3) * q(3), - p(0) * q(1) + p(1) * q(0) + p(2) * q(3) - p(3) * q(2), - p(0) * q(2) - p(1) * q(3) + p(2) * q(0) + p(3) * q(1), - p(0) * q(3) + p(1) * q(2) - p(2) * q(1) + p(3) * q(0)}; + q(0) * p(0) - q(1) * p(1) - q(2) * p(2) - q(3) * p(3), + q(1) * p(0) + q(0) * p(1) - q(3) * p(2) + q(2) * p(3), + q(2) * p(0) + q(3) * p(1) + q(0) * p(2) - q(1) * p(3), + q(3) * p(0) - q(2) * p(1) + q(1) * p(2) + q(0) * p(3) }; } /** From 38b3acce961ffb3d387082c749130fa9c61c240c Mon Sep 17 00:00:00 2001 From: Nicolas MARTIN Date: Thu, 11 Jun 2020 15:04:03 +0200 Subject: [PATCH 349/388] fix conjugate_inversed comment --- matrix/Quaternion.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index db4eced28f..9acbb4afff 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -407,7 +407,7 @@ public: * Rotates vector v_2 in frame 2 to vector v_1 in frame 1 * using the rotation quaternion q_21 * describing the rotation from frame 1 to 2 - * v_1 = q_21^-1 * v_1 * q_21 + * v_1 = q_21^-1 * v_2 * q_21 * * @param vec vector to rotate in frame 2 (typically reference frame) * @return rotated vector in frame 1 (typically body frame) From 674bd99f3b9284e1088d100d765b3a09cf0c192f Mon Sep 17 00:00:00 2001 From: kamilritz Date: Thu, 11 Jun 2020 19:44:29 +0200 Subject: [PATCH 350/388] Add operator* and operator/ for slice with type --- matrix/Slice.hpp | 18 ++++++++++++++++++ test/slice.cpp | 10 ++++++++++ 2 files changed, 28 insertions(+) diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 91cd7f7aea..5157da20e6 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -184,6 +184,24 @@ public: return operator*=(Type(1) / other); } + Matrix operator*(const Type& other) + { + Slice& self = *this; + Matrix res; + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + res(i, j) = self(i, j) * other; + } + } + return res; + } + + Matrix operator/(const Type& other) + { + Slice& self = *this; + return self * (Type(1) / other); + } + template const Slice slice(size_t x0, size_t y0) const { diff --git a/test/slice.cpp b/test/slice.cpp index 2987ba3ee4..7e4667b56a 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -208,6 +208,16 @@ int main() float O_check_data_10 [9] = {0, 2, 3, 4, 2.5, 6, 7, 4, 10}; TEST(isEqual(O, SquareMatrix3f(O_check_data_10))); + // Different operations + O = SquareMatrix3f(data); + SquareMatrix res_11(O.slice<2,2>(1,1) * 2.f); + float O_check_data_11 [4] = {10, 12, 16, 20}; + TEST(isEqual(res_11, SquareMatrix(O_check_data_11))); + + O = SquareMatrix3f(data); + SquareMatrix res_12(O.slice<2,2>(1,1) / 2.f); + float O_check_data_12 [4] = {2.5, 3, 4, 5}; + TEST(isEqual(res_12, SquareMatrix(O_check_data_12))); return 0; } From f529358e9ac28b0809572c14a964ba7ba691adc4 Mon Sep 17 00:00:00 2001 From: kamilritz Date: Sat, 27 Jun 2020 09:21:21 +0200 Subject: [PATCH 351/388] Add missing const modifier --- matrix/Slice.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 5157da20e6..a6e093aca8 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -184,9 +184,9 @@ public: return operator*=(Type(1) / other); } - Matrix operator*(const Type& other) + Matrix operator*(const Type& other) const { - Slice& self = *this; + const Slice& self = *this; Matrix res; for (size_t i = 0; i < P; i++) { for (size_t j = 0; j < Q; j++) { @@ -196,9 +196,9 @@ public: return res; } - Matrix operator/(const Type& other) + Matrix operator/(const Type& other) const { - Slice& self = *this; + const Slice& self = *this; return self * (Type(1) / other); } From f3cf6150239ee6d6af471b3fc3d49e3b9b834e78 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Tue, 30 Jun 2020 15:47:23 +0200 Subject: [PATCH 352/388] Do += -= and scalar *= /= in place --- matrix/Matrix.hpp | 26 ++++++++++++++++++++------ 1 file changed, 20 insertions(+), 6 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 524ecee33a..a910d4fb04 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -238,13 +238,21 @@ public: void operator+=(const Matrix &other) { Matrix &self = *this; - self = self + other; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) += other(i, j); + } + } } void operator-=(const Matrix &other) { Matrix &self = *this; - self = self - other; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) -= other(i, j); + } + } } template @@ -302,7 +310,7 @@ public: for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { - self(i, j) = self(i, j) * scalar; + self(i, j) *= scalar; } } } @@ -310,17 +318,23 @@ public: void operator/=(Type scalar) { Matrix &self = *this; - self = self * (Type(1) / scalar); + self *= (Type(1) / scalar); } inline void operator+=(Type scalar) { - *this = (*this) + scalar; + Matrix &self = *this; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) += scalar; + } + } } inline void operator-=(Type scalar) { - *this = (*this) - scalar; + Matrix &self = *this; + self += (-scalar); } bool operator==(const Matrix &other) const From 9a30828a0a1d79e87fd09653bb9f936d7ca0ba17 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Tue, 30 Jun 2020 16:21:02 +0200 Subject: [PATCH 353/388] Add explicit matrix + scalar test --- test/matrixMult.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/test/matrixMult.cpp b/test/matrixMult.cpp index 799ab1c009..ca00d0d100 100644 --- a/test/matrixMult.cpp +++ b/test/matrixMult.cpp @@ -56,6 +56,15 @@ int main() Matrix m42_check(data_42); TEST(isEqual(m42, m42_check)) + float data_42_plus2[8] = {17,34, + 13,26, + 19,35, + 29,45 + }; + Matrix m42_plus2_check(data_42_plus2); + Matrix m42_plus2 = m42 - (-2); + TEST(isEqual(m42_plus2, m42_plus2_check)); + return 0; } From 8a59b463f27b3e4df942da4579b9f77856e7eaac Mon Sep 17 00:00:00 2001 From: kamilritz Date: Fri, 17 Jul 2020 10:29:08 +0200 Subject: [PATCH 354/388] Quaternion: Use template type instead of single hardcoded type --- matrix/Quaternion.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 9acbb4afff..24e8c7d806 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -530,7 +530,7 @@ public: * XXX DEPRECATED, can use assignment or ctor */ Quaternion from_dcm(const Matrix& dcm) { - return Quaternion(Dcmf(dcm)); + return Quaternion(Dcm(dcm)); } /** From 0fd99c59f1740a7aa2ead03168705b4211bf29e8 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Jul 2020 16:28:47 +0200 Subject: [PATCH 355/388] Switch operator() to return a const reference --- matrix/Matrix.hpp | 2 +- matrix/Slice.hpp | 2 +- matrix/Vector.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index a910d4fb04..97e1ebf76f 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -94,7 +94,7 @@ public: */ - inline Type operator()(size_t i, size_t j) const + inline const Type &operator()(size_t i, size_t j) const { assert(i >= 0); assert(i < M); diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index a6e093aca8..faf211ca73 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -34,7 +34,7 @@ public: assert(y0 + Q <= N); } - Type operator()(size_t i, size_t j) const + const Type &operator()(size_t i, size_t j) const { assert(i >= 0); assert(i < P); diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 40803ba8cc..e9c0d1f1ab 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -40,7 +40,7 @@ public: { } - inline Type operator()(size_t i) const + inline const Type &operator()(size_t i) const { assert(i >= 0); assert(i < M); From 7a3009f7a397dca9a86b7e4f2ee441f9bba3eb7d Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Jul 2020 08:47:42 +0200 Subject: [PATCH 356/388] Remove asserts for unsigned integer >= 0 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit GCC 10 gives a warning "comparison of unsigned expression in ‘>= 0’ is always true" for these asserts since checking if an unsigned integer cannot be negative and hence the statement gets droped. --- matrix/Matrix.hpp | 8 -------- matrix/Slice.hpp | 6 ------ matrix/SquareMatrix.hpp | 7 ------- matrix/Vector.hpp | 2 -- 4 files changed, 23 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index 97e1ebf76f..e54c99a257 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -96,9 +96,7 @@ public: inline const Type &operator()(size_t i, size_t j) const { - assert(i >= 0); assert(i < M); - assert(j >= 0); assert(j < N); return _data[i][j]; @@ -106,9 +104,7 @@ public: inline Type &operator()(size_t i, size_t j) { - assert(i >= 0); assert(i < M); - assert(j >= 0); assert(j < N); return _data[i][j]; @@ -494,9 +490,7 @@ public: inline void swapRows(size_t a, size_t b) { - assert(a >= 0); assert(a < M); - assert(b >= 0); assert(b < M); if (a == b) { @@ -514,9 +508,7 @@ public: inline void swapCols(size_t a, size_t b) { - assert(a >= 0); assert(a < N); - assert(b >= 0); assert(b < N); if (a == b) { diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index faf211ca73..4040099839 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -28,17 +28,13 @@ public: _data(const_cast*>(data)) { static_assert(P <= M, "Slice rows bigger than backing matrix"); static_assert(Q <= N, "Slice cols bigger than backing matrix"); - assert(x0 >= 0); assert(x0 + P <= M); - assert(y0 >= 0); assert(y0 + Q <= N); } const Type &operator()(size_t i, size_t j) const { - assert(i >= 0); assert(i < P); - assert(j >= 0); assert(j < Q); return (*_data)(_x0 + i, _y0 + j); @@ -47,9 +43,7 @@ public: Type &operator()(size_t i, size_t j) { - assert(i >= 0); assert(i < P); - assert(j >= 0); assert(j < Q); return (*_data)(_x0 + i, _y0 + j); diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 216ff172d8..8c35351664 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -136,7 +136,6 @@ public: void uncorrelateCovariance(size_t first) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; @@ -148,7 +147,6 @@ public: void uncorrelateCovarianceSetVariance(size_t first, const Vector &vec) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; @@ -168,7 +166,6 @@ public: void uncorrelateCovarianceSetVariance(size_t first, Type val) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; @@ -187,7 +184,6 @@ public: void makeBlockSymmetric(size_t first) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; @@ -207,7 +203,6 @@ public: void makeRowColSymmetric(size_t first) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; @@ -231,7 +226,6 @@ public: bool isBlockSymmetric(size_t first, const Type eps = 1e-8f) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; @@ -252,7 +246,6 @@ public: bool isRowColSymmetric(size_t first, const Type eps = 1e-8f) { static_assert(Width <= M, "Width bigger than matrix"); - assert(first >= 0); assert(first + Width <= M); SquareMatrix &self = *this; diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index e9c0d1f1ab..e5bdd43dc5 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -42,7 +42,6 @@ public: inline const Type &operator()(size_t i) const { - assert(i >= 0); assert(i < M); const MatrixM1 &v = *this; @@ -51,7 +50,6 @@ public: inline Type &operator()(size_t i) { - assert(i >= 0); assert(i < M); MatrixM1 &v = *this; From 242b38ee9ebcbbdc8089748f701ccdfc51f48573 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Jul 2020 09:21:01 +0200 Subject: [PATCH 357/388] Quaternion: remove deprecated axis_angle conversions --- matrix/Quaternion.hpp | 93 ------------------------------------------- test/attitude.cpp | 18 +++++---- 2 files changed, 11 insertions(+), 100 deletions(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 24e8c7d806..1e8ca2b6ca 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -224,7 +224,6 @@ public: q.normalize(); } - /** * Constructor from quaternion values * @@ -358,7 +357,6 @@ public: *this = this->canonical(); } - /** * Return canonical form of the quaternion * @@ -420,82 +418,6 @@ public: return Vector3(res(1), res(2), res(3)); } - /** - * Rotation quaternion from vector - * - * The axis of rotation is given by vector direction and - * the angle is given by the norm. - * - * @param vec rotation vector - * @return quaternion representing the rotation - */ - void from_axis_angle(Vector vec) - { - Quaternion &q = *this; - Type theta = vec.norm(); - - if (theta < Type(1e-10)) { - q(0) = Type(1); - q(1) = q(2) = q(3) = Type(0); - return; - } - - vec /= theta; - from_axis_angle(vec, theta); - } - - /** - * Rotation quaternion from axis and angle - * XXX DEPRECATED, use AxisAngle class - * - * @param axis axis of rotation - * @param theta scalar describing angle of rotation - * @return quaternion representing the rotation - */ - void from_axis_angle(const Vector &axis, Type theta) - { - Quaternion &q = *this; - - if (theta < Type(1e-10)) { - q(0) = Type(1); - q(1) = q(2) = q(3) = Type(0); - } - - Type magnitude = sin(theta / 2.0f); - - q(0) = cos(theta / 2.0f); - q(1) = axis(0) * magnitude; - q(2) = axis(1) * magnitude; - q(3) = axis(2) * magnitude; - } - - - /** - * Rotation vector from quaternion - * XXX DEPRECATED, use AxisAngle class - * - * The axis of rotation is given by vector direction and - * the angle is given by the norm. - * - * @return vector, direction representing rotation axis and norm representing angle - */ - Vector to_axis_angle() const - { - const Quaternion &q = *this; - Type axis_magnitude = Type(sqrt(q(1) * q(1) + q(2) * q(2) + q(3) * q(3))); - Vector vec; - vec(0) = q(1); - vec(1) = q(2); - vec(2) = q(3); - - if (axis_magnitude >= Type(1e-10)) { - vec = vec / axis_magnitude; - vec = vec * wrap_pi(Type(2) * atan2(axis_magnitude, q(0))); - } - - return vec; - } - /** * Imaginary components of quaternion */ @@ -525,21 +447,6 @@ public: R_z(2) = a * a - b * b - c * c + d * d; return R_z; } - - /** - * XXX DEPRECATED, can use assignment or ctor - */ - Quaternion from_dcm(const Matrix& dcm) { - return Quaternion(Dcm(dcm)); - } - - /** - * XXX DEPRECATED, can use assignment or ctor - */ - Dcm to_dcm() { - return Dcm(*this); - } - }; typedef Quaternion Quatf; diff --git a/test/attitude.cpp b/test/attitude.cpp index 3acab686f5..3e3c1d164c 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -341,29 +341,29 @@ int main() // get rotation axis from quaternion (nonzero rotation) q = Quatf(cos(1.0f / 2), 0.0f, sin(1.0f / 2), 0.0f); - rot = q.to_axis_angle(); + rot = AxisAnglef(q); TEST(fabs(rot(0)) < eps); TEST(fabs(rot(1) - 1.0f) < eps); TEST(fabs(rot(2)) < eps); // get rotation axis from quaternion (zero rotation) q = Quatf(1.0f, 0.0f, 0.0f, 0.0f); - rot = q.to_axis_angle(); + rot = AxisAnglef(q); TEST(fabs(rot(0)) < eps); TEST(fabs(rot(1)) < eps); TEST(fabs(rot(2)) < eps); // from axis angle (zero rotation) rot(0) = rot(1) = rot(2) = 0.0f; - q.from_axis_angle(rot, 0.0f); + q = Quatf(AxisAnglef(rot)); q_true = Quatf(1.0f, 0.0f, 0.0f, 0.0f); TEST(isEqual(q, q_true)); // from axis angle, with length of vector the rotation float n = float(sqrt(4*M_PI*M_PI/3)); - q.from_axis_angle(Vector3f(n, n, n)); + q = AxisAnglef(n, n, n); TEST(isEqual(q, Quatf(-1, 0, 0, 0))); - q.from_axis_angle(Vector3f(0, 0, 0)); + q = AxisAnglef(0, 0, 0); TEST(isEqual(q, Quatf(1, 0, 0, 0))); // Quaternion initialisation per array @@ -388,13 +388,17 @@ int main() TEST(isEqualF(aa_norm_check.angle(), 0.0f)); q = Quatf(-0.29555112749297824f, 0.25532186f, 0.51064372f, 0.76596558f); + float r_array[9] = {-0.6949206f, 0.713521f, 0.089292854f, -0.19200698f, -0.30378509f, 0.93319237f, 0.69297814f, 0.63134968f, 0.34810752f}; + R = Dcmf(r_array); TEST(isEqual(q.imag(), Vector3f(0.25532186f, 0.51064372f, 0.76596558f))); // from dcm - TEST(isEqual(Eulerf(q.from_dcm(Dcmf(q))), Eulerf(q))); + TEST(isEqual(Quatf(R), q)); + TEST(isEqual(Quatf(Dcmf(q)), q)); // to dcm - TEST(isEqual(Dcmf(q), q.to_dcm())); + TEST(isEqual(Dcmf(q), R)); + TEST(isEqual(Dcmf(Quatf(R)), R)); // conjugate v = Vector3f(1.5f, 2.2f, 3.2f); From 572bafb01f4310027caf0a8594da6f0615c3aa79 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Jul 2020 09:31:43 +0200 Subject: [PATCH 358/388] Quaternion: use template type for division by two --- matrix/Quaternion.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 1e8ca2b6ca..5bd23457e5 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -174,7 +174,7 @@ public: q(1) = q(2) = q(3) = 0; } else { Type magnitude = sin(angle / Type(2)); - q(0) = cos(angle / 2.0f); + q(0) = cos(angle / Type(2)); q(1) = axis(0) * magnitude; q(2) = axis(1) * magnitude; q(3) = axis(2) * magnitude; From a126be0882f46336b06111995896ad85da97beef Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Jul 2020 09:39:53 +0200 Subject: [PATCH 359/388] attitude test: refactoring to avoid identity quaternion confusion --- test/attitude.cpp | 24 ++++++++++-------------- 1 file changed, 10 insertions(+), 14 deletions(-) diff --git a/test/attitude.cpp b/test/attitude.cpp index 3e3c1d164c..cbdcf3d6df 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -307,30 +307,26 @@ int main() // quaternion setIdentity Quatf q_nonIdentity(-0.7f, 0.4f, 0.5f, -0.3f); - Quatf q_identity(1.0f, 0.0f, 0.0f, 0.0f); q_nonIdentity.setIdentity(); - TEST(isEqual(q_nonIdentity, q_identity)); + TEST(isEqual(q_nonIdentity, Quatf())); // non-unit quaternion invese - Quatf qI(1.0f, 0.0f, 0.0f, 0.0f); Quatf q_nonunit(0.1f, 0.2f, 0.3f, 0.4f); - TEST(isEqual(qI, q_nonunit*q_nonunit.inversed())); + TEST(isEqual(q_nonunit*q_nonunit.inversed(), Quatf())); // rotate quaternion (nonzero rotation) - Vector rot; - rot(0) = 1.0f; - rot(1) = rot(2) = 0.0f; - qI.rotate(rot); + Vector3f rot(1.f, 0.f, 0.f); + Quatf q_test; + q_test.rotate(rot); Quatf q_true(cos(1.0f / 2), sin(1.0f / 2), 0.0f, 0.0f); - TEST(isEqual(qI, q_true)); + TEST(isEqual(q_test, q_true)); // rotate quaternion (zero rotation) - qI = Quatf(1.0f, 0.0f, 0.0f, 0.0f); - rot(0) = 0.0f; - rot(1) = rot(2) = 0.0f; - qI.rotate(rot); + rot(0) = rot(1) = rot(2) = 0.0f; + q_test = Quatf(); + q_test.rotate(rot); q_true = Quatf(cos(0.0f), sin(0.0f), 0.0f, 0.0f); - TEST(isEqual(qI, q_true)); + TEST(isEqual(q_test, q_true)); // rotate quaternion (random non-commutating rotation) q = Quatf(AxisAnglef(5.1f, 3.2f, 8.4f)); From 6ed5dbc2db0544e121c081532794d7db16b30924 Mon Sep 17 00:00:00 2001 From: kamilritz Date: Wed, 5 Aug 2020 22:29:32 +0200 Subject: [PATCH 360/388] Construct Vector from Slice<1,M> alias row() --- matrix/Vector.hpp | 9 +++++++++ matrix/Vector2.hpp | 5 +++++ matrix/Vector3.hpp | 5 +++++ test/slice.cpp | 6 ++++++ 4 files changed, 25 insertions(+) diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index e5bdd43dc5..64a9fe54db 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -40,6 +40,15 @@ public: { } + template + Vector(const Slice& slice_in) + { + Vector &self(*this); + for (size_t i = 0; i + Vector2(const Slice& slice_in) : Vector(slice_in) + { + } + explicit Vector2(const Vector3 & other) { Vector2 &v(*this); diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 70d503aafd..5f463b61cb 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -56,6 +56,11 @@ public: { } + template + Vector3(const Slice& slice_in) : Vector(slice_in) + { + } + Vector3 cross(const Matrix31 & b) const { const Vector3 &a(*this); return {a(1)*b(2,0) - a(2)*b(1,0), -a(0)*b(2,0) + a(2)*b(0,0), a(0)*b(1,0) - a(1)*b(0,0)}; diff --git a/test/slice.cpp b/test/slice.cpp index 7e4667b56a..a8db0acd47 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -153,6 +153,12 @@ int main() Vector2f v8 = N.slice<3,2>(0,1).diag(); Vector2f v8_check = {2, 6}; TEST(isEqual(v8,v8_check)); + Vector2f v9(N.slice<1,2>(1,1)); + Vector2f v9_check = {5, 6}; + TEST(isEqual(v9,v9_check)); + Vector3f v10(N.slice<1,3>(1,0)); + Vector3f v10_check = {4, 5, 6}; + TEST(isEqual(v10,v10_check)); // Different assignment operators SquareMatrix3f O(data); From 18699416b010ed9fdd488df21b66bf4332536ca6 Mon Sep 17 00:00:00 2001 From: kritz Date: Fri, 7 Aug 2020 18:44:48 +0200 Subject: [PATCH 361/388] SparseVector (#140) * Add SparseVector temp * Add gtest * Some reworking of the sparse concept * Change type of M from int to size_t * Add const modifier * Add needed declaration for accessing elements of _indices * Add norm_squared, norm, longerThan * Add test for all sparse vector functions * Add missing const to slice's norm_squared, norm and longerThan * Construction from Vector and carray[N] * try to fix ci Co-authored-by: Julian Kent --- .travis.yml | 2 +- CMakeLists.txt | 2 +- matrix/Slice.hpp | 8 +- matrix/SparseVector.hpp | 160 ++++++++++++++++++++++++++++++++++++++++ matrix/math.hpp | 1 + test/CMakeLists.txt | 4 + test/CMakeLists.txt.in | 18 +++++ test/gtest.cmake | 12 +++ test/sparseVector.cpp | 98 ++++++++++++++++++++++++ 9 files changed, 299 insertions(+), 6 deletions(-) create mode 100644 matrix/SparseVector.hpp create mode 100644 test/CMakeLists.txt.in create mode 100644 test/gtest.cmake create mode 100644 test/sparseVector.cpp diff --git a/.travis.yml b/.travis.yml index dab3adef51..3b5f105333 100644 --- a/.travis.yml +++ b/.travis.yml @@ -25,7 +25,7 @@ addons: packages: - clang - cmake - - g++ + - g++-8 - gcc - lcov diff --git a/CMakeLists.txt b/CMakeLists.txt index b37a1de914..a899d67989 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ set(VERSION_PATCH "2") project(matrix CXX) -set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD 14) set(CMAKE_CXX_STANDARD_REQUIRED ON) if (NOT CMAKE_BUILD_TYPE) diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 4040099839..6ab54c0be3 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -240,9 +240,9 @@ public: return res; } - Type norm_squared() + Type norm_squared() const { - Slice& self = *this; + const Slice& self = *this; Type accum(0); for (size_t i = 0; i < P; i++) { for (size_t j = 0; j < Q; j++) { @@ -252,12 +252,12 @@ public: return accum; } - Type norm() + Type norm() const { return matrix::sqrt(norm_squared()); } - bool longerThan(Type testVal) + bool longerThan(Type testVal) const { return norm_squared() > testVal*testVal; } diff --git a/matrix/SparseVector.hpp b/matrix/SparseVector.hpp new file mode 100644 index 0000000000..3910130f64 --- /dev/null +++ b/matrix/SparseVector.hpp @@ -0,0 +1,160 @@ +/** + * @file SparseVector.hpp + * + * SparseVector class. + * + * @author Kamil Ritz + * @author Julian Kent + * + */ + +#pragma once + +#include "math.hpp" + +namespace matrix { +template struct force_constexpr_eval { + static const int value = N; +}; + +// Vector that only store nonzero elements, +// which indices are specified as parameter pack +template +class SparseVector { +private: + static constexpr size_t N = sizeof...(Idxs); + static constexpr int _indices[N] {Idxs...}; + + static constexpr bool duplicateIndices() { + for (int i = 0; i < N; i++) + for (int j = 0; j < i; j++) + if (_indices[i] == _indices[j]) + return true; + return false; + } + static constexpr int findMaxIndex() { + int maxIndex = -1; + for (int i = 0; i < N; i++) { + if (maxIndex < _indices[i]) { + maxIndex = _indices[i]; + } + } + return maxIndex; + } + static_assert(duplicateIndices() == false, "Duplicate indices"); + static_assert(N < M, "More entries than elements, use a dense vector"); + static_assert(findMaxIndex() < M, "Largest entry doesn't fit in sparse vector"); + + Type _data[N] {}; + + static constexpr int findCompressedIndex(int index) { + int compressedIndex = -1; + for (int i = 0; i < N; i++) { + if (index == _indices[i]) { + compressedIndex = i; + } + } + return compressedIndex; + } + +public: + static constexpr int non_zeros() { + return N; + } + + constexpr int index(int i) const { + return SparseVector::_indices[i]; + } + + SparseVector() = default; + + SparseVector(const matrix::Vector& data) { + for (int i = 0; i < N; i++) { + _data[i] = data(_indices[i]); + } + } + + explicit SparseVector(const Type data[N]) { + memcpy(_data, data, sizeof(_data)); + } + + template + inline Type at() const { + static constexpr int compressed_index = force_constexpr_eval::value; + static_assert(compressed_index >= 0, "cannot access unpopulated indices"); + return _data[compressed_index]; + } + + template + inline Type& at() { + static constexpr int compressed_index = force_constexpr_eval::value; + static_assert(compressed_index >= 0, "cannot access unpopulated indices"); + return _data[compressed_index]; + } + + void setZero() { + for (size_t i = 0; i < N; i++) { + _data[i] = Type(0); + } + } + + Type dot(const matrix::Vector& other) const { + Type accum (0); + for (size_t i = 0; i < N; i++) { + accum += _data[i] * other(_indices[i]); + } + return accum; + } + + matrix::Vector operator+(const matrix::Vector& other) const { + matrix::Vector vec = other; + for (size_t i = 0; i < N; i++) { + vec(_indices[i]) += _data[i]; + } + return vec; + } + + SparseVector& operator+=(Type t) { + for (size_t i = 0; i < N; i++) { + _data[i] += t; + } + return *this; + } + + Type norm_squared() const + { + Type accum(0); + for (size_t i = 0; i < N; i++) { + accum += _data[i] * _data[i]; + } + return accum; + } + + Type norm() const + { + return matrix::sqrt(norm_squared()); + } + + bool longerThan(Type testVal) const + { + return norm_squared() > testVal*testVal; + } +}; + +template +matrix::Vector operator*(const matrix::Matrix& mat, const matrix::SparseVector& vec) { + matrix::Vector res; + for (size_t i = 0; i < Q; i++) { + const Vector row = mat.row(i); + res(i) = vec.dot(row); + } + return res; +} + +template +constexpr int SparseVector::_indices[SparseVector::N]; + +template +using SparseVectorf = SparseVector; + +} diff --git a/matrix/math.hpp b/matrix/math.hpp index edfc1591fc..cc4e5e81d7 100644 --- a/matrix/math.hpp +++ b/matrix/math.hpp @@ -20,3 +20,4 @@ #include "LeastSquaresSolver.hpp" #include "Dual.hpp" #include "PseudoInverse.hpp" +#include "SparseVector.hpp" diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index c1f8e7a024..944bfc32a3 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,3 +1,5 @@ +include(gtest.cmake) + set(tests setIdentity inverse @@ -13,6 +15,7 @@ set(tests attitude filter integration + sparseVector squareMatrix helper hatvee @@ -30,6 +33,7 @@ foreach(test_name ${tests}) add_test(test_${test_name} ${test_name}) add_dependencies(test_build ${test_name}) endforeach() +target_link_libraries(sparseVector gtest_main) if (${CMAKE_BUILD_TYPE} STREQUAL "Coverage") diff --git a/test/CMakeLists.txt.in b/test/CMakeLists.txt.in new file mode 100644 index 0000000000..fb9ff2f0ab --- /dev/null +++ b/test/CMakeLists.txt.in @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 2.8.4) + +project(googletest-download NONE) + +include(ExternalProject) +ExternalProject_Add(googletest + URL https://github.com/google/googletest/archive/8b6d3f9c4a774bef3081195d422993323b6bb2e0.zip + SOURCE_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-src" + BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-build" + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" + TEST_COMMAND "" + # Wrap download, configure and build steps in a script to log output + LOG_DOWNLOAD ON + LOG_CONFIGURE ON + LOG_BUILD ON +) diff --git a/test/gtest.cmake b/test/gtest.cmake new file mode 100644 index 0000000000..f1c07b3576 --- /dev/null +++ b/test/gtest.cmake @@ -0,0 +1,12 @@ +set_directory_properties(PROPERTIES COMPILE_OPTIONS "") + +# Download and unpack googletest at configure time +configure_file(${CMAKE_CURRENT_LIST_DIR}/CMakeLists.txt.in googletest-download/CMakeLists.txt) +execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" . RESULT_VARIABLE result1 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download) +execute_process(COMMAND ${CMAKE_COMMAND} --build . RESULT_VARIABLE result2 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download) +if(result1 OR result2) + message(FATAL_ERROR "Preparing googletest failed: ${result1} ${result2}") +endif() + +# Add googletest, defines gtest and gtest_main targets +add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/googletest-src ${CMAKE_CURRENT_BINARY_DIR}/googletest-build EXCLUDE_FROM_ALL) diff --git a/test/sparseVector.cpp b/test/sparseVector.cpp new file mode 100644 index 0000000000..2b0dc0c3bb --- /dev/null +++ b/test/sparseVector.cpp @@ -0,0 +1,98 @@ +#include +#include + +using namespace matrix; + +TEST(sparseVectorTest, defaultConstruction) { + SparseVectorf<24, 4, 6> a; + EXPECT_EQ(a.non_zeros(), 2); + EXPECT_EQ(a.index(0), 4); + EXPECT_EQ(a.index(1), 6); + a.at<4>() = 1.f; + a.at<6>() = 2.f; +} + +TEST(sparseVectorTest, initializationWithData) { + const float data[3] = {1.f, 2.f, 3.f}; + SparseVectorf<24, 4, 6, 22> a(data); + EXPECT_EQ(a.non_zeros(), 3); + EXPECT_EQ(a.index(0), 4); + EXPECT_EQ(a.index(1), 6); + EXPECT_EQ(a.index(2), 22); + EXPECT_FLOAT_EQ(a.at<4>(), data[0]); + EXPECT_FLOAT_EQ(a.at<6>(), data[1]); + EXPECT_FLOAT_EQ(a.at<22>(), data[2]); +} + +TEST(sparseVectorTest, initialisationFromVector) { + const Vector3f vec(1.f, 2.f, 3.f); + const SparseVectorf<3, 0, 2> a(vec); + EXPECT_FLOAT_EQ(a.at<0>(), vec(0)); + EXPECT_FLOAT_EQ(a.at<2>(), vec(2)); +} + +TEST(sparseVectorTest, setZero) { + const float data[3] = {1.f, 2.f, 3.f}; + SparseVectorf<24, 4, 6, 22> a(data); + a.setZero(); + EXPECT_FLOAT_EQ(a.at<4>(), 0.f); + EXPECT_FLOAT_EQ(a.at<6>(), 0.f); + EXPECT_FLOAT_EQ(a.at<22>(), 0.f); +} + +TEST(sparseVectorTest, additionWithDenseVector) { + Vector dense_vec; + dense_vec.setAll(1.f); + const float data[3] = {1.f, 2.f, 3.f}; + const SparseVectorf<4, 1, 2, 3> sparse_vec(data); + const Vector res = sparse_vec + dense_vec; + EXPECT_FLOAT_EQ(res(0), 1.f); + EXPECT_FLOAT_EQ(res(1), 2.f); + EXPECT_FLOAT_EQ(res(2), 3.f); + EXPECT_FLOAT_EQ(res(3), 4.f); +} + +TEST(sparseVectorTest, addScalar) { + const float data[3] = {1.f, 2.f, 3.f}; + SparseVectorf<4, 1, 2, 3> sparse_vec(data); + sparse_vec += 2.f; + EXPECT_FLOAT_EQ(sparse_vec.at<1>(), 3.f); + EXPECT_FLOAT_EQ(sparse_vec.at<2>(), 4.f); + EXPECT_FLOAT_EQ(sparse_vec.at<3>(), 5.f); +} + +TEST(sparseVectorTest, dotProductWithDenseVector) { + Vector dense_vec; + dense_vec.setAll(3.f); + const float data[3] = {1.f, 2.f, 3.f}; + const SparseVectorf<4, 1, 2, 3> sparse_vec(data); + float res = sparse_vec.dot(dense_vec); + EXPECT_FLOAT_EQ(res, 18.f); +} + +TEST(sparseVectorTest, multiplicationWithDenseMatrix) { + Matrix dense_matrix; + dense_matrix.setAll(2.f); + dense_matrix(1, 1) = 3.f; + const Vector3f dense_vec(0.f, 1.f, 5.f); + const SparseVectorf<3, 1, 2> sparse_vec(dense_vec); + const Vector res_sparse = dense_matrix * sparse_vec; + const Vector res_dense = dense_matrix * dense_vec; + EXPECT_TRUE(isEqual(res_dense, res_sparse)); +} + +TEST(sparseVectorTest, norms) { + const float data[2] = {3.f, 4.f}; + const SparseVectorf<4, 1, 3> sparse_vec(data); + EXPECT_FLOAT_EQ(sparse_vec.norm_squared(), 25.f); + EXPECT_FLOAT_EQ(sparse_vec.norm(), 5.f); + EXPECT_TRUE(sparse_vec.longerThan(4.5f)); + EXPECT_FALSE(sparse_vec.longerThan(5.5f)); +} + + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + std::cout << "Run SparseVector tests" << std::endl; + return RUN_ALL_TESTS(); +} From e714a28c836773605bd1eb81a7a0dc0208746aef Mon Sep 17 00:00:00 2001 From: kamilritz Date: Fri, 7 Aug 2020 19:23:58 +0200 Subject: [PATCH 362/388] use size_t instead of int in sparseVector --- matrix/SparseVector.hpp | 40 +++++++++++++++++++++------------------- 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/matrix/SparseVector.hpp b/matrix/SparseVector.hpp index 3910130f64..ae7cc3a608 100644 --- a/matrix/SparseVector.hpp +++ b/matrix/SparseVector.hpp @@ -19,57 +19,59 @@ template struct force_constexpr_eval { // Vector that only store nonzero elements, // which indices are specified as parameter pack -template +template class SparseVector { private: static constexpr size_t N = sizeof...(Idxs); - static constexpr int _indices[N] {Idxs...}; + static constexpr size_t _indices[N] {Idxs...}; static constexpr bool duplicateIndices() { - for (int i = 0; i < N; i++) - for (int j = 0; j < i; j++) + for (size_t i = 0; i < N; i++) + for (size_t j = 0; j < i; j++) if (_indices[i] == _indices[j]) return true; return false; } - static constexpr int findMaxIndex() { - int maxIndex = -1; - for (int i = 0; i < N; i++) { + static constexpr size_t findMaxIndex() { + size_t maxIndex = 0; + for (size_t i = 0; i < N; i++) { if (maxIndex < _indices[i]) { maxIndex = _indices[i]; } } return maxIndex; } + static_assert(duplicateIndices() == false, "Duplicate indices"); static_assert(N < M, "More entries than elements, use a dense vector"); + static_assert(N > 0, "A sparse vector needs at least one element"); static_assert(findMaxIndex() < M, "Largest entry doesn't fit in sparse vector"); Type _data[N] {}; - static constexpr int findCompressedIndex(int index) { + static constexpr int findCompressedIndex(size_t index) { int compressedIndex = -1; - for (int i = 0; i < N; i++) { + for (size_t i = 0; i < N; i++) { if (index == _indices[i]) { - compressedIndex = i; + compressedIndex = static_cast(i); } } return compressedIndex; } public: - static constexpr int non_zeros() { + static constexpr size_t non_zeros() { return N; } - constexpr int index(int i) const { + constexpr size_t index(size_t i) const { return SparseVector::_indices[i]; } SparseVector() = default; SparseVector(const matrix::Vector& data) { - for (int i = 0; i < N; i++) { + for (size_t i = 0; i < N; i++) { _data[i] = data(_indices[i]); } } @@ -78,14 +80,14 @@ public: memcpy(_data, data, sizeof(_data)); } - template + template inline Type at() const { static constexpr int compressed_index = force_constexpr_eval::value; static_assert(compressed_index >= 0, "cannot access unpopulated indices"); return _data[compressed_index]; } - template + template inline Type& at() { static constexpr int compressed_index = force_constexpr_eval::value; static_assert(compressed_index >= 0, "cannot access unpopulated indices"); @@ -141,7 +143,7 @@ public: } }; -template +template matrix::Vector operator*(const matrix::Matrix& mat, const matrix::SparseVector& vec) { matrix::Vector res; for (size_t i = 0; i < Q; i++) { @@ -151,10 +153,10 @@ matrix::Vector operator*(const matrix::Matrix& mat, const m return res; } -template -constexpr int SparseVector::_indices[SparseVector::N]; +template +constexpr size_t SparseVector::_indices[SparseVector::N]; -template +template using SparseVectorf = SparseVector; } From f981cea2aebfc9cfd930dce73ba6d4d6681e99c1 Mon Sep 17 00:00:00 2001 From: kritz Date: Sun, 9 Aug 2020 09:44:49 +0200 Subject: [PATCH 363/388] add possibility to iterate over SparseVector data at runtime (#143) --- matrix/SparseVector.hpp | 12 +++++++++++- test/sparseVector.cpp | 10 ++++++++++ 2 files changed, 21 insertions(+), 1 deletion(-) diff --git a/matrix/SparseVector.hpp b/matrix/SparseVector.hpp index ae7cc3a608..7e1631183b 100644 --- a/matrix/SparseVector.hpp +++ b/matrix/SparseVector.hpp @@ -60,7 +60,7 @@ private: } public: - static constexpr size_t non_zeros() { + constexpr size_t non_zeros() const { return N; } @@ -94,6 +94,16 @@ public: return _data[compressed_index]; } + inline Type atCompressedIndex(size_t i) const { + assert(i < N); + return _data[i]; + } + + inline Type& atCompressedIndex(size_t i) { + assert(i < N); + return _data[i]; + } + void setZero() { for (size_t i = 0; i < N; i++) { _data[i] = Type(0); diff --git a/test/sparseVector.cpp b/test/sparseVector.cpp index 2b0dc0c3bb..4bfb718bd1 100644 --- a/test/sparseVector.cpp +++ b/test/sparseVector.cpp @@ -31,6 +31,16 @@ TEST(sparseVectorTest, initialisationFromVector) { EXPECT_FLOAT_EQ(a.at<2>(), vec(2)); } +TEST(sparseVectorTest, accessDataWithCompressedIndices) { + const Vector3f vec(1.f, 2.f, 3.f); + SparseVectorf<3, 0, 2> a(vec); + for (size_t i = 0; i < a.non_zeros(); i++) { + a.atCompressedIndex(i) = static_cast(i); + } + EXPECT_FLOAT_EQ(a.at<0>(), a.atCompressedIndex(0)); + EXPECT_FLOAT_EQ(a.at<2>(), a.atCompressedIndex(1)); +} + TEST(sparseVectorTest, setZero) { const float data[3] = {1.f, 2.f, 3.f}; SparseVectorf<24, 4, 6, 22> a(data); From 25c04553488bb86470592a1cdccac56979bf59bb Mon Sep 17 00:00:00 2001 From: kamilritz Date: Mon, 10 Aug 2020 08:03:37 +0200 Subject: [PATCH 364/388] comply with Firmware style requirements --- matrix/SparseVector.hpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/matrix/SparseVector.hpp b/matrix/SparseVector.hpp index 7e1631183b..2940076e50 100644 --- a/matrix/SparseVector.hpp +++ b/matrix/SparseVector.hpp @@ -26,10 +26,13 @@ private: static constexpr size_t _indices[N] {Idxs...}; static constexpr bool duplicateIndices() { - for (size_t i = 0; i < N; i++) - for (size_t j = 0; j < i; j++) - if (_indices[i] == _indices[j]) + for (size_t i = 0; i < N; i++) { + for (size_t j = 0; j < i; j++) { + if (_indices[i] == _indices[j]) { return true; + } + } + } return false; } static constexpr size_t findMaxIndex() { @@ -42,7 +45,7 @@ private: return maxIndex; } - static_assert(duplicateIndices() == false, "Duplicate indices"); + static_assert(!duplicateIndices(), "Duplicate indices"); static_assert(N < M, "More entries than elements, use a dense vector"); static_assert(N > 0, "A sparse vector needs at least one element"); static_assert(findMaxIndex() < M, "Largest entry doesn't fit in sparse vector"); From cd8ad1584c80889ae3893b45d3764fa06b678762 Mon Sep 17 00:00:00 2001 From: Morten Fyhn Amundsen Date: Mon, 24 Aug 2020 10:49:12 +0200 Subject: [PATCH 365/388] Make wrap() work with integer types (#145) * Make wrap() work with integers --- matrix/helper_functions.hpp | 61 ++++++++++++++++++++++++++++++------- test/helper.cpp | 7 +++++ 2 files changed, 57 insertions(+), 11 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 89f2dbffb9..a5c3fbc3a5 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -39,25 +39,64 @@ bool isEqualF(const Type x, const Type y, const Type eps = 1e-4f) || (isinf(x) && isinf(y) && isnan(x - y)); } +namespace detail +{ + +template +Floating wrap_floating(Floating x, Floating low, Floating high) { + // already in range + if (low <= x && x < high) { + return x; + } + + const auto range = high - low; + const auto inv_range = Floating(1) / range; // should evaluate at compile time, multiplies below at runtime + const auto num_wraps = floor((x - low) * inv_range); + return x - range * num_wraps; +} + +} // namespace detail + /** - * Wrap value to stay in range [low, high) + * Wrap single precision floating point value to stay in range [low, high) * * @param x input possibly outside of the range * @param low lower limit of the allowed range * @param high upper limit of the allowed range * @return wrapped value inside the range */ -template -Type wrap(Type x, Type low, Type high) { - // already in range - if (low <= x && x < high) { - return x; - } +float wrap(float x, float low, float high) { + return matrix::detail::wrap_floating(x, low, high); +} - const Type range = high - low; - const Type inv_range = Type(1) / range; // should evaluate at compile time, multiplies below at runtime - const Type num_wraps = floor((x - low) * inv_range); - return x - range * num_wraps; +/** + * Wrap double precision floating point value to stay in range [low, high) + * + * @param x input possibly outside of the range + * @param low lower limit of the allowed range + * @param high upper limit of the allowed range + * @return wrapped value inside the range + */ +double wrap(double x, double low, double high) { + return matrix::detail::wrap_floating(x, low, high); +} + +/** + * Wrap integer value to stay in range [low, high) + * + * @param x input possibly outside of the range + * @param low lower limit of the allowed range + * @param high upper limit of the allowed range + * @return wrapped value inside the range + */ +template +Integer wrap(Integer x, Integer low, Integer high) { + const auto range = high - low; + + if (x < low) + x += range * ((low - x) / range + 1); + + return low + (x - low) % range; } /** diff --git a/test/helper.cpp b/test/helper.cpp index c9f42cfdd5..6d8b539f3a 100644 --- a/test/helper.cpp +++ b/test/helper.cpp @@ -21,6 +21,13 @@ int main() TEST(fabs(wrap(360. - FLT_EPSILON, 0., 360.) - (360. - FLT_EPSILON)) < FLT_EPSILON); TEST(fabs(wrap(360. + FLT_EPSILON, 0., 360.) - FLT_EPSILON) < FLT_EPSILON); + // integer wraps + TEST(wrap(-10, 0, 10) == 0); + TEST(wrap(-4, 0, 10) == 6); + TEST(wrap(0, 0, 10) == 0) + TEST(wrap(4, 0, 10) == 4); + TEST(wrap(10, 0, 10) == 0); + // wrap pi TEST(fabs(wrap_pi(0.)) < FLT_EPSILON); TEST(fabs(wrap_pi(4.) - (4. - M_TWOPI)) < FLT_EPSILON); From e101edc0e7616a224dacd1ef52f0ef3a6d00c53e Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 24 Aug 2020 14:19:43 +0200 Subject: [PATCH 366/388] Matrix: fix warning if M == N (#146) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This fixes the warning appearing with GCC 10.2: ../../src/lib/matrix/matrix/Matrix.hpp:481:34: error: logical ‘and’ of equal expressions [-Werror=logical-op] 481 | for (size_t i = 0; i < M && i < N; i++) { | I would prefered something with if constexpr but we don't have that yet in because we're using C++14. --- matrix/Matrix.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index e54c99a257..d7e57e37ef 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -478,7 +478,8 @@ public: setZero(); Matrix &self = *this; - for (size_t i = 0; i < M && i < N; i++) { + const size_t min_i = M > N ? N : M; + for (size_t i = 0; i < min_i; i++) { self(i, i) = 1; } } From 3a5bfb2bd1c81299c5a3f7f06bfdc12a9b55109d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 25 Aug 2020 12:58:04 +0200 Subject: [PATCH 367/388] matrix: inline to prevent multiple definitions (#147) Without inline we get multiple definitions during linking. --- matrix/helper_functions.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index a5c3fbc3a5..9c85fcda82 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -65,7 +65,7 @@ Floating wrap_floating(Floating x, Floating low, Floating high) { * @param high upper limit of the allowed range * @return wrapped value inside the range */ -float wrap(float x, float low, float high) { +inline float wrap(float x, float low, float high) { return matrix::detail::wrap_floating(x, low, high); } @@ -77,7 +77,7 @@ float wrap(float x, float low, float high) { * @param high upper limit of the allowed range * @return wrapped value inside the range */ -double wrap(double x, double low, double high) { +inline double wrap(double x, double low, double high) { return matrix::detail::wrap_floating(x, low, high); } From 13f092a30fe8d51426df532f1fceb701b8e70884 Mon Sep 17 00:00:00 2001 From: Kamil Ritz Date: Wed, 26 Aug 2020 18:23:07 +0200 Subject: [PATCH 368/388] sparse quadratic form --- matrix/SparseVector.hpp | 14 ++++++++++++++ test/sparseVector.cpp | 11 +++++++++++ 2 files changed, 25 insertions(+) diff --git a/matrix/SparseVector.hpp b/matrix/SparseVector.hpp index 2940076e50..ca4659a7a3 100644 --- a/matrix/SparseVector.hpp +++ b/matrix/SparseVector.hpp @@ -166,6 +166,20 @@ matrix::Vector operator*(const matrix::Matrix& mat, const m return res; } +// returns x.T * A * x +template +Type quadraticForm(const matrix::SquareMatrix& A, const matrix::SparseVector& x) { + Type res = Type(0); + for (size_t i = 0; i < x.non_zeros(); i++) { + Type tmp = Type(0); + for (size_t j = 0; j < x.non_zeros(); j++) { + tmp += A(x.index(i), x.index(j)) * x.atCompressedIndex(j); + } + res += x.atCompressedIndex(i) * tmp; + } + return res; +} + template constexpr size_t SparseVector::_indices[SparseVector::N]; diff --git a/test/sparseVector.cpp b/test/sparseVector.cpp index 4bfb718bd1..9c2dbd1224 100644 --- a/test/sparseVector.cpp +++ b/test/sparseVector.cpp @@ -91,6 +91,17 @@ TEST(sparseVectorTest, multiplicationWithDenseMatrix) { EXPECT_TRUE(isEqual(res_dense, res_sparse)); } +TEST(sparseVectorTest, quadraticForm) { + float matrix_data[9] = {1, 2, 3, + 2, 4, 5, + 3, 5, 6 + }; + const SquareMatrix dense_matrix(matrix_data); + const Vector3f dense_vec(0.f, 1.f, 5.f); + const SparseVectorf<3, 1, 2> sparse_vec(dense_vec); + EXPECT_FLOAT_EQ(quadraticForm(dense_matrix, sparse_vec), 204.f); +} + TEST(sparseVectorTest, norms) { const float data[2] = {3.f, 4.f}; const SparseVectorf<4, 1, 3> sparse_vec(data); From ce6b10b99af722a4e653387d40019a8428d2a54f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 27 Aug 2020 17:37:20 +0200 Subject: [PATCH 369/388] Fix clang-tidy warnings This comes from PX4 CI. --- matrix/helper_functions.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 9c85fcda82..37d2191f94 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -93,8 +93,9 @@ template Integer wrap(Integer x, Integer low, Integer high) { const auto range = high - low; - if (x < low) + if (x < low) { x += range * ((low - x) / range + 1); + } return low + (x - low) % range; } From a504b6e88152d88dba936bc74e449f2f281b84e2 Mon Sep 17 00:00:00 2001 From: Mitchell-Lee-93 <56542570+Mitchell-Lee-93@users.noreply.github.com> Date: Wed, 4 Nov 2020 00:13:28 +0900 Subject: [PATCH 370/388] precision of tol for float has been changed --- matrix/PseudoInverse.hxx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matrix/PseudoInverse.hxx b/matrix/PseudoInverse.hxx index 99408f5e2f..a03184dc43 100644 --- a/matrix/PseudoInverse.hxx +++ b/matrix/PseudoInverse.hxx @@ -14,7 +14,7 @@ template void fullRankCholeskyTolerance(Type &tol) { - tol /= 1000000000; + tol /= 10000000; } template<> inline From 158409abceaf9fb902f9b9bac086267220ce5ecc Mon Sep 17 00:00:00 2001 From: JacobCrabill Date: Mon, 23 Mar 2020 19:37:28 -0700 Subject: [PATCH 371/388] Vector3f: Add operator+/- for scalars --- matrix/Vector3.hpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 5f463b61cb..6e8cc601a1 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -75,11 +75,21 @@ public: return Matrix31::operator+(other); } + inline Vector3 operator+(Type scalar) const + { + return Matrix31::operator+(scalar); + } + inline Vector3 operator-(Vector3 other) const { return Matrix31::operator-(other); } + inline Vector3 operator-(Type scalar) const + { + return Matrix31::operator-(scalar); + } + inline Vector3 operator-() const { return Matrix31::operator-(); From ea43303c1cd55b0da8e152373b49dd2d5e381772 Mon Sep 17 00:00:00 2001 From: JacobCrabill Date: Wed, 16 Dec 2020 14:34:12 -0800 Subject: [PATCH 372/388] test/vector3: Add test for scalar +/- operators --- test/vector3.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/test/vector3.cpp b/test/vector3.cpp index b5cef674b9..8143c8ab32 100644 --- a/test/vector3.cpp +++ b/test/vector3.cpp @@ -50,6 +50,11 @@ int main() Vector3f k_test(1,2,3); TEST(isEqual(k,k_test)); + Vector3f m1(1, 2, 3); + Vector3f m2(3.1f, 4.1f, 5.1f); + TEST(isEqual(m2, m1 + 2.1f)); + TEST(isEqual(m2 - 2.1f, m1)); + return 0; } From d9a5e3dec209e1f221b302f6b3156455053e5f26 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Wed, 4 Nov 2020 12:54:15 +0100 Subject: [PATCH 373/388] Add test for new cutoff threshold --- test/pseudoInverse.cpp | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/test/pseudoInverse.cpp b/test/pseudoInverse.cpp index 476e45dd37..35ee8c5262 100644 --- a/test/pseudoInverse.cpp +++ b/test/pseudoInverse.cpp @@ -133,6 +133,25 @@ int main() fullRankCholeskyTolerance(double_scale); TEST(static_cast(float_scale) > double_scale); + // Real-world test case + const float real_alloc[5][6] = {{ 0.794079, 0.794079, 0.794079, 0.794079, 0.0000, 0.0000}, + { 0.607814, 0.607814, 0.607814, 0.607814, 1.0000, 1.0000}, + {-0.672516, 0.915642, -0.915642, 0.672516, 0.0000, 0.0000}, + { 0.159704, 0.159704, 0.159704, 0.159704, -0.2500, -0.2500}, + { 0.607814, -0.607814, 0.607814, -0.607814, 1.0000, 1.0000}}; + Matrix real ( real_alloc); + Matrix real_pinv = geninv(real); + + // from SVD-based inverse + const float real_pinv_expected_alloc[6][5] = {{ 2.096205, -2.722267, 2.056547, 1.503279, 3.098087}, + { 1.612621, -1.992694, 2.056547, 1.131090, 2.275467}, + {-1.062688, 2.043479, -2.056547, -0.927950, -2.275467}, + {-1.546273, 2.773052, -2.056547, -1.300139, -3.098087}, + {-0.293930, 0.443445, 0.000000, -0.226222, 0.000000}, + {-0.293930, 0.443445, 0.000000, -0.226222, 0.000000}}; + Matrix real_pinv_expected(real_pinv_expected_alloc); + TEST((real_pinv - real_pinv_expected).abs().max() < 1e-4); + return 0; } From 15e54ceda176f05e1ae38e71692d15cafb9e3a62 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Wed, 4 Nov 2020 13:08:23 +0100 Subject: [PATCH 374/388] Rework rank-detection tolerance in pseudoinverse --- matrix/PseudoInverse.hxx | 23 +++++------------------ test/pseudoInverse.cpp | 32 +++++++++++++++----------------- 2 files changed, 20 insertions(+), 35 deletions(-) diff --git a/matrix/PseudoInverse.hxx b/matrix/PseudoInverse.hxx index a03184dc43..bd5ae6bbb4 100644 --- a/matrix/PseudoInverse.hxx +++ b/matrix/PseudoInverse.hxx @@ -12,32 +12,20 @@ * Full rank Cholesky factorization of A */ template -void fullRankCholeskyTolerance(Type &tol) -{ - tol /= 10000000; -} +Type typeEpsilon(); template<> inline -void fullRankCholeskyTolerance(double &tol) +float typeEpsilon() { - tol /= 1000000000000000000.0; + return FLT_EPSILON; } template SquareMatrix fullRankCholesky(const SquareMatrix & A, size_t& rank) { - // Compute - // dA = np.diag(A) - // tol = np.min(dA[dA > 0]) * 1e-9 - Vector d = A.diag(); - Type tol = d.max(); - for (size_t k = 0; k < N; k++) { - if ((d(k) > 0) && (d(k) < tol)) { - tol = d(k); - } - } - fullRankCholeskyTolerance(tol); + // Loses one ulp accuracy per row of diag, relative to largest magnitude + const Type tol = N * typeEpsilon() * A.diag().max(); Matrix L; @@ -59,7 +47,6 @@ SquareMatrix fullRankCholesky(const SquareMatrix & A, L(i, r) = A(i, k) - LL; } } - if (L(k, r) > tol) { L(k, r) = sqrt(L(k, r)); diff --git a/test/pseudoInverse.cpp b/test/pseudoInverse.cpp index 35ee8c5262..58a934fd83 100644 --- a/test/pseudoInverse.cpp +++ b/test/pseudoInverse.cpp @@ -127,28 +127,26 @@ int main() TEST((retM1 - retM_check).abs().max() < 1e-5); TEST((retN1 - retN_check).abs().max() < 1e-5); - float float_scale = 1.f; - fullRankCholeskyTolerance(float_scale); - double double_scale = 1.; - fullRankCholeskyTolerance(double_scale); - TEST(static_cast(float_scale) > double_scale); - // Real-world test case - const float real_alloc[5][6] = {{ 0.794079, 0.794079, 0.794079, 0.794079, 0.0000, 0.0000}, - { 0.607814, 0.607814, 0.607814, 0.607814, 1.0000, 1.0000}, - {-0.672516, 0.915642, -0.915642, 0.672516, 0.0000, 0.0000}, - { 0.159704, 0.159704, 0.159704, 0.159704, -0.2500, -0.2500}, - { 0.607814, -0.607814, 0.607814, -0.607814, 1.0000, 1.0000}}; + const float real_alloc[5][6] = { + { 0.794079, 0.794079, 0.794079, 0.794079, 0.0000, 0.0000}, + { 0.607814, 0.607814, 0.607814, 0.607814, 1.0000, 1.0000}, + {-0.672516, 0.915642, -0.915642, 0.672516, 0.0000, 0.0000}, + { 0.159704, 0.159704, 0.159704, 0.159704, -0.2500, -0.2500}, + { 0.607814, -0.607814, 0.607814, -0.607814, 1.0000, 1.0000} + }; Matrix real ( real_alloc); Matrix real_pinv = geninv(real); // from SVD-based inverse - const float real_pinv_expected_alloc[6][5] = {{ 2.096205, -2.722267, 2.056547, 1.503279, 3.098087}, - { 1.612621, -1.992694, 2.056547, 1.131090, 2.275467}, - {-1.062688, 2.043479, -2.056547, -0.927950, -2.275467}, - {-1.546273, 2.773052, -2.056547, -1.300139, -3.098087}, - {-0.293930, 0.443445, 0.000000, -0.226222, 0.000000}, - {-0.293930, 0.443445, 0.000000, -0.226222, 0.000000}}; + const float real_pinv_expected_alloc[6][5] = { + { 2.096205, -2.722267, 2.056547, 1.503279, 3.098087}, + { 1.612621, -1.992694, 2.056547, 1.131090, 2.275467}, + {-1.062688, 2.043479, -2.056547, -0.927950, -2.275467}, + {-1.546273, 2.773052, -2.056547, -1.300139, -3.098087}, + {-0.293930, 0.443445, 0.000000, -0.226222, 0.000000}, + {-0.293930, 0.443445, 0.000000, -0.226222, 0.000000} + }; Matrix real_pinv_expected(real_pinv_expected_alloc); TEST((real_pinv - real_pinv_expected).abs().max() < 1e-4); From 054f8b12f4da79767df6e05bb1d2cc8d679b99f3 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Mon, 4 Jan 2021 14:26:11 +0100 Subject: [PATCH 375/388] Use a single inverse implementation for a single matrix size --- matrix/PseudoInverse.hpp | 84 +++++++++++++++++++++----- matrix/PseudoInverse.hxx | 126 --------------------------------------- matrix/SquareMatrix.hpp | 26 ++++---- test/pseudoInverse.cpp | 16 ----- 4 files changed, 83 insertions(+), 169 deletions(-) delete mode 100644 matrix/PseudoInverse.hxx diff --git a/matrix/PseudoInverse.hpp b/matrix/PseudoInverse.hpp index 469e358100..2463529640 100644 --- a/matrix/PseudoInverse.hpp +++ b/matrix/PseudoInverse.hpp @@ -4,6 +4,7 @@ * Implementation of matrix pseudo inverse * * @author Julien Lecoeur + * @author Julian Kent */ #pragma once @@ -13,17 +14,6 @@ namespace matrix { -/** - * Full rank Cholesky factorization of A - */ -template -SquareMatrix fullRankCholesky(const SquareMatrix & A, size_t& rank); - -/** - * Geninv implementation detail - */ -template class GeninvImpl; - /** * Geninv * Fast pseudoinverse based on full rank cholesky factorisation @@ -38,18 +28,84 @@ Matrix geninv(const Matrix & G) SquareMatrix A = G * G.transpose(); SquareMatrix L = fullRankCholesky(A, rank); - return GeninvImpl::genInvUnderdetermined(G, L, rank); + SquareMatrix LtL = L.transpose() * L; + SquareMatrix X; + if (!inv(LtL, X, rank)) { + return Matrix(); // LCOV_EXCL_LINE -- this can only be hit from numerical issues + } + return G.transpose() * L * X * X * L.transpose(); } else { SquareMatrix A = G.transpose() * G; SquareMatrix L = fullRankCholesky(A, rank); - return GeninvImpl::genInvOverdetermined(G, L, rank); + SquareMatrix LtL = L.transpose() * L; + SquareMatrix X; + if(!inv(LtL, X, rank)) { + return Matrix(); // LCOV_EXCL_LINE -- this can only be hit from numerical issues + } + return L * X * X * L.transpose() * G.transpose(); } } -#include "PseudoInverse.hxx" +template +Type typeEpsilon(); + +template<> inline +float typeEpsilon() +{ + return FLT_EPSILON; +} + +/** + * Full rank Cholesky factorization of A + */ +template +SquareMatrix fullRankCholesky(const SquareMatrix & A, + size_t& rank) +{ + // Loses one ulp accuracy per row of diag, relative to largest magnitude + const Type tol = N * typeEpsilon() * A.diag().max(); + + Matrix L; + + size_t r = 0; + for (size_t k = 0; k < N; k++) { + + if (r == 0) { + for (size_t i = k; i < N; i++) { + L(i, r) = A(i, k); + } + + } else { + for (size_t i = k; i < N; i++) { + // Compute LL = L[k:n, :r] * L[k, :r].T + Type LL = Type(); + for (size_t j = 0; j < r; j++) { + LL += L(i, j) * L(k, j); + } + L(i, r) = A(i, k) - LL; + } + } + if (L(k, r) > tol) { + L(k, r) = sqrt(L(k, r)); + + if (k < N - 1) { + for (size_t i = k + 1; i < N; i++) { + L(i, r) = L(i, r) / L(k, r); + } + } + + r = r + 1; + } + } + + // Return rank + rank = r; + + return L; +} } // namespace matrix diff --git a/matrix/PseudoInverse.hxx b/matrix/PseudoInverse.hxx deleted file mode 100644 index bd5ae6bbb4..0000000000 --- a/matrix/PseudoInverse.hxx +++ /dev/null @@ -1,126 +0,0 @@ -/** - * @file pseudoinverse.hxx - * - * Implementation of matrix pseudo inverse - * - * @author Julien Lecoeur - */ - - - -/** - * Full rank Cholesky factorization of A - */ -template -Type typeEpsilon(); - -template<> inline -float typeEpsilon() -{ - return FLT_EPSILON; -} - -template -SquareMatrix fullRankCholesky(const SquareMatrix & A, - size_t& rank) -{ - // Loses one ulp accuracy per row of diag, relative to largest magnitude - const Type tol = N * typeEpsilon() * A.diag().max(); - - Matrix L; - - size_t r = 0; - for (size_t k = 0; k < N; k++) { - - if (r == 0) { - for (size_t i = k; i < N; i++) { - L(i, r) = A(i, k); - } - - } else { - for (size_t i = k; i < N; i++) { - // Compute LL = L[k:n, :r] * L[k, :r].T - Type LL = Type(); - for (size_t j = 0; j < r; j++) { - LL += L(i, j) * L(k, j); - } - L(i, r) = A(i, k) - LL; - } - } - if (L(k, r) > tol) { - L(k, r) = sqrt(L(k, r)); - - if (k < N - 1) { - for (size_t i = k + 1; i < N; i++) { - L(i, r) = L(i, r) / L(k, r); - } - } - - r = r + 1; - } - } - - // Return rank - rank = r; - - return L; -} - -template< typename Type, size_t M, size_t N, size_t R> -class GeninvImpl -{ -public: - static Matrix genInvUnderdetermined(const Matrix & G, const Matrix & L, size_t rank) - { - if (rank < R) { - // Recursive call - return GeninvImpl::genInvUnderdetermined(G, L, rank); - - } else if (rank > R) { - // Error - return Matrix(); - - } else { - // R == rank - Matrix LL = L. template slice(0, 0); - SquareMatrix X = inv(SquareMatrix(LL.transpose() * LL)); - return G.transpose() * LL * X * X * LL.transpose(); - - } - } - - static Matrix genInvOverdetermined(const Matrix & G, const Matrix & L, size_t rank) - { - if (rank < R) { - // Recursive call - return GeninvImpl::genInvOverdetermined(G, L, rank); - - } else if (rank > R) { - // Error - return Matrix(); - - } else { - // R == rank - Matrix LL = L. template slice(0, 0); - SquareMatrix X = inv(SquareMatrix(LL.transpose() * LL)); - return LL * X * X * LL.transpose() * G.transpose(); - - } - } -}; - -// Partial template specialisation for R==0, allows to stop recursion in genInvUnderdetermined and genInvOverdetermined -template< typename Type, size_t M, size_t N> -class GeninvImpl -{ -public: - static Matrix genInvUnderdetermined(const Matrix & G, const Matrix & L, size_t rank) - { - return Matrix(); - } - - static Matrix genInvOverdetermined(const Matrix & G, const Matrix & L, size_t rank) - { - return Matrix(); - } -}; diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 8c35351664..ba2721879b 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -305,7 +305,7 @@ SquareMatrix expm(const Matrix & A, size_t order=5) * inverse based on LU factorization with partial pivotting */ template -bool inv(const SquareMatrix & A, SquareMatrix & inv) +bool inv(const SquareMatrix & A, SquareMatrix & inv, size_t rank = M) { SquareMatrix L; L.setIdentity(); @@ -316,12 +316,12 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) //printf("A:\n"); A.print(); // for all diagonal elements - for (size_t n = 0; n < M; n++) { + for (size_t n = 0; n < rank; n++) { // if diagonal is zero, swap with row below if (fabs(static_cast(U(n, n))) < FLT_EPSILON) { //printf("trying pivot for row %d\n",n); - for (size_t i = n + 1; i < M; i++) { + for (size_t i = n + 1; i < rank; i++) { //printf("\ttrying row %d\n",i); if (fabs(static_cast(U(i, n))) > 1e-8f) { @@ -349,12 +349,12 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) } // for all rows below diagonal - for (size_t i = (n + 1); i < M; i++) { + for (size_t i = (n + 1); i < rank; i++) { L(i, n) = U(i, n) / U(n, n); // add i-th row and n-th row // multiplied by: -a(i,n)/a(n,n) - for (size_t k = n; k < M; k++) { + for (size_t k = n; k < rank; k++) { U(i, k) -= L(i, n) * U(n, k); } } @@ -367,9 +367,9 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) //SquareMatrix Y = P; // for all columns of Y - for (size_t c = 0; c < M; c++) { + for (size_t c = 0; c < rank; c++) { // for all rows of L - for (size_t i = 0; i < M; i++) { + for (size_t i = 0; i < rank; i++) { // for all columns of L for (size_t j = 0; j < i; j++) { // for all existing y @@ -392,14 +392,14 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) //SquareMatrix X = Y; // for all columns of X - for (size_t c = 0; c < M; c++) { + for (size_t c = 0; c < rank; c++) { // for all rows of U - for (size_t k = 0; k < M; k++) { + for (size_t k = 0; k < rank; k++) { // have to go in reverse order - size_t i = M - 1 - k; + size_t i = rank - 1 - k; // for all columns of U - for (size_t j = i + 1; j < M; j++) { + for (size_t j = i + 1; j < rank; j++) { // for all existing x // subtract the component they // contribute to the solution @@ -416,8 +416,8 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv) } //check sanity of results - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < M; j++) { + for (size_t i = 0; i < rank; i++) { + for (size_t j = 0; j < rank; j++) { if (!is_finite(P(i,j))) { return false; } diff --git a/test/pseudoInverse.cpp b/test/pseudoInverse.cpp index 58a934fd83..e7d8b10187 100644 --- a/test/pseudoInverse.cpp +++ b/test/pseudoInverse.cpp @@ -111,22 +111,6 @@ int main() Matrix A = geninv(B); TEST((A - A_check).abs().max() < 1e-5); - // Test error case with erroneous rank in internal impl functions - Matrix L; - Matrix GM; - Matrix retM_check; - Matrix retM0 = GeninvImpl::genInvUnderdetermined(GM, L, 5); - Matrix GN; - Matrix retN_check; - Matrix retN0 = GeninvImpl::genInvOverdetermined(GN, L, 5); - TEST((retM0 - retM_check).abs().max() < 1e-5); - TEST((retN0 - retN_check).abs().max() < 1e-5); - - Matrix retM1 = GeninvImpl::genInvUnderdetermined(GM, L, 5); - Matrix retN1 = GeninvImpl::genInvOverdetermined(GN, L, 5); - TEST((retM1 - retM_check).abs().max() < 1e-5); - TEST((retN1 - retN_check).abs().max() < 1e-5); - // Real-world test case const float real_alloc[5][6] = { { 0.794079, 0.794079, 0.794079, 0.794079, 0.0000, 0.0000}, From d540ca5de20a5f3b4346fbb8bc716129f38119c4 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Wed, 13 Jan 2021 09:57:23 +0100 Subject: [PATCH 376/388] Coerce default epsilon values to Type --- matrix/Matrix.hpp | 2 +- matrix/SquareMatrix.hpp | 6 +++--- matrix/helper_functions.hpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index d7e57e37ef..bc9dbfc7a5 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -605,7 +605,7 @@ Matrix operator*(Type scalar, const Matrix &other) template bool isEqual(const Matrix &x, - const Matrix &y, const Type eps=1e-4f) { + const Matrix &y, const Type eps=Type(1e-4f)) { for (size_t i = 0; i < M; i++) { for (size_t j = 0; j < N; j++) { if (!isEqualF(x(i,j), y(i,j), eps)) { diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index ba2721879b..827eb497b0 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -223,7 +223,7 @@ public: // checks if block diagonal is symmetric template - bool isBlockSymmetric(size_t first, const Type eps = 1e-8f) + bool isBlockSymmetric(size_t first, const Type eps = Type(1e-8f)) { static_assert(Width <= M, "Width bigger than matrix"); assert(first + Width <= M); @@ -243,7 +243,7 @@ public: // checks if rows and columns are symmetric template - bool isRowColSymmetric(size_t first, const Type eps = 1e-8f) + bool isRowColSymmetric(size_t first, const Type eps = Type(1e-8f)) { static_assert(Width <= M, "Width bigger than matrix"); assert(first + Width <= M); @@ -324,7 +324,7 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv, size_t ra for (size_t i = n + 1; i < rank; i++) { //printf("\ttrying row %d\n",i); - if (fabs(static_cast(U(i, n))) > 1e-8f) { + if (fabs(static_cast(U(i, n))) > Type(1e-8f)) { //printf("swapped %d\n",i); U.swapRows(i, n); P.swapRows(i, n); diff --git a/matrix/helper_functions.hpp b/matrix/helper_functions.hpp index 37d2191f94..191ff12228 100644 --- a/matrix/helper_functions.hpp +++ b/matrix/helper_functions.hpp @@ -32,7 +32,7 @@ bool is_finite(Type x) { * @return true if the two values are considered equal, false otherwise */ template -bool isEqualF(const Type x, const Type y, const Type eps = 1e-4f) +bool isEqualF(const Type x, const Type y, const Type eps = Type(1e-4f)) { return (matrix::fabs(x - y) <= eps) || (isnan(x) && isnan(y)) From 4837316f9b967d6a229ee9c4edc0f2daaa028ffd Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Fri, 22 Jan 2021 17:21:49 +0100 Subject: [PATCH 377/388] Fix small inconsistencies and compiler warnings --- matrix/SquareMatrix.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 827eb497b0..9cb02cddfb 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -319,12 +319,12 @@ bool inv(const SquareMatrix & A, SquareMatrix & inv, size_t ra for (size_t n = 0; n < rank; n++) { // if diagonal is zero, swap with row below - if (fabs(static_cast(U(n, n))) < FLT_EPSILON) { + if (fabs(U(n, n)) < Type(FLT_EPSILON)) { //printf("trying pivot for row %d\n",n); for (size_t i = n + 1; i < rank; i++) { //printf("\ttrying row %d\n",i); - if (fabs(static_cast(U(i, n))) > Type(1e-8f)) { + if (fabs(U(i, n)) > Type(FLT_EPSILON)) { //printf("swapped %d\n",i); U.swapRows(i, n); P.swapRows(i, n); From 977cf52322ab3ca93125423a0f9e9b3eca0516d7 Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Fri, 22 Jan 2021 17:26:21 +0100 Subject: [PATCH 378/388] Ignore debug line in code coverage --- test/matrixAssignment.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/matrixAssignment.cpp b/test/matrixAssignment.cpp index c3844c769e..6e5a0783c6 100644 --- a/test/matrixAssignment.cpp +++ b/test/matrixAssignment.cpp @@ -226,7 +226,7 @@ int main() printf("%s\n", output); // for debugging in case of failure for (size_t i = 0; i < len; i++) { if(buffer[i] != output[i]) { // for debugging in case of failure - printf("%d: \"%c\" != \"%c\"", int(i), buffer[i], output[i]); + printf("%d: \"%c\" != \"%c\"", int(i), buffer[i], output[i]); // LCOV_EXCL_LINE only print on failure } TEST(buffer[i] == output[i]); if (buffer[i] == '\0') { From 3679f7fd5160c7d2a8271b1134ca1e601f1a4254 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 11 Feb 2021 10:33:00 -0500 Subject: [PATCH 379/388] add double precision alias declarations and remove typedefs --- matrix/AxisAngle.hpp | 5 +++-- matrix/Dcm.hpp | 5 +++-- matrix/Euler.hpp | 3 ++- matrix/Quaternion.hpp | 11 +++++++---- matrix/Scalar.hpp | 3 ++- matrix/SquareMatrix.hpp | 6 ++++-- matrix/Vector.hpp | 2 +- matrix/Vector2.hpp | 8 +++++--- matrix/Vector3.hpp | 5 +++-- 9 files changed, 30 insertions(+), 18 deletions(-) diff --git a/matrix/AxisAngle.hpp b/matrix/AxisAngle.hpp index d72de6269a..41a9711541 100644 --- a/matrix/AxisAngle.hpp +++ b/matrix/AxisAngle.hpp @@ -30,7 +30,7 @@ template class AxisAngle : public Vector { public: - typedef Matrix Matrix31; + using Matrix31 = Matrix; /** * Constructor from array @@ -152,7 +152,8 @@ public: } }; -typedef AxisAngle AxisAnglef; +using AxisAnglef = AxisAngle; +using AxisAngled = AxisAngle; } // namespace matrix diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index f4a4c3ca68..62bac589f7 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -39,7 +39,7 @@ template class Dcm : public SquareMatrix { public: - typedef Matrix Vector3; + using Vector3 = Matrix; /** * Standard constructor @@ -182,7 +182,8 @@ public: } }; -typedef Dcm Dcmf; +using Dcmf = Dcm; +using Dcmd = Dcm; } // namespace matrix diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index a0b8226cbd..bcaa85753c 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -153,7 +153,8 @@ public: }; -typedef Euler Eulerf; +using Eulerf = Euler; +using Eulerd = Euler; } // namespace matrix diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 5bd23457e5..309cd53952 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -53,8 +53,8 @@ template class Quaternion : public Vector { public: - typedef Matrix Matrix41; - typedef Matrix Matrix31; + using Matrix41 = Matrix; + using Matrix31 = Matrix; /** * Constructor from array @@ -449,8 +449,11 @@ public: } }; -typedef Quaternion Quatf; -typedef Quaternion Quaternionf; +using Quatf = Quaternion; +using Quaternionf = Quaternion; + +using Quatd = Quaternion; +using Quaterniond = Quaternion; } // namespace matrix diff --git a/matrix/Scalar.hpp b/matrix/Scalar.hpp index c9765028c3..182e0f7786 100644 --- a/matrix/Scalar.hpp +++ b/matrix/Scalar.hpp @@ -50,7 +50,8 @@ private: }; -typedef Scalar Scalarf; +using Scalarf = Scalar; +using Scalard = Scalar; } // namespace matrix diff --git a/matrix/SquareMatrix.hpp b/matrix/SquareMatrix.hpp index 9cb02cddfb..127e89b2f1 100644 --- a/matrix/SquareMatrix.hpp +++ b/matrix/SquareMatrix.hpp @@ -266,7 +266,8 @@ public: }; -typedef SquareMatrix SquareMatrix3f; +using SquareMatrix3f = SquareMatrix; +using SquareMatrix3d = SquareMatrix; template SquareMatrix eye() { @@ -535,7 +536,8 @@ SquareMatrix choleskyInv(const SquareMatrix & A) return L_inv.T()*L_inv; } -typedef SquareMatrix Matrix3f; +using Matrix3f = SquareMatrix; +using Matrix3d = SquareMatrix; } // namespace matrix diff --git a/matrix/Vector.hpp b/matrix/Vector.hpp index 64a9fe54db..09e79d1bbb 100644 --- a/matrix/Vector.hpp +++ b/matrix/Vector.hpp @@ -20,7 +20,7 @@ template class Vector : public Matrix { public: - typedef Matrix MatrixM1; + using MatrixM1 = Matrix; Vector() = default; diff --git a/matrix/Vector2.hpp b/matrix/Vector2.hpp index c12e413d2b..33d0cda467 100644 --- a/matrix/Vector2.hpp +++ b/matrix/Vector2.hpp @@ -21,8 +21,8 @@ class Vector2 : public Vector { public: - typedef Matrix Matrix21; - typedef Vector Vector3; + using Matrix21 = Matrix; + using Vector3 = Vector; Vector2() = default; @@ -71,7 +71,9 @@ public: }; -typedef Vector2 Vector2f; + +using Vector2f = Vector2; +using Vector2d = Vector2; } // namespace matrix diff --git a/matrix/Vector3.hpp b/matrix/Vector3.hpp index 6e8cc601a1..f67ade4618 100644 --- a/matrix/Vector3.hpp +++ b/matrix/Vector3.hpp @@ -30,7 +30,7 @@ class Vector3 : public Vector { public: - typedef Matrix Matrix31; + using Matrix31 = Matrix; Vector3() = default; @@ -148,7 +148,8 @@ public: }; -typedef Vector3 Vector3f; +using Vector3f = Vector3; +using Vector3d = Vector3; } // namespace matrix From 1344ce06fddd8bedc9e9887059a3250653c6fa3a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 14 Apr 2021 15:40:24 -0400 Subject: [PATCH 380/388] Euler: simplify DCM constructor Co-authored-by: Matthias Grob --- matrix/Euler.hpp | 25 +++++++++++-------------- 1 file changed, 11 insertions(+), 14 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index bcaa85753c..0e062ed24a 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -91,23 +91,20 @@ public: */ Euler(const Dcm &dcm) { - Type phi_val = Type(atan2(dcm(2, 1), dcm(2, 2))); - Type theta_val = Type(asin(-dcm(2, 0))); - Type psi_val = Type(atan2(dcm(1, 0), dcm(0, 0))); - Type pi = Type(M_PI); + theta() = asin(-dcm(2, 0)); - if (Type(fabs(theta_val - pi / Type(2))) < Type(1.0e-3)) { - phi_val = Type(0); - psi_val = Type(atan2(dcm(1, 2), dcm(0, 2))); + if ((fabs(theta() - Type(M_PI / 2))) < Type(1.0e-3)) { + phi() = 0; + psi() = atan2(dcm(1, 2), dcm(0, 2)); - } else if (Type(fabs(theta_val + pi / Type(2))) < Type(1.0e-3)) { - phi_val = Type(0); - psi_val = Type(atan2(-dcm(1, 2), -dcm(0, 2))); + } else if ((fabs(theta() + Type(M_PI / 2))) < Type(1.0e-3)) { + phi() = 0; + psi() = atan2(-dcm(1, 2), -dcm(0, 2)); + + } else { + phi() = atan2(dcm(2, 1), dcm(2, 2)); + psi() = atan2(dcm(1, 0), dcm(0, 0)); } - - phi() = phi_val; - theta() = theta_val; - psi() = psi_val; } /** From 1d0e7f1ca1187c90c70a9dac92ca6294a320b1d3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 14 Apr 2021 15:44:18 -0400 Subject: [PATCH 381/388] Matrix: use naive per element copy instead of memcpy call --- matrix/Dcm.hpp | 5 +--- matrix/Matrix.hpp | 58 +++++++++++++++++++++++------------------------ 2 files changed, 29 insertions(+), 34 deletions(-) diff --git a/matrix/Dcm.hpp b/matrix/Dcm.hpp index 62bac589f7..0e1cf49960 100644 --- a/matrix/Dcm.hpp +++ b/matrix/Dcm.hpp @@ -46,10 +46,7 @@ public: * * Initializes to identity */ - Dcm() - { - (*this) = eye(); - } + Dcm() : SquareMatrix(eye()) {} /** * Constructor from array diff --git a/matrix/Matrix.hpp b/matrix/Matrix.hpp index bc9dbfc7a5..2b865f4ab3 100644 --- a/matrix/Matrix.hpp +++ b/matrix/Matrix.hpp @@ -18,14 +18,6 @@ #include "math.hpp" -// There is a bug in GCC 4.8, which causes the compiler to segfault due to array {} constructors. -// Do for-loop constructors just for GCC 4.8 -#ifdef __GNUC__ -#define MATRIX_GCC_4_8_WORKAROUND (__GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 9)) -#else -#define MATRIX_GCC_4_8_WORKAROUND 0 -#endif - namespace matrix { @@ -41,41 +33,38 @@ class Slice; template class Matrix { -#if MATRIX_GCC_4_8_WORKAROUND - Type _data[M][N]; -#else Type _data[M][N] {}; -#endif public: // Constructors -#if MATRIX_GCC_4_8_WORKAROUND - Matrix() - { - for (size_t i = 0; i < M; i++) { - for (size_t j = 0; j < N; j++) { - _data[i][j] = Type{}; - } - } - } -#else Matrix() = default; -#endif explicit Matrix(const Type data_[M*N]) { - memcpy(_data, data_, sizeof(_data)); + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + _data[i][j] = data_[N*i + j]; + } + } } explicit Matrix(const Type data_[M][N]) { - memcpy(_data, data_, sizeof(_data)); + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + _data[i][j] = data_[i][j]; + } + } } Matrix(const Matrix &other) { - memcpy(_data, other._data, sizeof(_data)); + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + _data[i][j] = other(i, j); + } + } } template @@ -113,14 +102,24 @@ public: Matrix & operator=(const Matrix &other) { if (this != &other) { - memcpy(_data, other._data, sizeof(_data)); + Matrix &self = *this; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + self(i, j) = other(i, j); + } + } } return (*this); } void copyTo(Type dst[M*N]) const { - memcpy(dst, _data, sizeof(Type)*M*N); + const Matrix &self = *this; + for (size_t i = 0; i < M; i++) { + for (size_t j = 0; j < N; j++) { + dst[N*i + j] = self(i, j); + } + } } void copyToColumnMajor(Type dst[M*N]) const @@ -146,8 +145,7 @@ public: Matrix operator*(const Matrix &other) const { const Matrix &self = *this; - Matrix res; - res.setZero(); + Matrix res{}; for (size_t i = 0; i < M; i++) { for (size_t k = 0; k < P; k++) { From b8568a89db8455d0ab2e2e391e2149ba2e5e10dd Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 14 Apr 2021 22:31:25 -0400 Subject: [PATCH 382/388] Euler: improve quaternion constructor --- matrix/Euler.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/matrix/Euler.hpp b/matrix/Euler.hpp index 0e062ed24a..6145cffd38 100644 --- a/matrix/Euler.hpp +++ b/matrix/Euler.hpp @@ -117,9 +117,8 @@ public: * * @param q quaternion */ - Euler(const Quaternion &q) + Euler(const Quaternion &q) : Vector(Euler(Dcm(q))) { - *this = Euler(Dcm(q)); } inline Type phi() const From 3d1c9b988dff1d95f36cdd1df3e84d7a2365501c Mon Sep 17 00:00:00 2001 From: romain-chiap Date: Thu, 5 Aug 2021 01:04:57 +0200 Subject: [PATCH 383/388] quaternion exponential (#164) --- matrix/Quaternion.hpp | 72 +++++++++++++++++++++++++++++++++++++++++++ test/attitude.cpp | 46 +++++++++++++++++++++++++++ 2 files changed, 118 insertions(+) diff --git a/matrix/Quaternion.hpp b/matrix/Quaternion.hpp index 309cd53952..ddcbdf9ec0 100644 --- a/matrix/Quaternion.hpp +++ b/matrix/Quaternion.hpp @@ -325,6 +325,78 @@ public: return v * q * Type(0.5); } + /** + * Computes the quaternion exponential of the 3D vector u + * as proposed in + * [1] Sveier A, Sjøberg AM, Egeland O. "Applied Runge–Kutta–Munthe-Kaas Integration + * for the Quaternion Kinematics".Journal of Guidance, Control, and Dynamics. 2019 + * + * return a quaternion computed as + * expq(u)=[cos||u||, sinc||u||*u] + * sinc(x)=sin(x)/x in the sin cardinal function + * + * This can be used to update a quaternion from the body rates + * rather than using + * qk+1=qk+qk.derivative1(wb)*dt + * we can use + * qk+1=qk*expq(dt*wb/2) + * which is a more robust update. + * A re-normalization step might necessary with both methods. + * + * @param u 3D vector u + */ + static Quaternion expq(const Vector3 &u) + { + const Type tol = Type(0.2); // ensures an error < 10^-10 + const Type c2 = Type(1.0 / 2.0); // 1 / 2! + const Type c3 = Type(1.0 / 6.0); // 1 / 3! + const Type c4 = Type(1.0 / 24.0); // 1 / 4! + const Type c5 = Type(1.0 / 120.0); // 1 / 5! + const Type c6 = Type(1.0 / 720.0); // 1 / 6! + const Type c7 = Type(1.0 / 5040.0); // 1 / 7! + + Type u_norm = u.norm(); + Type sinc_u, cos_u; + + if (u_norm < tol) { + Type u2 = u_norm * u_norm; + Type u4 = u2 * u2; + Type u6 = u4 * u2; + + // compute the first 4 terms of the Taylor serie + sinc_u = Type(1.0) - u2 * c3 + u4 * c5 - u6 * c7; + cos_u = Type(1.0) - u2 * c2 + u4 * c4 - u6 * c6; + } else { + sinc_u = Type(sin(u_norm) / u_norm); + cos_u = Type(cos(u_norm)); + } + Vector v = sinc_u * u; + return Quaternion (cos_u, v(0), v(1), v(2)); + } + + /** inverse right Jacobian of the quaternion logarithm u + * equation (20) in reference + * [1] Sveier A, Sjøberg AM, Egeland O. "Applied Runge–Kutta–Munthe-Kaas Integration + * for the Quaternion Kinematics".Journal of Guidance, Control, and Dynamics. 2019 + * + * This can be used to update a quaternion kinematic cleanly + * with higher order integration methods (like RK4) on the quaternion logarithm u. + * + * @param u 3D vector u + */ + static Dcm inv_r_jacobian (const Vector3 &u) + { + const Type tol = Type(1.0e-4); + Type u_norm = u.norm(); + Dcm u_hat = u.hat(); + + if (u_norm < tol) { // result smaller than O(||.||^3) + return Type(0.5) * (Dcm() + u_hat + (Type(1.0 / 3.0) + u_norm * u_norm / Type(45.0)) * u_hat * u_hat); + } else { + return Type(0.5) * (Dcm() + u_hat + (Type(1.0) - u_norm * Type(cos(u_norm) / sin(u_norm))) / (u_norm * u_norm) * u_hat * u_hat); + } + } + /** * Invert quaternion in place */ diff --git a/test/attitude.cpp b/test/attitude.cpp index cbdcf3d6df..d8954965d3 100644 --- a/test/attitude.cpp +++ b/test/attitude.cpp @@ -89,6 +89,52 @@ int main() q = Quatf(); TEST(isEqual(q, Quatf(1, 0, 0, 0))); + // quaternion exponential with v=0 + v = Vector3f(); + q = Quatf(1.0f, 0.0f, 0.0f, 0.0f); + Dcmf M = Dcmf()*0.5f; + TEST(isEqual(q, Quatf::expq(v))); + TEST(isEqual(M, Quatf::inv_r_jacobian(v))); + + // quaternion exponential with small v + v = Vector3f(0.001f,0.002f,-0.003f); + q = Quatf(0.999993000008167f, 0.000999997666668f, + 0.001999995333337f, -0.002999993000005f); + { + float M_data[] = { + 0.499997833331311f, 0.001500333333644f, 0.000999499999533f, + -0.001499666666356f, 0.499998333331778f, -0.000501000000933f, + -0.001000500000467f, 0.000498999999067f, 0.499999166665889f + }; + M = Dcmf(M_data); + } + TEST(isEqual(q, Quatf::expq(v))); + TEST(isEqual(M, Quatf::inv_r_jacobian(v))); + + // quaternion exponential with v + v = Vector3f(1.0f, -2.0f, 3.0f); + q = Quatf(-0.825299062075259f, -0.150921327219964f, + 0.301842654439929f, -0.452763981659893f); + { + float M_data[] = { + 2.574616981530584f, -1.180828156687602f, -1.478757764968596f, + 1.819171843312398f, 2.095859216561988f, 0.457515529937193f, + 0.521242235031404f, 1.457515529937193f, 1.297929608280994f + }; + M = Dcmf(M_data); + } + TEST(isEqual(q, Quatf::expq(v))); + TEST(isEqual(M, Quatf::inv_r_jacobian(v))); + + // quaternion kinematic update + q = Quatf(); + float h=0.001f; // sampling time [s] + Vector3f w_B=Vector3f(0.1f,0.2f,0.3f); // body rate in body frame + Quatf qa=q+0.5f*h*q.derivative1(w_B); + qa.normalize(); + Quatf qb=q*Quatf::expq(0.5f*h*w_B); + TEST(isEqual(qa, qb)); + // euler to quaternion q = Quatf(euler_check); TEST(isEqual(q, q_check)); From dc7f119b995d9530188280d2b6fe2d55553ff3df Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Sat, 21 Aug 2021 19:06:49 +0200 Subject: [PATCH 384/388] geninv(): improve runtime performance and reduce stack usage - use associativity of matrix operations to reduce size of temporary matrices and number of multiplications in the M <= N case - minimize the number of temporary matrices required --- matrix/PseudoInverse.hpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/matrix/PseudoInverse.hpp b/matrix/PseudoInverse.hpp index 2463529640..a2df21b5d2 100644 --- a/matrix/PseudoInverse.hpp +++ b/matrix/PseudoInverse.hpp @@ -28,23 +28,27 @@ Matrix geninv(const Matrix & G) SquareMatrix A = G * G.transpose(); SquareMatrix L = fullRankCholesky(A, rank); - SquareMatrix LtL = L.transpose() * L; + A = L.transpose() * L; SquareMatrix X; - if (!inv(LtL, X, rank)) { + if (!inv(A, X, rank)) { return Matrix(); // LCOV_EXCL_LINE -- this can only be hit from numerical issues } - return G.transpose() * L * X * X * L.transpose(); + // doing an intermediate assignment reduces stack usage + A = X * X * L.transpose(); + return G.transpose() * (L * A); } else { SquareMatrix A = G.transpose() * G; SquareMatrix L = fullRankCholesky(A, rank); - SquareMatrix LtL = L.transpose() * L; + A = L.transpose() * L; SquareMatrix X; - if(!inv(LtL, X, rank)) { + if(!inv(A, X, rank)) { return Matrix(); // LCOV_EXCL_LINE -- this can only be hit from numerical issues } - return L * X * X * L.transpose() * G.transpose(); + // doing an intermediate assignment reduces stack usage + A = X * X * L.transpose(); + return (L * A) * G.transpose(); } } From 7c1860f2861354f909f1275ee7eafb0210f2a1f4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Sat, 21 Aug 2021 19:12:34 +0200 Subject: [PATCH 385/388] geninv(): pass result as argument depending on usage, this reduces stack usage a bit. --- matrix/PseudoInverse.hpp | 13 ++++++++----- test/pseudoInverse.cpp | 27 ++++++++++++++++++++------- 2 files changed, 28 insertions(+), 12 deletions(-) diff --git a/matrix/PseudoInverse.hpp b/matrix/PseudoInverse.hpp index a2df21b5d2..1590efecfd 100644 --- a/matrix/PseudoInverse.hpp +++ b/matrix/PseudoInverse.hpp @@ -21,7 +21,7 @@ namespace matrix * Courrieu, P. (2008). Fast Computation of Moore-Penrose Inverse Matrices, 8(2), 25–29. http://arxiv.org/abs/0804.4809 */ template -Matrix geninv(const Matrix & G) +bool geninv(const Matrix & G, Matrix& res) { size_t rank; if (M <= N) { @@ -31,11 +31,12 @@ Matrix geninv(const Matrix & G) A = L.transpose() * L; SquareMatrix X; if (!inv(A, X, rank)) { - return Matrix(); // LCOV_EXCL_LINE -- this can only be hit from numerical issues + res = Matrix(); + return false; // LCOV_EXCL_LINE -- this can only be hit from numerical issues } // doing an intermediate assignment reduces stack usage A = X * X * L.transpose(); - return G.transpose() * (L * A); + res = G.transpose() * (L * A); } else { SquareMatrix A = G.transpose() * G; @@ -44,12 +45,14 @@ Matrix geninv(const Matrix & G) A = L.transpose() * L; SquareMatrix X; if(!inv(A, X, rank)) { - return Matrix(); // LCOV_EXCL_LINE -- this can only be hit from numerical issues + res = Matrix(); + return false; // LCOV_EXCL_LINE -- this can only be hit from numerical issues } // doing an intermediate assignment reduces stack usage A = X * X * L.transpose(); - return (L * A) * G.transpose(); + res = (L * A) * G.transpose(); } + return true; } diff --git a/test/pseudoInverse.cpp b/test/pseudoInverse.cpp index e7d8b10187..a313a58bcd 100644 --- a/test/pseudoInverse.cpp +++ b/test/pseudoInverse.cpp @@ -22,7 +22,9 @@ int main() }; Matrix A0(data0); - Matrix A0_I = geninv(A0); + Matrix A0_I; + bool ret = geninv(A0, A0_I); + TEST(ret); Matrix A0_I_check(data0_check); TEST((A0_I - A0_I_check).abs().max() < 1e-5); @@ -42,7 +44,9 @@ int main() }; Matrix A1(data1); - Matrix A1_I = geninv(A1); + Matrix A1_I; + ret = geninv(A1, A1_I); + TEST(ret); Matrix A1_I_check(data1_check); TEST((A1_I - A1_I_check).abs().max() < 1e-5); @@ -53,7 +57,8 @@ int main() Matrix A_large_I; for (size_t i = 0; i < n_large; i++) { - A_large_I = geninv(A_large); + ret = geninv(A_large, A_large_I); + TEST(ret); TEST(isEqual(A_large, A_large_I.T())); } @@ -69,13 +74,17 @@ int main() }; SquareMatrix A2(data2); - SquareMatrix A2_I = geninv(A2); + SquareMatrix A2_I; + ret = geninv(A2, A2_I); + TEST(ret); SquareMatrix A2_I_check(data2_check); TEST((A2_I - A2_I_check).abs().max() < 1e-3); // Null matrix test Matrix A3; - Matrix A3_I = geninv(A3); + Matrix A3_I; + ret = geninv(A3, A3_I); + TEST(ret); Matrix A3_I_check; TEST((A3_I - A3_I_check).abs().max() < 1e-5); @@ -108,7 +117,9 @@ int main() { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f} }; Matrix A_check = Matrix(A_quad_w); - Matrix A = geninv(B); + Matrix A; + ret = geninv(B, A); + TEST(ret); TEST((A - A_check).abs().max() < 1e-5); // Real-world test case @@ -120,7 +131,9 @@ int main() { 0.607814, -0.607814, 0.607814, -0.607814, 1.0000, 1.0000} }; Matrix real ( real_alloc); - Matrix real_pinv = geninv(real); + Matrix real_pinv; + ret = geninv(real, real_pinv); + TEST(ret); // from SVD-based inverse const float real_pinv_expected_alloc[6][5] = { From c96f0a48b6cfce519a78625971d3343f91b126f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 31 Aug 2021 17:37:56 +0200 Subject: [PATCH 386/388] test: update gtest to v1.11.0 --- test/CMakeLists.txt.in | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/CMakeLists.txt.in b/test/CMakeLists.txt.in index fb9ff2f0ab..a341cac5c5 100644 --- a/test/CMakeLists.txt.in +++ b/test/CMakeLists.txt.in @@ -4,7 +4,7 @@ project(googletest-download NONE) include(ExternalProject) ExternalProject_Add(googletest - URL https://github.com/google/googletest/archive/8b6d3f9c4a774bef3081195d422993323b6bb2e0.zip + URL https://github.com/google/googletest/archive/e2239ee6043f73722e7aa812a459f54a28552929.zip SOURCE_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-src" BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-build" CONFIGURE_COMMAND "" From 007a7f78ae014499ecb18d8c92a312fc5a70899b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 31 Aug 2021 17:38:47 +0200 Subject: [PATCH 387/388] CI: switch to github actions --- .github/workflows/test.yml | 53 ++++++++++++++++++++++++++++++++++++++ .travis.yml | 41 ----------------------------- 2 files changed, 53 insertions(+), 41 deletions(-) create mode 100644 .github/workflows/test.yml delete mode 100644 .travis.yml diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml new file mode 100644 index 0000000000..c368930777 --- /dev/null +++ b/.github/workflows/test.yml @@ -0,0 +1,53 @@ +name: Tests + +on: + push: + branches: + - 'master' + pull_request: + branches: + - '*' + +jobs: + build: + runs-on: ubuntu-latest + strategy: + fail-fast: false # don't cancel if a job from the matrix fails + matrix: + compiler: + - { compiler: GNU, CC: gcc, CXX: g++, FORMAT: ON } + - { compiler: LLVM, CC: clang, CXX: clang++, FORMAT: OFF } + #flavor: [ Release, Coverage ] # TODO + flavor: [ Release ] + exclude: + - compiler: { compiler: LLVM, CC: clang, CXX: clang++ } + flavor: Coverage + + steps: + - uses: actions/checkout@v2 + with: + submodules: 'recursive' + - name: Install Dependencies + run: | + sudo apt install -y clang cmake g++ gcc lcov + - name: Fetch coveralls + if: matrix.flavor == 'Coverage' + run: | + pip install --user cpp-coveralls + + - name: Build & Run + run: | + cmake -DCMAKE_BUILD_TYPE=${{ matrix.flavor }} -DSUPPORT_STDIOSTREAM=ON -DTESTING=ON -DFORMAT=${{ matrix.compiler.FORMAT }} . + make check + + # TODO: enable +# - name: Coveralls build +# if: matrix.flavor == 'Coverage' +# run: | +# cpp-coveralls -i matrix +# - name: Coveralls +# if: matrix.flavor == 'Coverage' +# uses: coverallsapp/github-action@master +# with: +# github-token: ${{ secrets.GITHUB_TOKEN }} + diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 3b5f105333..0000000000 --- a/.travis.yml +++ /dev/null @@ -1,41 +0,0 @@ -language: c - -env: - global: - - export COVERALLS_SERVICE_NAME=travis-ci - - secure: "dA+jGAR9O3f+xsh6h7e7coeM0dU1vHiiM7kIPh5TvbbifDQiF5s2uxFQziZVSnLuohRD9oNODiJFz077n+svp7S9t77sdks0+7r61pkD5LlVItZ6ol5jQCfiksyMw6q5ChEes9KSKEfdFRjuDvQUHwShgpsXVAurizA2Hs3MziWxfIlOPULY4UCCm5+TLoY+vXmfFc4bwk2knxpIP8pYRd+xKYAiN9QC1fJiglipuKHaYbo2+ZYrM92RD0Cl+BZdWyI7vD7zmeXV6mstzAFZ20c63NhNNCYRy0VIC3hLB8zKMuvCZdJnpmSRfFt5uJYJPNcORc1ypeY7/CGMm5Rq1lNwxehFO3/++/aHE8H7GR0cTiKndPO0jDu48j+GUB4k1HHSsVEpj7vO7F3FOO0619xxybDFk1zFjHw8KTbdSXmBERldYAKZOP0JKZxp6CU5DXOO2dunumZAzl6WHJjhRMPFqPheE4e+I2YOEHvXTwDcEO/lMwacr6nuaZZXxEh/TwEdqsIRd9bvsoG1zuVQnZm+atLp3oF4QW8nI5l6qe6R+3l5dEgJGtz5hOsiEpWrwWk6ub2VCdELcgpPZyZcdwu/bKvXx3ndW6LjqzcLxMGxM3rdxx6J+b7Es/vkmT1SXFcxiUjpKkUf04Bb8SmGdbJdAKRZuSRFtjqsU0tHPfo=" - -matrix: - fast_finish: true - include: - - os: linux - dist: bionic - compiler: gcc-8 - env: CMAKE_BUILD_TYPE=Coverage FORMAT=ON - - os: linux - dist: bionic - compiler: clang - env: CMAKE_BUILD_TYPE=Release CC=clang CXX=clang++ FORMAT=OFF - - os: osx - osx_image: xcode11.3 - env: CMAKE_BUILD_TYPE=Release FORMAT=OFF - -addons: - apt: - packages: - - clang - - cmake - - g++-8 - - gcc - - lcov - -install: - - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then pip install --user cpp-coveralls; fi - -script: - - cmake -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DSUPPORT_STDIOSTREAM=ON -DTESTING=ON -DFORMAT=${FORMAT} . - - make check - -after_success: - - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then cpp-coveralls -i matrix; fi - - if [ "${CMAKE_BUILD_TYPE}" = "Coverage" ]; then bash <(curl -s https://codecov.io/bash) -F matrix_tests; fi From d03bf42f6071f71cbc71bb820a0a4479575e9931 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 6 Oct 2021 13:59:43 +0200 Subject: [PATCH 388/388] slice: add min and max functions --- matrix/Slice.hpp | 34 ++++++++++++++++++++++++++++++++++ test/slice.cpp | 5 +++++ 2 files changed, 39 insertions(+) diff --git a/matrix/Slice.hpp b/matrix/Slice.hpp index 6ab54c0be3..f98ac483c0 100644 --- a/matrix/Slice.hpp +++ b/matrix/Slice.hpp @@ -262,6 +262,40 @@ public: return norm_squared() > testVal*testVal; } + Type max() const + { + Type max_val = (*this)(0,0); + + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + Type val = (*this)(i,j); + + if (val > max_val) { + max_val = val; + } + } + } + + return max_val; + } + + Type min() const + { + Type min_val = (*this)(0,0); + + for (size_t i = 0; i < P; i++) { + for (size_t j = 0; j < Q; j++) { + Type val = (*this)(i,j); + + if (val < min_val) { + min_val = val; + } + } + } + + return min_val; + } + private: size_t _x0, _y0; Matrix* _data; diff --git a/test/slice.cpp b/test/slice.cpp index a8db0acd47..6f838f0ccf 100644 --- a/test/slice.cpp +++ b/test/slice.cpp @@ -125,6 +125,11 @@ int main() TEST(!v5.xy().longerThan(5.f)); TEST(isEqualF(5.f, v5.xy().norm())); + // min/max + TEST(m33.row(1).max() == 5); + TEST(m33.col(0).min() == 0); + TEST((m33.slice<2,2>(1,1).max()) == 10); + // assign scalar value to slice Matrix L; L(0,0) = -1;