From 3dcbf3aaacbef907927455bd3a9f7f79b285f635 Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 6 Dec 2020 20:04:57 -0500 Subject: [PATCH 01/67] fix == constness --- include/manif/impl/lie_group_base.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/manif/impl/lie_group_base.h b/include/manif/impl/lie_group_base.h index e4218c85..afec8075 100644 --- a/include/manif/impl/lie_group_base.h +++ b/include/manif/impl/lie_group_base.h @@ -275,7 +275,7 @@ struct LieGroupBase * @see isApprox. */ template - bool operator ==(const LieGroupBase<_DerivedOther>& m); + bool operator ==(const LieGroupBase<_DerivedOther>& m) const; /** * @brief Right oplus operator. @@ -618,7 +618,7 @@ LieGroupBase<_Derived>::act( template template bool LieGroupBase<_Derived>::operator ==( - const LieGroupBase<_DerivedOther>& m) + const LieGroupBase<_DerivedOther>& m) const { return isApprox(m); } From 43d59aefa6ca720bc64a30d6a4f1649806078a38 Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 6 Dec 2020 20:05:17 -0500 Subject: [PATCH 02/67] fix tan constants --- include/manif/impl/tangent_base.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/include/manif/impl/tangent_base.h b/include/manif/impl/tangent_base.h index f1f223fb..e2689049 100644 --- a/include/manif/impl/tangent_base.h +++ b/include/manif/impl/tangent_base.h @@ -337,6 +337,13 @@ struct TangentBase inline const _Derived& derived() const & noexcept { return *static_cast< const _Derived* >(this); } }; +template +constexpr int TangentBase<_Derived>::Dim; +template +constexpr int TangentBase<_Derived>::DoF; +template +constexpr int TangentBase<_Derived>::RepSize; + // Copy template From 0048e59070454540f85f00ae301687924ca6eca9 Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 6 Dec 2020 20:05:46 -0500 Subject: [PATCH 03/67] wip python bindings --- .travis.yml | 18 +++ CMakeLists.txt | 9 ++ python/CMakeLists.txt | 20 +++ python/bindings_lie_group_base.h | 150 +++++++++++++++++++ python/bindings_manif.cpp | 17 +++ python/bindings_optional.h | 11 ++ python/bindings_se2.cpp | 22 +++ python/bindings_se3.cpp | 22 +++ python/bindings_so2.cpp | 22 +++ python/bindings_so3.cpp | 22 +++ python/bindings_tangent_base.h | 141 ++++++++++++++++++ test/CMakeLists.txt | 4 + test/python/.cache/v/cache/lastfailed | 14 ++ test/python/CMakeLists.txt | 13 ++ test/python/pytest_manif.py | 205 ++++++++++++++++++++++++++ 15 files changed, 690 insertions(+) create mode 100644 python/CMakeLists.txt create mode 100644 python/bindings_lie_group_base.h create mode 100644 python/bindings_manif.cpp create mode 100644 python/bindings_optional.h create mode 100644 python/bindings_se2.cpp create mode 100644 python/bindings_se3.cpp create mode 100644 python/bindings_so2.cpp create mode 100644 python/bindings_so3.cpp create mode 100644 python/bindings_tangent_base.h create mode 100644 test/python/.cache/v/cache/lastfailed create mode 100644 test/python/CMakeLists.txt create mode 100644 test/python/pytest_manif.py diff --git a/.travis.yml b/.travis.yml index 605ccb1e..e0e8468b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -363,6 +363,24 @@ matrix: - make -j2 - make test + # + # Python bindings + # + - os: linux + env: + - TEST="G++ 9" + addons: + apt: + sources: + - ubuntu-toolchain-r-test + packages: + - gcc-9 + - g++-9 + script: + - cmake -DCMAKE_CXX_COMPILER="g++-9" -DBUILD_EXAMPLES=OFF -DBUILD_TESTING=ON -DBUILD_PYTHON_BINDINGS=ON.. + - make + - make test + allow_failures: - os: linux env: diff --git a/CMakeLists.txt b/CMakeLists.txt index f6b8f4d1..1c075718 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -54,6 +54,15 @@ endif() option(BUILD_TESTING "Build all tests." OFF) option(ENABLE_CPPCHECK "Enable cppcheck." OFF) option(BUILD_EXAMPLES "Build all examples." OFF) +option(BUILD_PYTHON_BINDINGS "Build Python bindings with pybind11." OFF) + +if (BUILD_PYTHON_BINDINGS) + find_package(pybind11 REQUIRED) + add_subdirectory(python) + # message(FATAL_ERROR OK) +endif() + +# message(FATAL_ERROR "NOT OK") ########### ## Build ## diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt new file mode 100644 index 00000000..7e8cc289 --- /dev/null +++ b/python/CMakeLists.txt @@ -0,0 +1,20 @@ +set(PYBIND11_CPP_STANDARD -std=c++11) +pybind11_add_module(PyManif + bindings_so2.cpp + bindings_so3.cpp + bindings_se2.cpp + bindings_se3.cpp + bindings_manif.cpp +) +target_link_libraries(PyManif PRIVATE ${PROJECT_NAME}) + +message(WARNING ${PROJECT_NAME}) + +# Set required C++11 flag +if(CMAKE_VERSION VERSION_LESS "3.1") + set_target_properties(PyManif PROPERTIES COMPILE_FLAGS "-std=c++11") +else() + set_property(TARGET PyManif PROPERTY CXX_STANDARD 11) + set_property(TARGET PyManif PROPERTY CXX_STANDARD_REQUIRED ON) + set_property(TARGET PyManif PROPERTY CXX_EXTENSIONS OFF) +endif() diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h new file mode 100644 index 00000000..e4897191 --- /dev/null +++ b/python/bindings_lie_group_base.h @@ -0,0 +1,150 @@ +#ifndef _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_ +#define _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_ + +namespace py = pybind11; + +template +void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { + + using Scalar = typename _LieGroup::Scalar; + using Tangent = typename _LieGroup::Tangent; + using Vector = typename _LieGroup::Vector; + using DataType = typename _LieGroup::DataType; + using OptJacobianRef = typename _LieGroup::OptJacobianRef; + + py_class.attr("Dim") = _LieGroup::Dim; + py_class.attr("DoF") = _LieGroup::DoF; + py_class.attr("RepSize") = _LieGroup::RepSize; + + py_class.def(py::init<>()); + py_class.def(py::init()); + + py_class.def( + "coeffs_copy", + static_cast(&_LieGroup::coeffs) + ); // Makes a copy! + + py_class.def( + "coeffs", + static_cast(&_LieGroup::coeffs), + py::return_value_policy::reference_internal + ); + + py_class.def( + "inverse", + &_LieGroup::inverse, + py::arg_v("J_m_t", OptJacobianRef(), + "None") + ); + + py_class.def( + "log", + &_LieGroup::log, + py::arg_v("J_m_t", OptJacobianRef(), + "None") + ); + + py_class.def("adj", &_LieGroup::adj); + + py_class.def( + "compose", &_LieGroup::template compose<_LieGroup>, + py::arg("other"), + py::arg_v("J_mc_ma", OptJacobianRef(), "None"), + py::arg_v("J_mc_mb", OptJacobianRef(), "None") + ); + + py_class.def( + "between", &_LieGroup::template between<_LieGroup>, + py::arg("other"), + py::arg_v("J_mc_ma", OptJacobianRef(), "None"), + py::arg_v("J_mc_mb", OptJacobianRef(), "None") + ); + + // py_class.def("act", &_LieGroup::template act, + // py::arg("v"), + // py::arg_v("J_vout_m", tl::optional>>(), "None"), + // py::arg_v("J_vout_v", tl::optional>>(), "None") + // ); + py_class.def("act", [](const _LieGroup& self, const Vector& v) { + return self.act(v); + }); + + py_class.def( + "isApprox", + &_LieGroup::template isApprox<_LieGroup>, + py::arg("other"), + py::arg_v("eps", Scalar(manif::Constants::eps), "eps") + ); + + py_class.def( + "rplus", + &_LieGroup::template rplus, + py::arg("t"), + py::arg_v("J_mout_m", OptJacobianRef(), "None"), + py::arg_v("J_mout_t", OptJacobianRef(), "None") + ); + + py_class.def( + "lplus", + &_LieGroup::template lplus, + py::arg("t"), + py::arg_v("J_mout_m", OptJacobianRef(), "None"), + py::arg_v("J_mout_t", OptJacobianRef(), "None") + ); + + py_class.def( + "plus", + &_LieGroup::template plus, + py::arg("t"), + py::arg_v("J_mout_m", OptJacobianRef(), "None"), + py::arg_v("J_mout_t", OptJacobianRef(), "None") + ); + + py_class.def( + "rminus", + &_LieGroup::template rminus<_LieGroup>, + py::arg("t"), + py::arg_v("J_t_ma", OptJacobianRef(), "None"), + py::arg_v("J_t_mb", OptJacobianRef(), "None") + ); + + py_class.def( + "lminus", + &_LieGroup::template lminus<_LieGroup>, + py::arg("t"), + py::arg_v("J_t_ma", OptJacobianRef(), "None"), + py::arg_v("J_t_mb", OptJacobianRef(), "None") + ); + + py_class.def( + "minus", + &_LieGroup::template minus<_LieGroup>, + py::arg("t"), + py::arg_v("J_t_ma", OptJacobianRef(), "None"), + py::arg_v("J_t_mb", OptJacobianRef(), "None") + ); + + py_class.def("setIdentity", &_LieGroup::setIdentity); + py_class.def("setRandom", &_LieGroup::setRandom); + + py_class.def_static("Identity", &_LieGroup::Identity); + py_class.def_static("Random", &_LieGroup::Random); + + py_class.def(py::self + Tangent()) + // .def(py::self += Tangent()) + .def(py::self - py::self) + .def(py::self * py::self) + // .def(py::self *= py::self) + .def(py::self == py::self) + ; + + py_class.def( + "__str__", + [](const _LieGroup &o) { + std::ostringstream ss; ss << o; + return ss.str(); + } + ); +} + +#endif // _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_ diff --git a/python/bindings_manif.cpp b/python/bindings_manif.cpp new file mode 100644 index 00000000..2e6371ba --- /dev/null +++ b/python/bindings_manif.cpp @@ -0,0 +1,17 @@ +#include + +void wrap_SO2(pybind11::module &m); +void wrap_SO3(pybind11::module &m); + +void wrap_SE2(pybind11::module &m); +void wrap_SE3(pybind11::module &m); + +PYBIND11_MODULE(PyManif, m) { + m.doc() = "Python bindings for the manif library."; + + wrap_SO3(m); + wrap_SO2(m); + + wrap_SE3(m); + wrap_SE2(m); +} diff --git a/python/bindings_optional.h b/python/bindings_optional.h new file mode 100644 index 00000000..52b838e2 --- /dev/null +++ b/python/bindings_optional.h @@ -0,0 +1,11 @@ +#ifndef _MANIF_PYTHON_BINDINGS_OPTIONAL_H_ +#define _MANIF_PYTHON_BINDINGS_OPTIONAL_H_ + +#include "lt/optional.hpp" + +namespace pybind11 { namespace detail { + template + struct type_caster> : optional_caster> {}; +}} + +#endif // _MANIF_PYTHON_BINDINGS_OPTIONAL_H_ diff --git a/python/bindings_se2.cpp b/python/bindings_se2.cpp new file mode 100644 index 00000000..b421bf1a --- /dev/null +++ b/python/bindings_se2.cpp @@ -0,0 +1,22 @@ +#include +#include +#include +#include + +#include "manif/SE2.h" + +#include "bindings_optional.h" +#include "bindings_lie_group_base.h" +#include "bindings_tangent_base.h" + +void wrap_SE2(pybind11::module &m) +{ + pybind11::class_, std::unique_ptr, py::nodelete>> SE2_base(m, "SE2Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> SE2_tan_base(m, "SE2TangentBase"); + + pybind11::class_> SE2(m, "SE2"); + pybind11::class_> SE2_tan(m, "SE2Tangent"); + + wrap_lie_group_base>(SE2); + wrap_tangent_base>(SE2_tan); +} diff --git a/python/bindings_se3.cpp b/python/bindings_se3.cpp new file mode 100644 index 00000000..36a469b6 --- /dev/null +++ b/python/bindings_se3.cpp @@ -0,0 +1,22 @@ +#include +#include +#include +#include + +#include "manif/SE3.h" + +#include "bindings_optional.h" +#include "bindings_lie_group_base.h" +#include "bindings_tangent_base.h" + +void wrap_SE3(pybind11::module &m) +{ + pybind11::class_, std::unique_ptr, py::nodelete>> SE3_base(m, "SE3Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> SE3_tan_base(m, "SE3TangentBase"); + + pybind11::class_> SE3(m, "SE3"); + pybind11::class_> SE3_tan(m, "SE3Tangent"); + + wrap_lie_group_base>(SE3); + wrap_tangent_base>(SE3_tan); +} diff --git a/python/bindings_so2.cpp b/python/bindings_so2.cpp new file mode 100644 index 00000000..4437db9b --- /dev/null +++ b/python/bindings_so2.cpp @@ -0,0 +1,22 @@ +#include +#include +#include +#include + +#include "manif/SO2.h" + +#include "bindings_optional.h" +#include "bindings_lie_group_base.h" +#include "bindings_tangent_base.h" + +void wrap_SO2(pybind11::module &m) +{ + pybind11::class_, std::unique_ptr, py::nodelete>> SO2_base(m, "SO2Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> SO2_tan_base(m, "SO2TangentBase"); + + pybind11::class_> SO2(m, "SO2"); + pybind11::class_> SO2_tan(m, "SO2Tangent"); + + wrap_lie_group_base>(SO2); + wrap_tangent_base>(SO2_tan); +} diff --git a/python/bindings_so3.cpp b/python/bindings_so3.cpp new file mode 100644 index 00000000..884e07ec --- /dev/null +++ b/python/bindings_so3.cpp @@ -0,0 +1,22 @@ +#include +#include +#include +#include + +#include "manif/SO3.h" + +#include "bindings_optional.h" +#include "bindings_lie_group_base.h" +#include "bindings_tangent_base.h" + +void wrap_SO3(pybind11::module &m) +{ + pybind11::class_, std::unique_ptr, py::nodelete>> SO3_base(m, "SO3Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> SO3_tan_base(m, "SO3TangentBase"); + + pybind11::class_> SO3(m, "SO3"); + pybind11::class_> SO3_tan(m, "SO3Tangent"); + + wrap_lie_group_base>(SO3); + wrap_tangent_base>(SO3_tan); +} diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h new file mode 100644 index 00000000..d8ba85e8 --- /dev/null +++ b/python/bindings_tangent_base.h @@ -0,0 +1,141 @@ +#ifndef _MANIF_PYTHON_BINDINGS_TANGENT_BASE_H_ +#define _MANIF_PYTHON_BINDINGS_TANGENT_BASE_H_ + +namespace py = pybind11; + +template +void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { + + using Scalar = typename _Tangent::Scalar; + using LieGroup = typename _Tangent::LieGroup; + using DataType = typename _Tangent::DataType; + using Jacobian = typename _Tangent::Jacobian; + using OptJacobianRef = typename _Tangent::OptJacobianRef; + using InnerWeight = typename _Tangent::InnerWeight; + + py_class.attr("Dim") = _Tangent::Dim; + py_class.attr("DoF") = _Tangent::DoF; + py_class.attr("RepSize") = _Tangent::RepSize; + + py_class.def(py::init<>()); + py_class.def(py::init()); + + py_class.def( + "coeffs_copy", + static_cast(&_Tangent::coeffs) + ); // Makes a copy! + py_class.def( + "coeffs", + static_cast(&_Tangent::coeffs), + py::return_value_policy::reference_internal + ); + + py_class.def("generator", &_Tangent::generator); + + // py_class.def("w", &_Tangent::w); + py_class.def("inner", &_Tangent::template inner<_Tangent>); + + py_class.def("weightedNorm", &_Tangent::weightedNorm); + py_class.def("squaredWeightedNorm", &_Tangent::squaredWeightedNorm); + py_class.def("hat", &_Tangent::hat); + + py_class.def( + "exp", + &_Tangent::exp, + py::arg_v("J_m_t", OptJacobianRef(), "None") + ); + + py_class.def( + "rplus", + &_Tangent::rplus, + py::arg("m"), + py::arg_v("J_mout_t", OptJacobianRef(), "None"), + py::arg_v("J_mout_m", OptJacobianRef(), "None") + ); + + py_class.def( + "lplus", + &_Tangent::lplus, + py::arg("m"), + py::arg_v("J_mout_t", OptJacobianRef(), "None"), + py::arg_v("J_mout_m", OptJacobianRef(), "None") + ); + + py_class.def( + "plus", + static_cast(&_Tangent::plus), + py::arg("m"), + py::arg_v("J_mout_t", OptJacobianRef(), "None"), + py::arg_v("J_mout_m", OptJacobianRef(), "None") + ); + + py_class.def( + "plus", + &_Tangent::template plus<_Tangent>, + py::arg("other"), + py::arg_v("J_mout_t", OptJacobianRef(), "None"), + py::arg_v("J_mout_o", OptJacobianRef(), "None") + ); + + py_class.def( + "minus", + &_Tangent::template minus<_Tangent>, + py::arg("other"), + py::arg_v("J_mout_ta", OptJacobianRef(), "None"), + py::arg_v("J_mout_tb", OptJacobianRef(), "None") + ); + + // py_class.def("rjac", &_Tangent::rjac); + // py_class.def("ljac", &_Tangent::ljac); + // py_class.def("rjacinv", &_Tangent::rjacinv); + // py_class.def("ljacinv", &_Tangent::ljacinv); + + py_class.def("smallAdj", &_Tangent::smallAdj); + + py_class.def( + "isApprox", + [](const _Tangent& self, const _Tangent& t, Scalar eps) { + return self.isApprox(t, eps); + }, + py::arg("other"), + py::arg_v("eps", Scalar(manif::Constants::eps), "eps")); + + py_class.def( + "isApprox", + [](const _Tangent& self, const DataType& t, Scalar eps) { + return self.isApprox(t, eps); + }, + py::arg("other"), + py::arg_v("eps", Scalar(manif::Constants::eps), "eps")); + + py_class.def("setZero", &_Tangent::setZero); + py_class.def("setRandom", &_Tangent::setRandom); + + py_class.def_static("Zero", &_Tangent::Zero); + py_class.def_static("Random", &_Tangent::Random); + py_class.def_static("Generator", &_Tangent::Generator); + py_class.def_static("W", &_Tangent::W); + + // operator overloads + py_class.def(-py::self) + .def(py::self + LieGroup()) + .def(py::self + py::self) + .def(py::self += py::self) + .def(py::self - py::self) + .def(py::self -= py::self) + .def(py::self * double()) + .def(Jacobian() * py::self) + .def(py::self / double()) + .def(py::self == py::self) + ; + + py_class.def( + "__str__", + [](const _Tangent &t) { + std::ostringstream ss; ss << t; + return ss.str(); + } + ); +} + +#endif // _MANIF_PYTHON_BINDINGS_TANGENT_BASE_H_ diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 7067fc91..14c4e3bf 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -98,3 +98,7 @@ else() set_property(TARGET ${CXX_11_TEST_TARGETS} PROPERTY CXX_STANDARD_REQUIRED ON) set_property(TARGET ${CXX_11_TEST_TARGETS} PROPERTY CXX_EXTENSIONS OFF) endif() + +if(BUILD_PYTHON_BINDINGS) + add_subdirectory(python) +endif() diff --git a/test/python/.cache/v/cache/lastfailed b/test/python/.cache/v/cache/lastfailed new file mode 100644 index 00000000..a7bfee4d --- /dev/null +++ b/test/python/.cache/v/cache/lastfailed @@ -0,0 +1,14 @@ +{ + "pytest_manif.py::TestCommon::()::test_smallAdj[SE2-SE2Tangent]": true, + "pytest_manif.py::TestCommon::()::test_smallAdj[SO2-SO2Tangent]": true, + "pytest_manif.py::TestCommon::()::test_smallAdj[SO3-SO3Tangent]": true, + "pytest_se3.py::TestCommon": true, + "pytest_se3.py::TestCommon::()::test_ExpLog[SE3-SE3Tangent]": true, + "pytest_se3.py::TestCommon::()::test_ExpLog[SO3-SO3Tangent]": true, + "pytest_se3.py::TestCommon::()::test_assignment": true, + "pytest_se3.py::TestCommon::()::test_assignment1[SE3-SE3Tangent]": true, + "pytest_se3.py::TestCommon::()::test_assignment2[SE3-SE3Tangent]": true, + "pytest_se3.py::TestCommon::()::test_plusEq[SE3-SE3Tangent]": true, + "pytest_se3.py::TestCommon::()::test_smallAdl[SE3-SE3Tangent]": true, + "pytest_se3.py::test_tt": true +} \ No newline at end of file diff --git a/test/python/CMakeLists.txt b/test/python/CMakeLists.txt new file mode 100644 index 00000000..db4403b6 --- /dev/null +++ b/test/python/CMakeLists.txt @@ -0,0 +1,13 @@ +# small helper function +function(manif_add_pytest target) + add_test( + NAME ${target} + COMMAND ${PYTHON_EXECUTABLE} -m pytest ${target}.py + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + ) + set_tests_properties(${target} + PROPERTIES ENVIRONMENT "PYTHONPATH=${CMAKE_BINARY_DIR}/python:$ENV{PYTHONPATH}" + ) +endfunction() + +manif_add_pytest(pytest_manif) diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py new file mode 100644 index 00000000..5f0659b9 --- /dev/null +++ b/test/python/pytest_manif.py @@ -0,0 +1,205 @@ +import numpy as np +import pytest + +from PyManif import SO2, SO2Tangent, SE2, SE2Tangent, SO3, SO3Tangent, SE3, SE3Tangent + + +@pytest.mark.parametrize( + "LieGroup, Tangent", + [ + (SO2, SO2Tangent), + (SO3, SO3Tangent), + (SE2, SE2Tangent), + # (SE3, SE3Tangent), + ] +) +class TestCommon: + + def test_Init(self, LieGroup, Tangent): + state = LieGroup.Random() + + assert state != LieGroup.Identity() + state = LieGroup.Identity() + assert state == LieGroup.Identity() + state.setRandom() + assert state != LieGroup.Identity() + state.setIdentity() + assert state == LieGroup.Identity() + + delta = Tangent.Random() + + assert delta != Tangent.Zero() + delta = Tangent.Zero() + assert delta == Tangent.Zero() + delta.setRandom() + assert delta != Tangent.Zero() + delta.setZero() + assert delta == Tangent.Zero() + + def test_Assignment(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + + assert state != state_other + + state_other = state + assert state == state_other + + delta = Tangent.Random() + delta_other = Tangent.Random() + + assert delta != delta_other + + delta_other = delta + assert delta == delta_other + + delta = Tangent(np.zeros(Tangent.DoF)) + assert (delta.coeffs() == np.zeros(Tangent.DoF)).all() + data = np.random.rand(Tangent.DoF) + delta = Tangent(data) + assert (delta.coeffs() == data).all() + assert not (delta.coeffs() == np.zeros(Tangent.DoF)).all() + + def test_Plus(self, LieGroup, Tangent): + state = LieGroup.Random() + delta = Tangent.Random() + + assert state.plus(delta) == (state + delta) + assert state.plus(delta) == state.rplus(delta) + assert state == state + Tangent.Zero() + assert state == Tangent.Zero() + state + assert LieGroup.Identity() == LieGroup.Identity() + Tangent.Zero() + + def test_Minus(self, LieGroup, Tangent): + state = LieGroup.Random() + other = LieGroup.Random() + delta = Tangent.Random() + + assert state.minus(other) == state - other + assert state.minus(other) == state.rminus(other) + assert Tangent.Zero() == state - state + assert Tangent.Zero() == delta - delta + + # def test_plusEq(self, LieGroup, Tangent): + # state = LieGroup.Random() + # copy = state + # delta = Tangent.Random() + # + # state += delta + # + # assert copy + delta == state + + def test_Compose(self, LieGroup, Tangent): + state = LieGroup.Random() + other = LieGroup.Random() + + assert state.compose(other) == state * other + assert state.compose(LieGroup.Identity()) == state + assert LieGroup.Identity().compose(state) == state + assert LieGroup.Identity() == state.compose(state.inverse()) + assert LieGroup.Identity() == state.inverse().compose(state) + + def test_Exp(self, LieGroup, Tangent): + assert LieGroup.Identity() == Tangent.Zero().exp() + + def test_Log(self, LieGroup, Tangent): + assert Tangent.Zero() == LieGroup.Identity().log() + + def test_LogExp(self, LieGroup, Tangent): + state = LieGroup.Random() + + assert state == state.log().exp() + + def test_ExpLog(self, LieGroup, Tangent): + delta = Tangent.Random() + + state = delta.exp() + delta_other = state.log() + print(delta) + print(delta.exp().log()) + print(delta_other) + + assert delta == delta_other + + def test_Between(self, LieGroup, Tangent): + state = LieGroup.Random() + + assert LieGroup.Identity() == state.between(state) + + def test_Random(self, LieGroup, Tangent): + assert LieGroup.Random() != LieGroup.Random() + assert Tangent.Random() != Tangent.Random() + + def test_isApprox(self, LieGroup, Tangent): + state = LieGroup.Random() + other = LieGroup.Random() + + assert state.isApprox(state) + assert not state.isApprox(other) + + state = Tangent.Random() + other = Tangent.Random() + + assert state.isApprox(state) + assert not state.isApprox(other) + + assert LieGroup.Identity().isApprox(LieGroup.Identity()) + assert Tangent.Zero().isApprox(Tangent.Zero()) + assert Tangent.Zero().isApprox(np.zeros(Tangent.DoF)) + + def test_Inner(self, LieGroup, Tangent): + assert 0 == Tangent.Zero().weightedNorm() + assert 0 == Tangent.Zero().squaredWeightedNorm() + assert 0 == Tangent.Zero().inner(Tangent.Zero()) + + delta = Tangent.Random() + delta_other = Tangent.Random() + assert delta.squaredWeightedNorm() == delta.inner(delta) + assert delta.inner(delta_other) == delta_other.inner(delta) + + def test_Act(self, LieGroup, Tangent): + state = LieGroup.Identity() + point = np.random.rand(Tangent.Dim) + + pout = state.act(point) + + assert (point == pout).all() + + state = LieGroup.Random() + + pout = state.act(point) + + assert not (point == pout).all() + + pout = state.inverse().act(pout) + + # allclose: absolute(a - b) <= (1e-08 + 1e-05 * absolute(b)) + assert np.allclose(point, pout) + + # def test_smallAdj(self, LieGroup, Tangent): + # delta = Tangent.Random() + # delta_other = Tangent.Random() + # + # assert (delta.smallAdj() * delta_other).hat() == delta.hat() * delta_other.hat() - delta_other.hat() * delta.hat() + + def test_InverseJac(self, LieGroup, Tangent): + + state = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + + # https://pybind11.readthedocs.io/en/stable/advanced/cast/eigen.html#storage-orders + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF), order='F') + + state_out = state.inverse(J_sout_s) + + print(type(J_sout_s)) + print(J_sout_s) + print(type(w)) + print(w) + # print(type(J_sout_s)) + # print(J_sout_s*w) + + state_pert = (state+w).inverse() + # state_lin = state_out.rplus(J_sout_s*w) + + # assert state_pert == state_lin From ed78690e9249d15b3087cfed8710c2439b546aba Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 8 Dec 2020 11:49:50 -0500 Subject: [PATCH 04/67] add bindings Rn & SE_2_3 --- python/bindings_manif.cpp | 12 ++++- python/bindings_rn.cpp | 103 ++++++++++++++++++++++++++++++++++++ python/bindings_se_2_3.cpp | 22 ++++++++ test/python/pytest_manif.py | 26 ++++++++- 4 files changed, 160 insertions(+), 3 deletions(-) create mode 100644 python/bindings_rn.cpp create mode 100644 python/bindings_se_2_3.cpp diff --git a/python/bindings_manif.cpp b/python/bindings_manif.cpp index 2e6371ba..34694ce7 100644 --- a/python/bindings_manif.cpp +++ b/python/bindings_manif.cpp @@ -1,17 +1,25 @@ #include +void wrap_Rn(pybind11::module &m); + void wrap_SO2(pybind11::module &m); void wrap_SO3(pybind11::module &m); void wrap_SE2(pybind11::module &m); void wrap_SE3(pybind11::module &m); +void wrap_SE_2_3(pybind11::module &m); + PYBIND11_MODULE(PyManif, m) { m.doc() = "Python bindings for the manif library."; - wrap_SO3(m); + wrap_Rn(m); + wrap_SO2(m); + wrap_SO3(m); - wrap_SE3(m); wrap_SE2(m); + wrap_SE3(m); + + wrap_SE_2_3(m); } diff --git a/python/bindings_rn.cpp b/python/bindings_rn.cpp new file mode 100644 index 00000000..5dd93703 --- /dev/null +++ b/python/bindings_rn.cpp @@ -0,0 +1,103 @@ +#include +#include +#include +#include + +#include "manif/Rn.h" + +#include "bindings_optional.h" +#include "bindings_lie_group_base.h" +#include "bindings_tangent_base.h" + +void wrap_Rn(pybind11::module &m) +{ + // R1 + pybind11::class_, std::unique_ptr, py::nodelete>> R1_base(m, "R1Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R1_tan_base(m, "R1TangentBase"); + + pybind11::class_> R1(m, "R1"); + pybind11::class_> R1_tan(m, "R1Tangent"); + + wrap_lie_group_base>(R1); + wrap_tangent_base>(R1_tan); + + // R2 + pybind11::class_, std::unique_ptr, py::nodelete>> R2_base(m, "R2Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R2_tan_base(m, "R2TangentBase"); + + pybind11::class_> R2(m, "R2"); + pybind11::class_> R2_tan(m, "R2Tangent"); + + wrap_lie_group_base>(R2); + wrap_tangent_base>(R2_tan); + + // R3 + pybind11::class_, std::unique_ptr, py::nodelete>> R3_base(m, "R3Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R3_tan_base(m, "R3TangentBase"); + + pybind11::class_> R3(m, "R3"); + pybind11::class_> R3_tan(m, "R3Tangent"); + + wrap_lie_group_base>(R3); + wrap_tangent_base>(R3_tan); + + // R4 + pybind11::class_, std::unique_ptr, py::nodelete>> R4_base(m, "R4Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R4_tan_base(m, "R4TangentBase"); + + pybind11::class_> R4(m, "R4"); + pybind11::class_> R4_tan(m, "R4Tangent"); + + wrap_lie_group_base>(R4); + wrap_tangent_base>(R4_tan); + + // R5 + pybind11::class_, std::unique_ptr, py::nodelete>> R5_base(m, "R5Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R5_tan_base(m, "R5TangentBase"); + + pybind11::class_> R5(m, "R5"); + pybind11::class_> R5_tan(m, "R5Tangent"); + + wrap_lie_group_base>(R5); + wrap_tangent_base>(R5_tan); + + // R6 + pybind11::class_, std::unique_ptr, py::nodelete>> R6_base(m, "R6Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R6_tan_base(m, "R6TangentBase"); + + pybind11::class_> R6(m, "R6"); + pybind11::class_> R6_tan(m, "R6Tangent"); + + wrap_lie_group_base>(R6); + wrap_tangent_base>(R6_tan); + + // R7 + pybind11::class_, std::unique_ptr, py::nodelete>> R7_base(m, "R7Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R7_tan_base(m, "R7TangentBase"); + + pybind11::class_> R7(m, "R7"); + pybind11::class_> R7_tan(m, "R7Tangent"); + + wrap_lie_group_base>(R7); + wrap_tangent_base>(R7_tan); + + // R8 + pybind11::class_, std::unique_ptr, py::nodelete>> R8_base(m, "R8Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R8_tan_base(m, "R8TangentBase"); + + pybind11::class_> R8(m, "R8"); + pybind11::class_> R8_tan(m, "R8Tangent"); + + wrap_lie_group_base>(R8); + wrap_tangent_base>(R8_tan); + + // R9 + pybind11::class_, std::unique_ptr, py::nodelete>> R9_base(m, "R9Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> R9_tan_base(m, "R9TangentBase"); + + pybind11::class_> R9(m, "R9"); + pybind11::class_> R9_tan(m, "R9Tangent"); + + wrap_lie_group_base>(R9); + wrap_tangent_base>(R9_tan); +} diff --git a/python/bindings_se_2_3.cpp b/python/bindings_se_2_3.cpp new file mode 100644 index 00000000..72fe147a --- /dev/null +++ b/python/bindings_se_2_3.cpp @@ -0,0 +1,22 @@ +#include +#include +#include +#include + +#include "manif/SE_2_3.h" + +#include "bindings_optional.h" +#include "bindings_lie_group_base.h" +#include "bindings_tangent_base.h" + +void wrap_SE_2_3(pybind11::module &m) +{ + pybind11::class_, std::unique_ptr, py::nodelete>> SE_2_3_base(m, "SE_2_3Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> SE_2_3_tan_base(m, "SE_2_3TangentBase"); + + pybind11::class_> SE_2_3(m, "SE_2_3"); + pybind11::class_> SE_2_3_tan(m, "SE_2_3Tangent"); + + wrap_lie_group_base>(SE_2_3); + wrap_tangent_base>(SE_2_3_tan); +} diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index 5f0659b9..f6431ff5 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -1,16 +1,40 @@ import numpy as np import pytest -from PyManif import SO2, SO2Tangent, SE2, SE2Tangent, SO3, SO3Tangent, SE3, SE3Tangent +from PyManif import \ + R1, R1Tangent, \ + R2, R2Tangent, \ + R3, R3Tangent, \ + R4, R4Tangent, \ + R5, R5Tangent, \ + R6, R6Tangent, \ + R7, R7Tangent, \ + R8, R8Tangent, \ + R9, R9Tangent, \ + SO2, SO2Tangent, \ + SE2, SE2Tangent, \ + SO3, SO3Tangent, \ + SE3, SE3Tangent, \ + SE_2_3, SE_2_3Tangent @pytest.mark.parametrize( "LieGroup, Tangent", [ + (R1, R1Tangent), + (R2, R2Tangent), + (R3, R3Tangent), + (R4, R4Tangent), + (R5, R5Tangent), + (R6, R6Tangent), + (R7, R7Tangent), + (R8, R8Tangent), + (R9, R9Tangent), (SO2, SO2Tangent), (SO3, SO3Tangent), (SE2, SE2Tangent), # (SE3, SE3Tangent), + (SE_2_3, SE_2_3Tangent), ] ) class TestCommon: From 3d6e879ced90c5ad5f6aca8fc59d9f9807d902db Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 8 Dec 2020 11:50:11 -0500 Subject: [PATCH 05/67] cosmetic --- python/bindings_lie_group_base.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h index e4897191..e93f92e6 100644 --- a/python/bindings_lie_group_base.h +++ b/python/bindings_lie_group_base.h @@ -33,15 +33,13 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py_class.def( "inverse", &_LieGroup::inverse, - py::arg_v("J_m_t", OptJacobianRef(), - "None") + py::arg_v("J_m_t", OptJacobianRef(), "None") ); py_class.def( "log", &_LieGroup::log, - py::arg_v("J_m_t", OptJacobianRef(), - "None") + py::arg_v("J_m_t", OptJacobianRef(), "None") ); py_class.def("adj", &_LieGroup::adj); From 995db64ea21885d2d56cc560c71c0812f55f0150 Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 8 Dec 2020 12:58:47 -0500 Subject: [PATCH 06/67] CI install pybind11 & pytest --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index e0e8468b..a7a0c443 100644 --- a/.travis.yml +++ b/.travis.yml @@ -373,6 +373,8 @@ matrix: apt: sources: - ubuntu-toolchain-r-test + - pybind11-dev + - python3-pytest packages: - gcc-9 - g++-9 From b96f002102bb7e088631afc55a49f94bb35a28b6 Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 8 Dec 2020 13:01:39 -0500 Subject: [PATCH 07/67] fix CMake --- python/CMakeLists.txt | 2 ++ test/python/pytest_manif.py | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 7e8cc289..e8ffe2ee 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,9 +1,11 @@ set(PYBIND11_CPP_STANDARD -std=c++11) pybind11_add_module(PyManif + bindings_rn.cpp bindings_so2.cpp bindings_so3.cpp bindings_se2.cpp bindings_se3.cpp + bindings_se_2_3.cpp bindings_manif.cpp ) target_link_libraries(PyManif PRIVATE ${PROJECT_NAME}) diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index f6431ff5..dd08977c 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -33,7 +33,7 @@ (SO2, SO2Tangent), (SO3, SO3Tangent), (SE2, SE2Tangent), - # (SE3, SE3Tangent), + (SE3, SE3Tangent), (SE_2_3, SE_2_3Tangent), ] ) From 7f09a447d622bbe7707f43ddb4ace7c1f86b691f Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 8 Dec 2020 13:04:21 -0500 Subject: [PATCH 08/67] rm python cache --- .gitignore | 1 + test/python/.cache/v/cache/lastfailed | 14 -------------- 2 files changed, 1 insertion(+), 14 deletions(-) delete mode 100644 test/python/.cache/v/cache/lastfailed diff --git a/.gitignore b/.gitignore index 8e53b8e7..aeefac73 100644 --- a/.gitignore +++ b/.gitignore @@ -6,3 +6,4 @@ build doc doxygen_warnings.txt +*.cache diff --git a/test/python/.cache/v/cache/lastfailed b/test/python/.cache/v/cache/lastfailed deleted file mode 100644 index a7bfee4d..00000000 --- a/test/python/.cache/v/cache/lastfailed +++ /dev/null @@ -1,14 +0,0 @@ -{ - "pytest_manif.py::TestCommon::()::test_smallAdj[SE2-SE2Tangent]": true, - "pytest_manif.py::TestCommon::()::test_smallAdj[SO2-SO2Tangent]": true, - "pytest_manif.py::TestCommon::()::test_smallAdj[SO3-SO3Tangent]": true, - "pytest_se3.py::TestCommon": true, - "pytest_se3.py::TestCommon::()::test_ExpLog[SE3-SE3Tangent]": true, - "pytest_se3.py::TestCommon::()::test_ExpLog[SO3-SO3Tangent]": true, - "pytest_se3.py::TestCommon::()::test_assignment": true, - "pytest_se3.py::TestCommon::()::test_assignment1[SE3-SE3Tangent]": true, - "pytest_se3.py::TestCommon::()::test_assignment2[SE3-SE3Tangent]": true, - "pytest_se3.py::TestCommon::()::test_plusEq[SE3-SE3Tangent]": true, - "pytest_se3.py::TestCommon::()::test_smallAdl[SE3-SE3Tangent]": true, - "pytest_se3.py::test_tt": true -} \ No newline at end of file From 37bd4501fe41fc640d212e3c24e46413a076167c Mon Sep 17 00:00:00 2001 From: artivis Date: Fri, 11 Dec 2020 11:26:12 -0500 Subject: [PATCH 09/67] isolate python tests --- CMakeLists.txt | 11 ++++++++--- python/CMakeLists.txt | 2 -- test/CMakeLists.txt | 4 ---- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1c075718..832580a2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -55,15 +55,13 @@ option(BUILD_TESTING "Build all tests." OFF) option(ENABLE_CPPCHECK "Enable cppcheck." OFF) option(BUILD_EXAMPLES "Build all examples." OFF) option(BUILD_PYTHON_BINDINGS "Build Python bindings with pybind11." OFF) +option(BUILD_TESTING_PYTHON "Build Python tests only." OFF) if (BUILD_PYTHON_BINDINGS) find_package(pybind11 REQUIRED) add_subdirectory(python) - # message(FATAL_ERROR OK) endif() -# message(FATAL_ERROR "NOT OK") - ########### ## Build ## ########### @@ -272,3 +270,10 @@ if(BUILD_TESTING) add_subdirectory(test) endif(BUILD_TESTING) + +if(BUILD_PYTHON_BINDINGS AND (BUILD_TESTING OR BUILD_TESTING_PYTHON)) + + enable_testing() + add_subdirectory(test/python) + +endif() diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index e8ffe2ee..6fa87342 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -10,8 +10,6 @@ pybind11_add_module(PyManif ) target_link_libraries(PyManif PRIVATE ${PROJECT_NAME}) -message(WARNING ${PROJECT_NAME}) - # Set required C++11 flag if(CMAKE_VERSION VERSION_LESS "3.1") set_target_properties(PyManif PROPERTIES COMPILE_FLAGS "-std=c++11") diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 14c4e3bf..7067fc91 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -98,7 +98,3 @@ else() set_property(TARGET ${CXX_11_TEST_TARGETS} PROPERTY CXX_STANDARD_REQUIRED ON) set_property(TARGET ${CXX_11_TEST_TARGETS} PROPERTY CXX_EXTENSIONS OFF) endif() - -if(BUILD_PYTHON_BINDINGS) - add_subdirectory(python) -endif() From 99e55f3e7061f5c57a11da6da66ff97aaf1f9c68 Mon Sep 17 00:00:00 2001 From: artivis Date: Fri, 11 Dec 2020 11:26:36 -0500 Subject: [PATCH 10/67] add GHA CI python --- .github/workflows/ci.yml | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 8b7515b4..2a52028f 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -167,6 +167,26 @@ jobs: working-directory: ${{runner.workspace}}/build run: make test + pybind11: + needs: [build-ubuntu] + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@v2 + - name: Setup + run: | + sudo apt install -y libeigen3-dev pybind11-dev python3-pytest + mkdir ${{runner.workspace}}/build + - name: Configure CMake + working-directory: ${{runner.workspace}}/build + run: cmake $GITHUB_WORKSPACE -DBUILD_PYTHON_BINDINGS=ON -DBUILD_TESTING_PYTHON=ON + - name: Build + working-directory: ${{runner.workspace}}/build + run: make -j2 + - name: Test + working-directory: ${{runner.workspace}}/build + run: make test + # arm64: # needs: [build-ubuntu] # runs-on: ubuntu-latest From 85a3d6f08489f216d94cbd2925e1780128094096 Mon Sep 17 00:00:00 2001 From: artivis Date: Fri, 11 Dec 2020 19:47:19 -0500 Subject: [PATCH 11/67] fix pybind ci --- .github/workflows/ci.yml | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 2a52028f..77e1c43a 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -9,6 +9,9 @@ on: - devel workflow_dispatch: +env: + CTEST_OUTPUT_ON_FAILURE: 1 + jobs: build-ubuntu: @@ -175,11 +178,12 @@ jobs: uses: actions/checkout@v2 - name: Setup run: | - sudo apt install -y libeigen3-dev pybind11-dev python3-pytest + sudo apt install -y libeigen3-dev + pip3 install numpy pybind11-global pytest mkdir ${{runner.workspace}}/build - name: Configure CMake working-directory: ${{runner.workspace}}/build - run: cmake $GITHUB_WORKSPACE -DBUILD_PYTHON_BINDINGS=ON -DBUILD_TESTING_PYTHON=ON + run: cmake $GITHUB_WORKSPACE -DBUILD_PYTHON_BINDINGS=ON -DBUILD_TESTING_PYTHON=ON -Dpybind11_DIR=~/.local/share/cmake/pybind11/ - name: Build working-directory: ${{runner.workspace}}/build run: make -j2 From 6f124b8db0fcfa615217ac687bd5bc5ee3695890 Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 15 Dec 2020 19:45:49 -0500 Subject: [PATCH 12/67] use EIGEN_DEFAULT_TO_ROW_MAJOR --- python/CMakeLists.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 6fa87342..8f02a010 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -9,6 +9,9 @@ pybind11_add_module(PyManif bindings_manif.cpp ) target_link_libraries(PyManif PRIVATE ${PROJECT_NAME}) +# Eigen and numpy have different default storage order. +# See e.g. https://pybind11.readthedocs.io/en/stable/advanced/cast/eigen.html#storage-orders +target_compile_definitions(PyManif PRIVATE EIGEN_DEFAULT_TO_ROW_MAJOR) # Set required C++11 flag if(CMAKE_VERSION VERSION_LESS "3.1") From 6a08872cbc8f4295c3c40597cbfef5cbda6b330f Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 15 Dec 2020 19:47:42 -0500 Subject: [PATCH 13/67] more API bindings & more tests --- python/bindings_se2.cpp | 31 +++++++++++++- python/bindings_se3.cpp | 27 +++++++++++- python/bindings_se_2_3.cpp | 34 ++++++++++++++- python/bindings_so2.cpp | 20 ++++++++- python/bindings_so3.cpp | 25 ++++++++++- test/python/CMakeLists.txt | 5 +++ test/python/pytest_manif.py | 3 +- test/python/pytest_se2.py | 76 +++++++++++++++++++++++++++++++++ test/python/pytest_se3.py | 68 ++++++++++++++++++++++++++++++ test/python/pytest_se_2_3.py | 82 ++++++++++++++++++++++++++++++++++++ test/python/pytest_so2.py | 40 ++++++++++++++++++ test/python/pytest_so3.py | 70 ++++++++++++++++++++++++++++++ 12 files changed, 470 insertions(+), 11 deletions(-) create mode 100644 test/python/pytest_se2.py create mode 100644 test/python/pytest_se3.py create mode 100644 test/python/pytest_se_2_3.py create mode 100644 test/python/pytest_so2.py create mode 100644 test/python/pytest_so3.py diff --git a/python/bindings_se2.cpp b/python/bindings_se2.cpp index b421bf1a..dfc5d683 100644 --- a/python/bindings_se2.cpp +++ b/python/bindings_se2.cpp @@ -2,6 +2,7 @@ #include #include #include +#include #include "manif/SE2.h" @@ -11,12 +12,38 @@ void wrap_SE2(pybind11::module &m) { + using Scalar = manif::SE2d::Scalar; + using Translation = manif::SE2d::Translation; + pybind11::class_, std::unique_ptr, py::nodelete>> SE2_base(m, "SE2Base"); pybind11::class_, std::unique_ptr, py::nodelete>> SE2_tan_base(m, "SE2TangentBase"); pybind11::class_> SE2(m, "SE2"); - pybind11::class_> SE2_tan(m, "SE2Tangent"); - wrap_lie_group_base>(SE2); + + SE2.def(py::init()); + SE2.def(py::init()); + SE2.def(py::init&>()); + SE2.def(py::init&>()); + SE2.def(py::init&>()); + + SE2.def("transform", &manif::SE2d::transform); + // SE2.def("isometry", &manif::SE2d::isometry); + SE2.def("rotation", &manif::SE2d::rotation); + SE2.def("translation", &manif::SE2d::translation); + SE2.def("real", &manif::SE2d::real); + SE2.def("imag", &manif::SE2d::imag); + SE2.def("angle", &manif::SE2d::angle); + SE2.def("x", &manif::SE2d::x); + SE2.def("y", &manif::SE2d::y); + SE2.def("normalize", &manif::SE2d::normalize); + + pybind11::class_> SE2_tan(m, "SE2Tangent"); wrap_tangent_base>(SE2_tan); + + SE2_tan.def(py::init()); + + SE2_tan.def("x", &manif::SE2Tangentd::x); + SE2_tan.def("y", &manif::SE2Tangentd::y); + SE2_tan.def("angle", &manif::SE2Tangentd::angle); } diff --git a/python/bindings_se3.cpp b/python/bindings_se3.cpp index 36a469b6..08f9556c 100644 --- a/python/bindings_se3.cpp +++ b/python/bindings_se3.cpp @@ -11,12 +11,35 @@ void wrap_SE3(pybind11::module &m) { + using Scalar = manif::SE3d::Scalar; + using Quaternion = Eigen::Quaternion; + pybind11::class_, std::unique_ptr, py::nodelete>> SE3_base(m, "SE3Base"); pybind11::class_, std::unique_ptr, py::nodelete>> SE3_tan_base(m, "SE3TangentBase"); pybind11::class_> SE3(m, "SE3"); - pybind11::class_> SE3_tan(m, "SE3Tangent"); - wrap_lie_group_base>(SE3); + + SE3.def(py::init()); + // SE3.def(py::init()); + // SE3.def(py::init&>()); + // SE3.def(py::init&>()); + // SE3.def(py::init&>()); + + SE3.def("transform", &manif::SE3d::transform); + // SE3.def("isometry", &manif::SE3d::isometry); + SE3.def("rotation", &manif::SE3d::rotation); + // SE3.def("quat", &manif::SE3d::quat); + // SE3.def("translation", &manif::SE3d::translation); + SE3.def("x", &manif::SE3d::x); + SE3.def("y", &manif::SE3d::y); + SE3.def("z", &manif::SE3d::z); + SE3.def("normalize", &manif::SE3d::normalize); + + pybind11::class_> SE3_tan(m, "SE3Tangent"); wrap_tangent_base>(SE3_tan); + + // SE3_tan.def("v", &manif::SE3Tangentd::v); + // SE3_tan.def("w", &manif::SE3Tangentd::w); } diff --git a/python/bindings_se_2_3.cpp b/python/bindings_se_2_3.cpp index 72fe147a..8598766c 100644 --- a/python/bindings_se_2_3.cpp +++ b/python/bindings_se_2_3.cpp @@ -11,12 +11,42 @@ void wrap_SE_2_3(pybind11::module &m) { + using Scalar = manif::SE_2_3d::Scalar; + using Translation = manif::SE_2_3d::Translation; + using Quaternion = Eigen::Quaternion; + using LinearVelocity = manif::SE_2_3d::LinearVelocity; + pybind11::class_, std::unique_ptr, py::nodelete>> SE_2_3_base(m, "SE_2_3Base"); pybind11::class_, std::unique_ptr, py::nodelete>> SE_2_3_tan_base(m, "SE_2_3TangentBase"); pybind11::class_> SE_2_3(m, "SE_2_3"); - pybind11::class_> SE_2_3_tan(m, "SE_2_3Tangent"); - wrap_lie_group_base>(SE_2_3); + + // SE_2_3.def(py::init()); + // SE_2_3.def(py::init&, const LinearVelocity&>()); + // SE_2_3.def(py::init&, const LinearVelocity&>()); + SE_2_3.def(py::init()); + // SE_2_3.def(py::init&, const LinearVelocity&>()); + + // SE_2_3.def("isometry", &manif::SE_2_3d::isometry); + SE_2_3.def("rotation", &manif::SE_2_3d::rotation); + SE_2_3.def("quat", &manif::SE_2_3d::quat); + SE_2_3.def("translation", &manif::SE_2_3d::translation); + SE_2_3.def("x", &manif::SE_2_3d::x); + SE_2_3.def("y", &manif::SE_2_3d::y); + SE_2_3.def("z", &manif::SE_2_3d::z); + SE_2_3.def("linearVelocity", &manif::SE_2_3d::linearVelocity); + SE_2_3.def("vx", &manif::SE_2_3d::vx); + SE_2_3.def("vy", &manif::SE_2_3d::vy); + SE_2_3.def("vz", &manif::SE_2_3d::vz); + SE_2_3.def("normalize", &manif::SE_2_3d::normalize); + + pybind11::class_> SE_2_3_tan(m, "SE_2_3Tangent"); wrap_tangent_base>(SE_2_3_tan); + + // SE_2_3_tan.def("v", &manif::SE3Tangentd::v); + // SE_2_3_tan.def("w", &manif::SE3Tangentd::w); + // SE_2_3_tan.def("a", &manif::SE3Tangentd::a); } diff --git a/python/bindings_so2.cpp b/python/bindings_so2.cpp index 4437db9b..eb24c326 100644 --- a/python/bindings_so2.cpp +++ b/python/bindings_so2.cpp @@ -11,12 +11,28 @@ void wrap_SO2(pybind11::module &m) { + using Scalar = manif::SO2d::Scalar; + pybind11::class_, std::unique_ptr, py::nodelete>> SO2_base(m, "SO2Base"); pybind11::class_, std::unique_ptr, py::nodelete>> SO2_tan_base(m, "SO2TangentBase"); pybind11::class_> SO2(m, "SO2"); - pybind11::class_> SO2_tan(m, "SO2Tangent"); - wrap_lie_group_base>(SO2); + + SO2.def(py::init()); + SO2.def(py::init()); + + SO2.def("transform", &manif::SO2d::transform); + SO2.def("rotation", &manif::SO2d::rotation); + SO2.def("real", &manif::SO2d::real); + SO2.def("imag", &manif::SO2d::imag); + SO2.def("angle", &manif::SO2d::angle); + SO2.def("normalize", &manif::SO2d::normalize); + + pybind11::class_> SO2_tan(m, "SO2Tangent"); wrap_tangent_base>(SO2_tan); + + SO2_tan.def(py::init()); + + SO2_tan.def("angle", &manif::SO2Tangentd::angle); } diff --git a/python/bindings_so3.cpp b/python/bindings_so3.cpp index 884e07ec..183ebc91 100644 --- a/python/bindings_so3.cpp +++ b/python/bindings_so3.cpp @@ -11,12 +11,33 @@ void wrap_SO3(pybind11::module &m) { + using Scalar = manif::SO3d::Scalar; + using Quaternion = Eigen::Quaternion; + pybind11::class_, std::unique_ptr, py::nodelete>> SO3_base(m, "SO3Base"); pybind11::class_, std::unique_ptr, py::nodelete>> SO3_tan_base(m, "SO3TangentBase"); pybind11::class_> SO3(m, "SO3"); - pybind11::class_> SO3_tan(m, "SO3Tangent"); - wrap_lie_group_base>(SO3); + + SO3.def(py::init()); + SO3.def(py::init()); + SO3.def(py::init()); + SO3.def(py::init&>()); + + SO3.def("transform", &manif::SO3d::transform); + SO3.def("rotation", &manif::SO3d::rotation); + SO3.def("x", &manif::SO3d::x); + SO3.def("y", &manif::SO3d::y); + SO3.def("z", &manif::SO3d::z); + SO3.def("w", &manif::SO3d::w); + SO3.def("quat", &manif::SO3d::quat); + SO3.def("normalize", &manif::SO3d::normalize); + + pybind11::class_> SO3_tan(m, "SO3Tangent"); wrap_tangent_base>(SO3_tan); + + SO3_tan.def("x", &manif::SO3Tangentd::x); + SO3_tan.def("y", &manif::SO3Tangentd::y); + SO3_tan.def("z", &manif::SO3Tangentd::z); } diff --git a/test/python/CMakeLists.txt b/test/python/CMakeLists.txt index db4403b6..1dd3c628 100644 --- a/test/python/CMakeLists.txt +++ b/test/python/CMakeLists.txt @@ -11,3 +11,8 @@ function(manif_add_pytest target) endfunction() manif_add_pytest(pytest_manif) +manif_add_pytest(pytest_so2) +manif_add_pytest(pytest_se2) +manif_add_pytest(pytest_so3) +manif_add_pytest(pytest_se3) +manif_add_pytest(pytest_se_2_3) diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index dd08977c..e15579ca 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -212,7 +212,8 @@ def test_InverseJac(self, LieGroup, Tangent): w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) # https://pybind11.readthedocs.io/en/stable/advanced/cast/eigen.html#storage-orders - J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF), order='F') + # J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF), order='F') + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) state_out = state.inverse(J_sout_s) diff --git a/test/python/pytest_se2.py b/test/python/pytest_se2.py new file mode 100644 index 00000000..ced73cbd --- /dev/null +++ b/test/python/pytest_se2.py @@ -0,0 +1,76 @@ +import numpy as np +import pytest + +from PyManif import SE2, SE2Tangent + + +def test_constructor(): + state = SE2(4, 2, 1, 0) + assert 4 == state.x() + assert 2 == state.y() + assert 1 == state.real() + assert 0 == state.imag() + assert 0 == state.angle() + + state = SE2(2, 4, 0.17) + assert 2 == state.x() + assert 4 == state.y() + assert 0.17 == state.angle() + + state = SE2(4, 2, 1+0j) + assert 4 == state.x() + assert 2 == state.y() + assert 0 == state.angle() + + state = SE2(np.array([2, 4]), 1+0j) + assert 2 == state.x() + assert 4 == state.y() + assert 0 == state.angle() + + delta = SE2Tangent(4, 2, 0.17) + assert 4 == delta.x() + assert 2 == delta.y() + assert 0.17 == delta.angle() + +def test_accessors(): + state = SE2.Identity() + + assert 0 == state.x() + assert 0 == state.y() + assert 1 == state.real() + assert 0 == state.imag() + assert 0 == state.angle() + + delta = SE2Tangent.Zero() + + assert 0 == delta.x() + assert 0 == delta.y() + assert 0 == delta.angle() + +def test_transform(): + state = SE2.Identity() + transform = state.transform() + + assert (3, 3) == transform.shape + assert (np.identity(3) == transform).all() + +# def test_isometry(): +# state = SE2.Identity() +# isometry = state.isometry() +# +# assert (3, 3) == isometry.shape +# assert (np.identity(3) == isometry).all() + +def test_rotation(): + state = SE2.Identity() + rotation = state.rotation() + + assert (2, 2) == rotation.shape + assert (np.identity(2) == rotation).all() + +def test_translation(): + state = SE2.Identity() + translation = state.translation() + + assert (2,) == translation.shape + assert (np.zeros(2,) == translation).all() diff --git a/test/python/pytest_se3.py b/test/python/pytest_se3.py new file mode 100644 index 00000000..6b43c414 --- /dev/null +++ b/test/python/pytest_se3.py @@ -0,0 +1,68 @@ +import numpy as np +import pytest + +from PyManif import SE3, SE3Tangent + + +def test_constructor(): + state = SE3(0,0,0,0,0,0) + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + # assert 1 == state.quat() + + # state = SE3(np.array([1,2,3]), Quaternion(1,0,0,0)) + # assert 0 == state.x() + # assert 0 == state.y() + # assert 0 == state.z() + + # state = SE3(np.array([1,2,3]), AngleAxis(0, UnitX())) + # assert 0 == state.x() + # assert 0 == state.y() + # assert 0 == state.z() + + # delta = SE3Tangent(1,2,3,4,5,6) + # assert 1 == delta.x() + # assert 2 == delta.y() + # assert 3 == delta.z() + +def test_accessors(): + state = SE3.Identity() + + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + + delta = SE3Tangent.Zero() + + # assert 0 == delta.x() + # assert 0 == delta.y() + # assert 0 == delta.z() + +def test_transform(): + state = SE3.Identity() + transform = state.transform() + + assert (4, 4) == transform.shape + assert (np.identity(4) == transform).all() + +def test_rotation(): + state = SE3.Identity() + rotation = state.rotation() + + assert (3, 3) == rotation.shape + assert (np.identity(3) == rotation).all() + +# def test_quaternion(): +# state = SO3.Identity() +# quaternion = state.quaternion() +# +# assert (4,) == quaternion.shape +# assert (np.zeros(4,) == quaternion).all() + +# def test_translation(): +# state = SE3.Identity() +# translation = state.translation() +# +# assert (3,) == translation.shape +# assert (np.zeros(3,) == translation).all() diff --git a/test/python/pytest_se_2_3.py b/test/python/pytest_se_2_3.py new file mode 100644 index 00000000..7fa8fe9d --- /dev/null +++ b/test/python/pytest_se_2_3.py @@ -0,0 +1,82 @@ +import numpy as np +import pytest + +from PyManif import SE_2_3, SE_2_3Tangent + + +def test_constructor(): + state = SE_2_3(0,0,0, 0,0,0, 0,0,0) + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + # assert 0 == state.quat() + assert 0 == state.vx() + assert 0 == state.vy() + assert 0 == state.vz() + + # state = SE_2_3(np.array([1,2,3]), Quaternion(1,0,0,0), np.array([4,5,6])) + # assert 1 == state.x() + # assert 2 == state.y() + # assert 3 == state.z() + # assert 1 == state.quat() + # assert 4 == state.vx() + # assert 5 == state.vy() + # assert 6 == state.vz() + + # state = SE_2_3(np.array([1,2,3]), AngleAxis(0, UnitX()), np.array([4,5,6])) + # assert 1 == state.x() + # assert 2 == state.y() + # assert 3 == state.z() + # assert 1 == state.w() + # assert 4 == state.vx() + # assert 5 == state.vy() + # assert 6 == state.vz() + + # delta = SE_2_3Tangent(1,2,3) + # assert 1 == delta.x() + # assert 2 == delta.y() + # assert 3 == delta.z() + +def test_accessors(): + state = SE_2_3.Identity() + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + # assert 0 == state.quat() + assert 0 == state.vx() + assert 0 == state.vy() + assert 0 == state.vz() + + delta = SE_2_3Tangent.Zero() + + # assert 0 == delta.x() + # assert 0 == delta.y() + # assert 0 == delta.z() + +# def test_isometry(): +# state = SE_2_3.Identity() +# isometry = state.isometry() +# +# assert (4, 4) == isometry.shape +# assert (np.identity(4) == isometry).all() + +def test_rotation(): + state = SE_2_3.Identity() + rotation = state.rotation() + + assert (3, 3) == rotation.shape + assert (np.identity(3) == rotation).all() + +# def test_quaternion(): +# state = SO3.Identity() +# quaternion = state.quaternion() +# +# assert (4,) == quaternion.shape +# assert (np.zeros(4,) == quaternion).all() + +def test_translation(): + state = SE_2_3.Identity() + translation = state.translation() + + assert (3,) == translation.shape + assert (np.zeros(3,) == translation).all() diff --git a/test/python/pytest_so2.py b/test/python/pytest_so2.py new file mode 100644 index 00000000..a234c5c4 --- /dev/null +++ b/test/python/pytest_so2.py @@ -0,0 +1,40 @@ +import numpy as np +import pytest + +from PyManif import SO2, SO2Tangent + + +def test_constructor(): + state = SO2(0.17) + assert 0.17 == state.angle() + + state = SO2(1, 0) + assert 0 == state.angle() + + delta = SO2Tangent(0.17) + assert 0.17 == delta.angle() + +def test_accessors(): + state = SO2.Identity() + + assert 1 == state.real() + assert 0 == state.imag() + assert 0 == state.angle() + + delta = SO2Tangent.Zero() + + assert 0 == delta.angle() + +def test_transform(): + state = SO2.Identity() + transform = state.transform() + + assert (3, 3) == transform.shape + assert (np.identity(3) == transform).all() + +def test_rotation(): + state = SO2.Identity() + rotation = state.rotation() + + assert (2, 2) == rotation.shape + assert (np.identity(2) == rotation).all() diff --git a/test/python/pytest_so3.py b/test/python/pytest_so3.py new file mode 100644 index 00000000..350337b1 --- /dev/null +++ b/test/python/pytest_so3.py @@ -0,0 +1,70 @@ +import numpy as np +import pytest + +from PyManif import SO3, SO3Tangent + + +def test_constructor(): + state = SO3(0,0,0,1) + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + assert 1 == state.w() + + state = SO3(0,0,0) + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + assert 1 == state.w() + + # state = SO3(Quaternion(1,0,0,0)) + # assert 0 == state.x() + # assert 0 == state.y() + # assert 0 == state.z() + # assert 1 == state.w() + + # state = SO3(AngleAxis(0, UnitX())) + # assert 0 == state.x() + # assert 0 == state.y() + # assert 0 == state.z() + # assert 1 == state.w() + + # delta = SO3Tangent(1,2,3) + # assert 1 == delta.x() + # assert 2 == delta.y() + # assert 3 == delta.z() + +def test_accessors(): + state = SO3.Identity() + + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + assert 1 == state.w() + + delta = SO3Tangent.Zero() + + assert 0 == delta.x() + assert 0 == delta.y() + assert 0 == delta.z() + +def test_transform(): + state = SO3.Identity() + transform = state.transform() + + assert (4, 4) == transform.shape + assert (np.identity(4) == transform).all() + +def test_rotation(): + state = SO3.Identity() + rotation = state.rotation() + + assert (3, 3) == rotation.shape + assert (np.identity(3) == rotation).all() + +# def test_quaternion(): +# state = SO3.Identity() +# quaternion = state.quaternion() +# +# assert (4,) == quaternion.shape +# assert (np.zeros(4,) == quaternion).all() From fcf73e306d664a4b139fd6b8e74afbacad46bb41 Mon Sep 17 00:00:00 2001 From: artivis Date: Wed, 16 Dec 2020 19:48:04 -0500 Subject: [PATCH 14/67] fix Jac*Tan --- python/bindings_tangent_base.h | 66 +++++++++++++++++++++++++++++++--- test/python/pytest_manif.py | 17 ++------- 2 files changed, 64 insertions(+), 19 deletions(-) diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index d8ba85e8..361da7ab 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -120,15 +120,71 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def(-py::self) .def(py::self + LieGroup()) .def(py::self + py::self) - .def(py::self += py::self) + // .def(py::self += py::self) .def(py::self - py::self) - .def(py::self -= py::self) - .def(py::self * double()) - .def(Jacobian() * py::self) - .def(py::self / double()) + // .def(py::self -= py::self) + .def(py::self * Scalar()) + .def(Scalar() * py::self) + .def(py::self / Scalar()) .def(py::self == py::self) ; + // Jacobian() @ py::self + py_class.def("__rmatmul__", [](const _Tangent& t, py::array_t lhs) { + + py::buffer_info lhs_buf = lhs.request(); + + if (lhs_buf.ndim != 2) + throw std::runtime_error("Number of dimensions must be 2"); + + if (lhs_buf.size != _Tangent::DoF * _Tangent::DoF) + throw std::runtime_error("Input shapes must match"); + + /* No pointer is passed, so NumPy will allocate the buffer */ + auto result = py::array_t(_Tangent::RepSize); + + Eigen::Map<_Tangent> result_map(static_cast(result.request().ptr)); + + result_map = Eigen::Map(static_cast(lhs_buf.ptr)) * t; + + return _Tangent(result_map); + + // @todo(artivis) fix error: use of deleted function ‘Eigen::Map::Map(const Eigen::Map lhs) { + + py::buffer_info lhs_buf = lhs.request(); + + if (lhs_buf.ndim != 2) + throw std::runtime_error("Number of dimensions must be 2"); + + if (lhs_buf.size != _Tangent::DoF * _Tangent::DoF) + throw std::runtime_error("Input shapes must match"); + + /* No pointer is passed, so NumPy will allocate the buffer */ + auto result = py::array_t(_Tangent::RepSize); + + Eigen::Map<_Tangent> result_map(static_cast(result.request().ptr)); + + result_map = Eigen::Map(static_cast(lhs_buf.ptr)) * t; + + return _Tangent(result_map); + + // @todo(artivis) fix error: use of deleted function ‘Eigen::Map::Map(const Eigen::Map Date: Thu, 17 Dec 2020 12:47:09 -0500 Subject: [PATCH 15/67] add more test and rename py pkg --- python/CMakeLists.txt | 14 +- python/bindings_lie_group_base.h | 8 +- python/bindings_manif.cpp | 2 +- test/python/pytest_manif.py | 358 ++++++++++++++++++++++++++++++- test/python/pytest_se2.py | 2 +- test/python/pytest_se3.py | 2 +- test/python/pytest_se_2_3.py | 2 +- test/python/pytest_so2.py | 2 +- test/python/pytest_so3.py | 2 +- 9 files changed, 375 insertions(+), 17 deletions(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 8f02a010..d85e66b7 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,5 +1,5 @@ set(PYBIND11_CPP_STANDARD -std=c++11) -pybind11_add_module(PyManif +pybind11_add_module(manifpy bindings_rn.cpp bindings_so2.cpp bindings_so3.cpp @@ -8,16 +8,16 @@ pybind11_add_module(PyManif bindings_se_2_3.cpp bindings_manif.cpp ) -target_link_libraries(PyManif PRIVATE ${PROJECT_NAME}) +target_link_libraries(manifpy PRIVATE ${PROJECT_NAME}) # Eigen and numpy have different default storage order. # See e.g. https://pybind11.readthedocs.io/en/stable/advanced/cast/eigen.html#storage-orders -target_compile_definitions(PyManif PRIVATE EIGEN_DEFAULT_TO_ROW_MAJOR) +target_compile_definitions(manifpy PRIVATE EIGEN_DEFAULT_TO_ROW_MAJOR) # Set required C++11 flag if(CMAKE_VERSION VERSION_LESS "3.1") - set_target_properties(PyManif PROPERTIES COMPILE_FLAGS "-std=c++11") + set_target_properties(manifpy PROPERTIES COMPILE_FLAGS "-std=c++11") else() - set_property(TARGET PyManif PROPERTY CXX_STANDARD 11) - set_property(TARGET PyManif PROPERTY CXX_STANDARD_REQUIRED ON) - set_property(TARGET PyManif PROPERTY CXX_EXTENSIONS OFF) + set_property(TARGET manifpy PROPERTY CXX_STANDARD 11) + set_property(TARGET manifpy PROPERTY CXX_STANDARD_REQUIRED ON) + set_property(TARGET manifpy PROPERTY CXX_EXTENSIONS OFF) endif() diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h index e93f92e6..2225e45f 100644 --- a/python/bindings_lie_group_base.h +++ b/python/bindings_lie_group_base.h @@ -52,17 +52,21 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { ); py_class.def( - "between", &_LieGroup::template between<_LieGroup>, + "between", + &_LieGroup::template between<_LieGroup>, py::arg("other"), py::arg_v("J_mc_ma", OptJacobianRef(), "None"), py::arg_v("J_mc_mb", OptJacobianRef(), "None") ); - // py_class.def("act", &_LieGroup::template act, + // py_class.def( + // "act", + // &_LieGroup::act, // py::arg("v"), // py::arg_v("J_vout_m", tl::optional>>(), "None"), // py::arg_v("J_vout_v", tl::optional>>(), "None") // ); + py_class.def("act", [](const _LieGroup& self, const Vector& v) { return self.act(v); }); diff --git a/python/bindings_manif.cpp b/python/bindings_manif.cpp index 34694ce7..bb092036 100644 --- a/python/bindings_manif.cpp +++ b/python/bindings_manif.cpp @@ -10,7 +10,7 @@ void wrap_SE3(pybind11::module &m); void wrap_SE_2_3(pybind11::module &m); -PYBIND11_MODULE(PyManif, m) { +PYBIND11_MODULE(manifpy, m) { m.doc() = "Python bindings for the manif library."; wrap_Rn(m); diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index 23d403da..edd42a53 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from PyManif import \ +from manifpy import \ R1, R1Tangent, \ R2, R2Tangent, \ R3, R3Tangent, \ @@ -216,4 +216,358 @@ def test_InverseJac(self, LieGroup, Tangent): state_pert = (state+w).inverse() state_lin = state_out.rplus(J_sout_s * w) - assert state_pert == state_lin + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_LogJac(self, LieGroup, Tangent): + state = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.log(J_sout_s) + + state_pert = (state+w).log() + state_lin = state_out + (J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_ExpJac(self, LieGroup, Tangent): + delta = Tangent.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = delta.exp(J_sout_s) + + state_pert = (delta+w).exp() + state_lin = state_out + (J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + delta.setZero() + state_out = delta.exp(J_sout_s) + + state_pert = (delta+w).exp() + state_lin = state_out + (J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_ComposeJac(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_so = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.compose(state_other, J_sout_s, J_sout_so) + + state_pert = (state+w).compose(state_other) + state_lin = state_out + J_sout_s*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.compose(state_other+w) + state_lin = state_out + J_sout_so*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + # + + state_out = state.compose(state_other, J_mc_ma = J_sout_s, J_mc_mb = J_sout_so) + + state_pert = (state+w).compose(state_other) + state_lin = state_out + J_sout_s*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.compose(state_other+w) + state_lin = state_out + J_sout_so*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + # + + state_out = state.compose(state_other, J_mc_mb = J_sout_so, J_mc_ma = J_sout_s) + + state_pert = (state+w).compose(state_other) + state_lin = state_out + J_sout_s*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.compose(state_other+w) + state_lin = state_out + J_sout_so*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + # + + state_out = state.compose(state_other, J_mc_ma = J_sout_s) + + state_pert = (state+w).compose(state_other) + state_lin = state_out + J_sout_s*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + # + + state_out = state.compose(state_other, J_mc_mb = J_sout_so) + + state_pert = state.compose(state_other+w) + state_lin = state_out + J_sout_so*w + + assert state_pert.isApprox(state_lin, eps=1e-7) + + + def test_BetweenJac(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_so = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.between(state_other, J_sout_s, J_sout_so) + + state_pert = (state + w).between(state_other) + state_lin = state_out + (J_sout_s * w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.between(state_other + w) + state_lin = state_out + (J_sout_so * w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_RplusJac(self, LieGroup, Tangent): + state = LieGroup.Random() + delta = Tangent.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_t = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.rplus(delta, J_sout_s, J_sout_t) + + state_pert = (state+w).rplus(delta) + state_lin = state_out.rplus(J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.rplus(delta+w) + state_lin = state_out.rplus(J_sout_t*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_LplusJac(self, LieGroup, Tangent): + state = LieGroup.Random() + delta = Tangent.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_t = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.lplus(delta, J_sout_s, J_sout_t) + + state_pert = (state+w).lplus(delta) + state_lin = state_out.rplus(J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.lplus(delta+w) + state_lin = state_out.rplus(J_sout_t*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_PlusJac(self, LieGroup, Tangent): + state = LieGroup.Random() + delta = Tangent.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_t = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.plus(delta, J_sout_s, J_sout_t) + + state_pert = (state+w).plus(delta) + state_lin = state_out.plus(J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.plus(delta+w) + state_lin = state_out.plus(J_sout_t*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_RminusJac(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_so = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.rminus(state_other, J_sout_s, J_sout_so) + + state_pert = (state+w).rminus(state_other) + state_lin = state_out.plus(J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.rminus(state_other+w) + state_lin = state_out.plus(J_sout_so*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_LminusJac(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_so = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.lminus(state_other, J_sout_s, J_sout_so) + + state_pert = (state+w).lminus(state_other) + state_lin = state_out.plus(J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.lminus(state_other+w) + state_lin = state_out.plus(J_sout_so*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_MinusJac(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + J_sout_s = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_sout_so = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + state_out = state.minus(state_other, J_sout_s, J_sout_so) + + state_pert = (state+w).minus(state_other) + state_lin = state_out.plus(J_sout_s*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + state_pert = state.minus(state_other+w) + state_lin = state_out.plus(J_sout_so*w) + + assert state_pert.isApprox(state_lin, eps=1e-7) + + def test_Adj(self, LieGroup, Tangent): + state = LieGroup.Random() + state_other = LieGroup.Random() + delta = Tangent.Random() + + Adja = state.adj() + Adjb = state_other.adj() + Adjc = state.compose(state_other).adj() + + # assert ((Adja @ Adjb) == Adjc).all() + + assert np.allclose(Adja @ Adjb, Adjc) + + assert state + delta == state.adj() * delta + state + + if LieGroup in (SO2, R1): + pytest.skip("Adj is a scalar (Dim 1), numpy doesn't support inversion") + + assert np.allclose(np.linalg.inv(state.adj()), state.inverse().adj()) + + @pytest.mark.skip(reason="rjac/ljac not implemented yet") + def test_Adj(self, LieGroup, Tangent): + state = LieGroup.Random() + + Adj = state.adj(); + tan = state.log(); + + Jr = tan.rjac(); + Jl = tan.ljac(); + + assert Jl == Adj @ Jr + assert Adj == Jl @ np.linalg.inv(Jr) + assert Jl == (-tan).rjac() + + state.setIdentity(); + + Adj = state.adj(); + tan = state.log(); + + Jr = tan.rjac(); + Jl = tan.ljac(); + + assert Jl == Adj @ Jr + assert Adj == Jl @ np.linalg.inv(Jr) + assert Jl == (-tan).rjac() + + # def test_JrJrinvJlJlinv(self, LieGroup, Tangent): + # state = LieGroup.Random() + # + # tan = state.log(); + # Jr = tan.rjac(); + # Jl = tan.ljac(); + # + # Jrinv = tan.rjacinv(); + # Jlinv = tan.ljacinv(); + # + # I = np.identity(LieGroup.DoF) + # + # assert I == Jr @ Jrinv + # assert I == Jl @ Jlinv + + # def test_ActJac(self, LieGroup, Tangent): + # state = LieGroup.Identity() + # point = np.random.rand(Tangent.Dim) + # w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + # + # J_pout_s = np.zeros((LieGroup.Dim, LieGroup.DoF)) + # J_pout_p = np.zeros((LieGroup.Dim, LieGroup.Dim)) + # + # pointout = state.act(point, J_pout_s, J_pout_p) + # + # w_point = np.random.rand(Tangent.Dim) * 1e-4 + # + # point_pert = (state + w).act(point) + # point_lin = pointout + (J_pout_s * w.coeffs()) + # + # assert point_pert == point_lin + # + # point_pert = state.act(point + w_point) + # point_lin = pointout + J_pout_p * w_point + # + # assert point_pert == point_lin + + def test_TanPlusTanJac(self, LieGroup, Tangent): + delta = Tangent.Random() + delta_other = Tangent.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + + J_tout_t0 = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_tout_t1 = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + delta_out = delta.plus(delta_other, J_tout_t0, J_tout_t1); + + delta_pert = (delta+w).plus(delta_other); + delta_lin = delta_out.plus(J_tout_t0*w); + + assert delta_pert == delta_lin + + delta_pert = delta.plus(delta_other+w); + delta_lin = delta_out.plus(J_tout_t1*w); + + assert delta_pert == delta_lin + + def test_TanMinusTanJac(self, LieGroup, Tangent): + delta = Tangent.Random() + delta_other = Tangent.Random() + w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + + J_tout_t0 = np.zeros((LieGroup.DoF, LieGroup.DoF)) + J_tout_t1 = np.zeros((LieGroup.DoF, LieGroup.DoF)) + + delta_out = delta.minus(delta_other, J_tout_t0, J_tout_t1); + + delta_pert = (delta+w).minus(delta_other); + delta_lin = delta_out.plus(J_tout_t0*w); + + assert delta_pert == delta_lin + + delta_pert = delta.minus(delta_other+w); + delta_lin = delta_out.plus(J_tout_t1*w); + + assert delta_pert == delta_lin diff --git a/test/python/pytest_se2.py b/test/python/pytest_se2.py index ced73cbd..f3904771 100644 --- a/test/python/pytest_se2.py +++ b/test/python/pytest_se2.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from PyManif import SE2, SE2Tangent +from manifpy import SE2, SE2Tangent def test_constructor(): diff --git a/test/python/pytest_se3.py b/test/python/pytest_se3.py index 6b43c414..b8a0ba28 100644 --- a/test/python/pytest_se3.py +++ b/test/python/pytest_se3.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from PyManif import SE3, SE3Tangent +from manifpy import SE3, SE3Tangent def test_constructor(): diff --git a/test/python/pytest_se_2_3.py b/test/python/pytest_se_2_3.py index 7fa8fe9d..a222c1bf 100644 --- a/test/python/pytest_se_2_3.py +++ b/test/python/pytest_se_2_3.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from PyManif import SE_2_3, SE_2_3Tangent +from manifpy import SE_2_3, SE_2_3Tangent def test_constructor(): diff --git a/test/python/pytest_so2.py b/test/python/pytest_so2.py index a234c5c4..aeeac28c 100644 --- a/test/python/pytest_so2.py +++ b/test/python/pytest_so2.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from PyManif import SO2, SO2Tangent +from manifpy import SO2, SO2Tangent def test_constructor(): diff --git a/test/python/pytest_so3.py b/test/python/pytest_so3.py index 350337b1..a1ecdc69 100644 --- a/test/python/pytest_so3.py +++ b/test/python/pytest_so3.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from PyManif import SO3, SO3Tangent +from manifpy import SO3, SO3Tangent def test_constructor(): From 882ee05dd1b826fa0e8ddbd30383690efb89c1d2 Mon Sep 17 00:00:00 2001 From: artivis Date: Thu, 17 Dec 2020 13:46:56 -0500 Subject: [PATCH 16/67] some more tests --- python/bindings_tangent_base.h | 26 ++-------- test/python/pytest_manif.py | 89 +++++++++++++++++++--------------- 2 files changed, 53 insertions(+), 62 deletions(-) diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index 361da7ab..b06cf0b2 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -140,18 +140,9 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { if (lhs_buf.size != _Tangent::DoF * _Tangent::DoF) throw std::runtime_error("Input shapes must match"); - /* No pointer is passed, so NumPy will allocate the buffer */ - auto result = py::array_t(_Tangent::RepSize); + _Tangent result = Eigen::Map(static_cast(lhs_buf.ptr)) * t; - Eigen::Map<_Tangent> result_map(static_cast(result.request().ptr)); - - result_map = Eigen::Map(static_cast(lhs_buf.ptr)) * t; - - return _Tangent(result_map); - - // @todo(artivis) fix error: use of deleted function ‘Eigen::Map::Map(const Eigen::Map& py_class) { if (lhs_buf.size != _Tangent::DoF * _Tangent::DoF) throw std::runtime_error("Input shapes must match"); - /* No pointer is passed, so NumPy will allocate the buffer */ - auto result = py::array_t(_Tangent::RepSize); - - Eigen::Map<_Tangent> result_map(static_cast(result.request().ptr)); - - result_map = Eigen::Map(static_cast(lhs_buf.ptr)) * t; - - return _Tangent(result_map); + _Tangent result = Eigen::Map(static_cast(lhs_buf.ptr)) * t; - // @todo(artivis) fix error: use of deleted function ‘Eigen::Map::Map(const Eigen::Map Date: Thu, 17 Dec 2020 14:31:19 -0500 Subject: [PATCH 17/67] add rjac/ljac --- python/bindings_lie_group_base.h | 10 ++++++---- python/bindings_tangent_base.h | 4 ++-- test/python/pytest_manif.py | 17 ++++++++++------- 3 files changed, 18 insertions(+), 13 deletions(-) diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h index 2225e45f..1b4dd130 100644 --- a/python/bindings_lie_group_base.h +++ b/python/bindings_lie_group_base.h @@ -45,7 +45,8 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py_class.def("adj", &_LieGroup::adj); py_class.def( - "compose", &_LieGroup::template compose<_LieGroup>, + "compose", + &_LieGroup::template compose<_LieGroup>, py::arg("other"), py::arg_v("J_mc_ma", OptJacobianRef(), "None"), py::arg_v("J_mc_mb", OptJacobianRef(), "None") @@ -67,9 +68,10 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { // py::arg_v("J_vout_v", tl::optional>>(), "None") // ); - py_class.def("act", [](const _LieGroup& self, const Vector& v) { - return self.act(v); - }); + py_class.def( + "act", + [](const _LieGroup& self, const Vector& v) { return self.act(v);} + ); py_class.def( "isApprox", diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index b06cf0b2..4182d71d 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -85,8 +85,8 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py::arg_v("J_mout_tb", OptJacobianRef(), "None") ); - // py_class.def("rjac", &_Tangent::rjac); - // py_class.def("ljac", &_Tangent::ljac); + py_class.def("rjac", &_Tangent::rjac); + py_class.def("ljac", &_Tangent::ljac); // py_class.def("rjacinv", &_Tangent::rjacinv); // py_class.def("ljacinv", &_Tangent::ljacinv); diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index c06bf98c..bc99d737 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -476,8 +476,11 @@ def test_Adj(self, LieGroup, Tangent): assert np.allclose(np.linalg.inv(state.adj()), state.inverse().adj()) - @pytest.mark.skip(reason="rjac/ljac not implemented yet") def test_Adj(self, LieGroup, Tangent): + + if LieGroup in (SO2, R1): + pytest.skip("Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support matmul") + state = LieGroup.Random() Adj = state.adj(); @@ -486,9 +489,9 @@ def test_Adj(self, LieGroup, Tangent): Jr = tan.rjac(); Jl = tan.ljac(); - assert Jl == Adj @ Jr - assert Adj == Jl @ np.linalg.inv(Jr) - assert Jl == (-tan).rjac() + assert np.allclose(Jl, Adj @ Jr) + assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) + assert np.allclose(Jl, (-tan).rjac()) state.setIdentity(); @@ -498,9 +501,9 @@ def test_Adj(self, LieGroup, Tangent): Jr = tan.rjac(); Jl = tan.ljac(); - assert Jl == Adj @ Jr - assert Adj == Jl @ np.linalg.inv(Jr) - assert Jl == (-tan).rjac() + assert np.allclose(Jl, Adj @ Jr) + assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) + assert np.allclose(Jl, (-tan).rjac()) @pytest.mark.skip(reason="rjac/ljac not implemented yet") def test_JrJrinvJlJlinv(self, LieGroup, Tangent): From 3847589394f60b02a163aa8e47cefc6c55c0e0b1 Mon Sep 17 00:00:00 2001 From: artivis Date: Thu, 17 Dec 2020 15:39:40 -0500 Subject: [PATCH 18/67] fix act --- python/bindings_lie_group_base.h | 14 ++++++++++++-- test/python/pytest_manif.py | 15 ++++++--------- 2 files changed, 18 insertions(+), 11 deletions(-) diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h index 1b4dd130..90f7852f 100644 --- a/python/bindings_lie_group_base.h +++ b/python/bindings_lie_group_base.h @@ -60,9 +60,10 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py::arg_v("J_mc_mb", OptJacobianRef(), "None") ); + // That pops some nasty compilation errors. // py_class.def( // "act", - // &_LieGroup::act, + // &_LieGroup::template act, // py::arg("v"), // py::arg_v("J_vout_m", tl::optional>>(), "None"), // py::arg_v("J_vout_v", tl::optional>>(), "None") @@ -70,7 +71,16 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py_class.def( "act", - [](const _LieGroup& self, const Vector& v) { return self.act(v);} + []( + const _LieGroup& self, + const Vector& v, + tl::optional>> Ja, + tl::optional>> Jb) { + return self.act(v, Ja, Jb); + }, + py::arg("v"), + py::arg_v("J_vout_m", tl::optional>>(), "None"), + py::arg_v("J_vout_v", tl::optional>>(), "None") ); py_class.def( diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index bc99d737..81998c05 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -322,7 +322,6 @@ def test_ComposeJac(self, LieGroup, Tangent): assert state_pert.isApprox(state_lin, eps=1e-7) - def test_BetweenJac(self, LieGroup, Tangent): state = LieGroup.Random() state_other = LieGroup.Random() @@ -505,7 +504,7 @@ def test_Adj(self, LieGroup, Tangent): assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) assert np.allclose(Jl, (-tan).rjac()) - @pytest.mark.skip(reason="rjac/ljac not implemented yet") + @pytest.mark.skip(reason="invrjac/invljac not implemented yet") def test_JrJrinvJlJlinv(self, LieGroup, Tangent): state = LieGroup.Random() @@ -521,28 +520,26 @@ def test_JrJrinvJlJlinv(self, LieGroup, Tangent): assert I == Jr @ Jrinv assert I == Jl @ Jlinv - @pytest.mark.skip(reason="act Jacobians not implemented yet") def test_ActJac(self, LieGroup, Tangent): state = LieGroup.Identity() point = np.random.rand(Tangent.Dim) w = Tangent(np.random.rand(Tangent.DoF, 1)*1e-4) + w_point = np.random.rand(Tangent.Dim) * 1e-4 J_pout_s = np.zeros((LieGroup.Dim, LieGroup.DoF)) J_pout_p = np.zeros((LieGroup.Dim, LieGroup.Dim)) pointout = state.act(point, J_pout_s, J_pout_p) - w_point = np.random.rand(Tangent.Dim) * 1e-4 - point_pert = (state + w).act(point) - point_lin = pointout + (J_pout_s * w.coeffs()) + point_lin = pointout + J_pout_s @ w.coeffs() - assert point_pert == point_lin + assert np.allclose(point_pert, point_lin) point_pert = state.act(point + w_point) - point_lin = pointout + J_pout_p * w_point + point_lin = pointout + J_pout_p @ w_point - assert point_pert == point_lin + assert np.allclose(point_pert, point_lin) def test_TanPlusTanJac(self, LieGroup, Tangent): delta = Tangent.Random() From 1c0646352ff42f5e3c4eb01f24b7593032b168bf Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 19 Dec 2020 14:47:20 -0500 Subject: [PATCH 19/67] uniformise a little arg naming --- python/bindings_lie_group_base.h | 54 ++++++++++++++++---------------- python/bindings_tangent_base.h | 38 +++++++++++----------- test/python/pytest_manif.py | 8 ++--- 3 files changed, 51 insertions(+), 49 deletions(-) diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h index 90f7852f..219b803b 100644 --- a/python/bindings_lie_group_base.h +++ b/python/bindings_lie_group_base.h @@ -33,13 +33,13 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py_class.def( "inverse", &_LieGroup::inverse, - py::arg_v("J_m_t", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None") ); py_class.def( "log", &_LieGroup::log, - py::arg_v("J_m_t", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None") ); py_class.def("adj", &_LieGroup::adj); @@ -48,16 +48,16 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { "compose", &_LieGroup::template compose<_LieGroup>, py::arg("other"), - py::arg_v("J_mc_ma", OptJacobianRef(), "None"), - py::arg_v("J_mc_mb", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); py_class.def( "between", &_LieGroup::template between<_LieGroup>, py::arg("other"), - py::arg_v("J_mc_ma", OptJacobianRef(), "None"), - py::arg_v("J_mc_mb", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); // That pops some nasty compilation errors. @@ -78,9 +78,9 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { tl::optional>> Jb) { return self.act(v, Ja, Jb); }, - py::arg("v"), - py::arg_v("J_vout_m", tl::optional>>(), "None"), - py::arg_v("J_vout_v", tl::optional>>(), "None") + py::arg("p"), + py::arg_v("J_out_self", tl::optional>>(), "None"), + py::arg_v("J_out_p", tl::optional>>(), "None") ); py_class.def( @@ -93,49 +93,49 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py_class.def( "rplus", &_LieGroup::template rplus, - py::arg("t"), - py::arg_v("J_mout_m", OptJacobianRef(), "None"), - py::arg_v("J_mout_t", OptJacobianRef(), "None") + py::arg("tau"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_tau", OptJacobianRef(), "None") ); py_class.def( "lplus", &_LieGroup::template lplus, - py::arg("t"), - py::arg_v("J_mout_m", OptJacobianRef(), "None"), - py::arg_v("J_mout_t", OptJacobianRef(), "None") + py::arg("tau"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_mout_tau", OptJacobianRef(), "None") ); py_class.def( "plus", &_LieGroup::template plus, - py::arg("t"), - py::arg_v("J_mout_m", OptJacobianRef(), "None"), - py::arg_v("J_mout_t", OptJacobianRef(), "None") + py::arg("tau"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_mout_tau", OptJacobianRef(), "None") ); py_class.def( "rminus", &_LieGroup::template rminus<_LieGroup>, - py::arg("t"), - py::arg_v("J_t_ma", OptJacobianRef(), "None"), - py::arg_v("J_t_mb", OptJacobianRef(), "None") + py::arg("other"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); py_class.def( "lminus", &_LieGroup::template lminus<_LieGroup>, - py::arg("t"), - py::arg_v("J_t_ma", OptJacobianRef(), "None"), - py::arg_v("J_t_mb", OptJacobianRef(), "None") + py::arg("other"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); py_class.def( "minus", &_LieGroup::template minus<_LieGroup>, - py::arg("t"), - py::arg_v("J_t_ma", OptJacobianRef(), "None"), - py::arg_v("J_t_mb", OptJacobianRef(), "None") + py::arg("other"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); py_class.def("setIdentity", &_LieGroup::setIdentity); diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index 4182d71d..85c78a75 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -32,7 +32,7 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def("generator", &_Tangent::generator); - // py_class.def("w", &_Tangent::w); + // py_class.def("innerWeights", &_Tangent::w); py_class.def("inner", &_Tangent::template inner<_Tangent>); py_class.def("weightedNorm", &_Tangent::weightedNorm); @@ -42,47 +42,47 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def( "exp", &_Tangent::exp, - py::arg_v("J_m_t", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None") ); py_class.def( "rplus", &_Tangent::rplus, - py::arg("m"), - py::arg_v("J_mout_t", OptJacobianRef(), "None"), - py::arg_v("J_mout_m", OptJacobianRef(), "None") + py::arg("state"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_state", OptJacobianRef(), "None") ); py_class.def( "lplus", &_Tangent::lplus, - py::arg("m"), - py::arg_v("J_mout_t", OptJacobianRef(), "None"), - py::arg_v("J_mout_m", OptJacobianRef(), "None") + py::arg("state"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_state", OptJacobianRef(), "None") ); py_class.def( "plus", static_cast(&_Tangent::plus), - py::arg("m"), - py::arg_v("J_mout_t", OptJacobianRef(), "None"), - py::arg_v("J_mout_m", OptJacobianRef(), "None") + py::arg("state"), + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_state", OptJacobianRef(), "None") ); py_class.def( "plus", &_Tangent::template plus<_Tangent>, py::arg("other"), - py::arg_v("J_mout_t", OptJacobianRef(), "None"), - py::arg_v("J_mout_o", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); py_class.def( "minus", &_Tangent::template minus<_Tangent>, py::arg("other"), - py::arg_v("J_mout_ta", OptJacobianRef(), "None"), - py::arg_v("J_mout_tb", OptJacobianRef(), "None") + py::arg_v("J_out_self", OptJacobianRef(), "None"), + py::arg_v("J_out_other", OptJacobianRef(), "None") ); py_class.def("rjac", &_Tangent::rjac); @@ -98,7 +98,8 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { return self.isApprox(t, eps); }, py::arg("other"), - py::arg_v("eps", Scalar(manif::Constants::eps), "eps")); + py::arg_v("eps", Scalar(manif::Constants::eps), "eps") + ); py_class.def( "isApprox", @@ -106,7 +107,8 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { return self.isApprox(t, eps); }, py::arg("other"), - py::arg_v("eps", Scalar(manif::Constants::eps), "eps")); + py::arg_v("eps", Scalar(manif::Constants::eps), "eps") + ); py_class.def("setZero", &_Tangent::setZero); py_class.def("setRandom", &_Tangent::setRandom); @@ -114,7 +116,7 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def_static("Zero", &_Tangent::Zero); py_class.def_static("Random", &_Tangent::Random); py_class.def_static("Generator", &_Tangent::Generator); - py_class.def_static("W", &_Tangent::W); + py_class.def_static("InnerWeights", &_Tangent::W); // operator overloads py_class.def(-py::self) diff --git a/test/python/pytest_manif.py b/test/python/pytest_manif.py index 81998c05..e71eb380 100644 --- a/test/python/pytest_manif.py +++ b/test/python/pytest_manif.py @@ -278,7 +278,7 @@ def test_ComposeJac(self, LieGroup, Tangent): # - state_out = state.compose(state_other, J_mc_ma = J_sout_s, J_mc_mb = J_sout_so) + state_out = state.compose(state_other, J_out_self = J_sout_s, J_out_other = J_sout_so) state_pert = (state+w).compose(state_other) state_lin = state_out + J_sout_s*w @@ -292,7 +292,7 @@ def test_ComposeJac(self, LieGroup, Tangent): # - state_out = state.compose(state_other, J_mc_mb = J_sout_so, J_mc_ma = J_sout_s) + state_out = state.compose(state_other, J_out_other = J_sout_so, J_out_self = J_sout_s) state_pert = (state+w).compose(state_other) state_lin = state_out + J_sout_s*w @@ -306,7 +306,7 @@ def test_ComposeJac(self, LieGroup, Tangent): # - state_out = state.compose(state_other, J_mc_ma = J_sout_s) + state_out = state.compose(state_other, J_out_self = J_sout_s) state_pert = (state+w).compose(state_other) state_lin = state_out + J_sout_s*w @@ -315,7 +315,7 @@ def test_ComposeJac(self, LieGroup, Tangent): # - state_out = state.compose(state_other, J_mc_mb = J_sout_so) + state_out = state.compose(state_other, J_out_other = J_sout_so) state_pert = state.compose(state_other+w) state_lin = state_out + J_sout_so*w From ab9798acb838e2b618bc7416ccc874e3d1af9145 Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 10 Jan 2021 18:06:56 -0500 Subject: [PATCH 20/67] lt::optional fix missing return value --- external/lt/lt/optional.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/external/lt/lt/optional.hpp b/external/lt/lt/optional.hpp index 34e4f47c..dbc6d7d5 100644 --- a/external/lt/lt/optional.hpp +++ b/external/lt/lt/optional.hpp @@ -1254,6 +1254,7 @@ class optional : private detail::optional_move_assign_base, *this = nullopt; this->construct(std::forward(args)...); + return value(); } /// \group emplace From de15a30424f9bb8c6087eecc556ff2f737eeecba Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 10 Jan 2021 18:08:11 -0500 Subject: [PATCH 21/67] add Eigen::Quaternion bindings --- python/CMakeLists.txt | 3 ++ python/bindings_eigen_quaternion.cpp | 79 ++++++++++++++++++++++++++++ python/bindings_manif.cpp | 7 ++- python/bindings_tangent_base.h | 4 +- 4 files changed, 90 insertions(+), 3 deletions(-) create mode 100644 python/bindings_eigen_quaternion.cpp diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index d85e66b7..97b940ec 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,5 +1,8 @@ set(PYBIND11_CPP_STANDARD -std=c++11) pybind11_add_module(manifpy + + bindings_eigen_quaternion.cpp + bindings_rn.cpp bindings_so2.cpp bindings_so3.cpp diff --git a/python/bindings_eigen_quaternion.cpp b/python/bindings_eigen_quaternion.cpp new file mode 100644 index 00000000..1353535a --- /dev/null +++ b/python/bindings_eigen_quaternion.cpp @@ -0,0 +1,79 @@ +#include + +#include +#include +#include + +void wrap_Eigen_quaternion(pybind11::module &m) +{ + using Scalar = double; + using Quaternion = Eigen::Quaternion; + + pybind11::class_> quat_base(m, "QuaternionBase"); + pybind11::class_> quat(m, "Quaternion"); + + quat.attr("__doc__") = "Python bindings for Eigen::Quaternion."; + + quat.def(pybind11::init<>()) + .def_static("Identity", &Quaternion::Identity) +#if EIGEN_VERSION_AT_LEAST(3,3,0) + .def_static("UnitRandom", &Quaternion::UnitRandom) +#endif + .def(pybind11::init()) + .def(pybind11::init()) + .def(pybind11::init()) + .def(pybind11::init()) + // .def(pybind11::init([](const Class& other) { + // return other; + // }), pybind11::arg("other")) + + // .def( + // "coeffs", + // static_cast::Coefficients& (Quaternion::*)(void)>(&Quaternion::coeffs), + // pybind11::return_value_policy::reference_internal + // ) + + .def("angularDistance", &Quaternion::template angularDistance) + .def("conjugate", &Quaternion::conjugate) + .def("dot", &Quaternion::template dot) + .def("inverse", &Quaternion::inverse) + .def( + "isApprox", + &Quaternion::template isApprox, + pybind11::arg("other"), + pybind11::arg_v("prec", Eigen::NumTraits::dummy_precision(), "Precision") + ) + .def("norm", &Quaternion::norm) + .def("normalize", &Quaternion::normalize) + .def("normalized", &Quaternion::normalized) + .def("setIdentity", &Quaternion::setIdentity) + .def("slerp", &Quaternion::template slerp) + .def("squaredNorm", &Quaternion::squaredNorm) + .def("toRotationMatrix", &Quaternion::toRotationMatrix) + // .def("setFromTwoVectors", &Quaternion::setFromTwoVectors) + + .def("matrix", &Quaternion::matrix) + + .def( + "vec", + [](const Quaternion& self) { return self.vec(); }, + pybind11::return_value_policy::reference_internal + ) + + .def("x", static_cast(&Quaternion::x)) + .def("y", static_cast(&Quaternion::y)) + .def("z", static_cast(&Quaternion::z)) + .def("w", static_cast(&Quaternion::w)) + + .def(pybind11::self * pybind11::self) + // .def(pybind11::self = Eigen::AngleAxisd()) + // .def(pybind11::self = Eigen::Matrix) + + .def( + "__str__", + [](const Quaternion &q) { + std::ostringstream ss; ss << q.coeffs(); + return ss.str(); + } + ); +} diff --git a/python/bindings_manif.cpp b/python/bindings_manif.cpp index bb092036..3d5ac8f0 100644 --- a/python/bindings_manif.cpp +++ b/python/bindings_manif.cpp @@ -1,5 +1,7 @@ #include +void wrap_Eigen_quaternion(pybind11::module &m); + void wrap_Rn(pybind11::module &m); void wrap_SO2(pybind11::module &m); @@ -11,7 +13,10 @@ void wrap_SE3(pybind11::module &m); void wrap_SE_2_3(pybind11::module &m); PYBIND11_MODULE(manifpy, m) { - m.doc() = "Python bindings for the manif library."; + m.doc() = "Python bindings for the manif library," + "a small library for Lie theory."; + + wrap_Eigen_quaternion(m); wrap_Rn(m); diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index 85c78a75..a56e4483 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -153,8 +153,8 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py::buffer_info lhs_buf = lhs.request(); - if (lhs_buf.ndim != 2) - throw std::runtime_error("Number of dimensions must be 2"); + // if (lhs_buf.ndim != 2) + // throw std::runtime_error("Number of dimensions must be 2"); if (lhs_buf.size != _Tangent::DoF * _Tangent::DoF) throw std::runtime_error("Input shapes must match"); From 9dfddbfd0ceb9595005bcfb56864b5fa47f6006f Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 10 Jan 2021 18:09:51 -0500 Subject: [PATCH 22/67] rename python tests for pytest --- test/python/CMakeLists.txt | 12 ++-- .../python/{pytest_manif.py => test_manif.py} | 66 +++++++++---------- test/python/{pytest_se2.py => test_se2.py} | 0 test/python/{pytest_se3.py => test_se3.py} | 0 .../{pytest_se_2_3.py => test_se_2_3.py} | 0 test/python/{pytest_so2.py => test_so2.py} | 0 test/python/{pytest_so3.py => test_so3.py} | 23 ++++--- 7 files changed, 50 insertions(+), 51 deletions(-) rename test/python/{pytest_manif.py => test_manif.py} (93%) rename test/python/{pytest_se2.py => test_se2.py} (100%) rename test/python/{pytest_se3.py => test_se3.py} (100%) rename test/python/{pytest_se_2_3.py => test_se_2_3.py} (100%) rename test/python/{pytest_so2.py => test_so2.py} (100%) rename test/python/{pytest_so3.py => test_so3.py} (76%) diff --git a/test/python/CMakeLists.txt b/test/python/CMakeLists.txt index 1dd3c628..c74efbfb 100644 --- a/test/python/CMakeLists.txt +++ b/test/python/CMakeLists.txt @@ -10,9 +10,9 @@ function(manif_add_pytest target) ) endfunction() -manif_add_pytest(pytest_manif) -manif_add_pytest(pytest_so2) -manif_add_pytest(pytest_se2) -manif_add_pytest(pytest_so3) -manif_add_pytest(pytest_se3) -manif_add_pytest(pytest_se_2_3) +manif_add_pytest(test_manif) +manif_add_pytest(test_so2) +manif_add_pytest(test_se2) +manif_add_pytest(test_so3) +manif_add_pytest(test_se3) +manif_add_pytest(test_se_2_3) diff --git a/test/python/pytest_manif.py b/test/python/test_manif.py similarity index 93% rename from test/python/pytest_manif.py rename to test/python/test_manif.py index e71eb380..aeb1995b 100644 --- a/test/python/pytest_manif.py +++ b/test/python/test_manif.py @@ -134,16 +134,16 @@ def test_LogExp(self, LieGroup, Tangent): assert state == state.log().exp() - def test_ExpLog(self, LieGroup, Tangent): - delta = Tangent.Random() + # def test_ExpLog(self, LieGroup, Tangent): + # delta = Tangent.Random() - state = delta.exp() - delta_other = state.log() - print(delta) - print(delta.exp().log()) - print(delta_other) + # state = delta.exp() + # delta_other = state.log() + # print(delta) + # print(delta.exp().log()) + # print(delta_other) - assert delta == delta_other + # assert delta == delta_other def test_Between(self, LieGroup, Tangent): state = LieGroup.Random() @@ -475,30 +475,30 @@ def test_Adj(self, LieGroup, Tangent): assert np.allclose(np.linalg.inv(state.adj()), state.inverse().adj()) - def test_Adj(self, LieGroup, Tangent): + def test_Adj2(self, LieGroup, Tangent): if LieGroup in (SO2, R1): pytest.skip("Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support matmul") state = LieGroup.Random() - Adj = state.adj(); - tan = state.log(); + Adj = state.adj() + tan = state.log() - Jr = tan.rjac(); - Jl = tan.ljac(); + Jr = tan.rjac() + Jl = tan.ljac() assert np.allclose(Jl, Adj @ Jr) assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) assert np.allclose(Jl, (-tan).rjac()) - state.setIdentity(); + state.setIdentity() - Adj = state.adj(); - tan = state.log(); + Adj = state.adj() + tan = state.log() - Jr = tan.rjac(); - Jl = tan.ljac(); + Jr = tan.rjac() + Jl = tan.ljac() assert np.allclose(Jl, Adj @ Jr) assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) @@ -508,12 +508,12 @@ def test_Adj(self, LieGroup, Tangent): def test_JrJrinvJlJlinv(self, LieGroup, Tangent): state = LieGroup.Random() - tan = state.log(); - Jr = tan.rjac(); - Jl = tan.ljac(); + tan = state.log() + Jr = tan.rjac() + Jl = tan.ljac() - Jrinv = tan.rjacinv(); - Jlinv = tan.ljacinv(); + Jrinv = tan.rjacinv() + Jlinv = tan.ljacinv() I = np.identity(LieGroup.DoF) @@ -549,15 +549,15 @@ def test_TanPlusTanJac(self, LieGroup, Tangent): J_tout_t0 = np.zeros((LieGroup.DoF, LieGroup.DoF)) J_tout_t1 = np.zeros((LieGroup.DoF, LieGroup.DoF)) - delta_out = delta.plus(delta_other, J_tout_t0, J_tout_t1); + delta_out = delta.plus(delta_other, J_tout_t0, J_tout_t1) - delta_pert = (delta+w).plus(delta_other); - delta_lin = delta_out.plus(J_tout_t0*w); + delta_pert = (delta+w).plus(delta_other) + delta_lin = delta_out.plus(J_tout_t0*w) assert delta_pert == delta_lin - delta_pert = delta.plus(delta_other+w); - delta_lin = delta_out.plus(J_tout_t1*w); + delta_pert = delta.plus(delta_other+w) + delta_lin = delta_out.plus(J_tout_t1*w) assert delta_pert == delta_lin @@ -569,14 +569,14 @@ def test_TanMinusTanJac(self, LieGroup, Tangent): J_tout_t0 = np.zeros((LieGroup.DoF, LieGroup.DoF)) J_tout_t1 = np.zeros((LieGroup.DoF, LieGroup.DoF)) - delta_out = delta.minus(delta_other, J_tout_t0, J_tout_t1); + delta_out = delta.minus(delta_other, J_tout_t0, J_tout_t1) - delta_pert = (delta+w).minus(delta_other); - delta_lin = delta_out.plus(J_tout_t0*w); + delta_pert = (delta+w).minus(delta_other) + delta_lin = delta_out.plus(J_tout_t0*w) assert delta_pert == delta_lin - delta_pert = delta.minus(delta_other+w); - delta_lin = delta_out.plus(J_tout_t1*w); + delta_pert = delta.minus(delta_other+w) + delta_lin = delta_out.plus(J_tout_t1*w) assert delta_pert == delta_lin diff --git a/test/python/pytest_se2.py b/test/python/test_se2.py similarity index 100% rename from test/python/pytest_se2.py rename to test/python/test_se2.py diff --git a/test/python/pytest_se3.py b/test/python/test_se3.py similarity index 100% rename from test/python/pytest_se3.py rename to test/python/test_se3.py diff --git a/test/python/pytest_se_2_3.py b/test/python/test_se_2_3.py similarity index 100% rename from test/python/pytest_se_2_3.py rename to test/python/test_se_2_3.py diff --git a/test/python/pytest_so2.py b/test/python/test_so2.py similarity index 100% rename from test/python/pytest_so2.py rename to test/python/test_so2.py diff --git a/test/python/pytest_so3.py b/test/python/test_so3.py similarity index 76% rename from test/python/pytest_so3.py rename to test/python/test_so3.py index a1ecdc69..09d1973f 100644 --- a/test/python/pytest_so3.py +++ b/test/python/test_so3.py @@ -1,7 +1,7 @@ import numpy as np import pytest -from manifpy import SO3, SO3Tangent +from manifpy import Quaternion, SO3, SO3Tangent def test_constructor(): @@ -17,11 +17,11 @@ def test_constructor(): assert 0 == state.z() assert 1 == state.w() - # state = SO3(Quaternion(1,0,0,0)) - # assert 0 == state.x() - # assert 0 == state.y() - # assert 0 == state.z() - # assert 1 == state.w() + state = SO3(Quaternion(1,0,0,0)) + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + assert 1 == state.w() # state = SO3(AngleAxis(0, UnitX())) # assert 0 == state.x() @@ -62,9 +62,8 @@ def test_rotation(): assert (3, 3) == rotation.shape assert (np.identity(3) == rotation).all() -# def test_quaternion(): -# state = SO3.Identity() -# quaternion = state.quaternion() -# -# assert (4,) == quaternion.shape -# assert (np.zeros(4,) == quaternion).all() +def test_quaternion(): + state = SO3.Identity() + quaternion = state.quat() + + assert Quaternion.Identity().isApprox(quaternion) From 64a730dea4cf25126de8af04e21f6caff11ed6fe Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 10 Jan 2021 18:10:22 -0500 Subject: [PATCH 23/67] add a couple quaternion pytest --- test/python/CMakeLists.txt | 2 ++ test/python/test_eigen_quaternion.py | 43 ++++++++++++++++++++++++++++ 2 files changed, 45 insertions(+) create mode 100644 test/python/test_eigen_quaternion.py diff --git a/test/python/CMakeLists.txt b/test/python/CMakeLists.txt index c74efbfb..43117963 100644 --- a/test/python/CMakeLists.txt +++ b/test/python/CMakeLists.txt @@ -10,6 +10,8 @@ function(manif_add_pytest target) ) endfunction() +manif_add_pytest(test_eigen_quaternion) + manif_add_pytest(test_manif) manif_add_pytest(test_so2) manif_add_pytest(test_se2) diff --git a/test/python/test_eigen_quaternion.py b/test/python/test_eigen_quaternion.py new file mode 100644 index 00000000..57519f0d --- /dev/null +++ b/test/python/test_eigen_quaternion.py @@ -0,0 +1,43 @@ +import numpy as np +import pytest + +from manifpy import Quaternion + + +def test_constructor(): + q = Quaternion(1,2,3,4) + assert 2 == q.x() + assert 3 == q.y() + assert 4 == q.z() + assert 1 == q.w() + +def test_identity(): + q = Quaternion.Identity() + + assert 0 == q.x() + assert 0 == q.y() + assert 0 == q.z() + assert 1 == q.w() + + q_other = Quaternion() + q_other.setIdentity() + + assert q.isApprox(q_other) + assert q.isApprox(q_other * q_other) + assert q.isApprox(q_other.normalized()) + + q_inv = q.inverse() + + assert q_inv.isApprox(q_other) + assert q_inv.isApprox(q.conjugate()) + + assert (3,3) == q.toRotationMatrix().shape + assert (np.identity(3) == q.toRotationMatrix()).all() + + assert (3,3) == q.matrix().shape + assert (np.identity(3) == q.matrix()).all() + + assert 1 == q.norm() + assert 1 == q.squaredNorm() + assert 1 == q.dot(q) # cos(0) + assert 0 == q.angularDistance(q) From 93c5c2245441863824cb2d9951923e825161c70b Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 10 Jan 2021 18:11:01 -0500 Subject: [PATCH 24/67] add python packaging --- requirements.txt | 1 + setup.py | 94 ++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 95 insertions(+) create mode 100644 requirements.txt create mode 100644 setup.py diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 00000000..296d6545 --- /dev/null +++ b/requirements.txt @@ -0,0 +1 @@ +numpy \ No newline at end of file diff --git a/setup.py b/setup.py new file mode 100644 index 00000000..fec138c4 --- /dev/null +++ b/setup.py @@ -0,0 +1,94 @@ +import setuptools +import os +import re +import sys +import sysconfig +import platform +import subprocess + +from distutils.version import LooseVersion +from setuptools import setup, find_packages, Extension +from setuptools.command.build_ext import build_ext + +''' +Modified from https://www.benjack.io/2017/06/12/python-cpp-tests.html +''' +class CMakeExtension(Extension): + def __init__(self, name, sourcedir=''): + Extension.__init__(self, name, sources=[]) + self.sourcedir = os.path.abspath(sourcedir) + + +class CMakeBuild(build_ext): + def run(self): + try: + out = subprocess.check_output(['cmake', '--version']) + except OSError: + raise RuntimeError( + "CMake must be installed to build the following extensions: " + + ", ".join(e.name for e in self.extensions)) + + # if platform.system() == "Windows": + # cmake_version = LooseVersion(re.search(r'version\s*([\d.]+)', + # out.decode()).group(1)) + # if cmake_version < '3.1.0': + # raise RuntimeError("CMake >= 3.1.0 is required on Windows") + + for ext in self.extensions: + self.build_extension(ext) + + def build_extension(self, ext): + extdir = os.path.abspath( + os.path.dirname(self.get_ext_fullpath(ext.name))) + + cmake_args = ['-DCMAKE_LIBRARY_OUTPUT_DIRECTORY=' + extdir, + '-DPYTHON_EXECUTABLE=' + sys.executable] + + cfg = 'Debug' if self.debug else 'Release' + build_args = ['--config', cfg] + + if platform.system() == "Windows": + cmake_args += ['-DCMAKE_LIBRARY_OUTPUT_DIRECTORY_{}={}'.format( + cfg.upper(), + extdir)] + if sys.maxsize > 2**32: + cmake_args += ['-A', 'x64'] + build_args += ['--', '/m'] + else: + cmake_args += ['-DCMAKE_BUILD_TYPE=' + cfg] + cmake_args += ['-DBUILD_PYTHON_BINDINGS=ON'] + build_args += ['--', '-j6'] + + env = os.environ.copy() + env['CXXFLAGS'] = '{} -DVERSION_INFO=\\"{}\\"'.format( + env.get('CXXFLAGS', ''), + self.distribution.get_version()) + if not os.path.exists(self.build_temp): + os.makedirs(self.build_temp) + subprocess.check_call(['cmake', ext.sourcedir] + cmake_args, + cwd=self.build_temp, env=env) + subprocess.check_call(['cmake', '--build', '.'] + build_args, + cwd=self.build_temp) + +with open("README.md", "r") as f: + long_description = f.read() + +setup( + name="manifpy", + version="0.0.3", + author="Jeremie Deray", + author_email="deray.jeremie@gmail.com", + description="A small library for Lie theory.", + long_description=long_description, + long_description_content_type="text/markdown", + packages=setuptools.find_packages(), + classifiers=[ + "Programming Language :: Python :: 3", + "Operating System :: POSIX :: Linux" + ], + ext_modules=[CMakeExtension('manifpy')], + python_requires='>=3.6', + cmdclass=dict(build_ext=CMakeBuild), + zip_safe=False, + install_requires=['numpy'] +) \ No newline at end of file From 487dcbc470c0db4e503b7a850a455d8208b541f3 Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 10 Jan 2021 18:11:48 -0500 Subject: [PATCH 25/67] update readme for python installation --- README.md | 45 ++++++++++++++++++++++++++++----------------- 1 file changed, 28 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index 89e723ad..153be747 100644 --- a/README.md +++ b/README.md @@ -9,8 +9,9 @@ [![JOSS](http://joss.theoj.org/papers/e3fc778689407f0edd19df8c2089c160/status.svg)](http://joss.theoj.org/papers/e3fc778689407f0edd19df8c2089c160) ## Package Summary -**manif** is a header-only C++11 Lie theory library for state-estimation +**manif** is a Lie theory library for state-estimation targeted at robotics applications. +It is developed as a header-only C++11 library with Python 3 wrappers. At the moment, it provides the groups: - R(n): Euclidean space with addition. @@ -39,7 +40,7 @@ It also supports template scalar types. In particular, it can work with the [see related paragraph on Jacobians below](#jacobians). All Lie group classes defined in **manif** have in common that they inherit from a templated base class ([CRTP](https://en.wikipedia.org/wiki/Curiously_recurring_template_pattern)). -It allows one to write generic code abstracting the Lie group details. +It allows one to write generic code abstracting the Lie group details. Please find more information in the related [wiki page](https://github.com/artivis/manif/wiki/Writing-generic-code) #### Details @@ -71,28 +72,29 @@ ___ ### Dependencies - Eigen 3 : - + Linux ( Ubuntu and similar ) - + + Linux ( Ubuntu and similar ) + ```terminal apt-get install libeigen3-dev ``` - - + OS X - + + + OS X + ```terminal brew install eigen ``` - [lt::optional](https://github.com/TartanLlama/optional) : included in the `external` folder -### Installation - - + +### Installation + +#### From source ```terminal $ git clone https://github.com/artivis/manif.git @@ -129,6 +131,15 @@ add_executable(${PROJECT_NAME} src/foo.cpp) target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${manif_INCLUDE_DIRS}) ``` +#### Python 3 + +```terminal +$ git clone https://github.com/artivis/manif.git +$ cd manif +$ pip install -r requirements +$ python setup.py install +``` + ## Features ### Available Operations @@ -157,7 +168,7 @@ Above, Date: Mon, 11 Jan 2021 08:41:00 -0500 Subject: [PATCH 32/67] CI on macOS too --- .github/workflows/ci.yml | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index a3af7f30..535ba143 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -172,11 +172,13 @@ jobs: pybind11: needs: [build-ubuntu] - runs-on: ubuntu-latest strategy: + fail-fast: false matrix: - # python-version: [2.7, 3.5, 3.6, 3.7, 3.8] + platform: [macos-latest, ubuntu-latest] #windows-latest, + # python-version: [3.5, 3.6, 3.7, 3.8] python-version: [3.6] + runs-on: ${{ matrix.platform }} steps: - name: Checkout uses: actions/checkout@v2 @@ -184,15 +186,21 @@ jobs: uses: actions/setup-python@v2 with: python-version: ${{ matrix.python-version }} - - name: Setup + - name: Setup apt + if: runner.os == 'Linux' run: | sudo apt update sudo apt install -y libeigen3-dev + - name: Setup brew + if: runner.os == 'macOS' + run: brew install eigen + - name: Setup + run: | python -m pip install --upgrade pip pip install pytest "pybind11[global]" pip install -r requirements.txt - name: Build - run: python setup.py install + run: pip install . - name: Test run: pytest From f2a1e377b40bdeeb052fcaec7e46807eea71a22c Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 11 Jan 2021 08:53:47 -0500 Subject: [PATCH 33/67] fix QuaternionBase bindings --- .github/workflows/ci.yml | 2 +- python/bindings_eigen_quaternion.cpp | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 535ba143..435ea194 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -171,7 +171,7 @@ jobs: run: make test pybind11: - needs: [build-ubuntu] + needs: [build-ubuntu, build-mac] strategy: fail-fast: false matrix: diff --git a/python/bindings_eigen_quaternion.cpp b/python/bindings_eigen_quaternion.cpp index 1353535a..f4575f03 100644 --- a/python/bindings_eigen_quaternion.cpp +++ b/python/bindings_eigen_quaternion.cpp @@ -9,7 +9,10 @@ void wrap_Eigen_quaternion(pybind11::module &m) using Scalar = double; using Quaternion = Eigen::Quaternion; - pybind11::class_> quat_base(m, "QuaternionBase"); + pybind11::class_< + Eigen::QuaternionBase, + std::unique_ptr, pybind11::nodelete> + > quat_base(m, "QuaternionBase"); pybind11::class_> quat(m, "Quaternion"); quat.attr("__doc__") = "Python bindings for Eigen::Quaternion."; From d8084095ee3e359d0cea01d9b67f98c760445182 Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 11 Jan 2021 19:04:30 -0500 Subject: [PATCH 34/67] fix quat.setId --- python/bindings_eigen_quaternion.cpp | 2 +- test/python/test_eigen_quaternion.py | 18 ++++++++++++++++++ 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/python/bindings_eigen_quaternion.cpp b/python/bindings_eigen_quaternion.cpp index f4575f03..dbedc31a 100644 --- a/python/bindings_eigen_quaternion.cpp +++ b/python/bindings_eigen_quaternion.cpp @@ -49,7 +49,7 @@ void wrap_Eigen_quaternion(pybind11::module &m) .def("norm", &Quaternion::norm) .def("normalize", &Quaternion::normalize) .def("normalized", &Quaternion::normalized) - .def("setIdentity", &Quaternion::setIdentity) + .def("setIdentity", &Quaternion::setIdentity, pybind11::return_value_policy::reference_internal) .def("slerp", &Quaternion::template slerp) .def("squaredNorm", &Quaternion::squaredNorm) .def("toRotationMatrix", &Quaternion::toRotationMatrix) diff --git a/test/python/test_eigen_quaternion.py b/test/python/test_eigen_quaternion.py index 57519f0d..2f2c84e4 100644 --- a/test/python/test_eigen_quaternion.py +++ b/test/python/test_eigen_quaternion.py @@ -11,6 +11,24 @@ def test_constructor(): assert 4 == q.z() assert 1 == q.w() + q = Quaternion(np.array([1,2,3,4])) + assert 1 == q.x() + assert 2 == q.y() + assert 3 == q.z() + assert 4 == q.w() + + q = Quaternion(np.identity(3)) + assert 0 == q.x() + assert 0 == q.y() + assert 0 == q.z() + assert 1 == q.w() + +def test_vec(): + vec = Quaternion(1,2,3,4).vec() + assert 2 == vec[0] + assert 3 == vec[1] + assert 4 == vec[2] + def test_identity(): q = Quaternion.Identity() From f27892c9ee96bccee0b933eb7bc32aec63e64f15 Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 12 Jan 2021 20:06:32 -0500 Subject: [PATCH 35/67] add seN_localization.py --- examples/se2_localization.py | 236 ++++++++++++++++++++++++++++++++++ examples/se3_localization.py | 237 +++++++++++++++++++++++++++++++++++ 2 files changed, 473 insertions(+) create mode 100644 examples/se2_localization.py create mode 100644 examples/se3_localization.py diff --git a/examples/se2_localization.py b/examples/se2_localization.py new file mode 100644 index 00000000..2fa424f2 --- /dev/null +++ b/examples/se2_localization.py @@ -0,0 +1,236 @@ +# \file se2_localization.py +# +# Created on: Jan 11, 2021 +# \author: Jeremie Deray +# +# --------------------------------------------------------- +# This file is: +# (c) 2021 Jeremie Deray +# +# This file is part of `manif`, a C++ template-only library +# for Lie theory targeted at estimation for robotics. +# Manif is: +# (c) 2021 Jeremie Deray +# --------------------------------------------------------- +# +# --------------------------------------------------------- +# Demonstration example: +# +# 2D Robot localization based on fixed beacons. +# +# See se3_localization.cpp for the 3D equivalent. +# See se3_sam.cpp for a more advanced example performing smoothing and mapping. +# --------------------------------------------------------- +# +# This demo corresponds to the application in chapter V, section A, +# in the paper Sola-18, [https://arxiv.org/abs/1812.01537]. +# +# The following is an abstract of the content of the paper. +# Please consult the paper for better reference. +# +# +# We consider a robot in the plane surrounded by a small +# number of punctual landmarks or _beacons_. +# The robot receives control actions in the form of axial +# and angular velocities, and is able to measure the location +# of the beacons w.r.t its own reference frame. +# +# The robot pose X is in SE(2) and the beacon positions b_k in R^2, +# +# | cos th -sin th x | +# X = | sin th cos th y | // position and orientation +# | 0 0 1 | +# +# b_k = (bx_k, by_k) // lmk coordinates in world frame +# +# The control signal u is a twist in se(2) comprising longitudinal +# velocity v and angular velocity w, with no lateral velocity +# component, integrated over the sampling time dt. +# +# u = (v*dt, 0, w*dt) +# +# The control is corrupted by additive Gaussian noise u_noise, +# with covariance +# +# Q = diagonal(sigma_v^2, sigma_s^2, sigma_w^2). +# +# This noise accounts for possible lateral slippage u_s +# through a non-zero value of sigma_s, +# +# At the arrival of a control u, the robot pose is updated +# with X <-- X * Exp(u) = X + u. +# +# Landmark measurements are of the range and bearing type, +# though they are put in Cartesian form for simplicity. +# Their noise n is zero mean Gaussian, and is specified +# with a covariances matrix R. +# We notice the rigid motion action y = h(X,b) = X^-1 * b +# (see appendix C), +# +# y_k = (brx_k, bry_k) // lmk coordinates in robot frame +# +# We consider the beacons b_k situated at known positions. +# We define the pose to estimate as X in SE(2). +# The estimation error dx and its covariance P are expressed +# in the tangent space at X. +# +# All these variables are summarized again as follows +# +# X : robot pose, SE(2) +# u : robot control, (v*dt ; 0 ; w*dt) in se(2) +# Q : control perturbation covariance +# b_k : k-th landmark position, R^2 +# y : Cartesian landmark measurement in robot frame, R^2 +# R : covariance of the measurement noise +# +# The motion and measurement models are +# +# X_(t+1) = f(X_t, u) = X_t * Exp ( w ) // motion equation +# y_k = h(X, b_k) = X^-1 * b_k // measurement equation +# +# The algorithm below comprises first a simulator to +# produce measurements, then uses these measurements +# to estimate the state, using a Lie-based error-state Kalman filter. +# +# This file has plain code with only one main() function. +# There are no function calls other than those involving `manif`. +# +# Printing simulated state and estimated state together +# with an unfiltered state (i.e. without Kalman corrections) +# allows for evaluating the quality of the estimates. + + +from manifpy import SE2, SE2Tangent +import numpy as np + + +Vector = np.array +Covariance = np.zeros((SE2.DoF, SE2.DoF)) +Jacobian = np.zeros((SE2.DoF, SE2.DoF)) + + +if __name__ == "__main__": + + # START CONFIGURATION + + NUMBER_OF_LMKS_TO_MEASURE = 3 + + # Define the robot pose element and its covariance + X_simulation = SE2.Identity() + X = SE2.Identity() + X_unfiltered = SE2.Identity() + P = Covariance + + u_nom = Vector([0.1, 0.0, 0.05]) + u_sigmas = Vector([0.1, 0.1, 0.1]) + U = np.diagflat(np.square(u_sigmas)) + + # Declare the Jacobians of the motion wrt robot and control + J_x = J_u = Jacobian + + # Define five landmarks in R^2 + landmarks = [] + landmarks.append(Vector([2.0, 0.0])) + landmarks.append(Vector([2.0, 1.0])) + landmarks.append(Vector([2.0, -1.0])) + + # Define the beacon's measurements + measurements = [Vector([0, 0])] * NUMBER_OF_LMKS_TO_MEASURE + + y_sigmas = Vector([0.01, 0.01]) + R = np.diagflat(np.square(y_sigmas)) + + # Declare some temporaries + J_xi_x = Jacobian + J_e_xi = np.zeros((SE2.Dim, SE2.DoF)) + + # CONFIGURATION DONE + + # pretty print + np.set_printoptions(precision=3) + + # DEBUG + print("X STATE : X Y Z TH_x TH_y TH_z ") + print("-------------------------------------------------------") + print("X initial : ", X_simulation.log().coeffs()) + print("-------------------------------------------------------") + # END DEBUG + + # START TEMPORAL LOOP + + # Make 10 steps. Measure up to three landmarks each time. + for t in range(10): + # I. Simulation + + # simulate noise + u_noise = u_sigmas * np.random.rand(SE2.DoF) # control noise + u_noisy = u_nom + u_noise # noisy control + + u_simu = SE2Tangent(u_nom) + u_est = SE2Tangent(u_noisy) + u_unfilt = SE2Tangent(u_noisy) + + # first we move + X_simulation = X_simulation + u_simu # overloaded X.rplus(u) = X * exp(u) + + # then we measure all landmarks + for i in range(NUMBER_OF_LMKS_TO_MEASURE): + b = landmarks[i] # lmk coordinates in world frame + + # simulate noise + y_noise = y_sigmas * np.random.rand(SE2.Dim) # measurement noise + + y = X_simulation.inverse().act(b) # landmark measurement, before adding noise + + y = Vector(y) + y_noise # landmark measurement, noisy + measurements[i] = y # store for the estimator just below + + # II. Estimation + + # First we move + + X = X.plus(u_est, J_x, J_u) # X * exp(u), with Jacobians + + P = J_x * P * J_x.transpose() + J_u * U * J_u.transpose() + + # Then we correct using the measurements of each lmk + for i in range(NUMBER_OF_LMKS_TO_MEASURE): + # landmark + b = landmarks[i] # lmk coordinates in world frame + + # measurement + y = measurements[i] # lmk measurement, noisy + + # expectation + e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). + e = Vector(e) + H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x + E = H @ P @ H.transpose() + + # innovation + z = y - e + Z = E + R + + # Kalman gain + K = P @ H.transpose() @ np.linalg.inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv + + # Correction step + dx = K @ z # dx is in the tangent space at X + + # Update + X = X + SE2Tangent(dx) # overloaded X.rplus(dx) = X * exp(dx) + P = P - K @ Z @ K.transpose() + + # III. Unfiltered + + # move also an unfiltered version for comparison purposes + X_unfiltered = X_unfiltered + u_unfilt + + # IV. Results + + # DEBUG + print("X simulated : ", X_simulation.log().coeffs().transpose()) + print("X estimated : ", X.log().coeffs().transpose()) + print("X unfilterd : ", X_unfiltered.log().coeffs().transpose()) + print("-------------------------------------------------------") + # END DEBUG diff --git a/examples/se3_localization.py b/examples/se3_localization.py new file mode 100644 index 00000000..b15b2c5e --- /dev/null +++ b/examples/se3_localization.py @@ -0,0 +1,237 @@ +# \file se3_localization.py +# +# Created on: Jan 11, 2021 +# \author: Jeremie Deray +# +# --------------------------------------------------------- +# This file is: +# (c) 2021 Jeremie Deray +# +# This file is part of `manif`, a C++ template-only library +# for Lie theory targeted at estimation for robotics. +# Manif is: +# (c) 2021 Jeremie Deray +# --------------------------------------------------------- +# +# --------------------------------------------------------- +# Demonstration example: +# +# 3D Robot localization based on fixed beacons. +# +# See se3_sam.py for a more advanced example performing smoothing and mapping. +# --------------------------------------------------------- +# +# This demo corresponds to the 3D version of the application +# in chapter V, section A, in the paper Sola-18, +# [https://arxiv.org/abs/1812.01537]. +# +# The following is an abstract of the content of the paper. +# Please consult the paper for better reference. +# +# +# We consider a robot in 3D space surrounded by a small +# number of punctual landmarks or _beacons_. +# The robot receives control actions in the form of axial +# and angular velocities, and is able to measure the location +# of the beacons w.r.t its own reference frame. +# +# The robot pose X is in SE(3) and the beacon positions b_k in R^3, +# +# X = | R t | // position and orientation +# | 0 1 | +# +# b_k = (bx_k, by_k, bz_k) // lmk coordinates in world frame +# +# The control signal u is a twist in se(3) comprising longitudinal +# velocity vx and angular velocity wz, with no other velocity +# components, integrated over the sampling time dt. +# +# u = (vx*dt, 0, 0, 0, 0, w*dt) +# +# The control is corrupted by additive Gaussian noise u_noise, +# with covariance +# +# Q = diagonal(sigma_x^2, sigma_y^2, sigma_z^2, sigma_roll^2, sigma_pitch^2, sigma_yaw^2). +# +# This noise accounts for possible lateral and rotational slippage +# through a non-zero values of sigma_y, sigma_z, sigma_roll and sigma_pitch. +# +# At the arrival of a control u, the robot pose is updated +# with X <-- X * Exp(u) = X + u. +# +# Landmark measurements are of the range and bearing type, +# though they are put in Cartesian form for simplicity. +# Their noise n is zero mean Gaussian, and is specified +# with a covariances matrix R. +# We notice the rigid motion action y = h(X,b) = X^-1 * b +# (see appendix D), +# +# y_k = (brx_k, bry_k, brz_k) // lmk coordinates in robot frame +# +# We consider the beacons b_k situated at known positions. +# We define the pose to estimate as X in SE(3). +# The estimation error dx and its covariance P are expressed +# in the tangent space at X. +# +# All these variables are summarized again as follows +# +# X : robot pose, SE(3) +# u : robot control, (v*dt; 0; 0; 0; 0; w*dt) in se(3) +# Q : control perturbation covariance +# b_k : k-th landmark position, R^3 +# y : Cartesian landmark measurement in robot frame, R^3 +# R : covariance of the measurement noise +# +# The motion and measurement models are +# +# X_(t+1) = f(X_t, u) = X_t * Exp ( w ) // motion equation +# y_k = h(X, b_k) = X^-1 * b_k // measurement equation +# +# The algorithm below comprises first a simulator to +# produce measurements, then uses these measurements +# to estimate the state, using a Lie-based error-state Kalman filter. +# +# This file has plain code with only one main() function. +# There are no function calls other than those involving `manif`. +# +# Printing simulated state and estimated state together +# with an unfiltered state (i.e. without Kalman corrections) +# allows for evaluating the quality of the estimates. + + +from manifpy import SE3, SE3Tangent +import numpy as np + + +Vector = np.array +Covariance = np.zeros((SE3.DoF, SE3.DoF)) +Jacobian = np.zeros((SE3.DoF, SE3.DoF)) + + +if __name__ == "__main__": + + # START CONFIGURATION + + NUMBER_OF_LMKS_TO_MEASURE = 5 + + # Define the robot pose element and its covariance + X_simulation = SE3.Identity() + X = SE3.Identity() + X_unfiltered = SE3.Identity() + P = Covariance + + u_nom = Vector([0.1, 0.0, 0.0, 0.0, 0.0, 0.05]) + u_sigmas = Vector([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) + U = np.diagflat(np.square(u_sigmas)) + + # Declare the Jacobians of the motion wrt robot and control + J_x = J_u = Jacobian + + # Define five landmarks in R^3 + landmarks = [] + landmarks.append(Vector([2.0, 0.0, 0.0])) + landmarks.append(Vector([3.0, -1.0, -1.0])) + landmarks.append(Vector([2.0, -1.0, 1.0])) + landmarks.append(Vector([2.0, 1.0, 1.0])) + landmarks.append(Vector([2.0, 1.0, -1.0])) + + # Define the beacon's measurements + measurements = [Vector([0, 0, 0])] * NUMBER_OF_LMKS_TO_MEASURE + + y_sigmas = Vector([0.01, 0.01, 0.01]) + R = np.diagflat(np.square(y_sigmas)) + + # Declare some temporaries + J_xi_x = Jacobian + J_e_xi = np.zeros((SE3.Dim, SE3.DoF)) + + # CONFIGURATION DONE + + # pretty print + np.set_printoptions(precision=3) + + # DEBUG + print("X STATE : X Y Z TH_x TH_y TH_z ") + print("-------------------------------------------------------") + print("X initial : ", X_simulation.log().coeffs()) + print("-------------------------------------------------------") + # END DEBUG + + # START TEMPORAL LOOP + + # Make 10 steps. Measure up to three landmarks each time. + for t in range(10): + # I. Simulation + + # simulate noise + u_noise = u_sigmas * np.random.rand(SE3.DoF) # control noise + u_noisy = u_nom + u_noise # noisy control + + u_simu = SE3Tangent(u_nom) + u_est = SE3Tangent(u_noisy) + u_unfilt = SE3Tangent(u_noisy) + + # first we move + X_simulation = X_simulation + u_simu # overloaded X.rplus(u) = X * exp(u) + + # then we measure all landmarks + for i in range(NUMBER_OF_LMKS_TO_MEASURE): + b = landmarks[i] # lmk coordinates in world frame + + # simulate noise + y_noise = y_sigmas * np.random.rand(SE3.Dim) # measurement noise + + y = X_simulation.inverse().act(b) # landmark measurement, before adding noise + + y = Vector(y) + y_noise # landmark measurement, noisy + measurements[i] = y # store for the estimator just below + + # II. Estimation + + # First we move + + X = X.plus(u_est, J_x, J_u) # X * exp(u), with Jacobians + + P = J_x * P * J_x.transpose() + J_u * U * J_u.transpose() + + # Then we correct using the measurements of each lmk + for i in range(NUMBER_OF_LMKS_TO_MEASURE): + # landmark + b = landmarks[i] # lmk coordinates in world frame + + # measurement + y = measurements[i] # lmk measurement, noisy + + # expectation + e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). + e = Vector(e) + H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x + E = H @ P @ H.transpose() + + # innovation + z = y - e + Z = E + R + + # Kalman gain + K = P @ H.transpose() @ np.linalg.inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv + + # Correction step + dx = K @ z # dx is in the tangent space at X + + # Update + X = X + SE3Tangent(dx) # overloaded X.rplus(dx) = X * exp(dx) + P = P - K @ Z @ K.transpose() + + # III. Unfiltered + + # move also an unfiltered version for comparison purposes + X_unfiltered = X_unfiltered + u_unfilt + + # IV. Results + + # DEBUG + print("X simulated : ", X_simulation.log().coeffs().transpose()) + print("X estimated : ", X.log().coeffs().transpose()) + print("X unfilterd : ", X_unfiltered.log().coeffs().transpose()) + print("-------------------------------------------------------") + # END DEBUG From 1416eb98f1c602f2a1a66fe25a37ef9ae25f1cd0 Mon Sep 17 00:00:00 2001 From: artivis Date: Wed, 13 Jan 2021 21:23:57 -0500 Subject: [PATCH 36/67] some flake8 fixes --- examples/se2_localization.py | 228 ++++++++++++------------ examples/se3_localization.py | 256 ++++++++++++++------------- setup.py | 51 +++--- test/python/test_eigen_quaternion.py | 21 +-- test/python/test_manif.py | 127 ++++++------- test/python/test_so3.py | 21 ++- 6 files changed, 368 insertions(+), 336 deletions(-) diff --git a/examples/se2_localization.py b/examples/se2_localization.py index 2fa424f2..17d28d36 100644 --- a/examples/se2_localization.py +++ b/examples/se2_localization.py @@ -1,107 +1,111 @@ -# \file se2_localization.py -# -# Created on: Jan 11, 2021 -# \author: Jeremie Deray -# -# --------------------------------------------------------- -# This file is: -# (c) 2021 Jeremie Deray -# -# This file is part of `manif`, a C++ template-only library -# for Lie theory targeted at estimation for robotics. -# Manif is: -# (c) 2021 Jeremie Deray -# --------------------------------------------------------- -# -# --------------------------------------------------------- -# Demonstration example: -# -# 2D Robot localization based on fixed beacons. -# -# See se3_localization.cpp for the 3D equivalent. -# See se3_sam.cpp for a more advanced example performing smoothing and mapping. -# --------------------------------------------------------- -# -# This demo corresponds to the application in chapter V, section A, -# in the paper Sola-18, [https://arxiv.org/abs/1812.01537]. -# -# The following is an abstract of the content of the paper. -# Please consult the paper for better reference. -# -# -# We consider a robot in the plane surrounded by a small -# number of punctual landmarks or _beacons_. -# The robot receives control actions in the form of axial -# and angular velocities, and is able to measure the location -# of the beacons w.r.t its own reference frame. -# -# The robot pose X is in SE(2) and the beacon positions b_k in R^2, -# -# | cos th -sin th x | -# X = | sin th cos th y | // position and orientation -# | 0 0 1 | -# -# b_k = (bx_k, by_k) // lmk coordinates in world frame -# -# The control signal u is a twist in se(2) comprising longitudinal -# velocity v and angular velocity w, with no lateral velocity -# component, integrated over the sampling time dt. -# -# u = (v*dt, 0, w*dt) -# -# The control is corrupted by additive Gaussian noise u_noise, -# with covariance -# -# Q = diagonal(sigma_v^2, sigma_s^2, sigma_w^2). -# -# This noise accounts for possible lateral slippage u_s -# through a non-zero value of sigma_s, -# -# At the arrival of a control u, the robot pose is updated -# with X <-- X * Exp(u) = X + u. -# -# Landmark measurements are of the range and bearing type, -# though they are put in Cartesian form for simplicity. -# Their noise n is zero mean Gaussian, and is specified -# with a covariances matrix R. -# We notice the rigid motion action y = h(X,b) = X^-1 * b -# (see appendix C), -# -# y_k = (brx_k, bry_k) // lmk coordinates in robot frame -# -# We consider the beacons b_k situated at known positions. -# We define the pose to estimate as X in SE(2). -# The estimation error dx and its covariance P are expressed -# in the tangent space at X. -# -# All these variables are summarized again as follows -# -# X : robot pose, SE(2) -# u : robot control, (v*dt ; 0 ; w*dt) in se(2) -# Q : control perturbation covariance -# b_k : k-th landmark position, R^2 -# y : Cartesian landmark measurement in robot frame, R^2 -# R : covariance of the measurement noise -# -# The motion and measurement models are -# -# X_(t+1) = f(X_t, u) = X_t * Exp ( w ) // motion equation -# y_k = h(X, b_k) = X^-1 * b_k // measurement equation -# -# The algorithm below comprises first a simulator to -# produce measurements, then uses these measurements -# to estimate the state, using a Lie-based error-state Kalman filter. -# -# This file has plain code with only one main() function. -# There are no function calls other than those involving `manif`. -# -# Printing simulated state and estimated state together -# with an unfiltered state (i.e. without Kalman corrections) -# allows for evaluating the quality of the estimates. +r""" + +\file se2_localization.py. + +Created on: Jan 11, 2021 +\author: Jeremie Deray + +--------------------------------------------------------- +This file is: +(c) 2021 Jeremie Deray + +This file is part of `manif`, a C++ template-only library +for Lie theory targeted at estimation for robotics. +Manif is: +(c) 2021 Jeremie Deray +--------------------------------------------------------- + +--------------------------------------------------------- +Demonstration example: + + 2D Robot localization based on fixed beacons. + + See se3_localization.cpp for the 3D equivalent. + See se3_sam.cpp for a more advanced example performing smoothing and mapping. +--------------------------------------------------------- + +This demo corresponds to the application in chapter V, section A, +in the paper Sola-18, [https://arxiv.org/abs/1812.01537]. + +The following is an abstract of the content of the paper. +Please consult the paper for better reference. + +We consider a robot in the plane surrounded by a small +number of punctual landmarks or _beacons_. +The robot receives control actions in the form of axial +and angular velocities, and is able to measure the location +of the beacons w.r.t its own reference frame. + +The robot pose X is in SE(2) and the beacon positions b_k in R^2, + + | cos th -sin th x | + X = | sin th cos th y | // position and orientation + | 0 0 1 | + + b_k = (bx_k, by_k) // lmk coordinates in world frame + +The control signal u is a twist in se(2) comprising longitudinal +velocity v and angular velocity w, with no lateral velocity +component, integrated over the sampling time dt. + + u = (v*dt, 0, w*dt) + +The control is corrupted by additive Gaussian noise u_noise, +with covariance + + Q = diagonal(sigma_v^2, sigma_s^2, sigma_w^2). + +This noise accounts for possible lateral slippage u_s +through a non-zero value of sigma_s, + +At the arrival of a control u, the robot pose is updated +with X <-- X * Exp(u) = X + u. + +Landmark measurements are of the range and bearing type, +though they are put in Cartesian form for simplicity. +Their noise n is zero mean Gaussian, and is specified +with a covariances matrix R. +We notice the rigid motion action y = h(X,b) = X^-1 * b +(see appendix C), + + y_k = (brx_k, bry_k) // lmk coordinates in robot frame + +We consider the beacons b_k situated at known positions. +We define the pose to estimate as X in SE(2). +The estimation error dx and its covariance P are expressed +in the tangent space at X. + +All these variables are summarized again as follows + + X : robot pose, SE(2) + u : robot control, (v*dt ; 0 ; w*dt) in se(2) + Q : control perturbation covariance + b_k : k-th landmark position, R^2 + y : Cartesian landmark measurement in robot frame, R^2 + R : covariance of the measurement noise + +The motion and measurement models are + + X_(t+1) = f(X_t, u) = X_t * Exp ( w ) // motion equation + y_k = h(X, b_k) = X^-1 * b_k // measurement equation + +The algorithm below comprises first a simulator to +produce measurements, then uses these measurements +to estimate the state, using a Lie-based error-state Kalman filter. + +This file has plain code with only one main() function. +There are no function calls other than those involving `manif`. + +Printing simulated state and estimated state together +with an unfiltered state (i.e. without Kalman corrections) +allows for evaluating the quality of the estimates. +""" from manifpy import SE2, SE2Tangent + import numpy as np +from numpy.linalg import inv Vector = np.array @@ -109,7 +113,7 @@ Jacobian = np.zeros((SE2.DoF, SE2.DoF)) -if __name__ == "__main__": +if __name__ == '__main__': # START CONFIGURATION @@ -150,10 +154,10 @@ np.set_printoptions(precision=3) # DEBUG - print("X STATE : X Y Z TH_x TH_y TH_z ") - print("-------------------------------------------------------") - print("X initial : ", X_simulation.log().coeffs()) - print("-------------------------------------------------------") + print('X STATE : X Y Z TH_x TH_y TH_z ') + print('-------------------------------------------------------') + print('X initial : ', X_simulation.log().coeffs()) + print('-------------------------------------------------------') # END DEBUG # START TEMPORAL LOOP @@ -166,8 +170,8 @@ u_noise = u_sigmas * np.random.rand(SE2.DoF) # control noise u_noisy = u_nom + u_noise # noisy control - u_simu = SE2Tangent(u_nom) - u_est = SE2Tangent(u_noisy) + u_simu = SE2Tangent(u_nom) + u_est = SE2Tangent(u_noisy) u_unfilt = SE2Tangent(u_noisy) # first we move @@ -212,7 +216,7 @@ Z = E + R # Kalman gain - K = P @ H.transpose() @ np.linalg.inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv + K = P @ H.transpose() @ inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv # Correction step dx = K @ z # dx is in the tangent space at X @@ -229,8 +233,8 @@ # IV. Results # DEBUG - print("X simulated : ", X_simulation.log().coeffs().transpose()) - print("X estimated : ", X.log().coeffs().transpose()) - print("X unfilterd : ", X_unfiltered.log().coeffs().transpose()) - print("-------------------------------------------------------") + print('X simulated : ', X_simulation.log().coeffs().transpose()) + print('X estimated : ', X.log().coeffs().transpose()) + print('X unfilterd : ', X_unfiltered.log().coeffs().transpose()) + print('-------------------------------------------------------') # END DEBUG diff --git a/examples/se3_localization.py b/examples/se3_localization.py index b15b2c5e..ed545573 100644 --- a/examples/se3_localization.py +++ b/examples/se3_localization.py @@ -1,106 +1,110 @@ -# \file se3_localization.py -# -# Created on: Jan 11, 2021 -# \author: Jeremie Deray -# -# --------------------------------------------------------- -# This file is: -# (c) 2021 Jeremie Deray -# -# This file is part of `manif`, a C++ template-only library -# for Lie theory targeted at estimation for robotics. -# Manif is: -# (c) 2021 Jeremie Deray -# --------------------------------------------------------- -# -# --------------------------------------------------------- -# Demonstration example: -# -# 3D Robot localization based on fixed beacons. -# -# See se3_sam.py for a more advanced example performing smoothing and mapping. -# --------------------------------------------------------- -# -# This demo corresponds to the 3D version of the application -# in chapter V, section A, in the paper Sola-18, -# [https://arxiv.org/abs/1812.01537]. -# -# The following is an abstract of the content of the paper. -# Please consult the paper for better reference. -# -# -# We consider a robot in 3D space surrounded by a small -# number of punctual landmarks or _beacons_. -# The robot receives control actions in the form of axial -# and angular velocities, and is able to measure the location -# of the beacons w.r.t its own reference frame. -# -# The robot pose X is in SE(3) and the beacon positions b_k in R^3, -# -# X = | R t | // position and orientation -# | 0 1 | -# -# b_k = (bx_k, by_k, bz_k) // lmk coordinates in world frame -# -# The control signal u is a twist in se(3) comprising longitudinal -# velocity vx and angular velocity wz, with no other velocity -# components, integrated over the sampling time dt. -# -# u = (vx*dt, 0, 0, 0, 0, w*dt) -# -# The control is corrupted by additive Gaussian noise u_noise, -# with covariance -# -# Q = diagonal(sigma_x^2, sigma_y^2, sigma_z^2, sigma_roll^2, sigma_pitch^2, sigma_yaw^2). -# -# This noise accounts for possible lateral and rotational slippage -# through a non-zero values of sigma_y, sigma_z, sigma_roll and sigma_pitch. -# -# At the arrival of a control u, the robot pose is updated -# with X <-- X * Exp(u) = X + u. -# -# Landmark measurements are of the range and bearing type, -# though they are put in Cartesian form for simplicity. -# Their noise n is zero mean Gaussian, and is specified -# with a covariances matrix R. -# We notice the rigid motion action y = h(X,b) = X^-1 * b -# (see appendix D), -# -# y_k = (brx_k, bry_k, brz_k) // lmk coordinates in robot frame -# -# We consider the beacons b_k situated at known positions. -# We define the pose to estimate as X in SE(3). -# The estimation error dx and its covariance P are expressed -# in the tangent space at X. -# -# All these variables are summarized again as follows -# -# X : robot pose, SE(3) -# u : robot control, (v*dt; 0; 0; 0; 0; w*dt) in se(3) -# Q : control perturbation covariance -# b_k : k-th landmark position, R^3 -# y : Cartesian landmark measurement in robot frame, R^3 -# R : covariance of the measurement noise -# -# The motion and measurement models are -# -# X_(t+1) = f(X_t, u) = X_t * Exp ( w ) // motion equation -# y_k = h(X, b_k) = X^-1 * b_k // measurement equation -# -# The algorithm below comprises first a simulator to -# produce measurements, then uses these measurements -# to estimate the state, using a Lie-based error-state Kalman filter. -# -# This file has plain code with only one main() function. -# There are no function calls other than those involving `manif`. -# -# Printing simulated state and estimated state together -# with an unfiltered state (i.e. without Kalman corrections) -# allows for evaluating the quality of the estimates. +r""" + +\file se3_localization.py. + +Created on: Jan 11, 2021 +\author: Jeremie Deray + +--------------------------------------------------------- +This file is: +(c) 2021 Jeremie Deray + +This file is part of `manif`, a C++ template-only library +for Lie theory targeted at estimation for robotics. +Manif is: +(c) 2021 Jeremie Deray +--------------------------------------------------------- + +--------------------------------------------------------- +Demonstration example: + + 3D Robot localization based on fixed beacons. + + See se3_sam.py for a more advanced example performing smoothing and mapping. +--------------------------------------------------------- + +This demo corresponds to the 3D version of the application +in chapter V, section A, in the paper Sola-18, +[https://arxiv.org/abs/1812.01537]. + +The following is an abstract of the content of the paper. +Please consult the paper for better reference. + +We consider a robot in 3D space surrounded by a small +number of punctual landmarks or _beacons_. +The robot receives control actions in the form of axial +and angular velocities, and is able to measure the location +of the beacons w.r.t its own reference frame. + +The robot pose X is in SE(3) and the beacon positions b_k in R^3, + + X = | R t | // position and orientation + | 0 1 | + + b_k = (bx_k, by_k, bz_k) // lmk coordinates in world frame + +The control signal u is a twist in se(3) comprising longitudinal +velocity vx and angular velocity wz, with no other velocity +components, integrated over the sampling time dt. + + u = (vx*dt, 0, 0, 0, 0, w*dt) + +The control is corrupted by additive Gaussian noise u_noise, +with covariance + + Q = diagonal(sigma_x^2, sigma_y^2, sigma_z^2, sigma_roll^2, sigma_pitch^2, sigma_yaw^2). + +This noise accounts for possible lateral and rotational slippage +through a non-zero values of sigma_y, sigma_z, sigma_roll and sigma_pitch. + +At the arrival of a control u, the robot pose is updated +with X <-- X * Exp(u) = X + u. + +Landmark measurements are of the range and bearing type, +though they are put in Cartesian form for simplicity. +Their noise n is zero mean Gaussian, and is specified +with a covariances matrix R. +We notice the rigid motion action y = h(X,b) = X^-1 * b +(see appendix D), + + y_k = (brx_k, bry_k, brz_k) // lmk coordinates in robot frame + +We consider the beacons b_k situated at known positions. +We define the pose to estimate as X in SE(3). +The estimation error dx and its covariance P are expressed +in the tangent space at X. + +All these variables are summarized again as follows + + X : robot pose, SE(3) + u : robot control, (v*dt; 0; 0; 0; 0; w*dt) in se(3) + Q : control perturbation covariance + b_k : k-th landmark position, R^3 + y : Cartesian landmark measurement in robot frame, R^3 + R : covariance of the measurement noise + +The motion and measurement models are + + X_(t+1) = f(X_t, u) = X_t * Exp ( w ) // motion equation + y_k = h(X, b_k) = X^-1 * b_k // measurement equation + +The algorithm below comprises first a simulator to +produce measurements, then uses these measurements +to estimate the state, using a Lie-based error-state Kalman filter. + +This file has plain code with only one main() function. +There are no function calls other than those involving `manif`. + +Printing simulated state and estimated state together +with an unfiltered state (i.e. without Kalman corrections) +allows for evaluating the quality of the estimates. +""" from manifpy import SE3, SE3Tangent + import numpy as np +from numpy.linalg import inv Vector = np.array @@ -108,7 +112,7 @@ Jacobian = np.zeros((SE3.DoF, SE3.DoF)) -if __name__ == "__main__": +if __name__ == '__main__': # START CONFIGURATION @@ -151,10 +155,10 @@ np.set_printoptions(precision=3) # DEBUG - print("X STATE : X Y Z TH_x TH_y TH_z ") - print("-------------------------------------------------------") - print("X initial : ", X_simulation.log().coeffs()) - print("-------------------------------------------------------") + print('X STATE : X Y Z TH_x TH_y TH_z ') + print('-------------------------------------------------------') + print('X initial : ', X_simulation.log().coeffs()) + print('-------------------------------------------------------') # END DEBUG # START TEMPORAL LOOP @@ -164,48 +168,48 @@ # I. Simulation # simulate noise - u_noise = u_sigmas * np.random.rand(SE3.DoF) # control noise - u_noisy = u_nom + u_noise # noisy control + u_noise = u_sigmas * np.random.rand(SE3.DoF) # control noise + u_noisy = u_nom + u_noise # noisy control - u_simu = SE3Tangent(u_nom) - u_est = SE3Tangent(u_noisy) + u_simu = SE3Tangent(u_nom) + u_est = SE3Tangent(u_noisy) u_unfilt = SE3Tangent(u_noisy) # first we move - X_simulation = X_simulation + u_simu # overloaded X.rplus(u) = X * exp(u) + X_simulation = X_simulation + u_simu # overloaded X.rplus(u) = X * exp(u) # then we measure all landmarks for i in range(NUMBER_OF_LMKS_TO_MEASURE): - b = landmarks[i] # lmk coordinates in world frame + b = landmarks[i] # lmk coordinates in world frame # simulate noise - y_noise = y_sigmas * np.random.rand(SE3.Dim) # measurement noise + y_noise = y_sigmas * np.random.rand(SE3.Dim) # measurement noise - y = X_simulation.inverse().act(b) # landmark measurement, before adding noise + y = X_simulation.inverse().act(b) # landmark measurement, before adding noise - y = Vector(y) + y_noise # landmark measurement, noisy - measurements[i] = y # store for the estimator just below + y = Vector(y) + y_noise # landmark measurement, noisy + measurements[i] = y # store for the estimator just below # II. Estimation # First we move - X = X.plus(u_est, J_x, J_u) # X * exp(u), with Jacobians + X = X.plus(u_est, J_x, J_u) # X * exp(u), with Jacobians P = J_x * P * J_x.transpose() + J_u * U * J_u.transpose() # Then we correct using the measurements of each lmk for i in range(NUMBER_OF_LMKS_TO_MEASURE): # landmark - b = landmarks[i] # lmk coordinates in world frame + b = landmarks[i] # lmk coordinates in world frame # measurement - y = measurements[i] # lmk measurement, noisy + y = measurements[i] # lmk measurement, noisy # expectation - e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). + e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). e = Vector(e) - H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x + H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x E = H @ P @ H.transpose() # innovation @@ -213,13 +217,13 @@ Z = E + R # Kalman gain - K = P @ H.transpose() @ np.linalg.inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv + K = P @ H.transpose() @ inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv # Correction step - dx = K @ z # dx is in the tangent space at X + dx = K @ z # dx is in the tangent space at X # Update - X = X + SE3Tangent(dx) # overloaded X.rplus(dx) = X * exp(dx) + X = X + SE3Tangent(dx) # overloaded X.rplus(dx) = X * exp(dx) P = P - K @ Z @ K.transpose() # III. Unfiltered @@ -230,8 +234,8 @@ # IV. Results # DEBUG - print("X simulated : ", X_simulation.log().coeffs().transpose()) - print("X estimated : ", X.log().coeffs().transpose()) - print("X unfilterd : ", X_unfiltered.log().coeffs().transpose()) - print("-------------------------------------------------------") + print('X simulated : ', X_simulation.log().coeffs().transpose()) + print('X estimated : ', X.log().coeffs().transpose()) + print('X unfilterd : ', X_unfiltered.log().coeffs().transpose()) + print('-------------------------------------------------------') # END DEBUG diff --git a/setup.py b/setup.py index fec138c4..1b60fea8 100644 --- a/setup.py +++ b/setup.py @@ -1,32 +1,38 @@ -import setuptools import os -import re -import sys -import sysconfig import platform import subprocess +import sys -from distutils.version import LooseVersion -from setuptools import setup, find_packages, Extension +import setuptools +# import re +# import sysconfig +# from distutils.version import LooseVersion +from setuptools import Extension, setup from setuptools.command.build_ext import build_ext -''' + +""" Modified from https://www.benjack.io/2017/06/12/python-cpp-tests.html -''' +""" + + class CMakeExtension(Extension): + def __init__(self, name, sourcedir=''): Extension.__init__(self, name, sources=[]) self.sourcedir = os.path.abspath(sourcedir) class CMakeBuild(build_ext): + def run(self): try: - out = subprocess.check_output(['cmake', '--version']) + # out = + subprocess.check_output(['cmake', '--version']) except OSError: raise RuntimeError( - "CMake must be installed to build the following extensions: " + - ", ".join(e.name for e in self.extensions)) + 'CMake must be installed to build the following extensions: ' + + ', '.join(e.name for e in self.extensions)) # if platform.system() == "Windows": # cmake_version = LooseVersion(re.search(r'version\s*([\d.]+)', @@ -47,7 +53,7 @@ def build_extension(self, ext): cfg = 'Debug' if self.debug else 'Release' build_args = ['--config', cfg] - if platform.system() == "Windows": + if platform.system() == 'Windows': cmake_args += ['-DCMAKE_LIBRARY_OUTPUT_DIRECTORY_{}={}'.format( cfg.upper(), extdir)] @@ -70,25 +76,26 @@ def build_extension(self, ext): subprocess.check_call(['cmake', '--build', '.'] + build_args, cwd=self.build_temp) -with open("README.md", "r") as f: + +with open('README.md', 'r') as f: long_description = f.read() setup( - name="manifpy", - version="0.0.3", - author="Jeremie Deray", - author_email="deray.jeremie@gmail.com", - description="A small library for Lie theory.", + name='manifpy', + version='0.0.3', + author='Jeremie Deray', + author_email='deray.jeremie@gmail.com', + description='A small library for Lie theory.', long_description=long_description, - long_description_content_type="text/markdown", + long_description_content_type='text/markdown', packages=setuptools.find_packages(), classifiers=[ - "Programming Language :: Python :: 3", - "Operating System :: POSIX :: Linux" + 'Programming Language :: Python :: 3', + 'Operating System :: POSIX :: Linux' ], ext_modules=[CMakeExtension('manifpy')], python_requires='>=3.6', cmdclass=dict(build_ext=CMakeBuild), zip_safe=False, install_requires=['numpy'] -) \ No newline at end of file +) diff --git a/test/python/test_eigen_quaternion.py b/test/python/test_eigen_quaternion.py index 2f2c84e4..b0d6aca4 100644 --- a/test/python/test_eigen_quaternion.py +++ b/test/python/test_eigen_quaternion.py @@ -1,17 +1,16 @@ -import numpy as np -import pytest - from manifpy import Quaternion +import numpy as np + def test_constructor(): - q = Quaternion(1,2,3,4) + q = Quaternion(1, 2, 3, 4) assert 2 == q.x() assert 3 == q.y() assert 4 == q.z() assert 1 == q.w() - q = Quaternion(np.array([1,2,3,4])) + q = Quaternion(np.array([1, 2, 3, 4])) assert 1 == q.x() assert 2 == q.y() assert 3 == q.z() @@ -23,12 +22,14 @@ def test_constructor(): assert 0 == q.z() assert 1 == q.w() + def test_vec(): - vec = Quaternion(1,2,3,4).vec() + vec = Quaternion(1, 2, 3, 4).vec() assert 2 == vec[0] assert 3 == vec[1] assert 4 == vec[2] + def test_identity(): q = Quaternion.Identity() @@ -37,7 +38,7 @@ def test_identity(): assert 0 == q.z() assert 1 == q.w() - q_other = Quaternion() + q_other = Quaternion.Identity() q_other.setIdentity() assert q.isApprox(q_other) @@ -49,13 +50,13 @@ def test_identity(): assert q_inv.isApprox(q_other) assert q_inv.isApprox(q.conjugate()) - assert (3,3) == q.toRotationMatrix().shape + assert (3, 3) == q.toRotationMatrix().shape assert (np.identity(3) == q.toRotationMatrix()).all() - assert (3,3) == q.matrix().shape + assert (3, 3) == q.matrix().shape assert (np.identity(3) == q.matrix()).all() assert 1 == q.norm() assert 1 == q.squaredNorm() - assert 1 == q.dot(q) # cos(0) + assert 1 == q.dot(q) # cos(0) assert 0 == q.angularDistance(q) diff --git a/test/python/test_manif.py b/test/python/test_manif.py index aeb1995b..ed397a9d 100644 --- a/test/python/test_manif.py +++ b/test/python/test_manif.py @@ -1,6 +1,3 @@ -import numpy as np -import pytest - from manifpy import \ R1, R1Tangent, \ R2, R2Tangent, \ @@ -11,15 +8,19 @@ R7, R7Tangent, \ R8, R8Tangent, \ R9, R9Tangent, \ - SO2, SO2Tangent, \ SE2, SE2Tangent, \ - SO3, SO3Tangent, \ SE3, SE3Tangent, \ - SE_2_3, SE_2_3Tangent + SE_2_3, SE_2_3Tangent, \ + SO2, SO2Tangent, \ + SO3, SO3Tangent + +import numpy as np + +import pytest @pytest.mark.parametrize( - "LieGroup, Tangent", + 'LieGroup, Tangent', [ (R1, R1Tangent), (R2, R2Tangent), @@ -30,11 +31,11 @@ (R7, R7Tangent), (R8, R8Tangent), (R9, R9Tangent), - (SO2, SO2Tangent), - (SO3, SO3Tangent), (SE2, SE2Tangent), (SE3, SE3Tangent), (SE_2_3, SE_2_3Tangent), + (SO2, SO2Tangent), + (SO3, SO3Tangent), ] ) class TestCommon: @@ -203,7 +204,9 @@ def test_Act(self, LieGroup, Tangent): def test_smallAdj(self, LieGroup, Tangent): if LieGroup in (SO2, R1): - pytest.skip("hat is a scalar (Dim 1), numpy doesn't support matmul") + pytest.skip( + "hat is a scalar (Dim 1), numpy doesn't support matmul" + ) delta = Tangent.Random() delta_other = Tangent.Random() @@ -221,7 +224,7 @@ def test_InverseJac(self, LieGroup, Tangent): state_out = state.inverse(J_sout_s) state_pert = (state+w).inverse() - state_lin = state_out.rplus(J_sout_s * w) + state_lin = state_out.rplus(J_sout_s * w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -233,7 +236,7 @@ def test_LogJac(self, LieGroup, Tangent): state_out = state.log(J_sout_s) state_pert = (state+w).log() - state_lin = state_out + (J_sout_s*w) + state_lin = state_out + (J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -245,7 +248,7 @@ def test_ExpJac(self, LieGroup, Tangent): state_out = delta.exp(J_sout_s) state_pert = (delta+w).exp() - state_lin = state_out + (J_sout_s*w) + state_lin = state_out + (J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -253,7 +256,7 @@ def test_ExpJac(self, LieGroup, Tangent): state_out = delta.exp(J_sout_s) state_pert = (delta+w).exp() - state_lin = state_out + (J_sout_s*w) + state_lin = state_out + (J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -267,58 +270,58 @@ def test_ComposeJac(self, LieGroup, Tangent): state_out = state.compose(state_other, J_sout_s, J_sout_so) state_pert = (state+w).compose(state_other) - state_lin = state_out + J_sout_s*w + state_lin = state_out + J_sout_s*w assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.compose(state_other+w) - state_lin = state_out + J_sout_so*w + state_lin = state_out + J_sout_so*w assert state_pert.isApprox(state_lin, eps=1e-7) - # - - state_out = state.compose(state_other, J_out_self = J_sout_s, J_out_other = J_sout_so) + state_out = state.compose( + state_other, + J_out_self=J_sout_s, + J_out_other=J_sout_so + ) state_pert = (state+w).compose(state_other) - state_lin = state_out + J_sout_s*w + state_lin = state_out + J_sout_s*w assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.compose(state_other+w) - state_lin = state_out + J_sout_so*w + state_lin = state_out + J_sout_so*w assert state_pert.isApprox(state_lin, eps=1e-7) - # - - state_out = state.compose(state_other, J_out_other = J_sout_so, J_out_self = J_sout_s) + state_out = state.compose( + state_other, + J_out_other=J_sout_so, + J_out_self=J_sout_s + ) state_pert = (state+w).compose(state_other) - state_lin = state_out + J_sout_s*w + state_lin = state_out + J_sout_s*w assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.compose(state_other+w) - state_lin = state_out + J_sout_so*w + state_lin = state_out + J_sout_so*w assert state_pert.isApprox(state_lin, eps=1e-7) - # - - state_out = state.compose(state_other, J_out_self = J_sout_s) + state_out = state.compose(state_other, J_out_self=J_sout_s) state_pert = (state+w).compose(state_other) - state_lin = state_out + J_sout_s*w + state_lin = state_out + J_sout_s*w assert state_pert.isApprox(state_lin, eps=1e-7) - # - - state_out = state.compose(state_other, J_out_other = J_sout_so) + state_out = state.compose(state_other, J_out_other=J_sout_so) state_pert = state.compose(state_other+w) - state_lin = state_out + J_sout_so*w + state_lin = state_out + J_sout_so*w assert state_pert.isApprox(state_lin, eps=1e-7) @@ -332,12 +335,12 @@ def test_BetweenJac(self, LieGroup, Tangent): state_out = state.between(state_other, J_sout_s, J_sout_so) state_pert = (state + w).between(state_other) - state_lin = state_out + (J_sout_s * w) + state_lin = state_out + (J_sout_s * w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.between(state_other + w) - state_lin = state_out + (J_sout_so * w) + state_lin = state_out + (J_sout_so * w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -351,12 +354,12 @@ def test_RplusJac(self, LieGroup, Tangent): state_out = state.rplus(delta, J_sout_s, J_sout_t) state_pert = (state+w).rplus(delta) - state_lin = state_out.rplus(J_sout_s*w) + state_lin = state_out.rplus(J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.rplus(delta+w) - state_lin = state_out.rplus(J_sout_t*w) + state_lin = state_out.rplus(J_sout_t*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -370,12 +373,12 @@ def test_LplusJac(self, LieGroup, Tangent): state_out = state.lplus(delta, J_sout_s, J_sout_t) state_pert = (state+w).lplus(delta) - state_lin = state_out.rplus(J_sout_s*w) + state_lin = state_out.rplus(J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.lplus(delta+w) - state_lin = state_out.rplus(J_sout_t*w) + state_lin = state_out.rplus(J_sout_t*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -389,12 +392,12 @@ def test_PlusJac(self, LieGroup, Tangent): state_out = state.plus(delta, J_sout_s, J_sout_t) state_pert = (state+w).plus(delta) - state_lin = state_out.plus(J_sout_s*w) + state_lin = state_out.plus(J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.plus(delta+w) - state_lin = state_out.plus(J_sout_t*w) + state_lin = state_out.plus(J_sout_t*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -408,12 +411,12 @@ def test_RminusJac(self, LieGroup, Tangent): state_out = state.rminus(state_other, J_sout_s, J_sout_so) state_pert = (state+w).rminus(state_other) - state_lin = state_out.plus(J_sout_s*w) + state_lin = state_out.plus(J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.rminus(state_other+w) - state_lin = state_out.plus(J_sout_so*w) + state_lin = state_out.plus(J_sout_so*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -427,12 +430,12 @@ def test_LminusJac(self, LieGroup, Tangent): state_out = state.lminus(state_other, J_sout_s, J_sout_so) state_pert = (state+w).lminus(state_other) - state_lin = state_out.plus(J_sout_s*w) + state_lin = state_out.plus(J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.lminus(state_other+w) - state_lin = state_out.plus(J_sout_so*w) + state_lin = state_out.plus(J_sout_so*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -446,12 +449,12 @@ def test_MinusJac(self, LieGroup, Tangent): state_out = state.minus(state_other, J_sout_s, J_sout_so) state_pert = (state+w).minus(state_other) - state_lin = state_out.plus(J_sout_s*w) + state_lin = state_out.plus(J_sout_s*w) assert state_pert.isApprox(state_lin, eps=1e-7) state_pert = state.minus(state_other+w) - state_lin = state_out.plus(J_sout_so*w) + state_lin = state_out.plus(J_sout_so*w) assert state_pert.isApprox(state_lin, eps=1e-7) @@ -471,14 +474,18 @@ def test_Adj(self, LieGroup, Tangent): assert state + delta == state.adj() * delta + state if LieGroup in (SO2, R1): - pytest.skip("Adj is a scalar (Dim 1), numpy doesn't support inversion") + pytest.skip( + "Adj is a scalar (Dim 1), numpy doesn't support inversion" + ) assert np.allclose(np.linalg.inv(state.adj()), state.inverse().adj()) def test_Adj2(self, LieGroup, Tangent): if LieGroup in (SO2, R1): - pytest.skip("Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support matmul") + pytest.skip( + "Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support matmul" + ) state = LieGroup.Random() @@ -504,7 +511,7 @@ def test_Adj2(self, LieGroup, Tangent): assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) assert np.allclose(Jl, (-tan).rjac()) - @pytest.mark.skip(reason="invrjac/invljac not implemented yet") + @pytest.mark.skip(reason='invrjac/invljac not implemented yet') def test_JrJrinvJlJlinv(self, LieGroup, Tangent): state = LieGroup.Random() @@ -515,10 +522,10 @@ def test_JrJrinvJlJlinv(self, LieGroup, Tangent): Jrinv = tan.rjacinv() Jlinv = tan.ljacinv() - I = np.identity(LieGroup.DoF) + Id = np.identity(LieGroup.DoF) - assert I == Jr @ Jrinv - assert I == Jl @ Jlinv + assert Id == Jr @ Jrinv + assert Id == Jl @ Jlinv def test_ActJac(self, LieGroup, Tangent): state = LieGroup.Identity() @@ -532,12 +539,12 @@ def test_ActJac(self, LieGroup, Tangent): pointout = state.act(point, J_pout_s, J_pout_p) point_pert = (state + w).act(point) - point_lin = pointout + J_pout_s @ w.coeffs() + point_lin = pointout + J_pout_s @ w.coeffs() assert np.allclose(point_pert, point_lin) point_pert = state.act(point + w_point) - point_lin = pointout + J_pout_p @ w_point + point_lin = pointout + J_pout_p @ w_point assert np.allclose(point_pert, point_lin) @@ -552,12 +559,12 @@ def test_TanPlusTanJac(self, LieGroup, Tangent): delta_out = delta.plus(delta_other, J_tout_t0, J_tout_t1) delta_pert = (delta+w).plus(delta_other) - delta_lin = delta_out.plus(J_tout_t0*w) + delta_lin = delta_out.plus(J_tout_t0*w) assert delta_pert == delta_lin delta_pert = delta.plus(delta_other+w) - delta_lin = delta_out.plus(J_tout_t1*w) + delta_lin = delta_out.plus(J_tout_t1*w) assert delta_pert == delta_lin @@ -572,11 +579,11 @@ def test_TanMinusTanJac(self, LieGroup, Tangent): delta_out = delta.minus(delta_other, J_tout_t0, J_tout_t1) delta_pert = (delta+w).minus(delta_other) - delta_lin = delta_out.plus(J_tout_t0*w) + delta_lin = delta_out.plus(J_tout_t0*w) assert delta_pert == delta_lin delta_pert = delta.minus(delta_other+w) - delta_lin = delta_out.plus(J_tout_t1*w) + delta_lin = delta_out.plus(J_tout_t1*w) assert delta_pert == delta_lin diff --git a/test/python/test_so3.py b/test/python/test_so3.py index 09d1973f..059568aa 100644 --- a/test/python/test_so3.py +++ b/test/python/test_so3.py @@ -1,23 +1,28 @@ -import numpy as np -import pytest - from manifpy import Quaternion, SO3, SO3Tangent +import numpy as np + def test_constructor(): - state = SO3(0,0,0,1) + state = SO3(0, 0, 0, 1) assert 0 == state.x() assert 0 == state.y() assert 0 == state.z() assert 1 == state.w() - state = SO3(0,0,0) + state = SO3(np.array([0, 0, 0, 1])) assert 0 == state.x() assert 0 == state.y() assert 0 == state.z() assert 1 == state.w() - state = SO3(Quaternion(1,0,0,0)) + state = SO3(0, 0, 0) + assert 0 == state.x() + assert 0 == state.y() + assert 0 == state.z() + assert 1 == state.w() + + state = SO3(Quaternion(1, 0, 0, 0)) assert 0 == state.x() assert 0 == state.y() assert 0 == state.z() @@ -34,6 +39,7 @@ def test_constructor(): # assert 2 == delta.y() # assert 3 == delta.z() + def test_accessors(): state = SO3.Identity() @@ -48,6 +54,7 @@ def test_accessors(): assert 0 == delta.y() assert 0 == delta.z() + def test_transform(): state = SO3.Identity() transform = state.transform() @@ -55,6 +62,7 @@ def test_transform(): assert (4, 4) == transform.shape assert (np.identity(4) == transform).all() + def test_rotation(): state = SO3.Identity() rotation = state.rotation() @@ -62,6 +70,7 @@ def test_rotation(): assert (3, 3) == rotation.shape assert (np.identity(3) == rotation).all() + def test_quaternion(): state = SO3.Identity() quaternion = state.quat() From 75b484c0059e15e2dc2683509b4719a3150227da Mon Sep 17 00:00:00 2001 From: artivis Date: Thu, 14 Jan 2021 19:42:47 -0500 Subject: [PATCH 37/67] learning python the hard way --- examples/se2_localization.py | 19 +++++++++++++------ examples/se3_localization.py | 19 +++++++++++++------ 2 files changed, 26 insertions(+), 12 deletions(-) diff --git a/examples/se2_localization.py b/examples/se2_localization.py index 17d28d36..e4785536 100644 --- a/examples/se2_localization.py +++ b/examples/se2_localization.py @@ -109,8 +109,14 @@ Vector = np.array -Covariance = np.zeros((SE2.DoF, SE2.DoF)) -Jacobian = np.zeros((SE2.DoF, SE2.DoF)) + + +def Covariance(): + return np.zeros((SE2.DoF, SE2.DoF)) + + +def Jacobian(): + return np.zeros((SE2.DoF, SE2.DoF)) if __name__ == '__main__': @@ -123,14 +129,15 @@ X_simulation = SE2.Identity() X = SE2.Identity() X_unfiltered = SE2.Identity() - P = Covariance + P = Covariance() u_nom = Vector([0.1, 0.0, 0.05]) u_sigmas = Vector([0.1, 0.1, 0.1]) U = np.diagflat(np.square(u_sigmas)) # Declare the Jacobians of the motion wrt robot and control - J_x = J_u = Jacobian + J_x = Jacobian() + J_u = Jacobian() # Define five landmarks in R^2 landmarks = [] @@ -145,13 +152,13 @@ R = np.diagflat(np.square(y_sigmas)) # Declare some temporaries - J_xi_x = Jacobian + J_xi_x = Jacobian() J_e_xi = np.zeros((SE2.Dim, SE2.DoF)) # CONFIGURATION DONE # pretty print - np.set_printoptions(precision=3) + np.set_printoptions(precision=3, suppress=True) # DEBUG print('X STATE : X Y Z TH_x TH_y TH_z ') diff --git a/examples/se3_localization.py b/examples/se3_localization.py index ed545573..ca774b15 100644 --- a/examples/se3_localization.py +++ b/examples/se3_localization.py @@ -108,8 +108,14 @@ Vector = np.array -Covariance = np.zeros((SE3.DoF, SE3.DoF)) -Jacobian = np.zeros((SE3.DoF, SE3.DoF)) + + +def Covariance(): + return np.zeros((SE3.DoF, SE3.DoF)) + + +def Jacobian(): + return np.zeros((SE3.DoF, SE3.DoF)) if __name__ == '__main__': @@ -122,14 +128,15 @@ X_simulation = SE3.Identity() X = SE3.Identity() X_unfiltered = SE3.Identity() - P = Covariance + P = Covariance() u_nom = Vector([0.1, 0.0, 0.0, 0.0, 0.0, 0.05]) u_sigmas = Vector([0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) U = np.diagflat(np.square(u_sigmas)) # Declare the Jacobians of the motion wrt robot and control - J_x = J_u = Jacobian + J_x = Jacobian() + J_u = Jacobian() # Define five landmarks in R^3 landmarks = [] @@ -146,13 +153,13 @@ R = np.diagflat(np.square(y_sigmas)) # Declare some temporaries - J_xi_x = Jacobian + J_xi_x = Jacobian() J_e_xi = np.zeros((SE3.Dim, SE3.DoF)) # CONFIGURATION DONE # pretty print - np.set_printoptions(precision=3) + np.set_printoptions(precision=3, suppress=True) # DEBUG print('X STATE : X Y Z TH_x TH_y TH_z ') From 828dd9ede57e755e0fd4517588af66acb81f8c4a Mon Sep 17 00:00:00 2001 From: artivis Date: Thu, 14 Jan 2021 19:43:19 -0500 Subject: [PATCH 38/67] bind SE3.translation() --- python/bindings_se3.cpp | 30 +++++++++++++++++------------- 1 file changed, 17 insertions(+), 13 deletions(-) diff --git a/python/bindings_se3.cpp b/python/bindings_se3.cpp index 08f9556c..1d58ef78 100644 --- a/python/bindings_se3.cpp +++ b/python/bindings_se3.cpp @@ -11,14 +11,15 @@ void wrap_SE3(pybind11::module &m) { - using Scalar = manif::SE3d::Scalar; + using SE3d = manif::SE3d; + using Scalar = SE3d::Scalar; using Quaternion = Eigen::Quaternion; - pybind11::class_, std::unique_ptr, py::nodelete>> SE3_base(m, "SE3Base"); + pybind11::class_, std::unique_ptr, py::nodelete>> SE3_base(m, "SE3Base"); pybind11::class_, std::unique_ptr, py::nodelete>> SE3_tan_base(m, "SE3TangentBase"); - pybind11::class_> SE3(m, "SE3"); - wrap_lie_group_base>(SE3); + pybind11::class_> SE3(m, "SE3"); + wrap_lie_group_base>(SE3); SE3.def(py::init()); @@ -27,15 +28,18 @@ void wrap_SE3(pybind11::module &m) // SE3.def(py::init&>()); // SE3.def(py::init&>()); - SE3.def("transform", &manif::SE3d::transform); - // SE3.def("isometry", &manif::SE3d::isometry); - SE3.def("rotation", &manif::SE3d::rotation); - // SE3.def("quat", &manif::SE3d::quat); - // SE3.def("translation", &manif::SE3d::translation); - SE3.def("x", &manif::SE3d::x); - SE3.def("y", &manif::SE3d::y); - SE3.def("z", &manif::SE3d::z); - SE3.def("normalize", &manif::SE3d::normalize); + SE3.def("transform", &SE3d::transform); + // SE3.def("isometry", &SE3d::isometry); + SE3.def("rotation", &SE3d::rotation); + // SE3.def("quat", &SE3d::quat); + SE3.def( + "translation", + static_cast(&SE3d::translation) + ); + SE3.def("x", &SE3d::x); + SE3.def("y", &SE3d::y); + SE3.def("z", &SE3d::z); + SE3.def("normalize", &SE3d::normalize); pybind11::class_> SE3_tan(m, "SE3Tangent"); wrap_tangent_base>(SE3_tan); From 36fb57108e1942e0d8dcad452c60314d40aaeec1 Mon Sep 17 00:00:00 2001 From: artivis Date: Thu, 14 Jan 2021 19:43:55 -0500 Subject: [PATCH 39/67] add se2/3_sam.py --- examples/se2_sam.py | 531 +++++++++++++++++++++++++++++++++++++++++++ examples/se3_sam.py | 543 ++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 1074 insertions(+) create mode 100644 examples/se2_sam.py create mode 100644 examples/se3_sam.py diff --git a/examples/se2_sam.py b/examples/se2_sam.py new file mode 100644 index 00000000..bcce2b35 --- /dev/null +++ b/examples/se2_sam.py @@ -0,0 +1,531 @@ +r""" + +\file se2_sam.py. + +Created on: Jan 11, 2021 +\author: Jeremie Deray + +--------------------------------------------------------- +This file is: +(c) 2021 Jeremie Deray + +This file is part of `manif`, a C++ template-only library +for Lie theory targeted at estimation for robotics. +Manif is: +(c) 2021 Jeremie Deray +--------------------------------------------------------- + +--------------------------------------------------------- +Demonstration example: + + 2D smoothing and mapping (SAM). + + See se3_sam.py for a 3D version of this example. + See se2_localization.py for a simpler localization example using EKF. +------------------------------------------------------------ + +This demo corresponds to the application +in chapter V, section B, in the paper Sola-18, +[https://arxiv.org/abs/1812.01537]. + +The following is an abstract of the content of the paper. +Please consult the paper for better reference. + + +We consider a robot in 2D space surrounded by a small +number of punctual landmarks or _beacons_. +The robot receives control actions in the form of axial +and angular velocities, and is able to measure the location +of the beacons w.r.t its own reference frame. + +The robot pose X_i is in SE(2) and the beacon positions b_k in R^2, + + X_i = | R_i t_i | // position and orientation + | 0 1 | + + b_k = (bx_k, by_k) // lmk coordinates in world frame + +The control signal u is a twist in se(2) comprising longitudinal +velocity vx and angular velocity wz, with no other velocity +components, integrated over the sampling time dt. + + u = (vx*dt, 0, w*dt) + +The control is corrupted by additive Gaussian noise u_noise, +with covariance + + Q = diagonal(sigma_v^2, sigma_s^2, sigma_yaw^2). + +This noise accounts for possible lateral slippage +through non-zero values of sigma_s. + +At the arrival of a control u, a new robot pose is created at + + X_j = X_i * Exp(u) = X_i + u. + +This new pose is then added to the graph. + +Landmark measurements are of the range and bearing type, +though they are put in Cartesian form for simplicity, + + y = (yx, yy) // lmk coordinates in robot frame + +Their noise n is zero mean Gaussian, and is specified +with a covariances matrix R. +We notice the rigid motion action y_ik = h(X_i,b_k) = X_i^-1 * b_k +(see appendix D). + +The world comprises 5 landmarks. +Not all of them are observed from each pose. +A set of pairs pose--landmark is created to establish which +landmarks are observed from each pose. +These pairs can be observed in the factor graph, as follows. + +The factor graph of the SAM problem looks like this: + + ------- b1 + b3 / | + | / b4 | + | / / \| + X0 ---- X1 ---- X2 + | \ / \ / + | b0 b2 + * + +where: + - X_i are SE2 robot poses + - b_k are R^2 landmarks or beacons + - * is a pose prior to anchor the map and make the problem observable + - segments indicate measurement factors: + - motion measurements from X_i to X_j + - landmark measurements from X_i to b_k + - absolute pose measurement from X0 to * (the origin of coordinates) + +We thus declare 9 factors pose---landmark, as follows: + + poses --- lmks + x0 --- b0 + x0 --- b1 + x0 --- b3 + x1 --- b0 + x1 --- b2 + x1 --- b4 + x2 --- b1 + x2 --- b2 + x2 --- b4 + + +The main variables are summarized again as follows + + Xi : robot pose at time i, SE(2) + u : robot control, (v*dt; 0; w*dt) in se(2) + Q : control perturbation covariance + b : landmark position, R^2 + y : Cartesian landmark measurement in robot frame, R^2 + R : covariance of the measurement noise + + +We define the state to estimate as a manifold composite: + + X in < SE2, SE2, SE2, R^2, R^2, R^2, R^2, R^2 > + + X = < X0, X1, X2, b0, b1, b2, b3, b4 > + +The estimation error dX is expressed +in the tangent space at X, + + dX in < se2, se2, se2, R^2, R^2, R^2, R^2, R^2 > + ~ < R^3, R^3, R^3, R^2, R^2, R^2, R^2, R^2 > = R^19 + + dX = [ dx0, dx1, dx2, db0, db1, db2, db3, db4 ] in R^19 + +with + dx_i: pose error in se(2) ~ R^3 + db_k: landmark error in R^2 + + +The prior, motion and measurement models are + + - for the prior factor: + p_0 = X_0 + + - for the motion factors - motion expectation equation: + d_ij = X_j (-) X_i = log(X_i.inv * X_j) + + - for the measurement factors - measurement expectation equation: + e_ik = h(X_i, b_k) = X_i^-1 * b_k + + +The algorithm below comprises first a simulator to +produce measurements, then uses these measurements +to estimate the state, using a graph representation +and Lie-based non-linear iterative least squares solver +that uses the pseudo-inverse method. + +This file has plain code with only one main() function. +There are no function calls other than those involving `manif`. + +Printing the prior state (before solving) and posterior state (after solving), +together with a ground-truth state defined by the simulator +allows for evaluating the quality of the estimates. + +This information is complemented with the evolution of +the optimizer's residual and optimal step norms. This allows +for evaluating the convergence of the optimizer. +""" + + +from manifpy import SE2, SE2Tangent + +import numpy as np +from numpy.linalg import inv, norm + + +Vector = np.array + + +def Jacobian(): + return np.zeros((SE2.DoF, SE2.DoF)) + + +def random(dim, s=0.1): + """Random vector Rdim in [-1*s, 1*s].""" + return np.random.uniform([-1*s]*dim, [1*s]*dim) + + +if __name__ == '__main__': + + print() + print('2D Smoothing and Mapping. 3 poses, 5 landmarks.') + print('-----------------------------------------------') + np.set_printoptions(precision=3, suppress=True) + + # START CONFIGURATION + + # some experiment constants + DoF = SE2.DoF + Dim = SE2.Dim + + NUM_POSES = 3 + NUM_LMKS = 5 + NUM_FACTORS = 9 + NUM_STATES = NUM_POSES * DoF + NUM_LMKS * Dim + NUM_MEAS = NUM_POSES * DoF + NUM_FACTORS * Dim + MAX_ITER = 20 # for the solver + + # Define the robot pose element + Xi = SE2.Identity() + X_simu = SE2.Identity() + + u_nom = Vector([0.1, 0.0, 0.05]) + u_sigmas = Vector([0.01, 0.01, 0.01]) + Q = np.diagflat(np.square(u_sigmas)) + W = np.diagflat(1./u_sigmas) # this is Q^(-T/2) + + # Declare the Jacobians of the motion wrt robot and control + J_x = Jacobian() + J_u = Jacobian() + + controls = [] + + # Define five landmarks in R^2 + landmarks = [0] * NUM_LMKS + landmarks_simu = [ + Vector([3.0, 0.0]), + Vector([2.0, -1.0]), + Vector([2.0, 1.0]), + Vector([3.0, -1.0]), + Vector([3.0, 1.0]), + ] + + y_sigmas = Vector([0.001, 0.001]) + R = np.diagflat(np.square(y_sigmas)) + S = np.diagflat(1./y_sigmas) # this is R^(-T/2) + + # Declare some temporaries + J_d_xi = Jacobian() + J_d_xj = Jacobian() + J_ix_x = Jacobian() + J_r_p0 = Jacobian() + J_e_ix = np.zeros((Dim, DoF)) + J_e_b = np.zeros((Dim, Dim)) + r = np.zeros(NUM_MEAS) + J = np.zeros((NUM_MEAS, NUM_STATES)) + + r""" + The factor graph of the SAM problem looks like this: + + ------- b1 + b3 / | + | / b4 | + | / / \| + X0 ---- X1 ---- X2 + | \ / \ / + | b0 b2 + * + + where: + - Xi are poses + - bk are landmarks or beacons + - * is a pose prior to anchor the map and make the problem observable + + Define pairs of nodes for all the landmark measurements + There are 3 pose nodes [0..2] and 5 landmarks [0..4]. + A pair pose -- lmk means that the lmk was measured from the pose + Each pair declares a factor in the factor graph + We declare 9 pairs, or 9 factors, as follows: + """ + + # 0-0,1,3 | 1-0,2,4 | 2-1,2,4 + pairs = [[0, 1, 3], [0, 2, 4], [1, 2, 4]] + + # Define the beacon's measurements + measurements = { + 0: {0: 0, 1: 0, 3: 0}, + 1: {0: 0, 2: 0, 4: 0}, + 2: {1: 0, 2: 0, 4: 0} + } + + # END CONFIGURATION + + # Simulator + + poses_simu = [] + poses_simu.append(X_simu) + poses = [] + poses.append(Xi + (SE2Tangent.Random()*0.1)) # use very noisy priors + + # Make 10 steps. Measure up to three landmarks each time. + for i in range(NUM_POSES): + + # make measurements + for k in pairs[i]: + + # simulate measurement + b = landmarks_simu[k] # lmk coordinates in world frame + y_noise = y_sigmas * random(Dim) # measurement noise + y = X_simu.inverse().act(b) # landmark measurement, before adding noise + + # add noise and compute prior lmk from prior pose + measurements[i][k] = y + y_noise # store noisy measurements + b = Xi.act(y + y_noise) # mapped landmark with noise + landmarks[k] = b + random(Dim) # use noisy priors + + # make motions + # do not make the last motion since we're done after 3rd pose + if i < NUM_POSES - 1: + + # move simulator, without noise + X_simu = X_simu + SE2Tangent(u_nom) + + # move prior, with noise + u_noise = u_sigmas * random(DoF) + Xi = Xi + SE2Tangent(u_nom + u_noise) + + # store + poses_simu.append(X_simu) + poses.append(Xi + (SE2Tangent.Random()*0.1)) # use noisy priors + controls.append(u_nom + u_noise) + + # Estimator + + # DEBUG INFO + print('prior') + for X in poses: + print('pose : ', X.translation().transpose(), ' ', X.angle()) + for l in landmarks: + print('lmk : ', l.transpose()) + print('-----------------------------------------------') + + # iterate + for iteration in range(MAX_ITER): + + # Clear residual vector and Jacobian matrix + r.fill(0) + J.fill(0) + + row = 0 + col = 0 + + """ + 1. evaluate prior factor + + NOTE (see Chapter 2, Section E, of Sola-18): + + To compute any residual, we consider the following variables: + r: residual + e: expectation + y: prior specification 'measurement' + W: sqrt information matrix of the measurement noise. + + In case of a non-trivial prior measurement, we need to consider + the nature of it: is it a global or a local specification? + + When prior information `y` is provided in the global reference, + we need a left-minus operation (.-) to compute the residual. + This is usually the case for pose priors, since it is natural + to specify position and orientation wrt a global reference, + + r = W * (e (.-) y) + = W * (e * y.inv).log() + + When `y` is provided as a local reference, + then right-minus (-.) is required, + + r = W * (e (-.) y) + = W * (y.inv * e).log() + + Notice that if y = Identity() + then local and global residuals are the same. + + + Here, expectation, measurement and info matrix are trivial, + as follows + + expectation + e = poses[0]; // first pose + + measurement + y = SE2d::Identity() // robot at the origin + + info matrix: + W = I // trivial + + residual uses left-minus since reference measurement is global + r = W * (poses[0] (.-) measurement) + = log(poses[0] * Id.inv) = poses[0].log() + + Jacobian matrix : + J_r_p0 = Jr_inv(log(poses[0])) // see proof below + + Proof: Let p0 = poses[0] and y = measurement. + We have the partials + + J_r_p0 = W^(T/2) * d(log(p0 * y.inv)/d(poses[0]) + + with W = i and y = I. + Since d(log(r))/d(r) = Jr_inv(r) for any r in the Lie algebra, + we have + J_r_p0 = Jr_inv(log(p0)) + + residual and Jacobian. + Notes: + We have residual = expectation - measurement, + in global tangent space + We have the Jacobian in J_r_p0 = J[row:row+DoF, col:col+DoF] + """ + + r[row:row+DoF] = poses[0].lminus(SE2.Identity(), J_r_p0).coeffs() + + J[row:row+DoF, col:col+DoF] = J_r_p0 + + row += DoF + + # loop poses + for i in range(NUM_POSES): + + # 2. evaluate motion factors + # do not make the last motion since we're done after 3rd pose + if i < NUM_POSES - 1: + + j = i + 1 # this is next pose's id + + # recover related states and data + Xi = poses[i] + Xj = poses[j] + u = SE2Tangent(controls[i]) + + # expectation + # (use right-minus since motion measurements are local) + d = Xj.rminus(Xi, J_d_xj, J_d_xi) # expected motion = Xj (-) Xi + + # residual + r[row:row+DoF] = W @ (d - u).coeffs() # residual + + # Jacobian of residual wrt first pose + col = i * DoF + J[row:row+DoF, col:col+DoF] = W @ J_d_xi + + # Jacobian of residual wrt second pose + col = j * DoF + J[row:row+DoF, col:col+DoF] = W @ J_d_xj + + # advance rows + row += DoF + + # 3. evaluate measurement factors + for k in pairs[i]: + + # recover related states and data + Xi = poses[i] + b = landmarks[k] + y = measurements[i][k] + + # expectation + e = Xi.inverse(J_ix_x).act(b, J_e_ix, J_e_b) # expected measurement = Xi.inv * bj + J_e_x = J_e_ix @ J_ix_x # chain rule + + # residual + r[row:row+Dim] = S @ (e - y) + + # Jacobian of residual wrt pose + col = i * DoF + J[row:row+Dim, col:col+DoF] = S @ J_e_x + + # Jacobian of residual wrt lmk + col = NUM_POSES * DoF + k * Dim + J[row:row+Dim, col:col+Dim] = S @ J_e_b + + # advance rows + row += Dim + + # 4. Solve + + # compute optimal step + # ATTENTION: This is an expensive step!! + # ATTENTION: Use QR factorization and + # column reordering for larger problems!! + dX = - inv(J.transpose() @ J) @ J.transpose() @ r + + # update all poses + for i in range(NUM_POSES): + # we go very verbose here + row = i * DoF + size = DoF + dx = dX[row:row+size] + poses[i] = poses[i] + SE2Tangent(dx) + + # update all landmarks + for k in range(NUM_LMKS): + # we go very verbose here + row = NUM_POSES * DoF + k * Dim + size = Dim + db = dX[row:row+size] + landmarks[k] = landmarks[k] + db + + # DEBUG INFO + print('residual norm: ', norm(r), ', step norm: ', norm(dX)) + + # conditional exit + if norm(dX) < 1e-6: + break + + print('-----------------------------------------------') + + # Print results + + # solved problem + print('posterior') + for X in poses: + print('pose : ', X.translation().transpose(), ' ', X.angle()) + for b in landmarks: + print('lmk : ', b.transpose()) + print('-----------------------------------------------') + + # ground truth + print('ground truth') + for X in poses_simu: + print('pose : ', X.translation().transpose(), ' ', X.angle()) + for b in landmarks_simu: + print('lmk : ', b.transpose()) + print('-----------------------------------------------') diff --git a/examples/se3_sam.py b/examples/se3_sam.py new file mode 100644 index 00000000..d87d8b2b --- /dev/null +++ b/examples/se3_sam.py @@ -0,0 +1,543 @@ +r""" + +\file se3_sam.py. + +Created on: Jan 11, 2021 +\author: Jeremie Deray + +--------------------------------------------------------- +This file is: +(c) 2021 Jeremie Deray + +This file is part of `manif`, a C++ template-only library +for Lie theory targeted at estimation for robotics. +Manif is: +(c) 2021 Jeremie Deray +--------------------------------------------------------- + +--------------------------------------------------------- +Demonstration example: + + 3D smoothing and mapping (SAM). + + See se2_sam.py for a 2D version of this example. + See se3_localization.py for a simpler localization example using EKF. +------------------------------------------------------------ + +This demo corresponds to the 3D version of the application +in chapter V, section B, in the paper Sola-18, +[https://arxiv.org/abs/1812.01537]. + +The following is an abstract of the content of the paper. +Please consult the paper for better reference. + + +We consider a robot in 3D space surrounded by a small +number of punctual landmarks or _beacons_. +The robot receives control actions in the form of axial +and angular velocities, and is able to measure the location +of the beacons w.r.t its own reference frame. + +The robot pose X_i is in SE(3) and the beacon positions b_k in R^3, + + X_i = | R_i t_i | // position and orientation + | 0 1 | + + b_k = (bx_k, by_k, bz_k) // lmk coordinates in world frame + +The control signal u is a twist in se(3) comprising longitudinal +velocity vx and angular velocity wz, with no other velocity +components, integrated over the sampling time dt. + + u = (vx*dt, 0, 0, 0, 0, w*dt) + +The control is corrupted by additive Gaussian noise u_noise, +with covariance + + Q = diagonal( + sigma_x^2, sigma_y^2, sigma_z^2, + sigma_roll^2, sigma_pitch^2, sigma_yaw^2 + ). + +This noise accounts for possible lateral slippage +through non-zero values of sigma_y, sigma_z, sigma_roll and sigma_pitch. + +At the arrival of a control u, a new robot pose is created at + + X_j = X_i * Exp(u) = X_i + u. + +This new pose is then added to the graph. + +Landmark measurements are of the range and bearing type, +though they are put in Cartesian form for simplicity, + + y = (yx, yy, yz) // lmk coordinates in robot frame + +Their noise n is zero mean Gaussian, and is specified +with a covariances matrix R. +We notice the rigid motion action y_ik = h(X_i,b_k) = X_i^-1 * b_k +(see appendix D). + +The world comprises 5 landmarks. +Not all of them are observed from each pose. +A set of pairs pose--landmark is created to establish which +landmarks are observed from each pose. +These pairs can be observed in the factor graph, as follows. + +The factor graph of the SAM problem looks like this: + + ------- b1 + b3 / | + | / b4 | + | / / \| + X0 ---- X1 ---- X2 + | \ / \ / + | b0 b2 + * + +where: + - X_i are SE3 robot poses + - b_k are R^3 landmarks or beacons + - * is a pose prior to anchor the map and make the problem observable + - segments indicate measurement factors: + - motion measurements from X_i to X_j + - landmark measurements from X_i to b_k + - absolute pose measurement from X0 to * (the origin of coordinates) + +We thus declare 9 factors pose---landmark, as follows: + + poses --- lmks + x0 --- b0 + x0 --- b1 + x0 --- b3 + x1 --- b0 + x1 --- b2 + x1 --- b4 + x2 --- b1 + x2 --- b2 + x2 --- b4 + + +The main variables are summarized again as follows + + Xi : robot pose at time i, SE(3) + u : robot control, (v*dt; 0; w*dt) in se(3) + Q : control perturbation covariance + b : landmark position, R^3 + y : Cartesian landmark measurement in robot frame, R^3 + R : covariance of the measurement noise + + +We define the state to estimate as a manifold composite: + + X in < SE3, SE3, SE3, R^3, R^3, R^3, R^3, R^3 > + + X = < X0, X1, X2, b0, b1, b2, b3, b4 > + +The estimation error dX is expressed +in the tangent space at X, + + dX in < se3, se3, se3, R^3, R^3, R^3, R^3, R^3 > + ~ < R^6, R^6, R^6, R^3, R^3, R^3, R^3, R^3 > = R^33 + + dX = [ dx0, dx1, dx2, db0, db1, db2, db3, db4 ] in R^33 + +with + dx_i: pose error in se(3) ~ R^6 + db_k: landmark error in R^3 + + +The prior, motion and measurement models are + + - for the prior factor: + p_0 = X_0 + + - for the motion factors - motion expectation equation: + d_ij = X_j (-) X_i = log(X_i.inv * X_j) + + - for the measurement factors - measurement expectation equation: + e_ik = h(X_i, b_k) = X_i^-1 * b_k + + +The algorithm below comprises first a simulator to +produce measurements, then uses these measurements +to estimate the state, using a graph representation +and Lie-based non-linear iterative least squares solver +that uses the pseudo-inverse method. + +This file has plain code with only one main() function. +There are no function calls other than those involving `manif`. + +Printing the prior state (before solving) and posterior state (after solving), +together with a ground-truth state defined by the simulator +allows for evaluating the quality of the estimates. + +This information is complemented with the evolution of +the optimizer's residual and optimal step norms. This allows +for evaluating the convergence of the optimizer. +""" + + +from manifpy import SE3, SE3Tangent + +import numpy as np +from numpy.linalg import inv, norm + + +Vector = np.array + + +def Jacobian(): + return np.zeros((SE3.DoF, SE3.DoF)) + + +def random(dim): + """Random vector Rdim in [-1, 1].""" + return np.random.uniform([-1]*dim, [1]*dim) + + +if __name__ == '__main__': + + print() + print('3D Smoothing and Mapping. 3 poses, 5 landmarks.') + print('-----------------------------------------------') + np.set_printoptions(precision=3, suppress=True) + + # START CONFIGURATION + + # some experiment constants + DoF = SE3.DoF + Dim = SE3.Dim + + NUM_POSES = 3 + NUM_LMKS = 5 + NUM_FACTORS = 9 + NUM_STATES = NUM_POSES * DoF + NUM_LMKS * Dim + NUM_MEAS = NUM_POSES * DoF + NUM_FACTORS * Dim + MAX_ITER = 20 # for the solver + + # Define the robot pose element + Xi = SE3.Identity() + X_simu = SE3.Identity() + + u_nom = Vector([0.1, 0.0, 0.0, 0.0, 0.0, 0.05]) + u_sigmas = Vector([0.01, 0.01, 0.01, 0.01, 0.01, 0.01]) + Q = np.diagflat(np.square(u_sigmas)) + W = np.diagflat(1./u_sigmas) # this is Q^(-T/2) + + # Declare the Jacobians of the motion wrt robot and control + J_x = Jacobian() + J_u = Jacobian() + + controls = [] + + # Define five landmarks in R^2 + landmarks = [0] * NUM_LMKS + landmarks_simu = [ + Vector([3.0, 0.0, 0.0]), + Vector([2.0, -1.0, -1.0]), + Vector([2.0, -1.0, 1.0]), + Vector([2.0, 1.0, 1.0]), + Vector([2.0, 1.0, -1.0]), + ] + + y_sigmas = Vector([0.001, 0.001, 0.001]) + R = np.diagflat(np.square(y_sigmas)) + S = np.diagflat(1./y_sigmas) # this is R^(-T/2) + + # Declare some temporaries + J_d_xi = Jacobian() + J_d_xj = Jacobian() + J_ix_x = Jacobian() + J_r_p0 = Jacobian() + J_e_ix = np.zeros((Dim, DoF)) + J_e_b = np.zeros((Dim, Dim)) + r = np.zeros(NUM_MEAS) + J = np.zeros((NUM_MEAS, NUM_STATES)) + + r""" + The factor graph of the SAM problem looks like this: + + ------- b1 + b3 / | + | / b4 | + | / / \| + X0 ---- X1 ---- X2 + | \ / \ / + | b0 b2 + * + + where: + - Xi are poses + - bk are landmarks or beacons + - * is a pose prior to anchor the map and make the problem observable + + Define pairs of nodes for all the landmark measurements + There are 3 pose nodes [0..2] and 5 landmarks [0..4]. + A pair pose -- lmk means that the lmk was measured from the pose + Each pair declares a factor in the factor graph + We declare 9 pairs, or 9 factors, as follows: + """ + + # 0-0,1,3 | 1-0,2,4 | 2-1,2,4 + pairs = [[0, 1, 3], [0, 2, 4], [1, 2, 4]] + + # Define the beacon's measurements + measurements = { + 0: {0: 0, 1: 0, 3: 0}, + 1: {0: 0, 2: 0, 4: 0}, + 2: {1: 0, 2: 0, 4: 0} + } + + # END CONFIGURATION + + # Simulator + + poses_simu = [] + poses_simu.append(X_simu) + poses = [] + poses.append(Xi + (SE3Tangent.Random()*0.1)) # use very noisy priors + + # Make 10 steps. Measure up to three landmarks each time. + for i in range(NUM_POSES): + + # make measurements + for k in pairs[i]: + + # simulate measurement + b = landmarks_simu[k] # lmk coordinates in world frame + y_noise = y_sigmas * random(Dim) # measurement noise + y = X_simu.inverse().act(b) # landmark measurement, before adding noise + + # add noise and compute prior lmk from prior pose + measurements[i][k] = y + y_noise # store noisy measurements + b = Xi.act(y + y_noise) # mapped landmark with noise + landmarks[k] = b + random(Dim) # use noisy priors + + # make motions + # do not make the last motion since we're done after 3rd pose + if i < NUM_POSES - 1: + + # move simulator, without noise + X_simu = X_simu + SE3Tangent(u_nom) + + # move prior, with noise + u_noise = u_sigmas * random(DoF) + + Xi = Xi + SE3Tangent(u_nom + u_noise) + + # store + poses_simu.append(X_simu) + poses.append(Xi + (SE3Tangent.Random()*0.1)) # use noisy priors + controls.append(u_nom + u_noise) + + # Estimator + + # DEBUG INFO + print('prior') + for X in poses: + print('pose : ', X.translation().transpose(), ' ', X.log().coeffs()[3:]) + for l in landmarks: + print('lmk : ', l.transpose()) + print('-----------------------------------------------') + + # iterate + for iteration in range(MAX_ITER): + + # Clear residual vector and Jacobian matrix + r.fill(0) + J.fill(0) + + row = 0 + col = 0 + + """ + 1. evaluate prior factor + + NOTE (see Chapter 2, Section E, of Sola-18): + + To compute any residual, we consider the following variables: + r: residual + e: expectation + y: prior specification 'measurement' + W: sqrt information matrix of the measurement noise. + + In case of a non-trivial prior measurement, we need to consider + the nature of it: is it a global or a local specification? + + When prior information `y` is provided in the global reference, + we need a left-minus operation (.-) to compute the residual. + This is usually the case for pose priors, since it is natural + to specify position and orientation wrt a global reference, + + r = W * (e (.-) y) + = W * (e * y.inv).log() + + When `y` is provided as a local reference, + then right-minus (-.) is required, + + r = W * (e (-.) y) + = W * (y.inv * e).log() + + Notice that if y = Identity() + then local and global residuals are the same. + + + Here, expectation, measurement and info matrix are trivial, + as follows + + expectation + e = poses[0]; // first pose + + measurement + y = SE3d::Identity() // robot at the origin + + info matrix: + W = I // trivial + + residual uses left-minus since reference measurement is global + r = W * (poses[0] (.-) measurement) + = log(poses[0] * Id.inv) = poses[0].log() + + Jacobian matrix : + J_r_p0 = Jr_inv(log(poses[0])) // see proof below + + Proof: Let p0 = poses[0] and y = measurement. + We have the partials + + J_r_p0 = W^(T/2) * d(log(p0 * y.inv)/d(poses[0]) + + with W = i and y = I. + Since d(log(r))/d(r) = Jr_inv(r) for any r in the Lie algebra, + we have + J_r_p0 = Jr_inv(log(p0)) + + residual and Jacobian. + Notes: + We have residual = expectation - measurement, + in global tangent space + We have the Jacobian in J_r_p0 = J[row:row+DoF, col:col+DoF] + """ + + r[row:row+DoF] = poses[0].lminus(SE3.Identity(), J_r_p0).coeffs() + + J[row:row+DoF, col:col+DoF] = J_r_p0 + + row += DoF + + # loop poses + for i in range(NUM_POSES): + + # 2. evaluate motion factors + # do not make the last motion since we're done after 3rd pose + if i < NUM_POSES - 1: + + j = i + 1 # this is next pose's id + + # recover related states and data + Xi = poses[i] + Xj = poses[j] + u = SE3Tangent(controls[i]) + + # expectation + # (use right-minus since motion measurements are local) + d = Xj.rminus(Xi, J_d_xj, J_d_xi) # expected motion = Xj (-) Xi + + # residual + r[row:row+DoF] = W @ (d - u).coeffs() # residual + + # Jacobian of residual wrt first pose + col = i * DoF + J[row:row+DoF, col:col+DoF] = W @ J_d_xi + + # Jacobian of residual wrt second pose + col = j * DoF + J[row:row+DoF, col:col+DoF] = W @ J_d_xj + + # advance rows + row += DoF + + # 3. evaluate measurement factors + for k in pairs[i]: + + # recover related states and data + Xi = poses[i] + b = landmarks[k] + y = measurements[i][k] + + # expectation + e = Xi.inverse(J_ix_x).act(b, J_e_ix, J_e_b) # expected measurement = Xi.inv * bj + J_e_x = J_e_ix @ J_ix_x # chain rule + + # residual + r[row:row+Dim] = S @ (e - y) + + # Jacobian of residual wrt pose + col = i * DoF + J[row:row+Dim, col:col+DoF] = S @ J_e_x + + # Jacobian of residual wrt lmk + col = NUM_POSES * DoF + k * Dim + J[row:row+Dim, col:col+Dim] = S @ J_e_b + + # advance rows + row += Dim + + # 4. Solve + + # compute optimal step + # ATTENTION: This is an expensive step!! + # ATTENTION: Use QR factorization and + # column reordering for larger problems!! + dX = - inv(J.transpose() @ J) @ J.transpose() @ r + + # update all poses + for i in range(NUM_POSES): + # we go very verbose here + row = i * DoF + size = DoF + dx = dX[row:row+size] + poses[i] = poses[i] + SE3Tangent(dx) + + # update all landmarks + for k in range(NUM_LMKS): + # we go very verbose here + row = NUM_POSES * DoF + k * Dim + size = Dim + db = dX[row:row+size] + landmarks[k] = landmarks[k] + db + + # DEBUG INFO + print('residual norm: ', norm(r), ', step norm: ', norm(dX)) + + # conditional exit + if norm(dX) < 1e-6: + break + + print('-----------------------------------------------') + + # Print results + + # solved problem + print('posterior') + for X in poses: + print( + 'pose : ', + X.translation().transpose(), + ' ', X.log().coeffs()[3:] + ) + for b in landmarks: + print('lmk : ', b.transpose()) + print('-----------------------------------------------') + + # ground truth + print('ground truth') + for X in poses_simu: + print( + 'pose : ', + X.translation().transpose(), ' ', + X.log().coeffs()[3:] + ) + for b in landmarks_simu: + print('lmk : ', b.transpose()) + print('-----------------------------------------------') From a581deb86545e330aea8acee022ab11f8db2304a Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 17 Jan 2021 11:35:40 -0500 Subject: [PATCH 40/67] remove some useless cast --- examples/se2_localization.py | 3 +-- examples/se3_localization.py | 3 +-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/examples/se2_localization.py b/examples/se2_localization.py index e4785536..873688f8 100644 --- a/examples/se2_localization.py +++ b/examples/se2_localization.py @@ -193,7 +193,7 @@ def Jacobian(): y = X_simulation.inverse().act(b) # landmark measurement, before adding noise - y = Vector(y) + y_noise # landmark measurement, noisy + y = y + y_noise # landmark measurement, noisy measurements[i] = y # store for the estimator just below # II. Estimation @@ -214,7 +214,6 @@ def Jacobian(): # expectation e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). - e = Vector(e) H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x E = H @ P @ H.transpose() diff --git a/examples/se3_localization.py b/examples/se3_localization.py index ca774b15..c70d6513 100644 --- a/examples/se3_localization.py +++ b/examples/se3_localization.py @@ -194,7 +194,7 @@ def Jacobian(): y = X_simulation.inverse().act(b) # landmark measurement, before adding noise - y = Vector(y) + y_noise # landmark measurement, noisy + y = y + y_noise # landmark measurement, noisy measurements[i] = y # store for the estimator just below # II. Estimation @@ -215,7 +215,6 @@ def Jacobian(): # expectation e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). - e = Vector(e) H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x E = H @ P @ H.transpose() From 6c5514423715c3485a25bacdf8b2fa50323f512d Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 17 Jan 2021 11:37:18 -0500 Subject: [PATCH 41/67] seed rand in examples --- examples/se2_localization.cpp | 2 ++ examples/se2_sam.cpp | 2 ++ examples/se3_localization.cpp | 2 ++ examples/se3_sam.cpp | 9 +++++---- 4 files changed, 11 insertions(+), 4 deletions(-) diff --git a/examples/se2_localization.cpp b/examples/se2_localization.cpp index 96816f0a..42f7cf4d 100644 --- a/examples/se2_localization.cpp +++ b/examples/se2_localization.cpp @@ -118,6 +118,8 @@ typedef Array Array3d; int main() { + std::srand((unsigned int) time(0)); + // START CONFIGURATION // // diff --git a/examples/se2_sam.cpp b/examples/se2_sam.cpp index 9054c4ce..eadb107d 100644 --- a/examples/se2_sam.cpp +++ b/examples/se2_sam.cpp @@ -229,6 +229,8 @@ static const int MAX_ITER = 20; // for the solver int main() { + std::srand((unsigned int) time(0)); + // DEBUG INFO cout << endl; cout << "2D Smoothing and Mapping. 3 poses, 5 landmarks." << endl; diff --git a/examples/se3_localization.cpp b/examples/se3_localization.cpp index 73a01958..b8e6b8ee 100644 --- a/examples/se3_localization.cpp +++ b/examples/se3_localization.cpp @@ -120,6 +120,8 @@ typedef Matrix Matrix6d; int main() { + std::srand((unsigned int) time(0)); + // START CONFIGURATION // // diff --git a/examples/se3_sam.cpp b/examples/se3_sam.cpp index 5146671d..8099ddbc 100644 --- a/examples/se3_sam.cpp +++ b/examples/se3_sam.cpp @@ -229,6 +229,8 @@ static const int MAX_ITER = 20; // for the solver int main() { + std::srand((unsigned int) time(0)); + // DEBUG INFO cout << endl; cout << "3D Smoothing and Mapping. 3 poses, 5 landmarks." << endl; @@ -349,7 +351,7 @@ int main() //// Simulator ################################################################### poses_simu. push_back(X_simu); - poses. push_back(Xi + SE3Tangentd::Random()); // use very noisy priors + poses. push_back(Xi + (SE3Tangentd::Random()*0.1)); // use very noisy priors // temporal loop for (int i = 0; i < NUM_POSES; ++i) @@ -358,7 +360,7 @@ int main() for (const auto& k : pairs[i]) { // simulate measurement - b = landmarks_simu[k]; // lmk coordinates in world frame + b = landmarks_simu[k]; // lmk coordinates in world frame y_noise = y_sigmas * ArrayY::Random(); // measurement noise y = X_simu.inverse().act(b); // landmark measurement, before adding noise @@ -380,7 +382,7 @@ int main() // store poses_simu. push_back(X_simu); - poses. push_back(Xi + SE3Tangentd::Random()); // use very noisy priors + poses. push_back(Xi + (SE3Tangentd::Random()*0.1)); // use very noisy priors controls. push_back(u_nom + u_noise); } } @@ -528,7 +530,6 @@ int main() // advance rows row += Dim; } - } // 4. Solve ----------------------------------------------------------------- From f65c23cc8182203eeb6cd4e81d850080d37aa0bf Mon Sep 17 00:00:00 2001 From: artivis Date: Sun, 17 Jan 2021 11:38:05 -0500 Subject: [PATCH 42/67] readme update --- README.md | 337 +++++++++++++++++++++++++++++++++++----------------- projects.md | 15 ++- 2 files changed, 238 insertions(+), 114 deletions(-) diff --git a/README.md b/README.md index 153be747..c3f3ca20 100644 --- a/README.md +++ b/README.md @@ -1,49 +1,58 @@ # manif -## A small header-only library for Lie theory. -[![GHA](https://github.com/artivis/manif/workflows/build-and-test/badge.svg?branch=devel)](https://github.com/artivis/manif/workflows/build-and-test/badge.svg?branch=devel) -[![appveyor](https://ci.appveyor.com/api/projects/status/l0q7b0shhonvejrd?svg=true)](https://ci.appveyor.com/project/artivis/manif) -[![Documentation](https://codedocs.xyz/artivis/manif.svg)](https://codedocs.xyz/artivis/manif/) -[![codecov](https://codecov.io/gh/artivis/manif/branch/devel/graph/badge.svg)](https://codecov.io/gh/artivis/manif) -![GitHub](https://img.shields.io/github/license/mashape/apistatus.svg) -[![JOSS](http://joss.theoj.org/papers/e3fc778689407f0edd19df8c2089c160/status.svg)](http://joss.theoj.org/papers/e3fc778689407f0edd19df8c2089c160) +## A small header-only library for Lie theory + +[![GHA][badge-ci-img]][badge-ci] +[![appveyor][badge-ci-win-img]][badge-ci-win] +[![Documentation][badge-doc-img]][manif-doc] +[![codecov][badge-cov-img]][badge-cov] +![GitHub][badge-license] +[![JOSS][badge-joss-img]][deray20] ## Package Summary + **manif** is a Lie theory library for state-estimation targeted at robotics applications. It is developed as a header-only C++11 library with Python 3 wrappers. At the moment, it provides the groups: - - R(n): Euclidean space with addition. - - SO(2): rotations in the plane. - - SE(2): rigid motion (rotation and translation) in the plane. - - SO(3): rotations in 3D space. - - SE(3): rigid motion (rotation and translation) in 3D space. - - SE_2(3): extended pose (rotation, translation and velocity) in 3D space, introduced (to the best of knowledge) in this [paper](https://arxiv.org/pdf/1410.1465.pdf). NOTE: The implementation here differs slightly from the developments in the [paper](https://arxiv.org/pdf/1410.1465.pdf). + +- ℝ(n): Euclidean space with addition. +- SO(2): rotations in the plane. +- SE(2): rigid motion (rotation and translation) in the plane. +- SO(3): rotations in 3D space. +- SE(3): rigid motion (rotation and translation) in 3D space. +- SE_2(3): extended pose (rotation, translation and velocity) in 3D space, + introduced (to the best of knowledge) in this [paper][barrau15]. + NOTE: The implementation here differs slightly from + the developments in the [paper][barrau15]. Other Lie groups can and will be added, contributions are welcome. -**manif** is based on the mathematical presentation of the Lie theory available in [this paper](http://arxiv.org/abs/1812.01537). +**manif** is based on the mathematical presentation of the Lie theory available in [this paper][jsola18]. We recommend every user of **manif** to read the paper (17 pages) before starting to use the library. -The paper provides a thorough introduction to Lie theory, in a simplified way so as to make the entrance to Lie theory easy for the average robotician who is interested in designing rigorous and elegant state estimation algorithms. -In a rush? Check out our [Lie group cheat sheet](paper/Lie_theory_cheat_sheet.pdf). +The paper provides a thorough introduction to Lie theory, +in a simplified way so as to make the entrance to Lie theory easy for the average roboticist +who is interested in designing rigorous and elegant state estimation algorithms. +In a rush? Check out our [Lie group cheat sheet][cheat_sheet]. **manif** has been designed for an easy integration to larger projects: - - A single dependency on [Eigen](http://eigen.tuxfamily.org), - - header-only for easy integration, - - templated on the underlying scalar type so that one can use its own, - - and C++11, since not everyone gets to enjoy the latest C++ features, especially in industry. + +- A single dependency on [Eigen][eigen], +- header-only for easy integration, +- templated on the underlying scalar type so that one can use its own, +- and C++11, since not everyone gets to enjoy the latest C++ features, especially in industry. It provides analytic computation of Jacobians for all the operations. It also supports template scalar types. In particular, it can work with the -[`ceres::Jet`](http://ceres-solver.org/automatic_derivatives.html#dual-numbers-jets) type, allowing for automatic Jacobian computation -- +[`ceres::Jet`][ceres-jet] type, allowing for automatic Jacobian computation -- [see related paragraph on Jacobians below](#jacobians). -All Lie group classes defined in **manif** have in common that they inherit from a templated base class ([CRTP](https://en.wikipedia.org/wiki/Curiously_recurring_template_pattern)). +All Lie group classes defined in **manif** have in common that they inherit from a templated base class ([CRTP][crtp]). It allows one to write generic code abstracting the Lie group details. Please find more information in the related [wiki page](https://github.com/artivis/manif/wiki/Writing-generic-code) -#### Details +### Details - Maintainer status: maintained - Maintainer: Jeremie Deray [deray.jeremie@gmail.com](mailto:deray.jeremie@gmail.com) @@ -51,8 +60,8 @@ Please find more information in the related [wiki page](https://github.com/artiv - Jeremie Deray [deray.jeremie@gmail.com](mailto:deray.jeremie@gmail.com) - Joan Sola [jsola@iri.upc.edu](mailto:jsola@iri.upc.edu) - License: MIT -- Bug / feature tracker: [github.com/artivis/manif/issues](https://github.com/artivis/manif/issues) -- Source: [github.com/artivis/manif.git](https://github.com/artivis/manif.git) (branch: devel) +- Bug / feature tracker: [github.com/artivis/manif/issues][manif-issue] +- Source: [github.com/artivis/manif.git][manif-repo] (branch: devel) ___ @@ -65,6 +74,7 @@ ___ They use manifContributing

+ ___ ## Quick Start @@ -72,24 +82,24 @@ ___ ### Dependencies - Eigen 3 : - + Linux ( Ubuntu and similar ) + - Linux ( Ubuntu and similar ) ```terminal apt-get install libeigen3-dev ``` - + OS X + - OS X ```terminal brew install eigen ``` -- [lt::optional](https://github.com/TartanLlama/optional) : included in the `external` folder +- [lt::optional][optional-repo] : included in the `external` folder For the Python 3 wrappers: ```terminal -$ pip install -r requirements +pip install -r requirements ``` ### Installation @@ -97,26 +107,21 @@ $ pip install -r requirements #### From source ```terminal -$ git clone https://github.com/artivis/manif.git -$ cd manif && mkdir build && cd build -$ cmake -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON .. -$ make -$ make install +git clone https://github.com/artivis/manif.git +cd manif && mkdir build && cd build +cmake -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON .. +make install ``` -###### Using catkin_tools -```terminal -$ git clone https://github.com/artivis/manif.git -$ catkin build manif --cmake-args -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON -``` +##### Using catkin_tools -###### Generate the documentation ```terminal -$ cd manif -$ doxygen .doxygen.txt +git clone https://github.com/artivis/manif.git +catkin build manif --cmake-args -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON ``` -#### Use **manif** in your project +#### Use **manif** in your C++ project + In your project `CMakeLists.txt` : ```cmake @@ -131,13 +136,59 @@ add_executable(${PROJECT_NAME} src/foo.cpp) target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${manif_INCLUDE_DIRS}) ``` -#### Python 3 +In your code: + +```cpp +#include + +... + +auto state = manif::SE3d::Identity(); + +... + +``` + +#### Use **manif** in your Python 3 project + +The Python wrappers are generated using [`pybind11`][pybind11]. So first we need to install it, +but we want it available directly in our environment root so that `CMake` can find it. +To do so we can use, + +```terminal +python3 -m pip install "pybind11[global]" +``` + +which is not recommended if we are installing with our system Python, +as it will add files to `/usr/local/include/pybind11` and `/usr/local/share/cmake/pybind11`. +Another way is to use `CMake` to install it, + +```terminal +git clone https://github.com/pybind/pybind11.git +cd pybind11 && mkdir build && cd build +cmake .. +make install +``` + +We can now generate `manif` Python bindings, ```terminal -$ git clone https://github.com/artivis/manif.git -$ cd manif -$ pip install -r requirements -$ python setup.py install +git clone https://github.com/artivis/manif.git +cd manif +python3 -m pip install -r requirements +python3 -m pip install . +``` + +##### Use **manifpy** in your project + +```python +from manifpy import SE3 + +... + +state = SE3.Identity() + +... ``` ## Features @@ -147,33 +198,37 @@ $ python setup.py install | Operation | | Code | | :--- | :---: | :---: | | | Base Operation | | -| Inverse | | `X.inverse()` | -| Composition | | `X * Y`
`X.compose(Y)` | -| Hat | | `w.hat()` | -| Act on vector | | `X.act(v)` | -| Retract to group element | | `w.exp()` | -| Lift to tangent space | | `X.log()` | -| Manifold Adjoint | | `X.adj()` | -| Tangent adjoint | | `w.smallAdj()` | +| Inverse | ![\mathbf\Phi^{-1}][latex1] | `X.inverse()` | +| Composition | ![\mathbf\mathcal{X}\circ\mathbf\mathcal{Y}][latex2] | `X * Y`
`X.compose(Y)` | +| Hat | ![\varphi^\wedge][latex3] | `w.hat()` | +| Act on vector | ![\mathbf\mathcal{X}\circ\mathbf v][latex4] | `X.act(v)` | +| Retract to group element | ![\exp(\mathbf\varphi^\wedge][latex5] | `w.exp()` | +| Lift to tangent space | ![\log(\mathbf\mathcal{X})^\vee][latex6] | `X.log()` | +| Manifold Adjoint | ![\operatorname{Adj}(\mathbf\mathcal{X})][latex7] | `X.adj()` | +| Tangent adjoint | ![\operatorname{adj}(\mathbf\varphi^\wedge][latex8] | `w.smallAdj()` | | | Composed Operation | | -| Manifold right plus | | `X + w`
`X.plus(w)`
`X.rplus(w)` | -| Manifold left plus | | `w + X`
`w.plus(X)`
`w.lplus(X)` | -| Manifold right minus | | `X - Y`
`X.minus(Y)`
`X.rminus(Y)` | -| Manifold left minus | | `X.lminus(Y)` | -| Between | | `X.between(Y)` | -| Inner Product | | `w.inner(t)` | -| Norm | | `w.weightedNorm()`
`w.squaredWeightedNorm()` | - -Above, \mathcal{Y} represent group elements, small phi represent elements in the Lie algebra of the Lie group, small phi or `w,t` represent the same elements of the tangent space but expressed in Cartesian coordinates in , and v or `v` represents any element of . +| Manifold right plus | ![\mathbf\mathcal{X}\circ\exp(\mathbf\varphi^\wedge)][latex9] | `X + w`
`X.plus(w)`
`X.rplus(w)` | +| Manifold left plus | ![\exp(\mathbf\varphi^\wedge)\circ\mathbf\mathcal{X}][latex10] | `w + X`
`w.plus(X)`
`w.lplus(X)` | +| Manifold right minus | ![\log(\mathbf\mathcal{Y}^{-1}\circ\mathbf\mathcal{X})^\vee][latex11] | `X - Y`
`X.minus(Y)`
`X.rminus(Y)` | +| Manifold left minus | ![\log(\mathbf\mathcal{X}\circ\mathbf\mathcal{Y}^{-1})^\vee][latex12] | `X.lminus(Y)` | +| Between | ![\mathbf\mathcal{X}^{-1}\circ\mathbf\mathcal{Y}][latex13] | `X.between(Y)` | +| Inner Product | ![\langle\varphi,\tau\rangle][latex14] | `w.inner(t)` | +| Norm | ![\left\lVert\varphi\right\rVert][latex15] | `w.weightedNorm()`
`w.squaredWeightedNorm()` | + +Above, ![\mathbf\mathcal{X},\mathbf\mathcal{Y}][latex16] represent group elements, +![\mathbf\varphi^\wedge,\tau^\wedge][latex17] represent elements in the Lie algebra of the Lie group, +![\mathbf\varphi,\tau][latex18] or `w,t` represent the same elements of the tangent space +but expressed in Cartesian coordinates in ![\mathbb{R}^n][latex19], +and ![\mathbf{v}][latex20] or `v` represents any element of ![\mathbb{R}^n][latex21]. ### Jacobians All operations come with their respective analytical Jacobian matrices. Throughout **manif**, **Jacobians are differentiated with respect to a local perturbation on the tangent space**. -Currently, **manif** implements the **right Jacobian** (see [here](http://arxiv.org/abs/1812.01537) for reference), whose definition reads: +Currently, **manif** implements the **right Jacobian** (see [here][jsola18] for reference), whose definition reads: -

  +![\frac{\delta f(\mathbf\mathcal{X})}{\delta\mathbf\mathcal{X}}][latex22] The Jacobians of any of the aforementionned operations can then be evaluated, e.g., @@ -209,48 +264,48 @@ or conversely, The **manif** package differentiates Jacobians with respect to a local perturbation on the tangent space. -These Jacobians map tangent spaces, as described in [this paper](http://arxiv.org/abs/1812.01537). +These Jacobians map tangent spaces, as described in [this paper][jsola18]. However, many non-linear solvers -(e.g. [Ceres](http://ceres-solver.org/)) expect functions to be differentiated with respect to the underlying +(e.g. [Ceres][ceres]) expect functions to be differentiated with respect to the underlying representation vector of the group element -(e.g. with respect to quaternion vector for ). +(e.g. with respect to quaternion vector for ![SO3][latex23]). + +For this reason **manif** is compliant with [Ceres][ceres] +auto-differentiation and the [`ceres::Jet`][ceres-jet] type. -For this reason **manif** is compliant with [Ceres](http://ceres-solver.org/) -auto-differentiation and the -[`ceres::Jet`](http://ceres-solver.org/automatic_derivatives.html#dual-numbers-jets) type. +For reference of the size of the Jacobians returned when using `ceres::Jet`, **manif** implements rotations in the following way: -For reference of the size of the Jacobians returned when using ```ceres::Jet```, **manif** implements rotations in the following way: - - SO(2) and SE(2): as a complex number with `real = cos(theta)` and `imag = sin(theta)` values. - - SO(3), SE(3) and SE_2(3): as a unit quaternion, using the underlying `Eigen::Quaternion` type. +- SO(2) and SE(2): as a complex number with `real = cos(theta)` and `imag = sin(theta)` values. +- SO(3), SE(3) and SE_2(3): as a unit quaternion, using the underlying `Eigen::Quaternion` type. -Therefore, the respective Jacobian sizes using ```ceres::Jet``` are as follows: - - SO(2) : size 2 - - SO(3) : size 4 - - SE(2) : size 4 - - SE(3) : size 7 - - SE_2(3): size 10 +Therefore, the respective Jacobian sizes using `ceres::Jet` are as follows: + +- SO(2) : size 2 +- SO(3) : size 4 +- SE(2) : size 4 +- SE(3) : size 7 +- SE_2(3): size 10 For more information, please refer to the [Ceres wiki page](https://github.com/artivis/manif/wiki/Using-manif-with-Ceres). ## Documentation -The API documentation can be found online at [codedocs.xyz/artivis/manif](https://codedocs.xyz/artivis/manif/). +The API documentation can be found online at [codedocs.xyz/artivis/manif][manif-doc]. Some more general documentation and tips on the use of the library is available on the [wiki-page](https://github.com/artivis/manif/wiki). - To generate the documentation on your machine, type in the terminal ```terminal -$ cd manif -$ doxygen .doxygen.txt +cd manif +doxygen .doxygen.txt ``` and find it at `manif/doc/html/index.html`. Throughout the code documentation we refer to 'the paper' which you can -find in the section Publications. +find in the section [Publications](#publications). ## Tutorials and application demos @@ -258,19 +313,18 @@ We provide some self-contained and self-explained executables implementing some Their source code is located in `manif/examples/`. These demos are: -- [`se2_localization.cpp`](examples/se2_localization.cpp): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. -- [`se3_localization.cpp`](examples/se3_localization.cpp): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. -- [`se2_sam.cpp`](examples/se2_sam.cpp): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. -- [`se3_sam.cpp`](examples/se3_sam.cpp): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. -- [`se3_sam_selfcalib.cpp`](examples/se3_sam_selfcalib.cpp): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. -- [`se_2_3_localization.cpp`](examples/se_2_3_localization.cpp): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). +- [`se2_localization.cpp`](examples/se2_localization.cpp)/[`se2_localization.py`](examples/se2_localization.py): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. +- [`se3_localization.cpp`](examples/se3_localization.cpp)/[`se3_localization.py`](examples/se3_localization.py): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. +- [`se2_sam.cpp`](examples/se2_sam.cpp): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. +- [`se3_sam.cpp`](examples/se3_sam.cpp): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. +- [`se3_sam_selfcalib.cpp`](examples/se3_sam_selfcalib.cpp): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. +- [`se_2_3_localization.cpp`](examples/se_2_3_localization.cpp): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). ## Publications -If you use this software, please consider citing -[this paper](https://joss.theoj.org/papers/10.21105/joss.01371#) as follows: +If you use this software, please consider citing [this paper][deray20] as follows: -``` +```latex @article{Deray-20-JOSS, doi = {10.21105/joss.01371}, url = {https://doi.org/10.21105/joss.01371}, @@ -283,12 +337,11 @@ If you use this software, please consider citing title = {Manif: A micro {L}ie theory library for state estimation in robotics applications}, journal = {Journal of Open Source Software} } - ``` -You can also consider citing [this paper](http://arxiv.org/abs/1812.01537) as follows: +You can also consider citing [this paper][jsola18] as follows: -``` +```latex @techreport{SOLA-18-Lie, Address = {Barcelona}, Author = {Joan Sol\`a and Jeremie Deray and Dinesh Atchuthan}, @@ -299,8 +352,10 @@ You can also consider citing [this paper](http://arxiv.org/abs/1812.01537) as fo Year = {2018} } ``` + Notice that this reference is the one referred to throughout the code documentation. -Since this is a versioned work, please refer to [version 4, available here](http://arxiv.org/abs/1812.01537v4), of the paper when cross-referencing with the **manif** documentation. +Since this is a versioned work, please refer to [version 4, available here][jsola18v], +of the paper when cross-referencing with the **manif** documentation. This will give the appropriate equation numbers. ### Lie group cheat sheets @@ -315,17 +370,77 @@ Your project is not listed? Let us know about it! ## Contributing -**manif** is developed according to Vincent Driessen's [Gitflow Workflow](http://nvie.com/posts/a-successful-git-branching-model/). +**manif** is developed according to Vincent Driessen's [Gitflow Workflow][git-workflow]. This means, -- the `master` branch is for releases only. -- development is done on feature branches. -- finished features are integrated via PullRequests into the branch `devel`. + +- the `master` branch is for releases only. +- development is done on feature branches. +- finished features are integrated via PullRequests into the branch `devel`. For a PullRequest to get merged into `devel`, it must pass -- Review by one of the maintainers. - + Are the changes introduced in scope of **manif**? - + Is the documentation updated? - + Are enough reasonable tests added? - + Will these changes break the API? - + Do the new changes follow the current style of naming? -- Compile / Test / Run on all target environments. + +- Review by one of the maintainers. + - Are the changes introduced in scope of **manif**? + - Is the documentation updated? + - Are enough reasonable tests added? + - Will these changes break the API? + - Do the new changes follow the current style of naming? +- Compile / Test / Run on all target environments. + +[//]: # (URLs) + +[jsola18]: http://arxiv.org/abs/1812.01537 +[jsola18v]: http://arxiv.org/abs/1812.01537v4 +[barrau15]: https://arxiv.org/pdf/1410.1465.pdf +[deray20]: https://joss.theoj.org/papers/10.21105/joss.01371 + +[eigen]: http://eigen.tuxfamily.org +[ceres]: http://ceres-solver.org/ +[ceres-jet]: http://ceres-solver.org/automatic_derivatives.html#dual-numbers-jets +[crtp]: https://en.wikipedia.org/wiki/Curiously_recurring_template_pattern + +[manif-repo]: https://github.com/artivis/manif.git +[manif-issue]: https://github.com/artivis/manif/issues +[manif-doc]: https://codedocs.xyz/artivis/manif +[cheat_sheet]: paper/Lie_theory_cheat_sheet.pdf + +[optional-repo]: https://github.com/TartanLlama/optional + +[pybind11]: https://pybind11.readthedocs.io/en/stable/index.html + +[git-workflow]: http://nvie.com/posts/a-successful-git-branching-model/ + +[badge-ci]: https://github.com/artivis/manif/workflows/build-and-test/badge.svg?branch=devel +[badge-ci-img]: https://github.com/artivis/manif/workflows/build-and-test/badge.svg?branch=devel +[badge-ci-win]: https://ci.appveyor.com/project/artivis/manif +[badge-ci-win-img]: https://ci.appveyor.com/api/projects/status/l0q7b0shhonvejrd?svg=true +[badge-doc-img]: https://codedocs.xyz/artivis/manif.svg +[badge-cov]: https://codecov.io/gh/artivis/manif +[badge-cov-img]: https://codecov.io/gh/artivis/manif/branch/devel/graph/badge.svg +[badge-license]: https://img.shields.io/github/license/mashape/apistatus.svg +[badge-joss]: http://joss.theoj.org/papers/e3fc778689407f0edd19df8c2089c160 +[badge-joss-img]: http://joss.theoj.org/papers/e3fc778689407f0edd19df8c2089c160/status.svg + +[latex1]: https://latex.codecogs.com/png.latex?\mathbf&space;\mathcal{X}^{-1} +[latex2]: https://latex.codecogs.com/png.latex?\mathbf&space;\mathcal{X}&space;\circ&space;\mathbf&space;\mathcal{Y} +[latex3]: https://latex.codecogs.com/png.latex?\varphi^\wedge +[latex4]: https://latex.codecogs.com/png.latex?\mathbf\mathcal{X}\circ\mathbf&space;v +[latex5]: https://latex.codecogs.com/png.latex?\exp(\mathbf\varphi^\wedge) +[latex6]: https://latex.codecogs.com/png.latex?\log(\mathbf&space;\mathcal{X})^\vee +[latex7]: https://latex.codecogs.com/png.latex?\operatorname{Adj}(\mathbf&space;\mathcal{X}) +[latex8]: https://latex.codecogs.com/png.latex?\operatorname{adj}(\mathbf&space;\varphi^\wedge) +[latex9]: https://latex.codecogs.com/png.latex?\mathbf\mathcal{X}\oplus\mathbf\varphi=\mathbf\mathcal{X}\circ\exp(\mathbf\varphi^\wedge) +[latex10]: https://latex.codecogs.com/png.latex?\mathbf\varphi\oplus\mathbf\mathcal{X}=\exp(\mathbf\varphi^\wedge)\circ\mathbf\mathcal{X} +[latex11]: https://latex.codecogs.com/png.latex?\mathbf\mathcal{X}\ominus\mathbf\mathcal{Y}=\log(\mathbf\mathcal{Y}^{-1}\circ\mathbf\mathcal{X})^\vee +[latex12]: https://latex.codecogs.com/png.latex?\mathbf\mathcal{X}\ominus\mathbf\mathcal{Y}=\log(\mathbf\mathcal{X}\circ\mathbf\mathcal{Y}^{-1})^\vee +[latex13]: https://latex.codecogs.com/png.latex?\mathbf\mathcal{X}^{-1}\circ\mathbf\mathcal{Y} +[latex14]: https://latex.codecogs.com/png.latex?\langle\varphi,\tau\rangle +[latex15]: https://latex.codecogs.com/png.latex?\left\lVert\varphi\right\rVert +[latex16]: https://latex.codecogs.com/png.latex?\mathbf\mathcal{X},\mathbf\mathcal{Y} +[latex17]: https://latex.codecogs.com/png.latex?\mathbf\varphi^\wedge,\tau^\wedge +[latex18]: https://latex.codecogs.com/png.latex?\mathbf\varphi,\tau +[latex19]: https://latex.codecogs.com/png.latex?\mathbb{R}^n +[latex20]: https://latex.codecogs.com/png.latex?\mathbf{v} +[latex21]: https://latex.codecogs.com/png.latex?\mathbb{R}^n +[latex22]: https://latex.codecogs.com/svg.latex?\frac{\delta&space;f(\mathbf\mathcal{X})}{\delta\mathbf\mathcal{X}}\triangleq\lim_{\varphi\to0}\frac{&space;f(\mathbf\mathcal{X}\oplus\varphi)\ominus&space;f(\mathbf\mathcal{X})}{\varphi}\triangleq\lim_{\varphi\to0}\frac{\log(f(\mathbf\mathcal{X})^{-1}&space;f(\mathbf\mathcal{X}\exp(\varphi^\wedge)))^\vee}{\varphi} +[latex23]: https://latex.codecogs.com/png.latex?SO(3) diff --git a/projects.md b/projects.md index c05dd4fe..807bc84b 100644 --- a/projects.md +++ b/projects.md @@ -1,10 +1,19 @@ # A curated list of work and projects using **manif** -## They cite us! +## They cite us -Find a list of publications that cite the [paper](http://arxiv.org/abs/1812.01537) -accompanying **manif** on [Google Scholar](https://scholar.google.com/scholar?oi=bibs&cites=16456301708818968338). +You may find on Google Scholar publications citing either: + +- the [Lie theory paper][jsola18] accompanying **manif**: see [here][jsola18-scholar] +- the [**manif** library paper][deray20]: see [here][deray20-scholar] ## They use **manif** Your project is not listed here? Let us know about it! + +[//]: # (URLs) + +[jsola18]: http://arxiv.org/abs/1812.01537 +[jsola18-scholar]: https://scholar.google.com/scholar?oi=bibs&cites=16456301708818968338 +[deray20]: https://joss.theoj.org/papers/10.21105/joss.01371 +[deray20-scholar]: https://scholar.google.fr/scholar?oi=bibs&hl=fr&cites=1235228860941456363 From a4f232dab22c5a5ff4398c2ccffbba9e907f5748 Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 18 Jan 2021 11:58:25 -0500 Subject: [PATCH 43/67] some more gitignore --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index aeefac73..8a4b54df 100644 --- a/.gitignore +++ b/.gitignore @@ -7,3 +7,6 @@ build doc doxygen_warnings.txt *.cache +.vscode +*.egg-info +*.so \ No newline at end of file From dd31ebb00a39e7851d5c5923f98c4cdeb2cfcb1a Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 18 Jan 2021 11:58:44 -0500 Subject: [PATCH 44/67] fix --- python/bindings_tangent_base.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index a56e4483..e0884543 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -32,7 +32,7 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def("generator", &_Tangent::generator); - // py_class.def("innerWeights", &_Tangent::w); + // py_class.def("innerWeights", &_Tangent::innerWeights); py_class.def("inner", &_Tangent::template inner<_Tangent>); py_class.def("weightedNorm", &_Tangent::weightedNorm); From 1c4700d14b95f6ea2d2f5518379b85fcb2710f9b Mon Sep 17 00:00:00 2001 From: artivis Date: Fri, 22 Jan 2021 19:12:18 -0500 Subject: [PATCH 45/67] add se3_sam_selfcalib.py --- examples/se3_sam_selfcalib.py | 570 ++++++++++++++++++++++++++++++++++ 1 file changed, 570 insertions(+) create mode 100644 examples/se3_sam_selfcalib.py diff --git a/examples/se3_sam_selfcalib.py b/examples/se3_sam_selfcalib.py new file mode 100644 index 00000000..d0576aea --- /dev/null +++ b/examples/se3_sam_selfcalib.py @@ -0,0 +1,570 @@ +r""" + +\file se3_sam_selfcalib.py. + +Created on: Jan 11, 2021 +\author: Jeremie Deray + +--------------------------------------------------------- +This file is: +(c) 2021 Jeremie Deray + +This file is part of `manif`, a C++ template-only library +for Lie theory targeted at estimation for robotics. +Manif is: +(c) 2021 Jeremie Deray +--------------------------------------------------------- + +--------------------------------------------------------- +Demonstration example: + + 3D smoothing and mapping (SAM) with sensor self-calibration. + + See se3_sam.cpp for a version of this example without self-calibration. +------------------------------------------------------------ + +This demo corresponds to the 3D version of the application +in chapter V, section B, in the paper Sola-18, +[https://arxiv.org/abs/1812.01537]. + +The following is an abstract of the content of the paper. +Please consult the paper for better reference. + + +We consider a robot in 3D space surrounded by a small +number of punctual landmarks or _beacons_. +The robot receives control actions in the form of axial +and angular velocities, and is able to measure the location +of the beacons w.r.t its own reference frame. + +The robot pose X_i is in SE(3) and the beacon positions b_k in R^3, + + X_i = | R_i t_i | // position and orientation + | 0 1 | + + b_k = (bx_k, by_k, bz_k) // lmk coordinates in world frame + +The control signal u is a twist in se(3) comprising longitudinal +velocity vx and angular velocity wz, with no other velocity +components, integrated over the sampling time dt. +The control suffers from unknown offsets which want to be calibrated, +c = (vc, wc), in the two variables of interest, vx*dt, w*dt. + + u = (vx*dt + vc, 0, 0, 0, 0, w*dt + vc) + +The control is corrupted by additive Gaussian noise u_noise, +with covariance + + Q = diagonal( + sigma_x^2, sigma_y^2, sigma_z^2, + sigma_roll^2, sigma_pitch^2, sigma_yaw^2 + ). + +This noise accounts for possible lateral slippage +through non-zero values of sigma_y, sigma_z, sigma_roll and sigma_pitch. + +At the arrival of a control u, a new robot pose is created at + + X_j = X_i * Exp(u) = X_i + u. + +This new pose is then added to the graph. + +Landmark measurements are of the range and bearing type, +though they are put in Cartesian form for simplicity, + + y = (yx, yy, yz) // lmk coordinates in robot frame + +Their noise n is zero mean Gaussian, and is specified +with a covariances matrix R. +We notice the rigid motion action y_ik = h(X_i,b_k) = X_i^-1 * b_k +(see appendix D). + +The world comprises 5 landmarks. +Not all of them are observed from each pose. +A set of pairs pose--landmark is created to establish which +landmarks are observed from each pose. +These pairs can be observed in the factor graph, as follows. + +The factor graph of the SAM problem looks like this +(calibration params not shown): + + ------- b1 + b3 / | + | / b4 | + | / / \| + X0 ---- X1 ---- X2 + | \ / \ / + | b0 b2 + * + +where: + - X_i are SE3 robot poses + - b_k are R^3 landmarks or beacons + - * is a pose prior to anchor the map and make the problem observable + - segments indicate measurement factors: + - motion measurements from X_i to X_j + - landmark measurements from X_i to b_k + - absolute pose measurement from X0 to * (the origin of coordinates) + - c are the calibration parameters + +We thus declare 9 factors pose---landmark, as follows: + + poses --- lmks + x0 --- b0 + x0 --- b1 + x0 --- b3 + x1 --- b0 + x1 --- b2 + x1 --- b4 + x2 --- b1 + x2 --- b2 + x2 --- b4 + + +The main variables are summarized again as follows + + Xi : robot pose at time i, SE(3) + u : robot control, (v*dt; 0; w*dt) in se(3) + c : control offset to be calibrated + Q : control perturbation covariance + b : landmark position, R^3 + y : Cartesian landmark measurement in robot frame, R^3 + R : covariance of the measurement noise + + +We define the state to estimate as a manifold composite: + + X in < R^2, SE3, SE3, SE3, R^3, R^3, R^3, R^3, R^3 > + + X = < c , X0, X1, X2, b0, b1, b2, b3, b4 > + +The estimation error dX is expressed +in the tangent space at X, + + dX in < R^2, se3, se3, se3, R^3, R^3, R^3, R^3, R^3 > + ~ < R^2, R^6, R^6, R^6, R^3, R^3, R^3, R^3, R^3 > = R^33 + + dX = [ dc, dx0, dx1, dx2, db0, db1, db2, db3, db4 ] in R^33 + +with + dc : calibration error in R^2 + dx_i: pose error in se(3) ~ R^6 + db_k: landmark error in R^3 + + +The prior, motion and measurement models are + + - for the prior factor: + p_0 = X_0 + + - for the motion factors - motion expectation equation: + d_ij = X_j (-) X_i = log(X_i.inv * X_j) + + - for the measurement factors - measurement expectation equation: + e_ik = h(X_i, b_k) = X_i^-1 * b_k + + +The algorithm below comprises first a simulator to +produce measurements, then uses these measurements +to estimate the state, using a graph representation +and Lie-based non-linear iterative least squares solver +that uses the pseudo-inverse method. + +This file has plain code with only one main() function. +There are no function calls other than those involving `manif`. + +Printing the prior state (before solving) and posterior state (after solving), +together with a ground-truth state defined by the simulator +allows for evaluating the quality of the estimates. + +This information is complemented with the evolution of +the optimizer's residual and optimal step norms. This allows +for evaluating the convergence of the optimizer. +""" + + +from manifpy import SE3, SE3Tangent + +import numpy as np +from numpy.linalg import inv, norm + + +Vector = np.array + + +def Jacobian(): + return np.zeros((SE3.DoF, SE3.DoF)) + + +def random(dim): + """Random vector Rdim in [-1, 1].""" + return np.random.uniform([-1]*dim, [1]*dim) + + +if __name__ == '__main__': + + print() + print('3D Smoothing and Mapping. Sensor offset, 3 poses, 5 landmarks.') + print('-----------------------------------------------') + np.set_printoptions(precision=3, suppress=True) + + # START CONFIGURATION + + # some experiment constants + DoF = SE3.DoF + Dim = SE3.Dim + DimC = 2 # Dimension of the calibration parameters + + NUM_POSES = 3 + NUM_LMKS = 5 + NUM_FACTORS = 9 + NUM_STATES = DimC + NUM_POSES * DoF + NUM_LMKS * Dim + NUM_MEAS = NUM_POSES * DoF + NUM_FACTORS * Dim + MAX_ITER = 20 # for the solver + + # Define the robot pose element + Xi = SE3.Identity() + X_simu = SE3.Identity() + + u_nom = Vector([0.1, 0.0, 0.0, 0.0, 0.0, 0.05]) + u_sigmas = Vector([0.01, 0.01, 0.01, 0.01, 0.01, 0.01]) + Q = np.diagflat(np.square(u_sigmas)) + W = np.diagflat(1./u_sigmas) # this is Q^(-T/2) + + # Declare the Jacobians of the motion wrt robot and control + J_x = Jacobian() + J_u = Jacobian() + + c_simu = Vector([0.05, 0.1]) + c = Vector([0., 0.]) + + J_u_c = np.zeros((DoF, DimC)) + J_u_c[0, 0] = 1.0 + J_u_c[5, 1] = 1.0 + + controls = [] + + # Define five landmarks in R^2 + landmarks = [0] * NUM_LMKS + landmarks_simu = [ + Vector([3.0, 0.0, 0.0]), + Vector([2.0, -1.0, -1.0]), + Vector([2.0, -1.0, 1.0]), + Vector([2.0, 1.0, 1.0]), + Vector([2.0, 1.0, -1.0]), + ] + + y_sigmas = Vector([0.001, 0.001, 0.001]) + R = np.diagflat(np.square(y_sigmas)) + S = np.diagflat(1./y_sigmas) # this is R^(-T/2) + + # Declare some temporaries + J_d_xi = Jacobian() + J_d_xj = Jacobian() + J_ix_x = Jacobian() + J_r_p0 = Jacobian() + J_e_ix = np.zeros((Dim, DoF)) + J_e_b = np.zeros((Dim, Dim)) + r = np.zeros(NUM_MEAS) + J = np.zeros((NUM_MEAS, NUM_STATES)) + + r""" + The factor graph of the SAM problem looks like this: + + ------- b1 + b3 / | + | / b4 | + | / / \| + X0 ---- X1 ---- X2 + | \ / \ / + | b0 b2 + * + + where: + - Xi are poses + - bk are landmarks or beacons + - * is a pose prior to anchor the map and make the problem observable + + Define pairs of nodes for all the landmark measurements + There are 3 pose nodes [0..2] and 5 landmarks [0..4]. + A pair pose -- lmk means that the lmk was measured from the pose + Each pair declares a factor in the factor graph + We declare 9 pairs, or 9 factors, as follows: + """ + + # 0-0,1,3 | 1-0,2,4 | 2-1,2,4 + pairs = [[0, 1, 3], [0, 2, 4], [1, 2, 4]] + + # Define the beacon's measurements + measurements = { + 0: {0: 0, 1: 0, 3: 0}, + 1: {0: 0, 2: 0, 4: 0}, + 2: {1: 0, 2: 0, 4: 0} + } + + # END CONFIGURATION + + # Simulator + + poses_simu = [] + poses_simu.append(X_simu) + poses = [] + poses.append(Xi + (SE3Tangent.Random()*0.1)) # use very noisy priors + + # Make 10 steps. Measure up to three landmarks each time. + for i in range(NUM_POSES): + + # make measurements + for k in pairs[i]: + + # simulate measurement + b = landmarks_simu[k] # lmk coordinates in world frame + y_noise = y_sigmas * random(Dim) # measurement noise + y = X_simu.inverse().act(b) # landmark measurement, before adding noise + + # add noise and compute prior lmk from prior pose + measurements[i][k] = y + y_noise # store noisy measurements + b = Xi.act(y + y_noise) # mapped landmark with noise + landmarks[k] = b + random(Dim) # use noisy priors + + # make motions + # do not make the last motion since we're done after 3rd pose + if i < NUM_POSES - 1: + + # move simulator, without noise, but with offset + u_offset = J_u_c @ c_simu + X_simu = X_simu + SE3Tangent(u_nom + u_offset) + + # move prior, with noise + u_noise = u_sigmas * random(DoF) + + Xi = Xi + SE3Tangent(u_nom + u_noise) + + # store + poses_simu.append(X_simu) + poses.append(Xi + (SE3Tangent.Random()*0.1)) # use noisy priors + controls.append(u_nom + u_noise) + + # Estimator + + # DEBUG INFO + print('prior') + print('Offset: ', c) + for X in poses: + print('pose : ', X.translation().transpose(), ' ', X.log().coeffs()[3:]) + for l in landmarks: + print('lmk : ', l.transpose()) + print('-----------------------------------------------') + + # iterate + for iteration in range(MAX_ITER): + + # Clear residual vector and Jacobian matrix + r.fill(0) + J.fill(0) + + row = 0 + col = 0 + + """ + 1. evaluate prior factor + + NOTE (see Chapter 2, Section E, of Sola-18): + + To compute any residual, we consider the following variables: + r: residual + e: expectation + y: prior specification 'measurement' + W: sqrt information matrix of the measurement noise. + + In case of a non-trivial prior measurement, we need to consider + the nature of it: is it a global or a local specification? + + When prior information `y` is provided in the global reference, + we need a left-minus operation (.-) to compute the residual. + This is usually the case for pose priors, since it is natural + to specify position and orientation wrt a global reference, + + r = W * (e (.-) y) + = W * (e * y.inv).log() + + When `y` is provided as a local reference, + then right-minus (-.) is required, + + r = W * (e (-.) y) + = W * (y.inv * e).log() + + Notice that if y = Identity() + then local and global residuals are the same. + + + Here, expectation, measurement and info matrix are trivial, + as follows + + expectation + e = poses[0]; // first pose + + measurement + y = SE3d::Identity() // robot at the origin + + info matrix: + W = I // trivial + + residual uses left-minus since reference measurement is global + r = W * (poses[0] (.-) measurement) + = log(poses[0] * Id.inv) = poses[0].log() + + Jacobian matrix : + J_r_p0 = Jr_inv(log(poses[0])) // see proof below + + Proof: Let p0 = poses[0] and y = measurement. + We have the partials + + J_r_p0 = W^(T/2) * d(log(p0 * y.inv)/d(poses[0]) + + with W = i and y = I. + Since d(log(r))/d(r) = Jr_inv(r) for any r in the Lie algebra, + we have + J_r_p0 = Jr_inv(log(p0)) + + residual and Jacobian. + Notes: + We have residual = expectation - measurement, + in global tangent space + We have the Jacobian in J_r_p0 = J[row:row+DoF, col:col+DoF] + """ + + r[row:row+DoF] = poses[0].lminus(SE3.Identity(), J_r_p0).coeffs() + + J[row:row+DoF, DimC+col:DimC+col+DoF] = J_r_p0 + + row += DoF + + # loop poses + for i in range(NUM_POSES): + + # 2. evaluate motion factors + # do not make the last motion since we're done after 3rd pose + if i < NUM_POSES - 1: + + j = i + 1 # this is next pose's id + + # recover related states and data + Xi = poses[i] + Xj = poses[j] + u = controls[i] + + # expectation + # (use right-minus since motion measurements are local) + d = Xj.rminus(Xi, J_d_xj, J_d_xi) # expected motion = Xj (-) Xi + + u_corr = SE3Tangent(u + J_u_c @ c) + + # residual + r[row:row+DoF] = W @ (d - u_corr).coeffs() # residual + + # Jacobian of residual wrt calibration params + col = 0 + J[row:row+DoF, col:col+DimC] = - W @ J_u_c + + # Jacobian of residual wrt first pose + col = DimC + i * DoF + J[row:row+DoF, col:col+DoF] = W @ J_d_xi + + # Jacobian of residual wrt second pose + col = DimC + j * DoF + J[row:row+DoF, col:col+DoF] = W @ J_d_xj + + # advance rows + row += DoF + + # 3. evaluate measurement factors + for k in pairs[i]: + + # recover related states and data + Xi = poses[i] + b = landmarks[k] + y = measurements[i][k] + + # expectation + e = Xi.inverse(J_ix_x).act(b, J_e_ix, J_e_b) # expected measurement = Xi.inv * bj + J_e_x = J_e_ix @ J_ix_x # chain rule + + # residual + r[row:row+Dim] = S @ (e - y) + + # Jacobian of residual wrt pose + col = DimC + i * DoF + J[row:row+Dim, col:col+DoF] = S @ J_e_x + + # Jacobian of residual wrt lmk + col = DimC + NUM_POSES * DoF + k * Dim + J[row:row+Dim, col:col+Dim] = S @ J_e_b + + # advance rows + row += Dim + + # 4. Solve + + # compute optimal step + # ATTENTION: This is an expensive step!! + # ATTENTION: Use QR factorization and + # column reordering for larger problems!! + dX = - inv(J.transpose() @ J) @ J.transpose() @ r + + # update calibrated offset + dc = dX[0:DimC] + c = c + dc + + # update all poses + for i in range(NUM_POSES): + # we go very verbose here + row = DimC + i * DoF + size = DoF + dx = dX[row:row+size] + poses[i] = poses[i] + SE3Tangent(dx) + + # update all landmarks + for k in range(NUM_LMKS): + # we go very verbose here + row = DimC + NUM_POSES * DoF + k * Dim + size = Dim + db = dX[row:row+size] + landmarks[k] = landmarks[k] + db + + # DEBUG INFO + print('residual norm: ', norm(r), ', step norm: ', norm(dX)) + + # conditional exit + if norm(dX) < 1e-6: + break + + print('-----------------------------------------------') + + # Print results + + # solved problem + print('posterior') + print('Offset: ', c) + for X in poses: + print( + 'pose : ', + X.translation().transpose(), + ' ', X.log().coeffs()[3:] + ) + for b in landmarks: + print('lmk : ', b.transpose()) + print('-----------------------------------------------') + + # ground truth + print('ground truth') + print('Offset: ', c_simu) + for X in poses_simu: + print( + 'pose : ', + X.translation().transpose(), ' ', + X.log().coeffs()[3:] + ) + for b in landmarks_simu: + print('lmk : ', b.transpose()) + print('-----------------------------------------------') From 285af7772b1b002de1ecb224e576dc50fa7663bf Mon Sep 17 00:00:00 2001 From: artivis Date: Fri, 22 Jan 2021 19:12:34 -0500 Subject: [PATCH 46/67] add se_2_3_localization.py --- examples/se_2_3_localization.py | 436 ++++++++++++++++++++++++++++++++ 1 file changed, 436 insertions(+) create mode 100644 examples/se_2_3_localization.py diff --git a/examples/se_2_3_localization.py b/examples/se_2_3_localization.py new file mode 100644 index 00000000..791f76ec --- /dev/null +++ b/examples/se_2_3_localization.py @@ -0,0 +1,436 @@ +r""" + +\file se_2_3_localization.py. + +Created on: Jan 11, 2021 +\author: Jeremie Deray + +--------------------------------------------------------- +This file is: +(c) 2021 Jeremie Deray + +This file is part of `manif`, a C++ template-only library +for Lie theory targeted at estimation for robotics. +Manif is: +(c) 2021 Jeremie Deray +--------------------------------------------------------- + +--------------------------------------------------------- +3D Robot localization and linear velocity estimation +based on strap-down IMU model and fixed beacons. + +--------------------------------------------------------- + +We consider a robot in 3D space surrounded by a small +number of punctual landmarks or _beacons_. +The robot is assumed to be mounted with an IMU whose +measurements are fed as exogeneous inputs to the system. +The robot is able to measure the location +of the beacons w.r.t its own reference frame. +We assume in this example that the IMU frame coincides with the robot frame. + +The robot extended pose X is in SE_2(3) and the beacon positions b_k in R^3, + + X = | R p v| // position, orientation and linear velocity + | 1 | + | 1| + + b_k = (bx_k, by_k, bz_k) // lmk coordinates in world frame + + alpha_k = (alphax_k, alphay_k, alphaz_k) // linear accelerometer measurements in IMU frame + + omega_k = (omegax_k, omegay_k, omegaz_k) // gyroscope measurements in IMU frame + + g = (0, 0, -9.80665) // acceleration due to gravity in world frame + +Consider robot coordinate frame B and world coordinate frame A. +- p is the position of the origin of the robot frame B with respect to the world frame A +- R is the orientation of the robot frame B with respect to the world frame A +- v is the velocity of the robot frame with respect to the world frame, + expressed in a frame whose origin coincides with the robot frame, + oriented similar to the world frame + (it is equivalent to p_dot in continuous time. + This is usually called mixed-frame representation + and is denoted as (B[A] v_AB), + where B[A] is the mixed frame as described above. + For reference, please see "Multibody Dynamics Notation" by + Silvio Traversaro and Alessandro Saccon. + Link: https://research.tue.nl/en/publications/multibody-dynamics-notation-version-2) +- a is the frame acceleration in mixed-representation (equivalent to p_doubledot in continuous time). +- omega_b as the angular velocity of the robot expressed in the robot frame + +The kinematic equations (1) can be written as, + p <-- p + v dt + 0.5 a dt^2 + R <-- R Exp_SO3(omega_b) + v <-- v + a dt + +However, we would like to express the kinematics equations in the form, +X <-- X * Exp(u) +where, X \in SE_2(3), u \in R^9 and u_hat \in se_2(3) +Note that here input vector u is expressed in the local frame (robot frame). +This can be seen as a motion integration on a manifold defined by the group SE_2(3). + +The exponential mapping of SE_2(3) is defined as, +for u = [u_p, u_w, u_v] + Exp(u) = | Exp_SO3(u_w) JlSO3(u_w) u_p JlSO3(u_w) u_v | + | 0 0 0 1 0 | + | 0 0 0 0 1 | +where, JlSO3 is the left Jacobian of the SO(3) group. + +Please see the Appendix C of the paper +"A micro Lie theory for state estimation in robotics", +for the definition of the left Jacobian of SO(3). +Please see the Appendix D of the paper, +for the definition of Exp map for SE(3). +The Exp map of SE_2(3) is a simple extension from the Exp map of SE(3). +Also, please refer to Example 7 of the paper to understand +when and how the left Jacobian of SO(3) appears in the definitions of Exp maps. +The Example 7 illustrates the scenario for SE(3). +We use a direct extension here for SE_2(3). +One can arrive to such a definition by following +the convergent Taylor's series expansion +for the matrix exponential of +the Lie algebra element (Equation 16 of the paper). + +As a result of X <-- X * Exp(u), we get (2) + p <-- p + R JlSO3(u_w) u_p + R <-- R Exp_SO3(u_w) + v <-- v + R JlSO3(u_w) u_v + +It is important to notice the subtle difference between (1) and (2) here, +which is specifically the influence of the left Jacobian of SO(3) in (2). +The approach in (1) considers the motion integration is done by defining +the exponential map in R3xSO(3)xR3 instead of SE_2(3), +in the sense explored in Example 7 of the Micro Lie theory paper. +It must be noted that as dt tends to 0, +both sets of equations (1) and (2) tend to be the same, +since JlSO3 tends to identity. + +Since, (2) exploits the algebra of the SE_2(3) group properly, +we would like to draw a relationship between the sets of equations (2) +and the IMU measurements which will constitute +the exogeneous input vector u \in se_2(3). + +Considering R.T as the transpose of R, the IMU measurements are modeled as, + - linear accelerometer measurements alpha = R.T (a - g) + w_acc + - gyroscope measurements omega = omega_b + w_omega +Note that the IMU measurements are expressed in the IMU frame +(coincides with the robot frame - assumption). +The IMU measurements are corrupted by noise, + - w_omega is the additive white noise affecting the gyroscope measurements + - w_acc is the additive white noise affecting + the linear accelerometer measurements +It must be noted that we do not consider IMU biases +in the IMU measurement model in this example. + +Taking into account all of the above considerations, +the exogenous input vector u (3) becomes, + u = (u_p, u_w, u_v) where, + u_w = omega dt + u_p = (R.T v dt + 0.5 dt^2 (alpha + R.T g) + u_v = (alpha + R.T g) dt + +This choice of input vector allows us to directly use measurements from the IMU +for an unified motion integration involving position, +orientation and linear velocity of the robot using SE_2(3). +Equations (2) and (3) lead us to the following evolution equations, + + p <-- p + JlSO3 R.T v dt + 0.5 JlSO3 (alpha + R.T g) dt^2 + R <-- R Exp_SO3(omega dt) + v <-- v + JlSO3 (alpha + R.T g) dt + +The system propagation noise covariance matrix becomes, + U = diagonal(0, 0, 0, + sigma_omegax^2, sigma_omegay^2, sigma_omegaz^2, + sigma_accx^2, sigma_accy^2, sigma_accz^2). + +At the arrival of a exogeneous input u, the robot pose is updated +with X <-- X * Exp(u) = X + u. + +Landmark measurements are of the range and bearing type, +though they are put in Cartesian form for simplicity. +Their noise n is zero mean Gaussian, and is specified +with a covariances matrix R. +We notice that the SE_2(3) action is the same as a +rigid motion action of SE(3). +This is the action of X \in SE_2(3) on a 3-d point b \in R^3 defined as, +X b = R b + p + +Thus, the landmark measurements can be expressed as +a group action on 3d points, +y = h(X,b) = X^-1 * b + + y_k = (brx_k, bry_k, brz_k) // lmk coordinates in robot frame + +We consider the beacons b_k situated at known positions. +We define the extended pose to estimate as X in SE_2(3). +The estimation error dx and its covariance P are expressed +in the tangent space at X. + +All these variables are summarized again as follows + + X : robot's extended pose, SE_2(3) + u : robot control input, u = u(X, y_imu) \in se_2(3) with X as state and + y_imu = [alpha, omega] as IMU readings, see Eq. (3) + U : control perturbation covariance + b_k : k-th landmark position, R^3 + y : Cartesian landmark measurement in robot frame, R^3 + R : covariance of the measurement noise + +The motion and measurement models are + + X_(t+1) = f(X_t, u) = X_t * Exp ( u ) // motion equation + y_k = h(X, b_k) = X^-1 * b_k // measurement equation + +The algorithm below comprises first a simulator to +produce measurements, then uses these measurements +to estimate the state, using a Lie-based error-state Kalman filter. + +This file has plain code with only one main() function. +There are no function calls other than those involving `manif`. + +Printing simulated state and estimated state together +with an unfiltered state (i.e. without Kalman corrections) +allows for evaluating the quality of the estimates. + +A side note: Besides the approach described here in this illustration example, +there are other interesting works like the paper, +The Invariant Extended Kalman filter as a stable observer +(https://arxiv.org/pdf/1410.1465.pdf) +which assume a specific structure for the +system propagation dynamics "f(X_t, u)" (group affine dynamics) +that simplifies the covariance propagation and +enables error dynamics with stronger convergence properties. +""" + + +from manifpy import SE_2_3, SE_2_3Tangent + +import numpy as np +from numpy.linalg import inv + + +Vector = np.array + + +def Covariance(): + return np.zeros((SE_2_3.DoF, SE_2_3.DoF)) + + +def Jacobian(): + return np.zeros((SE_2_3.DoF, SE_2_3.DoF)) + + +def random(dim): + """Random vector Rdim in [-1, 1].""" + return np.random.uniform([-1]*dim, [1]*dim) + + +def skew(vec): + mat = np.zeros((3, 3)) + mat[0, 1] = -vec[2] + mat[0, 2] = +vec[1] + mat[1, 0] = +vec[2] + mat[1, 2] = -vec[0] + mat[2, 0] = -vec[1] + mat[2, 1] = +vec[0] + return np.copy(mat) + + +def frange(start, stop, step): + return [ + x*step+start for x in range( + 0, + round(abs((stop-start)/step)+0.5001), + int((stop-start)/step < 0)*-2+1 + ) + ] + + +if __name__ == '__main__': + + # START CONFIGURATION + + NUMBER_OF_LMKS_TO_MEASURE = 5 + + # Define the robot pose element and its covariance + X_simulation = SE_2_3.Identity() + X = SE_2_3.Identity() + X_unfiltered = SE_2_3.Identity() + P = Covariance() + P[0:3, 0:3] = np.diagflat([0.001, 0.001, 0.001]) + P[3:6, 3:6] = np.diagflat([0.01, 0.01, 0.01]) + P[6:9, 6:9] = np.diagflat([0.001, 0.001, 0.001]) + + print("P: ", P) + + # acceleration due to gravity in world frame + g = Vector([0.0, 0.0, -9.80665]) + dt = 0.01 + + alpha_const = Vector([0.1, 0.01, 0.1]) # constant acceleration in IMU frame without gravity compensation + omega = Vector([0.01, 0.1, 0.0]) # constant angular velocity about x- and y-direction in IMU frame + + # Previous IMU measurements in IMU frame initialized + # to values expected when stationary + alpha_prev = alpha_const - X_simulation.rotation().transpose() @ g + alpha = alpha_const - X_simulation.rotation().transpose() @ g + omega_prev = Vector([0.0, 0.0, 0.0]) + + u_nom = Vector([0.0] * 9) + u_est = Vector([0.0] * 9) + u_sigmas = Vector([0.0, 0.0, 0.0, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]) + U = np.diagflat(np.square(u_sigmas)) + + # Declare the Jacobians of the motion wrt robot and control + F = Jacobian() # F = J_x_x + (J_x_u * J_u_x) + J_x_x = Jacobian() # d(X * exp(u)) / dX + J_x_u = Jacobian() # d(X * exp(u)) / du + J_u_x = Jacobian() # du / dX, since u is a state-dependent vector + + # Define five landmarks in R^3 + landmarks = [] + landmarks.append(Vector([2.0, 0.0, 0.0])) + landmarks.append(Vector([3.0, -1.0, -1.0])) + landmarks.append(Vector([2.0, -1.0, 1.0])) + landmarks.append(Vector([2.0, 1.0, 1.0])) + landmarks.append(Vector([2.0, 1.0, -1.0])) + + # Define the beacon's measurements + measurements = [Vector([0.0, 0.0, 0.0])] * NUMBER_OF_LMKS_TO_MEASURE + + y_sigmas = Vector([0.01, 0.01, 0.01]) + R = np.diagflat(np.square(y_sigmas)) + + # Declare some temporaries + J_xi_x = Jacobian() + J_e_xi = np.zeros((SE_2_3.Dim, SE_2_3.DoF)) + + # CONFIGURATION DONE + + # pretty print + np.set_printoptions(precision=3, suppress=True, linewidth=160) + + # DEBUG + print('X STATE : X Y Z TH_x TH_y TH_z ') + print('-------------------------------------------------------') + print('X initial : ', X_simulation.log().coeffs()) + print('-------------------------------------------------------') + + # END DEBUG + + # START TEMPORAL LOOP + + # Make 10/dt steps. Measure up to three landmarks each time. + for t in frange(0, 10, dt): + # I. Simulation + + # get current simulated state and measurements from previous step + R_k = X_simulation.rotation() + v_k = X_simulation.linearVelocity() + acc_k = alpha_prev + R_k.transpose() @ g + + # input vector + u_nom[0:3] = dt * R_k.transpose() @ v_k + 0.5 * dt * dt * acc_k + u_nom[3:6] = dt * omega_prev + u_nom[6:9] = dt * acc_k + + # simulate noise + u_noise = u_sigmas * random(SE_2_3.DoF) # control noise + u_noisy = u_nom + u_noise # noisy control + + u_simu = SE_2_3Tangent(u_nom) + u_unfilt = SE_2_3Tangent(u_noisy) + + # first we move + X_simulation = X_simulation + u_simu # X * exp(u) + # update expected IMU measurements after moving + alpha = alpha_const - X_simulation.rotation().transpose() @ g + + # then we measure all landmarks + for i in range(NUMBER_OF_LMKS_TO_MEASURE): + b = landmarks[i] # lmk coordinates in world frame + + # simulate noise + y_noise = y_sigmas * random(SE_2_3.Dim) # measurement noise + + y = X_simulation.inverse().act(b) # landmark measurement, before adding noise + + y = y + y_noise # landmark measurement, noisy + measurements[i] = y # store for the estimator just below + + # II. Estimation + + # get current state estimate to build + # the state-dependent control vector + R_k_est = X.rotation() + v_k_est = X.linearVelocity() + acc_k_est = alpha_prev + R_k_est.transpose() @ g + + accLin = dt * R_k_est.transpose() @ v_k_est + 0.5 * dt * dt * acc_k_est + gLin = R_k_est.transpose() @ g * dt + accLinCross = skew(accLin) + gCross = skew(gLin) + + u_est[0:3] = accLin + u_est[3:6] = dt * omega_prev + u_est[6:9] = dt * acc_k_est + + u_est += u_noise + + # First we move + + X = X.plus(SE_2_3Tangent(u_est), J_x_x, J_x_u) # X * exp(u), with Jacobians + + # Prepare Jacobian of state-dependent control vector + J_u_x[0:3, 3:6] = accLinCross + J_u_x[0:3, 6:9] = np.identity(3) * dt + J_u_x[6:9, 3:6] = gCross + F = J_x_x + J_x_u @ J_u_x # chain rule for system model Jacobian + + P = F @ P @ F.transpose() + J_x_u @ U @ J_x_u.transpose() + + # Then we correct using the measurements of each lmk + for i in range(NUMBER_OF_LMKS_TO_MEASURE): + # landmark + b = landmarks[i] # lmk coordinates in world frame + + # measurement + y = measurements[i] # lmk measurement, noisy + + # expectation + e = X.inverse(J_xi_x).act(b, J_e_xi) # note: e = R.tr * ( b - t ), for X = (R,t). + H = J_e_xi @ J_xi_x # Jacobian of the measurements wrt the robot pose. note: H = J_e_x = J_e_xi * J_xi_x + E = H @ P @ H.transpose() + + # innovation + z = y - e + Z = E + R + + # Kalman gain + K = P @ H.transpose() @ inv(Z) # K = P * H.tr * ( H * P * H.tr + R).inv + + # Correction step + dx = K @ z # dx is in the tangent space at X + + # Update + X = X + SE_2_3Tangent(dx) # overloaded X.rplus(dx) = X * exp(dx) + + P = P - K @ Z @ K.transpose() + + # III. Unfiltered + + # move also an unfiltered version for comparison purposes + X_unfiltered = X_unfiltered + u_unfilt + + alpha_prev = np.copy(alpha) + omega_prev = np.copy(omega) + + # IV. Results + + # DEBUG + print('X simulated : ', X_simulation.log().coeffs().transpose()) + print('X estimated : ', X.log().coeffs().transpose()) + print('X unfilterd : ', X_unfiltered.log().coeffs().transpose()) + print('-------------------------------------------------------') + # END DEBUG From 580dc7fdcdbd4e50c31b23c8f8e460272b4a5c2f Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 09:48:21 -0500 Subject: [PATCH 47/67] add some gitignore --- .gitignore | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index 8a4b54df..6a44b424 100644 --- a/.gitignore +++ b/.gitignore @@ -9,4 +9,6 @@ doxygen_warnings.txt *.cache .vscode *.egg-info -*.so \ No newline at end of file +*.so +__pycache__ +.pytest_cache From 40e21ab61abf54e239a1f353dd5e6a2d5960fcb7 Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 10:30:43 -0500 Subject: [PATCH 48/67] disable macos-11 in CI for now --- .github/workflows/ci.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 435ea194..dc5e56bb 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -58,7 +58,9 @@ jobs: strategy: matrix: # Xcode 10.3 & Xcode 12.2 - os: [macos-10.15, macos-11.0] + # removing macos-11.0 for now, see + #https://github.com/actions/virtual-environments/issues/841 + os: [macos-10.15] steps: - name: Checkout uses: actions/checkout@v2 From 2af4d8f8f5fad456203a9764375140a9df18cc6d Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 10:31:45 -0500 Subject: [PATCH 49/67] bind tangent innerWeights --- python/bindings_tangent_base.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index e0884543..0932b3df 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -11,7 +11,6 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { using DataType = typename _Tangent::DataType; using Jacobian = typename _Tangent::Jacobian; using OptJacobianRef = typename _Tangent::OptJacobianRef; - using InnerWeight = typename _Tangent::InnerWeight; py_class.attr("Dim") = _Tangent::Dim; py_class.attr("DoF") = _Tangent::DoF; @@ -32,7 +31,7 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def("generator", &_Tangent::generator); - // py_class.def("innerWeights", &_Tangent::innerWeights); + py_class.def("innerWeights", &_Tangent::innerWeights); py_class.def("inner", &_Tangent::template inner<_Tangent>); py_class.def("weightedNorm", &_Tangent::weightedNorm); @@ -116,7 +115,7 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.def_static("Zero", &_Tangent::Zero); py_class.def_static("Random", &_Tangent::Random); py_class.def_static("Generator", &_Tangent::Generator); - py_class.def_static("InnerWeights", &_Tangent::W); + py_class.def_static("InnerWeights", &_Tangent::InnerWeights); // operator overloads py_class.def(-py::self) From bfebc3285dce6cf20978ce635e6c372395f5050c Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 12:58:36 -0500 Subject: [PATCH 50/67] ex: seed random gen & reduce noise --- examples/se3_sam_selfcalib.cpp | 6 ++++-- examples/se_2_3_localization.cpp | 2 ++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/examples/se3_sam_selfcalib.cpp b/examples/se3_sam_selfcalib.cpp index f37361ba..4b326bd7 100644 --- a/examples/se3_sam_selfcalib.cpp +++ b/examples/se3_sam_selfcalib.cpp @@ -234,6 +234,8 @@ constexpr int MAX_ITER = 20; // for the solver int main() { + std::srand((unsigned int) time(0)); + // DEBUG INFO cout << endl; cout << "3D Smoothing and Mapping. Sensor offset, 3 poses, 5 landmarks." << endl; @@ -363,7 +365,7 @@ int main() //// Simulator ################################################################### poses_simu. push_back(X_simu); - poses. push_back(Xi + SE3Tangentd::Random()); // use very noisy priors + poses. push_back(Xi + SE3Tangentd::Random()*0.1); // use very noisy priors // temporal loop for (int i = 0; i < NUM_POSES; ++i) @@ -395,7 +397,7 @@ int main() // store poses_simu. push_back(X_simu); - poses. push_back(Xi + SE3Tangentd::Random()); // use very noisy priors + poses. push_back(Xi + SE3Tangentd::Random()*0.1); // use very noisy priors controls. push_back(u_nom + u_noise); } } diff --git a/examples/se_2_3_localization.cpp b/examples/se_2_3_localization.cpp index bc6f8047..3728393c 100644 --- a/examples/se_2_3_localization.cpp +++ b/examples/se_2_3_localization.cpp @@ -206,6 +206,8 @@ typedef Matrix Matrix9d; int main() { + std::srand((unsigned int) time(0)); + // START CONFIGURATION // // From d996595649cab5e8fa8a617dd9fdb4e03d8552de Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 16:01:32 -0500 Subject: [PATCH 51/67] rm eigen Quaternion bindings --- python/CMakeLists.txt | 3 - python/bindings_eigen_quaternion.cpp | 82 ---------------------------- python/bindings_manif.cpp | 4 -- test/python/CMakeLists.txt | 2 - test/python/test_eigen_quaternion.py | 62 --------------------- test/python/test_so3.py | 20 +++---- 6 files changed, 10 insertions(+), 163 deletions(-) delete mode 100644 python/bindings_eigen_quaternion.cpp delete mode 100644 test/python/test_eigen_quaternion.py diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 97b940ec..d85e66b7 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -1,8 +1,5 @@ set(PYBIND11_CPP_STANDARD -std=c++11) pybind11_add_module(manifpy - - bindings_eigen_quaternion.cpp - bindings_rn.cpp bindings_so2.cpp bindings_so3.cpp diff --git a/python/bindings_eigen_quaternion.cpp b/python/bindings_eigen_quaternion.cpp deleted file mode 100644 index dbedc31a..00000000 --- a/python/bindings_eigen_quaternion.cpp +++ /dev/null @@ -1,82 +0,0 @@ -#include - -#include -#include -#include - -void wrap_Eigen_quaternion(pybind11::module &m) -{ - using Scalar = double; - using Quaternion = Eigen::Quaternion; - - pybind11::class_< - Eigen::QuaternionBase, - std::unique_ptr, pybind11::nodelete> - > quat_base(m, "QuaternionBase"); - pybind11::class_> quat(m, "Quaternion"); - - quat.attr("__doc__") = "Python bindings for Eigen::Quaternion."; - - quat.def(pybind11::init<>()) - .def_static("Identity", &Quaternion::Identity) -#if EIGEN_VERSION_AT_LEAST(3,3,0) - .def_static("UnitRandom", &Quaternion::UnitRandom) -#endif - .def(pybind11::init()) - .def(pybind11::init()) - .def(pybind11::init()) - .def(pybind11::init()) - // .def(pybind11::init([](const Class& other) { - // return other; - // }), pybind11::arg("other")) - - // .def( - // "coeffs", - // static_cast::Coefficients& (Quaternion::*)(void)>(&Quaternion::coeffs), - // pybind11::return_value_policy::reference_internal - // ) - - .def("angularDistance", &Quaternion::template angularDistance) - .def("conjugate", &Quaternion::conjugate) - .def("dot", &Quaternion::template dot) - .def("inverse", &Quaternion::inverse) - .def( - "isApprox", - &Quaternion::template isApprox, - pybind11::arg("other"), - pybind11::arg_v("prec", Eigen::NumTraits::dummy_precision(), "Precision") - ) - .def("norm", &Quaternion::norm) - .def("normalize", &Quaternion::normalize) - .def("normalized", &Quaternion::normalized) - .def("setIdentity", &Quaternion::setIdentity, pybind11::return_value_policy::reference_internal) - .def("slerp", &Quaternion::template slerp) - .def("squaredNorm", &Quaternion::squaredNorm) - .def("toRotationMatrix", &Quaternion::toRotationMatrix) - // .def("setFromTwoVectors", &Quaternion::setFromTwoVectors) - - .def("matrix", &Quaternion::matrix) - - .def( - "vec", - [](const Quaternion& self) { return self.vec(); }, - pybind11::return_value_policy::reference_internal - ) - - .def("x", static_cast(&Quaternion::x)) - .def("y", static_cast(&Quaternion::y)) - .def("z", static_cast(&Quaternion::z)) - .def("w", static_cast(&Quaternion::w)) - - .def(pybind11::self * pybind11::self) - // .def(pybind11::self = Eigen::AngleAxisd()) - // .def(pybind11::self = Eigen::Matrix) - - .def( - "__str__", - [](const Quaternion &q) { - std::ostringstream ss; ss << q.coeffs(); - return ss.str(); - } - ); -} diff --git a/python/bindings_manif.cpp b/python/bindings_manif.cpp index 3d5ac8f0..898e5614 100644 --- a/python/bindings_manif.cpp +++ b/python/bindings_manif.cpp @@ -1,7 +1,5 @@ #include -void wrap_Eigen_quaternion(pybind11::module &m); - void wrap_Rn(pybind11::module &m); void wrap_SO2(pybind11::module &m); @@ -16,8 +14,6 @@ PYBIND11_MODULE(manifpy, m) { m.doc() = "Python bindings for the manif library," "a small library for Lie theory."; - wrap_Eigen_quaternion(m); - wrap_Rn(m); wrap_SO2(m); diff --git a/test/python/CMakeLists.txt b/test/python/CMakeLists.txt index 43117963..c74efbfb 100644 --- a/test/python/CMakeLists.txt +++ b/test/python/CMakeLists.txt @@ -10,8 +10,6 @@ function(manif_add_pytest target) ) endfunction() -manif_add_pytest(test_eigen_quaternion) - manif_add_pytest(test_manif) manif_add_pytest(test_so2) manif_add_pytest(test_se2) diff --git a/test/python/test_eigen_quaternion.py b/test/python/test_eigen_quaternion.py deleted file mode 100644 index b0d6aca4..00000000 --- a/test/python/test_eigen_quaternion.py +++ /dev/null @@ -1,62 +0,0 @@ -from manifpy import Quaternion - -import numpy as np - - -def test_constructor(): - q = Quaternion(1, 2, 3, 4) - assert 2 == q.x() - assert 3 == q.y() - assert 4 == q.z() - assert 1 == q.w() - - q = Quaternion(np.array([1, 2, 3, 4])) - assert 1 == q.x() - assert 2 == q.y() - assert 3 == q.z() - assert 4 == q.w() - - q = Quaternion(np.identity(3)) - assert 0 == q.x() - assert 0 == q.y() - assert 0 == q.z() - assert 1 == q.w() - - -def test_vec(): - vec = Quaternion(1, 2, 3, 4).vec() - assert 2 == vec[0] - assert 3 == vec[1] - assert 4 == vec[2] - - -def test_identity(): - q = Quaternion.Identity() - - assert 0 == q.x() - assert 0 == q.y() - assert 0 == q.z() - assert 1 == q.w() - - q_other = Quaternion.Identity() - q_other.setIdentity() - - assert q.isApprox(q_other) - assert q.isApprox(q_other * q_other) - assert q.isApprox(q_other.normalized()) - - q_inv = q.inverse() - - assert q_inv.isApprox(q_other) - assert q_inv.isApprox(q.conjugate()) - - assert (3, 3) == q.toRotationMatrix().shape - assert (np.identity(3) == q.toRotationMatrix()).all() - - assert (3, 3) == q.matrix().shape - assert (np.identity(3) == q.matrix()).all() - - assert 1 == q.norm() - assert 1 == q.squaredNorm() - assert 1 == q.dot(q) # cos(0) - assert 0 == q.angularDistance(q) diff --git a/test/python/test_so3.py b/test/python/test_so3.py index 059568aa..5df8ae4a 100644 --- a/test/python/test_so3.py +++ b/test/python/test_so3.py @@ -1,4 +1,4 @@ -from manifpy import Quaternion, SO3, SO3Tangent +from manifpy import SO3, SO3Tangent import numpy as np @@ -22,11 +22,11 @@ def test_constructor(): assert 0 == state.z() assert 1 == state.w() - state = SO3(Quaternion(1, 0, 0, 0)) - assert 0 == state.x() - assert 0 == state.y() - assert 0 == state.z() - assert 1 == state.w() + # state = SO3(Quaternion(1, 0, 0, 0)) + # assert 0 == state.x() + # assert 0 == state.y() + # assert 0 == state.z() + # assert 1 == state.w() # state = SO3(AngleAxis(0, UnitX())) # assert 0 == state.x() @@ -71,8 +71,8 @@ def test_rotation(): assert (np.identity(3) == rotation).all() -def test_quaternion(): - state = SO3.Identity() - quaternion = state.quat() +# def test_quaternion(): +# state = SO3.Identity() +# quaternion = state.quat() - assert Quaternion.Identity().isApprox(quaternion) +# assert Quaternion.Identity().isApprox(quaternion) From 04a7cf1fd9ca607105359bb9b6e1ff103dd68cc6 Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 16:01:58 -0500 Subject: [PATCH 52/67] update gitignore --- .gitignore | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.gitignore b/.gitignore index 6a44b424..e6b79290 100644 --- a/.gitignore +++ b/.gitignore @@ -4,11 +4,11 @@ .settings .tags build -doc +doc/html doxygen_warnings.txt *.cache .vscode *.egg-info *.so -__pycache__ +*__pycache__ .pytest_cache From c448b1feadbcccab808d61fb1db0acc166180527 Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 16:02:26 -0500 Subject: [PATCH 53/67] update README --- README.md | 22 ++++++++++++---------- projects.md | 8 ++++++-- 2 files changed, 18 insertions(+), 12 deletions(-) diff --git a/README.md b/README.md index c3f3ca20..db575d2d 100644 --- a/README.md +++ b/README.md @@ -55,7 +55,7 @@ Please find more information in the related [wiki page](https://github.com/artiv ### Details - Maintainer status: maintained -- Maintainer: Jeremie Deray [deray.jeremie@gmail.com](mailto:deray.jeremie@gmail.com) +- Maintainer: Jeremie Deray - Authors: - Jeremie Deray [deray.jeremie@gmail.com](mailto:deray.jeremie@gmail.com) - Joan Sola [jsola@iri.upc.edu](mailto:jsola@iri.upc.edu) @@ -96,7 +96,7 @@ ___ - [lt::optional][optional-repo] : included in the `external` folder -For the Python 3 wrappers: +In addition for the Python 3 wrappers: ```terminal pip install -r requirements @@ -159,8 +159,9 @@ To do so we can use, python3 -m pip install "pybind11[global]" ``` -which is not recommended if we are installing with our system Python, +Note that this is not recommended when using one's system Python, as it will add files to `/usr/local/include/pybind11` and `/usr/local/share/cmake/pybind11`. + Another way is to use `CMake` to install it, ```terminal @@ -281,6 +282,7 @@ For reference of the size of the Jacobians returned when using `ceres::Jet`, **m Therefore, the respective Jacobian sizes using `ceres::Jet` are as follows: +- ℝ(n) : size n - SO(2) : size 2 - SO(3) : size 4 - SE(2) : size 4 @@ -309,16 +311,16 @@ find in the section [Publications](#publications). ## Tutorials and application demos -We provide some self-contained and self-explained executables implementing some real problems. +We provide some self-contained and self-explained executables implementing some real problems both in C++ and Python. Their source code is located in `manif/examples/`. These demos are: -- [`se2_localization.cpp`](examples/se2_localization.cpp)/[`se2_localization.py`](examples/se2_localization.py): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. -- [`se3_localization.cpp`](examples/se3_localization.cpp)/[`se3_localization.py`](examples/se3_localization.py): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. -- [`se2_sam.cpp`](examples/se2_sam.cpp): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. -- [`se3_sam.cpp`](examples/se3_sam.cpp): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. -- [`se3_sam_selfcalib.cpp`](examples/se3_sam_selfcalib.cpp): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. -- [`se_2_3_localization.cpp`](examples/se_2_3_localization.cpp): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). +- `se2_localization` [`.cpp`](examples/se2_localization.cpp)/[`.py`](examples/se2_localization.py): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. +- `se3_localization` [`.cpp`](examples/se3_localization.cpp)/[`.py`](examples/se3_localization.py): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. +- `se2_sam.` [`cpp`](examples/se2_sam.cpp)/[`.py`](examples/se2_sam.py): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. +- `se3_sam` [`.cpp`](examples/se3_sam.cpp)/[`.py`](examples/se3_sam.py): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. +- `se3_sam_selfcalib` [`.cpp`](examples/se3_sam_selfcalib.cpp)/[`.py`](examples/se3_sam_selfcalib.py): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. +- `se_2_3_localization` [`.cpp`](examples/se_2_3_localization.cpp)/[`.py`](examples/se_2_3_localization.py): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). ## Publications diff --git a/projects.md b/projects.md index 807bc84b..dd91db50 100644 --- a/projects.md +++ b/projects.md @@ -4,11 +4,13 @@ You may find on Google Scholar publications citing either: -- the [Lie theory paper][jsola18] accompanying **manif**: see [here][jsola18-scholar] -- the [**manif** library paper][deray20]: see [here][deray20-scholar] +- the [Lie theory paper][jsola18] accompanying **manif** - see [here][jsola18-scholar] +- the [**manif** library paper][deray20] - see [here][deray20-scholar] ## They use **manif** +- [`lie-group-controllers`][lie-group-controllers-repo], header-only C++ libraries containing controllers designed for Lie Groups. + Your project is not listed here? Let us know about it! [//]: # (URLs) @@ -17,3 +19,5 @@ Your project is not listed here? Let us know about it! [jsola18-scholar]: https://scholar.google.com/scholar?oi=bibs&cites=16456301708818968338 [deray20]: https://joss.theoj.org/papers/10.21105/joss.01371 [deray20-scholar]: https://scholar.google.fr/scholar?oi=bibs&hl=fr&cites=1235228860941456363 + +[lie-group-controllers-repo]: https://github.com/dic-iit/lie-group-controllers \ No newline at end of file From d8f28246e5f875da0c9f3be4ad89877ca9a0533e Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 23 Jan 2021 17:03:01 -0500 Subject: [PATCH 54/67] migrating wiki to doc --- .doxygen.txt | 8 +- README.md | 6 +- doc/Interpolation.md | 30 ++++ doc/On-the-use-with-Ceres.md | 240 +++++++++++++++++++++++++++++ doc/Writing-generic-code.md | 67 ++++++++ doc/images/se2_interp_cnsmooth.png | Bin 0 -> 82946 bytes doc/images/se2_interp_cubic.png | Bin 0 -> 75911 bytes doc/images/se2_interp_slerp.png | Bin 0 -> 74792 bytes projects.md | 2 +- 9 files changed, 345 insertions(+), 8 deletions(-) create mode 100644 doc/Interpolation.md create mode 100644 doc/On-the-use-with-Ceres.md create mode 100644 doc/Writing-generic-code.md create mode 100644 doc/images/se2_interp_cnsmooth.png create mode 100644 doc/images/se2_interp_cubic.png create mode 100644 doc/images/se2_interp_slerp.png diff --git a/.doxygen.txt b/.doxygen.txt index 2a1218e0..f3ba8752 100644 --- a/.doxygen.txt +++ b/.doxygen.txt @@ -46,8 +46,8 @@ PROJECT_BRIEF = "A small library for Lie group theory with application # spaces. # Note: If this tag is empty the current directory is searched. -INPUT = include -INPUT += README.md +INPUT = include README.md doc + #--------------------------------------------------------------------------- # Shared @@ -767,7 +767,7 @@ INPUT_ENCODING = UTF-8 # *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, # *.qsf, *.as and *.js. -FILE_PATTERNS = *.c *.cpp *.h *.hpp +FILE_PATTERNS = *.c *.cpp *.h *.hpp *.md # The RECURSIVE tag can be used to specify whether or not subdirectories should # be searched for input files as well. @@ -835,7 +835,7 @@ EXAMPLE_RECURSIVE = NO # that contain images that are to be included in the documentation (see the # \image command). -IMAGE_PATH = +IMAGE_PATH = doc/images # The INPUT_FILTER tag can be used to specify a program that doxygen should # invoke to filter for each input file. Doxygen will invoke the filter program diff --git a/README.md b/README.md index db575d2d..d3b81a53 100644 --- a/README.md +++ b/README.md @@ -50,7 +50,7 @@ It also supports template scalar types. In particular, it can work with the All Lie group classes defined in **manif** have in common that they inherit from a templated base class ([CRTP][crtp]). It allows one to write generic code abstracting the Lie group details. -Please find more information in the related [wiki page](https://github.com/artivis/manif/wiki/Writing-generic-code) +Please find more information in the related [documentation page](doc/Writing-generic-code). ### Details @@ -289,13 +289,13 @@ Therefore, the respective Jacobian sizes using `ceres::Jet` are as follows: - SE(3) : size 7 - SE_2(3): size 10 -For more information, please refer to the [Ceres wiki page](https://github.com/artivis/manif/wiki/Using-manif-with-Ceres). +For more information, please refer to the [Ceres documentation page](doc/On-the-use-with-Ceres). ## Documentation The API documentation can be found online at [codedocs.xyz/artivis/manif][manif-doc]. -Some more general documentation and tips on the use of the library is available on the [wiki-page](https://github.com/artivis/manif/wiki). +Some more general information and tips on the use of the library is available on the documentation `Related Pages`. To generate the documentation on your machine, type in the terminal diff --git a/doc/Interpolation.md b/doc/Interpolation.md new file mode 100644 index 00000000..8dbe06fa --- /dev/null +++ b/doc/Interpolation.md @@ -0,0 +1,30 @@ +# Interpolation with manif + +`manif` provides three interpolation algorithms located in [`algorithms/interpolation.h`](../include/manif/algorithms/interpolation.h). +They are: + +1. Slerp interpolation +2. Cubic interpolation +3. CN-smooth interpolation + +A brief usage example is shown in [`examples/se2_interpolation.cpp`](../examples/se2_interpolation.cpp). +In this example, `k` points in `SE2` are generated on a 8-shaped curve (large blue arrows). +Between consecutive points, `p` new points are interpolated (in `]0,1[`, smaller red arrows). +The results for each interpolation algorithm is shown in the following figures: + +![SE2 Slerp interpolation](images/se2_interp_slerp.png) +![SE2 Cubic interpolation](images/se2_interp_cubic.png) +![SE2 Cn Smooth interpolation](images/se2_interp_cnsmooth.png) + +To reproduce the figures: + +```terminal +cd manif/build/examples +./se2_interpolation 9 0 40 > se2_interp_slerp.csv +./se2_interpolation 9 1 40 > se2_interp_cubic.csv +./se2_interpolation 9 2 40 > se2_interp_cnsmooth.csv +``` + +Then open Matlab and edit the visualization script [`examples/scripts/plot_interpolation.m`](../examples/scripts/plot_interpolation.m). +One should edit both the `path` and `file_base` variables. +Run the script to visualize the plot. diff --git a/doc/On-the-use-with-Ceres.md b/doc/On-the-use-with-Ceres.md new file mode 100644 index 00000000..1c0ea267 --- /dev/null +++ b/doc/On-the-use-with-Ceres.md @@ -0,0 +1,240 @@ +# Ceres + +While the `manif` package differentiates Jacobians with respect to a +local perturbation on the tangent space, +many non-linear solvers +(including [Ceres][ceres]) expect them to be differentiated +with respect to the underlying representation vector of the group element +(e.g. wrt the quaternion parameters vector +for ![SO3][latex1]. + +Considering, + +![x][latex2] a group element (e.g. S3), +![omega][latex3] the vector tangent to the group at ![x][latex4], +![f(x)][latex5] an error function, + +one is interested in expressing the Taylor series of the error function, + +![f(x(+)omega)][latex6] + +Therefore we have to compute the Jacobian + +![J_e_omega][latex7] + +the **Jacobian of ![f(x)][latex8] with respect to a perturbation on the tangent space**, +so that the state update happens on the manifold tangent space. + +In Ceres' framework, the computation of this Jacobian is decoupled +in two folds as explained hereafter. +The following terminology should sounds familiar to Ceres users. + +Ceres [`CostFunction`][ceres-costfunction] +is the class representing and implementing a function ![f(x)][latex9], +for instance, + +```cpp +class QuadraticCostFunction : public ceres::SizedCostFunction<1, 1> { + public: + virtual ~QuadraticCostFunction() {} + virtual bool Evaluate(double const* const* parameters, + double* residuals, + double** jacobians) const { + const double x = parameters[0][0]; + residuals[0] = 10 - x; + + // Compute the Jacobian if asked for. + if (jacobians != NULL && jacobians[0] != NULL) { + jacobians[0][0] = -1; + } + return true; + } +}; +``` + +It produces the Jacobian, + +![J_e_x(+)omega][latex10] + +In Ceres, a [`LocalParameterization`][ceres-localparam] can be associated to a state. + +```cpp +Eigen::Quaterniond my_state; + +ceres::Problem::Options problem_options; +ceres::Problem problem(problem_options); + +// Add the state to Ceres problem +problem->AddParameterBlock(my_state.data(), 4); + +// Associate a LocalParameterization to the state vector +problem_->SetParameterization(my_state.data(), + new EigenQuaternionParameterization() ); +``` + +The `LocalParameterization` class (and derived) performs the state update step +of the optimization - the ![x(+)omega][latex11] operation. +While the function operates for any ![omega][latex12], +its Jacobian is evaluated for ![omega=0][latex13] thus providing the Jacobian, + +![J_x(+)w_w][latex14] + +Once both the `CostFunction` and `LocalParameterization`'s Jacobians are evaluated, +`Ceres` internally computes `(1)` with the following product, + +![J_e_w = J_e_x(+)omega * J_x(+)w_w][latex15] + +Voila. + +The intermediate Jacobians (2-3) that `Ceres` requires are **not** available in `manif` +since it provide directly the final Jacobian detailed in `(1)`. + +However, one still wants to use `manif` with his `Ceres`-based project. +For this reason, `manif` is compliant with `Ceres` +auto-differentiation and the [`ceres::Jet`][ceres-jet] type to compute (2-3). + +Below are presented two small examples illustrating how `manif` can be used with `Ceres`. + +## Example : A group-abstract `LocalParameterization` + +Is shown here how one can implement a +`ceres::LocalParameterization`-derived class using `manif`, +that does the ![x(+)omega][latex16] for any group implemented in `manif` passed as a template parameter. + +```cpp +template +class CeresLocalParameterization +{ + using LieGroup = _LieGroup; + using Tangent = typename _LieGroup::Tangent; + + template + using LieGroupTemplate = typename LieGroup::template LieGroupTemplate<_Scalar>; + + template + using TangentTemplate = typename Tangent::template TangentTemplate<_Scalar>; + +public: + + CeresLocalParameterizationFunctor() = default; + virtual ~CeresLocalParameterizationFunctor() = default; + + template + bool operator()(const T* state_raw, + const T* delta_raw, + T* state_plus_delta_raw) const + { + const Eigen::Map> state(state_raw); + const Eigen::Map> delta(delta_raw); + + Eigen::Map> state_plus_delta(state_plus_delta_raw); + + state_plus_delta = state + delta; + + return true; + } +}; +// +... +// Some typedef helpers +using CeresLocalParameterizationSO2 = CeresLocalParameterizationFunctor; +using CeresLocalParameterizationSE2 = CeresLocalParameterizationFunctor; +using CeresLocalParameterizationSO3 = CeresLocalParameterizationFunctor; +using CeresLocalParameterizationSE3 = CeresLocalParameterizationFunctor; +``` + +## Example : A small Ceres problem + +This example highlights the use of the predefined `Ceres` +helper classes available with `manif`. +In this example, we compute an average point from 4 points in `SE2`. + +```cpp +// Tell ceres not to take ownership of the raw pointers +ceres::Problem::Options problem_options; +problem_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP; +problem_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP; + +ceres::Problem problem(problem_options); + +// We use a first manif helper that creates a ceres cost-function. +// The cost function computes the distance between +// the desired state and the current state + +// Create 4 objectives which are 'close' in SE2. +std::shared_ptr obj_pi_over_4 = manif::make_objective_autodiff(3, 3, M_PI/4.); +std::shared_ptr obj_3_pi_over_8 = manif::make_objective_autodiff(3, 1, 3.*M_PI/8.); +std::shared_ptr obj_5_pi_over_8 = manif::make_objective_autodiff(1, 1, 5.*M_PI/8.); +std::shared_ptr obj_3_pi_over_4 = manif::make_objective_autodiff(1, 3, 3.*M_PI/4.); + +SE2d average_state(0,0,0); + +///////////////////////////////// + +// Add residual blocks to ceres problem +problem.AddResidualBlock( obj_pi_over_4.get(), + nullptr, + average_state.data() ); + +problem.AddResidualBlock( obj_3_pi_over_8.get(), + nullptr, + average_state.data() ); + +problem.AddResidualBlock( obj_5_pi_over_8.get(), + nullptr, + average_state.data() ); + +problem.AddResidualBlock( obj_3_pi_over_4.get(), + nullptr, + average_state.data() ); + +// We use a second manif helper that creates a ceres local parameterization +// for our optimized state block. + +std::shared_ptr + auto_diff_local_parameterization = + manif::make_local_parametrization_autodiff(); + +problem.SetParameterization( average_state.data(), + auto_diff_local_parameterization.get() ); + +// Run the solver! +ceres::Solver::Options options; +options.minimizer_progress_to_stdout = true; + +ceres::Solver::Summary summary; +ceres::Solve(options, &problem, &summary); + +std::cout << "summary:\n" << summary.FullReport() << "\n"; + +std::cout << "Average state:\nx:" << average_state.x() + << "\ny:" << average_state.y() + << "\nt:" << average_state.angle() + << "\n\n"; +``` + +[//]: # (URLs) + +[ceres]: http://ceres-solver.org/ +[ceres-costfunction]: http://ceres-solver.org/nnls_modeling.html#costfunction +[ceres-localparam]: http://ceres-solver.org/nnls_modeling.html#localparameterization +[ceres-jet]: http://ceres-solver.org/automatic_derivatives.html#dual-numbers-jets + +[latex1]: https://latex.codecogs.com/png.latex?SO^3 +[latex2]: https://latex.codecogs.com/png.latex?\bf&space;x +[latex3]: https://latex.codecogs.com/png.latex?\omega +[latex4]: https://latex.codecogs.com/png.latex?\bf&space;x +[latex5]: https://latex.codecogs.com/png.latex?{\bf&space;e}=f({\bf&space;x}) +[latex6]: https://latex.codecogs.com/png.latex?f({\bf&space;x\oplus\omega})\approx{\bf&space;e}+{\bf&space;J}_{\omega}^{e}~\omega&space;. +[latex7]: https://latex.codecogs.com/svg.latex?{\bf&space;J}_{\omega}^{e}=\frac{\delta{\bf&space;e}}{\delta{\bf&space;x}}=\frac{\delta&space;f({\bf&space;x})}{\delta{\bf&space;x}}=\lim_{\omega\to0}\frac{f({\bf&space;x}\oplus\omega)\ominus&space;f({\bf&space;x})}{\omega},&space;(1) +[latex8]: https://latex.codecogs.com/png.latex?f({\bf&space;x}) +[latex9]: https://latex.codecogs.com/png.latex?{\bf&space;e}=f({\bf&space;x}) +[latex10]: https://latex.codecogs.com/svg.latex?{\bf&space;J}_{{\bf&space;x}\oplus\omega}^{e}=\frac{\delta{\bf&space;e}}{\delta({\bf&space;x}\oplus\omega)}=\lim_{\mathbf&space;h\to0}\frac{&space;f({\bf&space;x}+\mathbf&space;h)-f({\bf&space;x})}{\mathbf&space;h}.&space;(2) +[latex11]: https://latex.codecogs.com/png.latex?{\bf&space;x}\oplus\mathbf\omega +[latex12]: https://latex.codecogs.com/png.latex?\mathbf\omega +[latex13]: https://latex.codecogs.com/png.latex?\omega=0 +[latex14]: https://latex.codecogs.com/svg.latex?{\bf&space;J}_{\omega}^{{\bf&space;x}\oplus\omega}=\frac{\delta({\bf&space;x}\oplus\omega)}{\delta\omega}=\lim_{\delta\omega\to0}\frac{{\bf&space;x}\oplus(\omega+\delta\omega)-{\bf&space;x}\oplus\mathbf\omega}{\delta\omega}=\lim_{\delta\omega\to0}\frac{{\bf&space;x}\oplus\delta\omega-{\bf&space;x}}{\delta\omega}.&space;(3) +[latex15]: https://latex.codecogs.com/svg.latex?{\bf&space;J}_{\omega}^{e}={\bf&space;J}_{{\bf&space;x}\oplus\omega}^{e}\times{\bf&space;J}_{\omega}^{{\bf&space;x}\oplus\omega}.&space;(4) +[latex16]: https://latex.codecogs.com/png.latex?{\bf&space;x}\oplus\mathbf\omega +[latex17]: +[latex18]: diff --git a/doc/Writing-generic-code.md b/doc/Writing-generic-code.md new file mode 100644 index 00000000..874f8547 --- /dev/null +++ b/doc/Writing-generic-code.md @@ -0,0 +1,67 @@ +# Writing generic code + +All Lie group classes defined in `manif` have in common that they inherit from a templated base class. +Therefore, template-based generic code can be written - similarly to Eigen. + +## Examples + +### Small example + +Let us write a simple function that take any group object and prints some information about it, + +```cpp +#include +#include + +using namespace manif; + +template +void print(const LieGroupBase& g) +{ + std::cout << "Degrees of freedom: " << g::DoF << "\n" + << "Underlying representation vector size: " << g::RepSize << "\n" + << "Current values: " << g << "\n; +} + +int main() +{ + SE2d p_2d; + print(p_2d); + + SE3d p_3d; + print(p_3d); +} +``` + +### Multiple templated arguments + +Let us write a function that takes two group objects and performs some computation, + +```cpp +#include + +using namespace manif; + +template +typename DerivedA::Scalar +ominusSquaredWeightedNorm( + const LieGroupBase& state, + const LieGroupBase& state_other +) +{ + return (state-state_other).squaredWeightedNorm(); +} + +int main() +{ + SE2d state = SE2d::Random(); + + SE2d::DataType state_other_data = SE2d::DataType::Random(); + + Eigen::Map state_other_map(state_other_data.data()); + + double osn = ominusSquaredWeightedNorm(state, state_other_map); + + ... +} +``` diff --git a/doc/images/se2_interp_cnsmooth.png b/doc/images/se2_interp_cnsmooth.png new file mode 100644 index 0000000000000000000000000000000000000000..7d4fc6da4a1fdd76c3085040f64b20fec60a0707 GIT binary patch literal 82946 zcmeFY__^iYaj(7hifdha&-)i@@|2etE-?4zE3=-^_k@+#j>2U%A4HE*DLN>oV)+wouKT;te`Wwnk>4{E3VzVS&{XUH9z-^IVtax01=d@a1MvX-( zEPi>>V!*}i)z80wMl7h~ESp9Co^l3K$f%S;Ag%X!{Hdkx@tU+AWM<2q4-5OV$v1s? z_AKOr@1K@aGRVyCFvFQImm!nQfmNUFgEovInlYz++A(JzT{_dS@u%`H##G=A1ag<7 z6+){Ja`tl&+fwlLlsBxC!PH+ugwIKHI6&^UKfCnj9>umf#Z8%uYat;o$o2-$@eE!q z%)Z^jdSXhnN)`{1nw2c>oP_Gi)J7*`Fk zQ8G&DiCh=k^J(FB7duHnm;+8l#pPOc1rZ>}$jCyF^Ku_n^+F0?3n|9XH zu)?C`2D}|xVd4NmhhMA^S$hy2WcmBa6XQ>;{WNs%W`FU&GIYuR!Z3Bwh^~~$i%R$n zqSOED$d>DC#zyjKN~YkLw#A2`&jApPehY#A&j_oJ^BzGG6*j=SIWZcgRWgZ#Kl z3W<5T!?ME{?9!^A)3PFCd45dK*>1DB-l~5;rQG~1<3688I|su}E+q(SY-Nb1tX-i| zZlu<i)a^B(*~1h~u)k z`x$?}rqF=IlgJa9w-0mJf3w}-sZ`C=%~Q5|J|`5?`@(YaG4#Jj`Q`Od{?M)p*#j^)K(uC9mmoYoJ8I4B?TJcM&laME#jaY*T8 ze}1K7p~I(5GUkQ!LJrs}*nP2^v#Yj? zgbxcj3JM6`7TSbgul{17Xb@hrVV{d-!){?~uwL#j7`4*RrMHQ;A^#wI_3}&Yjf4u6 zM`}j;#vMn}2Q62EdAm&mQ_v*Bzi)O_)HHh;EE)jpMjg7tzbSTXE6%mZd=L^}~~ z*xh6vEnFu&0}Gfw$_*_FZT(%{VVcyCq?m+C5`YVix0l!%2-xL2(AbTcu~skW%j+}M z&|*0-&#{77@j9J~s9ML`^xBb1ao^qM24>hOgt9$7S1q?z%`;%iL`_Osg$6Brf60=OP=aPYmZ6L@XoobC5(|67+aFB<#d`G>!ttI8`N%BYe_xdhtVCE4-Xo%o6G zefjft=KTq6RZ@~}{dgs`ng{8)Z}qneEhTm`HByS39{jq&AwphQsn&GF`a7ATP(qE6 z{wu>y3h7x}8jpE773%J|lC~MWNxT1c|4OEt)WifFgF8S@mvs(srI$4^yJWB3pSSqc zk*MsQOv_tnnt{IIWnJlPITMe(r?*KU?o%1>eDR!Z*x5spd6FeN>EoXSj{IJzH=HuW z*Qq*tQKnt-Jb`T+E`D5oF~L|RCgIh$xqr3nR`U}J0oVDA*``$jeq-jYv6$!)^PjJ6 z6@MQ8YFi2yh>2rr^8R%Edbw-g<>>X6)=**Mz+8sVN$H+%_@MS{^KUK|f9g+n*y9_! z^a8C;D#UgE2A|}(8n`rAf45yYD%n}XC$E~QH7Nzw2y6`0(d7~p%9zJ+ck&kVKM)SBkwp$+_a^6K{k!fb2dPxTRHk)HPX;sJw9-Y zw@ejZzC57d&H31YuNRoZ0KLf;uSiqF)C`kW-q)^yVlAgccRi7t4U7j0|fk)7j`zTUR={vFGq}R;R z3UJc%ntYxR>G|%#Fazn?e*ORL!_7hj5q*A=nF=iDGlWD$Qu|=5dp^f39CD2d=w$LjA50)tVbUSVJ1NgkQc6TbgrH)q`2{ktlY`SnjujOZ zE#*n2s}1x8AnPz8Ut3$H@5e56m-WM{_I2P*Fbj(ueQqeCZ%KaMRRnZHC~hD4p>%Oy zu9vmUH{VHBDbPitwv{hICQGhB%#QOlA1W4U7q1^G<=^kxX_U*oZjAZ0=vJg%S-0yi zrR0*a*w@?3?OI0T_ZRoPq6A%%NpnR`lRj+7w6L&{E3w-k27XsSKp@V*H2P__nQ89R z>_ML%rTiP`-sGvUjfgsMT?nqHh#8BhguvRV}j#zlyIp2+ihZ--URkWM7RK3AH0A5{d0@1JBU75Zfy0{>60J*zpAO) zuUc-j_t$pv3o~GdazCi!{Ldh;*(i{um{*9o^egl16!#Q6VXDJ`<1(yjT+)Z1)>;Ktw`G*W%+zLUuZZbY5#^B&kd>^=}FIO z=uSaRErW*Pjg-1iW1iCv1EaWMS)BQLnG-s<4+0IJ^sUKQMc5#Up4aDiJldh9U;LgT zJDkR|R~jIE<|*h+qIrL9&PomLGM5SaBgfnQGT7)d*}TNS%!Fg58DGG6Gk zAp~n~|MCMlau6>VXz-Xf! zQ4TiO(UHa4oPB6+`>r=00hZ_>`)M6RM`WCnLVC85(V#i-9Q3<%RyQm{l zC8Ekv1UMUiYPGSB-;A^G!n%2KBU|O%KY1tOHl>NBrDOIzK4oWHVe$rKK^x@)x83TE zKulZQ0Y0fqm4wvi#wJ|>7Ma|`!=+IYDe*9~ZpX^d03nvbTDCmLi>kypz?o#xwD4&s z-U$5-KI2s83v12hmpu|H&NMp))++EOR|)@E+)-X=wc>xtnV55huZwVO#V=CFwOm>9 zlRTZk0Fe$~x_A+C`(CU<-pI0dpp|--UM-ocXu4YAh&g?KZ|~&78zh6Z%>wTgc+Fq` z#f8tc@T5i=B=GKmMgJMTo0mMtO>u{`kTr?QFl3QiYF8(0*>km38w zYvN^dQImT0)Y9zgqu<3-A%pB7JC0k-+%(OInv1G8(T3T8L3*C=>J3%s3%E#`%oQCWR7mO^AQxn`p(-l}m zUkZ%Z_9Ufi*u~gozLj+v{62oeFkFM1Ho3;B?=CcRpzdz_RkOs^T(J2Oa<$Kz@}A!x zg2s%NK90Y+S7u7uo1RwMz!dNu&ldDj8cpECYcIFQUbe7n4J@b(GXw>+HITALy-~kY z@+SqBoB*oYHRdi|DeT5@1C0k4`a!M4%b5Ococr)Qi+W%R*UoiW@sm=F4mT}3JNx>} zFQ~c6?t$MFTjFI#yrlFjhGn%u89F5PSR=kHG|3=OnOd-eYGZtkDKyASG zYNu=^f>mD}_yt&4d<%TuWHY z`!=`x(bAadQXOI>Qw}j=Kp{X-)SqKDTq<`nWgPh$Uq9FLcry{iw5_OfXR_ESQ=-M5 zlR?TEK$bM8FO|phWw5ccFQU>c$iH`Xy46p8A0UzkZCKy|u3P=qPnZAT_X-atkR0Me z11u@XBUUM2d;sBPDax%}pvMxFuI422DAT^C;mqtg&~{Du8UC&`A25<-_XdoE=W9#F=1pSrj8D^|_bUGr zl6YHk28MK?RiB%8m3Pm_82Ivqwpae=$w8Z$z&#Wyg82g2_oh!ED%3})!W~0vuC7nj z?^JZ&HT=p5uyat2$B3$M)A73V=01l{d(h(ooaK_sKke&sCU!VOg@kl?lerR=>WxY# zR+~4&%>lj;JED<~zEl7E1J}ZdEpdOH&u1t?m*0t7o-JPF^k^q=(JP=3N49LbPmI0V za_6hh--wpK5x$#E$;nv}8_mQGuf|zM<&(|xtDVi~gz@ep9dxEs>lM3Y&+mU#EPP@o{{k_meAa^%Gtuq(;c#j(*+$H!Cr)xc`02$p2sX|LyAk z5~CXI`gO>XF^RGWO6-B@AU%AqL40nK;*8n+-2i<)-_*1|rx-G6zJF{-$yBP%O8Z4) z7xFiht=I>o>{MbzZ~t1KFpVrKa-t%a9=P}KW%ti4Ie8rvXZpte3&<`li3(}$4$aO8 zFo=;XMwaPTe0HeCk)0iU_K!3{?%i(5cJ_Og8oBLF6M?@=8Dt_uB3bn7nLp;49?*=f zUOJnvsZ_YUOl9WykwmxX_V2JPiwtPc7wc$!}bec*v z6`RY79{L=T>GS*(q4;kzOTOl||NPFjc%qU$G*RK&B&6ihzvb$P5A^w}u<7t3F$tSU zO^qhC2n7i8=|4GW3=QKGx;|svCGLethX#L;g_@I&b$|+4M=^&;Cw?f_0m@jqX~z={a37#o_BlYV zDa-*=x3IiN5dMJWt`+ySC3L6>Enjzo}59Il8O^jr2!p?9h;n?lR2H z@Su(}acMcGuh;<9@4F!K=uxX{Mvc(u`kB@(f2rgiOb;M5ntRs;oEw%4BKVqLZ|r5@ z&w_0zDYOk)tM9wF<2~=1MwGHbU&OV)y>U^8b7uHPognR-mSxhdH=gj&JPJ;1_bawMhUGoV_4-xr=Qb8|)q_RZF@ zsZBh+pMK9UMyu$vNnxQBWY~ZkkW`i`b@FF+3w-=Ni#6E`RUw1fq0k@Ele#DA?jo1Y z&bxBbCiazf4MH4rNwVh~dD>_%W=ai6)&h{dUT(Wmuu*TQ=F&X#{qnwo5A(>=L9pp}1r;6eGBV?h08#U%7xYQwaIW!u-} ztD_)U&mx>ZI(kfZx9sue-;g+d699POLB3)gA%qh{o;9DqtsAXagUYkx-v470DrRJd zm+dH}TR!W~6W1AWaf;&`WcmX8)UYn~L~G!_Z?i9v(?s;7$X+z70lLFM zHgIx-LiCNo(_zWD?iQW=`!jl?eb1e;IsxIh+YHmH!3LYY4$nrPfs~kBb5G0C9Rvz! z&W}q|-Df`Ia|e8Bvx@!M<+1T#>1K6r%GR`HaT!!rVqiN#NT4e6eKG_Jc=4cVJrw7a zdGE{9%&At(3_&&5&-Ez4x#06uS%IWANg~E+ub(R(OL=k5jB=7MOw?4Zwo>;5a(E8R zA5(=Z;t`}AR$`m?_G_Xvqjdiw<7w4_Iy$pU2ByBNhwLIGPgg>(95~%>WmxhHS^M$9 z@PKT|8`z+PQ|$CHYHj#>e-e;C92kP`NH>$TGfCUlo8ERQTB-aS`^>3 zWMZi`ZaC&9rJ{EeS&EGXF1i{}7 z12Y{m{@0>6W}2sS?Xy9C2sFqEsBLhOq*8el2y2uDG6wrkRKm^;%8~~Bvu@x=MEIaZ z`?h%KJuW$jJ2mR)jU-_62F1o-G33#NePTJY#1Hg%90^=Xesr~XZ2Sp|HQpY&EOa&t z0Ti`MGNQZY0%Ha|233Bh&FWyRHEDWUl5v05op@6G(l4JfYn9X&z?Pu98oXs&f(l$$ z@OP9UOZQ20zXx;EO>R$!<_is2^0Nf-<^s7hNpj276f=L^EbIB2dgWr)ssmRb+q1LB zq`X2`;=OsIE0bjqbx{G*z@4aBrTAYwYAw)17MYkP1N)KSp9k8pHav(Q4{8R;r+hiF zXWO6rs}JMM&do4xW3oa2q6B*($><=-f32uhL4}Cw^UPPlca)B$Pnl6?CZ`;HkN4Ez zU3qD${U0IjnU3?OWnLhYK!NYJF2IycR_kp0Dg}5j9^n2BM)#z|gpB0YtqZ!SQeW+= zZy&J?K^vsy=z--xAB%~(Gyw)9|1IBnuuPc^D1e!kq{H{wPE-If@?H_P9ZIuSkAY;Z=IEZ>7O00v*S#<#D}T=# zf7_?v#yO>Y=*GmE*88L}Ad&#gweSplj|q4m1OjCu={@KlvU^DS94VYYf>ht@o=6Y; z1HulvU=w}*gJe}7K<_2R|GGqiE>!<@u^@G!|A*SBNo#BaYlJ`$w}B0r0KbDkCZ|YW z=lu6|gC5wJL;p#Qk>q-sfny);$uRire{+tdrr8fDc1GK6n&5qqL^yvDmA?Wtb@3R> z!wb7fbxXy_DfI|huVYT&eE(}m^q74iO<#$?fcE`t;U>F%`Le*KXr>9obY9UzulXL+ zQkYhJeD@;ja{a*AdL5ceLY*(Le)`x+v3Nr7(?6;1lBAOE6j$ea{bu@4*hr}#5y!eb zZa7bL+ME2@$hI-=yA5|%c2C9s7MaP*l5D^Upd9Y6+NNH_hu$W)K~pCwV+&z zWq$dRgnF7QQ9v`B{|W~8Uc$WhA+lw7CsRsnbCBRMpUA*4+!{1&$9ki9Vviy)3uU;s zJJRs;tg32}(Risbw&K}hW|_T?Fn(?W4Nqoc-)me{)RZi9&@EJ3-Ye6q`0VQa5)<)% zexSF|MDKn!&e^%;WZ*<4F5t*gRrO))E3Watr7_$`~IY2Q6u3#v;|QIzO_4{V9PI~Eg=_f=+nGP{K+MtN09QxwJLC$n6A z@`p-{i689d-DjlTOo`cC{p(`vk$9C+6!l(#-u^To-MheZZEzr<;Q7<#YLFw#LMZm? z0+CjlsgaV08jkqlipSm=lKYSQdY9sqciWikEuID*7Is_hrcErdOAXaJg4(8M8Hg)Z zuqb7U_EH|6OmS+`F|1t*VbX>o-F-6lTz4o_!MgeWDVF=^Gp4w_z$1Cq8&%eVikp6g zcYPEx3ct$u{|PD91)EjXKP+_|@AO6HpfOllKtOa;++?{%F5$Z#Y?LctpL2V4TjAsh6K)`ZrYV>_2nl1zbLOupmiDI5h6`e2vLr&J2iMhNLk7L4VDPQ2r)X3%?Mv3ir&8LoM`=kHo zE`Wc&X6eoSu`;FMy5{`47UPbb53`SmWlMV@K*p!s`o0W0uH@_2M0|jo`^p@nrhbHtZAhUodT)5sa8`I?U*`B#^1mRC>Cb2~^%poFg9MT692NHZht2sz_{$ z>FLP~SE44AYi2^YIU8Q8k)7rGlDNMdc=S_=Wyr}r>Zje!Eq}CZ-WCAn~(|Z5*+l!jC6%V>!-PY^VDA$)= zd72OL9?3+z?5s_H^|)f4rd8v^elKm*3U%gSkyhL;b^;Xhiu`h&F{`oiyDNIDWheI8 z;Q&_rk2o_#2}a2hM_jc(`mV3aay1*<)b0-zIl@etaHC9f+4H9vg-WuCANnN?Pj>=2 zLH)~v(BWUMHL9wsxctMxbz7X~Qt?EMWjLZRrDwUMilxX%_ZmlhY#wly)JR@5@WVf3 z*8B_%uD+E~QFg1k!dT1B-38%Qp|Vs$HYs+IPD>$!>e~n8bRPac$$Wla1P-*(q$fO6 z@<_Yl^Ono}PQ#(S|KGM^Z6h<}*v+uRZoS=BGEjIZJxtb;+~iH}v4_%}$u>mOp5DryV&=o2c|-d)P|Ioa6@VfwP?5E62DIH69=*Q_ai9y}oGQ2qS= z^>Z@3$*cR)KIg#A2*{w#2`+G?Kb_(BNHik|3kQvCY)0UGcCJTFrWaJfT!_RxD^20) z&!DDMHK-2b`CuP+DHPLf*lvPpXsU_wuC>c+lBp_kH;CIntIK4$W35XJ`f8&6exC8) ziU6}NN)`&Yyku8f`eUB{esC4PL6 zxw_T47feTTcHY9LG8u*L2D7t=UFy}&ncLo8{*s%n38-%v?-Md*j?!`T>mYidv4)@AWnRM}@%u}PdjYciB*J}Gk ziJeH6bkThG2A* zHKd$U`I5w)O;qKX=&{Xqdr?qz@9h3~fUQyP$k|_ai-$4=8p%h0v1AybozyHkv7a|Z zF2AAB<^ZLCEA~H`K-4=S>>W<5MhXA|ME_Htnl5i4Ov@&7{gQ31Qj(ILj{(>&=2zC$ z+DiGrwp7)+cc!+X@Yq&ZgdOS)kNx#qp&&|i$pPS&BQsVz3+yb5Om=zE?n|vRDPLH)TCXe7k+Hr1p*Hz1#h2G zdC43+8UTXB(ZVV2&gV}L8kKdMH;WBre(uY`DUEAsthE0YYhy=}YhIXDbyn{+y>q;t zs)lY;aynn2YU}x|)}RmH!3*nIG`=-hY9;2UZwUCMVXDB-;Y{O%7Cyz9liGd}d8y-~ zi~ua-KFWD4@GsTS=31ui$-Z|JVfrNP=slo|K#G?Dt34nl@nD+_ixT`yfjzV1`zM;E zaKn~925~no>Sa|-JYT<=yE~TD?G84p&sF0wPuejDh)(qO_T7x_y1#PX()PV6(Y0x_ zs##gsx2`&jXc+|g!FOgP_JPmJ!={5ihP&hSi!1NhcY6hVeqCnmqQ8}U+qqinKCv({ zuxTS>)RyRyML|j+(wmpgTJ!tNT~}3W@QfA^DApzsp#X+S{y9UJv^LCtJAduYkCEHI zxh}w{jlII0w}0@l)?9%t*FwWN5Y2LYw8(I0bZgdU zR|D8@z@e5R7OmIT=A<-7*J3NLf$SUK@zL3Z@YP#woVc~Z{=ry@zN9LU-iMfq^xYi^ zZXzHF!sNoK&_`NjXr<)!{UPitDGO@+ly{5|v|Mrh4Ns!0IX9;>=2pz!p+g@J_9gCa zm3Err5>sEeO1_aRdPCGZ!>LgNV5DO^W0%moelJ?~;c-A642*#BqGlHq=T?-DUdlWv zQa3oz`(ON#Ht)dB${EDJ`*#km2aTmICg5l2zk&M zG0%9x$2M9_e(!@>Op1(v@37R zf2ShmR#)SGjU2x(A+6%E02JoA_9!=3j^D73q3g<(ls9MGX8be2c{^*ykG`JfMgf71 zS&0j(?79*KA?16NWS$j%vN$9I<|!bma@%%%`bJ>CiL7yk-#wN4O8BIKLl8 z{WY=`II1bPm~Vr}grY+Cm4tp#u`BR5&l*z}W;n98diw(E3g?eme3@ps8|;bvx8nniC>0uTtd zy;Ov`?h-xm-QUGt@B4pI|38XYfU#UhGr|}W4KoLtQ!OR3er@)h<+xRl7d2fTXhsG zT@-gL=rJ}-|S%3eTvE-AVBk3pmeP*u1 zjhQ|_-%=2n~rwZP- zFg-lpO)7XxI~0&s!ze{%7PZR``zDS_G|b}8`?jf(!L3n!yq}4tr^;ooL%~^E^XB1S zQ`h&!I*v1?)a<*vBc-$N^0r)r7+_{UhnWHvhD-x{`cF3pk{^fBBPVo_ebnFM6}>Yq z|7=~5bwtqt@*^n%%K)w6XsOxPc*onDzBtZ+%eg#642(a1W((c>O}CmIE+}3SdtGAd zEqc12rF!R=-%Mgg&ePO%XM6RPb-{0;&&jKeN+n`sfw39apcbm}60tA%MFwKVKcOgS zFY#JUyG8^MysU+F(Yu<*OY(=msDNo?_-Xp?gQP!Yy*%1F*cyb{o-e-2WI~WBl@cQt z63uixew~@7StX*b|GgonwzgIQ-UO%@ZaO>4W9AQzL!mx+nhhwSy$7bHXOzu!@}jTc zD$_XJ6lsh$3hh|XyFKinh|<>NU*53QO4>xLMMm72Szx-|un^@5y+7IT5=XhRH&SeV z+tT8jj-I3aOp~D(J|BSEpIHHapLrn!`UkbtmwN?Tg!gk6k6-(|dS&(#O|U;bp=4YX zO-YLr6dS1Co5eRPMSYiRVepTx{=W-YzL5Ufj_>(IH9!Oa^yTvzKk9I}hP!Dsa94s* z4+=uo`0n|IiwT$#91OJ=yA(*iX6Z{oHq-`??!6*l{6N!M5|N zFwH9qiwp>q;5Rfql+?ebR6EW+0jfIU3w5>r8J~8iOh+y;;|c7uO8rsmg66hcz|u#^H`kno#~A@nkB4M_Uw+8c{)xaVQ5L--7!QuS#K$Pa&+k@ z;N!4~J>4+CKfJ%#w1>jhs-is=HQ91~H={aBeteb+Koz9k0tZORpofF!vcxt1TYbIN zb$>H^tZSvGUVhB6%kRd z>r<${hih+Vd$L6kx8@i1(=SSBK2VkT6STiMQR~P+PeOHDogTm6X1soit8Fs#(uxZU z_vmD7_!Z_9;~UyN&$>{}9$)A$dKPgN&h9^Mob$X&Lx=HDm;aJx{rHq6S<-^e4ev?aiE_D_9I zdQsI&?+jOf#?b3|>}*K^NE}5HI9*H+T!aI5*?hg_i|W1P5u{1}YUxND)#_IY5Flf( z3#+;h+@+*C-LBwMc8zC|+P*$<9H>=cs=_0fI95sN`nR`@bmS4#$1M8ZZ`BY#FSa?# zcUtMWp019}@mT&U z)sjX{8e&RVvb5;on7tC4PSNL~7e#s6-RVEo)WCV)d`*KexEWj@W&2YS{{fkP8v|helmI#gE5$5vp?@ladbj}+bYl* zWdR@mQ%>w&$PNef&;xY|w&m=t9oFSJl3>aM%u%VX7)MO`6Sij-T7bHhHj*t&X*oo0 z7|kAUP5_t*u13_Pnd~rtT({Fd!ex?8!8E#o2esccL1{Sq*|z^gEfF`Pdp|p#-Q!oN z&j=!+Zza`cj@Yom$$Dc$u#;EgX&D@f|MYdsMR;#uAx*AL)x{xQ1E#FnT$Y;3YEQSy zabb6_432|FMJo;GC$AJBw2Of0i9N?LROYG36^+{U46GGH!M#{D%w-<6Du=yZUJb)M z4!Q^$-=1IIO8M>s62Ki4u@!B`-V3SNI`v^wDUWvi_Iq~0$3rOdQk5F427Knxrmm)z!vwOD3zw&ouKrc-VN^|$M5Wqe0Vd`ip8ym2R6a$h1mgs74~XS zeA9a)ZRzlrx!d^5s)ROw!gTYj;^-414$92s&5WiF`6cnnm z&6?PBoqN+|)w{cEQCBA%-Q#QSgMFPLvMKKNw>(ybKJBTww>-zq$j#f}B0#~A{_pPs z0&G{rnzjlCZBtTj#Ve%(FjVVU=>I~2JYS9SYU(VG0 zfAs=zcOc(A$^u0oYqIUCuHvO$N`)EH3fzI| zygTApr|1eF7R~HLDAjjraW@piMwI(AJMP3yr*N)$Z~I&Gmp0b=)_HD>_NRO9VaLQy zH#!aX0l-QZf2at&s&jJz0fBHT#4qy)slv@e__Yo`s7=N)Z_9?q zMj@Sv?Z0XPX8Xg)r${W?>ihRdE8do=V~^7lj6H%ea&du}`Bn)BcC>SVp_?&3$Q%bv&|ezj(7Jkq`HDnnOf zWXdn|D(i^YUb^PN^$K2|RKcz}@reQAmQx|y?zA$4I=BEx3#g-|3?ICIpJ~~uqjP+o zfof60c?#C$Hm32fAx<6rL%B{7I0@g~!DrY?+1%WQxf^)zLeI^lJoNxgkd)ARQpD7| z0h2X14yG23YS!OS>`q$xEZkxg%_|EuR+q@%a$$S|BAp{92fg7sD?%_*Rr#ztB1_k` z<36T?Z3)cHq~_Kd^$hegdjA$~Yr@$@U#Fwb9(4z)Q>Tm6{_wSbV&{XWURBSs1Frkg zC!S=FO71S`%?ht-oC%-itM{{2<)Wd%&40+fGmxnDsiI%zl$7ZeIx&&ysEWsmKoCVA z{Hn#YOZz_mx)nI1QhwD--wFeVra_c+La+Vix%OgCKf}Paagg-mhV9m|`C5f6b{07N9A~!&#s3S{l%`l*)(r$jIt_y&RrFl>|E`;M63Fy(+nF(>n$&UK}D-Kltp-l>L(Me$4ZqGy9F?f(MRcX%7frw^0UJKdzN~8Y73+q}{pkU1Z z?b%tYSf)NbSsS=ezi98S{fuO@ZEbW*8S-_R4-|a~4G1Ab!{6V$SKVCpo61Xs{pd9f z+ZIOGi&FH-z~%FDmD^2DJO(_E1uV}~^dU_hIce%_=R*11{SSe|#yzCPpN&gyY`;Qv zdq6|7}yfi z0oegyN&Dt@{>zsYcw7E~6 zFp^K%+E7y?Yp_ZVDDZmd;VGsoPwcw*t5$^tEIeux;ZN*!%dli|+x;x|O!QUjohN2M zML^I^lLx6dCjoO?&kgs*f;f@IJC>1`VFCgR)S0i271mOJWIqFh3)%~jE@l&GoNHd% zIIIBL9!(g{s#$q$dM?_Z9!Q}-*SZyoylVaAHNAEVN23P7$EXj9fmbaEr$7t-J= z^iDqoCcPYR#~kI8wM6({fukVIceGPMkQ-+mK%Rd1An}8kHaq_LVf=9xJ!4dJ!U6R$ z8q@!5@zbnH=s!9Je;1Bkwj*?mHqsuvt~0hPpH_gwBdW(QE5KV_9c>M&Sg+tv17Vq$ zc^_ricy0(q-W;D!EdoO+QJpsGxa zBCgb8W&r~xs*SZVx1MiNvaa>8;+-(fuTo1;T4-49UHZ(kCR~?p$x`KyMiyf}!<1Ja z$9K`snEok@@N47?kT0Pb#$ri7wkV;(9b{uhGmqZ0_!H3Gi#1+lfNB7wv8pra{AEt@ zpc$Nig53Q(qQ*Lc1snze)^u#uXHkrmR4UEA^D`Bm;Z_u$%JMV$?{FB3%shHdXY$!^ z8YSra`(k1b$nj#H9GS^^dQD2p)pByXVlBBv4*^xbTBZj@5;sP``FP-7ncx$S0WJQb z(?e6%cC;I{|@4CF)%3)UIwn8njXnU#Sk>Y!}c^# zoQScxyziaHh%0Cb{oL%QGDV|lJnU7JvTFrCwLBJgXf6SUKc7!=81KauuTfLnrKqaH zk!d0peBcq*RrB&5&8^4*i*$0!Iy`gkzm-z%i7^!X>#JyjxsL)o3OwJp3?s#KY+FaMG8xk%h)ab z)})?W1BPqo!Fmfd*)ELxy?8=t=ja$a?gM@Tr(f!!2oDW5Y;{tPTE}e3($)7&7+Lau zX$8nkna@K)3dHX^D&H~?S~u_;Pf&Z+@KP7LOQGJplR|d+!)xSdl~Qfj&i4!oSbek0 zm!rZW?30aQ(|^tjf1?T*yd!Q~>+o1UrlD0t+`*~7gC{D!7u1F#LHGt2nfj>EB$?3s!jZzg_?;76X|<3vG2$ z{ZprSbIC+(X{QP3=dY|OvjwT|tCH#i{A+&$M>AD!wLf*X<3vh9%pDSPbe~Ds*2ii* zS<4#N3^*N&&V)5Lu$D&w3#|2Ks`7HyF@1KRV`;Gd$`;P2+pYv34JxZbWV$f1n|(7ugn$tL>-VJ*rli;Xjs#8y2TyDmsH4DApmv(ss!|{2tCbLAOndN z0KWBwq{OZo6M5|G-!;C8J=p+SD{^Rni)&LX8)$a-OFPB!^tVxt)Tn#&T;6*a9nXAO z&^PrAP$}MIh54hvdbuUlPa{e80DzY9hSvpo9=c9mPPbLGbk%XcB*=xg+`#QQzE}kTvuyMgL8dl9>GaM4 z$_SubtN%s!-`@VMjnhGka#r3mt%snk0cLn#pTm0NsG8eG#4Hq!i3P6aJiqS{Z$W;a z`}oq&cW%RVf6_BZ&!M+EnRQ)PCW2~eLHsJ6!E zSPrtYxL`99xp#G#w;C2Ozj9OJ%KhU{2(uA?Mi`{XetSwDrl`4HrI7#su)`EfdFZ#& zm|0IU&(eKr*`eWV8Loy!E1Gji$8Lo~c@bca%RH!w9`2PIr9li-Yp3hdM)UUc*u3Vj z5&6PqPY9mX?)(~xF&HC|uK#gkbu9h%`8q&?v-D~z7`s1%@b=pl+|38pWuB=~6 z@^#TQ8sOQ$g>V>hShP#(pY^zP@`K!y&jd=heGp|W$(gmXzEUz_-5+Oq?X~{HMNX3$ z0(M!22X1E#HZhq@NILoY@_n1NQ%o5E9Hv6qIpH~V$YPb>pFo|ps+Zew!b4q-1eo3EVO)dat z)sFD#n264kx+!a4&W1ts7d=4%KSrzGmVceFMF-i~c%oNq@cA8tsR#+N-JZ5v=*XAh z{>xZXz-R$^u@(|JF0dh&GB0tgPlN6bO<3aJkk-37gD#q!FP7>IwYx(co@{w+3=Hgz_8RW!`R!yRQ2T}f zFbsa!26cwa2k0<07=<379E0ZnL$T|zB;q{6xgYy?7W;v`rH`=x<)75Np9l1>oQbd} z11bs8$T>|a!6R{zda>MDfVjw_JL)o8(%dt8l_H9Q=yTo6!$N7Wk4EqJUak7hVIJ|4CEg}^MoUne~UT@8zhmD~;eaiV;?O2D;> z`|d*)9s#@OPa^JK8=BqHgr3-k%+;>!aTT|$)`}MmZW1V|Z(d0!)iahg%_)7+ zCIM}wwWhIouna~pH?WNs4o}gIn^>VVppzxOc6-{JokRqPNtTx}8--avZqc_+FlQH{ z^)P8s`w{?p7D`kIeAasfUl43qAq-{Puc;3US2nysefe%gwNlK%;%AP%*TCDR(mM*v^)ajZX2qAKdn7$iVvDb_-Mj+PDEo zZ;&MaH!4JCy{Va*vsD8I5Vwc8v!A_Ca-|cn&bE|!#iF~yVyLTItTwYdnfs+3pTQMp zBXlKDtl5nb+qD%ky-ZKzv7Fz&RBaLJ6H?rsm|JKn+*jJt zR;;>YZOCB5)?-&Nj$kp{@C^#gjA%_;oa}tErAo8>@}Z?rmcPs-%g0evx!wOlje0d- zjLt+q?bN#Ye({L+dK(o<<~R~hT?7ouO1QjiO3LixYwEAbD#~$XYn#w({LRSj6&0QR zJWdH^3at3Ns0Vyw8-4fy-KJWo6OBk|kb9BHOdP@xVXpJ#{0#N=j;;2mZX z4|O^@5+b+tuK;3Fnf&G(8lx7w*%#oChVfBK3UH`}PM|A?%{{(i@OJA9ibALuQn^X$s^1x4!V&RB3Gv+uJL9b}&@XD#l!@)lIGS^uBGfkiS=l!vS<%S#D^npva{?gGJz=p`QGl z@47OgCuU6eTnV@!dhH7j7|sehWYMRgMZ@z^$4cKs>1iNF2%g{w3a z%$;4J2<+Hx?jM(m)|wXcIp2|sJ=M?nMBSZp{Lay1MphhBck{FE)dCImz+kBjy14!ZMMl}yxT7$Z=0)8^ zzEEB@<%&URK$R$P6QsD*+pi!ZGD0@3h4v)?F7?iA^%*vd)0bZR1(fG5mew zpFoX}RC@~brq_eE(@(Tqz*8x)<~9N!qn1B3j@=-05}rQbL#8SYr!<_GWrZbR<#-j$ z61#uDDr?D9b556r{UOz6y(D>|owAzH;5YH%%BEg0H_YX#iGsH4E>4(~gVms-LoJQv zXe3*B+JzKW<9a0Pv)aNZ*Rg!iAOG5AGZ}ws!5t@2J+OnZMfA=_B~>r2*7=(tv&)(M z?+7_wLBwKc!2yC6jcwq{6wy+iIYN-M#H?mhz+IxL@xy8Zw*rb+5MYg|}MdHLG z?tk*p`WH%VSh7$)!;*CL(C?GlVOIhcj#qBd(kebpZZNV!6O|HBuEVQk`yw3*K1Um~ z+?`^3)M*)Ex58Q*HI;XRUDPADVvlH-IudV-%7z%3-4qnEYHG4n+@dE!o(m?^dF(T~ zm%z%_?aJ5NoE3^b)KAs_O%T}Zmib25G!JuM|F;>Nt~C>#KZ(Q^z(Vz@_tmWn_{%h` z@Y(IaGGKb;{U}+mm$($~?Ldrr@8>ms-Zc{AQhx+umoH}a- zvGCdS7?-{vvi&(wNcT|#*mzO=Gx9tp&3;!StJhhbi!j<^L5HF5PBg*fQ&h_Me5*tc z64r2?ZDD|pnNv%+$|k?3VY!EhwfZhTaM%Puk&LIgY4FJ;7wHryh@OQm%DD8W@Oelu zDR?>mjCb=%Y*tJbbaRdFo2|_beL+^)P=4<+lmR`GZSY&1bh-+KW4s>aI-oAZ z-LPCR&L@!ZA1IKX)NgR^+nsSdDE8OW(V=IxJ8G>D3k!Qk`IV76YD~HAkIRvE1rj0< zDl7zqtU#*SV_3&r5Wlako48#gB%^1q9U@CO+~c2yQOB`2{Mzy~-yodI7n-J>_AA(+ z-4BpYssmY{no%!F)qcW@tYa!}ny;@f*PqBoR!SRPTTMYp@y|}HT#$IX-W=28n&)+7 zSbKm=viALR0G&tKRd z$-VcAx8dFexs5;YcABU)M_!2!Tfea2N;>T_mMt>7p{k+Y}IMqvKA1N zbQrzjQa)@bwC-bfIY6b}6<;1ubW97q3UL#~ACkusbxHasGpNN55iM z()09MKn@_^vF?|I7T*G4?rMF3+d?@-sm5W(&Ur^_kNjtHAUH9{V&-rK1+ZNh{xa zf%Lk`{NuNUdTNHa&U;742WEO~6mtDS9ly)n`Jsm~q`R0TTS{3wS?)V#Cs}BaWEZJbPm}ZHcY}#v=c8f@EyOec-xaDIdu$ewrK8xp+9=5>w7Ll??FHw`?jboy6tFFq@ z3b|Jo)+yoZ4ec@C?Xh=bx1=y7I%hoDxgDP3oXIJuolbHfpI1CXL)dd5Q5L)eyU<-G zZw_WlN4uuhe3Q(+J?(vMD+5Ys!x0O9@mVFqb%m|08T)|FfkNJy4;UwN)cyZ;h zJ-{q}tNFa(goh_Xkm{&IK3Qp?ub*D{0FwE*^WEt3#iAM`Sy8PW+(VqfC=}oqmK;%e z49MW+r?hynwQ86g%^Sfa(=G-^(@VQx`^uj6)mVNUo%1SF1oD?)%;4!42@3VKrg|2& z`Qy3-ktnk)fgQ8#e%F#vk2<$P`l3~2U#Kkn5FEfmsR^*UV#(D>0 z?WX}_YH6W_c#BL-sq2JKD+(w{KU?KUlLoP3VSSOvSJ%{W+X63mQwLjedN7TM=eFH{ z^B!n9Na5&Q5v4G3KijE~-lo;~G$;S!(XFCpD+aE#m_l5)W1 zw5UZvLP5$Ox9U8++`7tFM+uS1?lrps#>UCy7mRz0+&q4fnBgNIDcPKrrP%!QOmx=0 zFpW6+qRY*EDhS0G8eE*Oev_w^GxYVn|IOQD&I7z~!_J!|tykz74J**8gs zV1_;6X?f2+ZQ{>u>SRt!$&OryG^x*fc3j{rx$}F=Z#fuA3W;#vR$~W95D{@s-P=K@ z{jI?^G8Lj#REMRZMwb{;c@4Z4Pq65phY=-6?^L;AU=!PsA20dKM6^!`s~pjUB(ojt zO3XzI!R~X0yEqQ>nzm9sP0M)~xDSDBZ7H(krqgUpOmFz(yq2Ej(>iL4s!%uQpZGjG>7@4Vl*kqSM9?C#` z!>_|_Fg+M8g zgF29da4JvgArb@hjY*9QVDc=jPQRnK6;yV9hzXd;bEv<)j@g#VS-D~#t zjB(dIn$)G3X+;ogG5#onSgwz=wAG+_wkngQW)@nL4bQb?9m;g6Zq1i(l6uW4*}{6Y zVQB<$0-wX4yV+~tNrrI*1v-wHt{NZgId(r!l)LCxv{UGi1$Ytza)#9BWYw+mhCZu) zD_h&nW9xaoqn3C)6$Az*q&FgOD6{!qpmL%n(T}MYXUPErrKngTw79!Yg9Dx5S|4sT&Q!tHe?X#1$bz^Mm%dt)AkUC^E*e2fAl znrlayxQ&w1#?`Q##=Q!6^t>xP^k1eWC1@yfI&=5wqu83C73u1?v_Cq`&tL?vb`gnW z(C2)uNg@-z*`Xd5gV5)!3=22ym2};o7N_`793pP02j9z7FtlO(3)(mNE4A^bBQ$+h zV9t>3obRm*ePJ4^yl_5sEeHqVN|u{aO@s}y4zxe4jBe4GSFf{gGic}P`7IJ|WJc_s z-Mf5Uszc=>`H2kSAuStY)hTyoX$?WtVh|qM2EIO%G}U{$E|aHUC0YnQJvaVY-c(RH zbEWhBVe2_Ix7F{7?(zoL{qmGFE=!E_?e**H?UrVW1i1ti5^-mdrO2!dYU0LbVsVHycE7`?DN8W9&2P3k1kCNTf=C*kMzA#k za9-?n>+6%(8SmaLOQ#q|0X1LkIcCQ#7JKVTN&SE|E(=Drzo4aMmIr~?q9yjZHv=>G zF7<)pUb>uQU(Yo?E*;u?sjo0eCQE`u$5Gp0HG^o&Ra!|N1&-9@#tMl+ix`fWyHIl-<->j(%M}3V6S(r9-t!GMd(asXKhQ*p z&rRz?{k)FU+sbZaV>ndgbn-W4WBNKBry?SFM&GtMC+NR4`{MkZi%7%d+}G_)sj%)7 z`kO@N?W2H<{x>06^BFw8Jkrt*v%j(gzjS4}ge7(_KeDxWa#~~O-jkN#dTD5s19|curv7ghJo&06zS6c_g zf}6?8#(PKYaL`A^o%E~ds(v}7CE85~3 zBh=p~sa~zQFEYEl#_e-O8qxUWxGE|iwN{N zeFLdOIdI@zIS?U#m0DoK?E^2FHTvagew3IE5`b5de+E4eJ(*L|lUt2!b)xoLxZcG+ zT9wKF4hpP^n6E25h!>vLwX-=w;VXtT{TeE-YKjlFh?O(=x;&D}`>;l6=wn&oPM6%M z&KUM``#iU(CMlN0XY(~4j<_S~^4(PMAvp^NS2R00J^6N$qSC?kdoyXn_0kp>O6l!W z|6i*{3j9>*rN%y?*UQ%1DqBOQBjmxRU40gf7wP~cI;izI>zBy=k#`}gSwY?&`KjX;g94qQ3y1moV&O+HSPoDq!wLYvG zFH>CHxlfC4XHt7;A~R3nL%hSAXdFlK$wa%i%2ebO<)E~x?Vjx&Q%{N3P^MO+hGvRb z5)?& z_0__Ng2``*d3hWBH&z;!%oc?P2EpRXF$<}mw_od=6p5>;BYn^x$Pw+uE#ANXMdhJc z?0_1QKYpm%Ek<*vzmF#;uu)+YLpE5b%)^Hya?b*VZ^2VievkdS-G*FSNUI6O{I{^t zACaUflu^AhTSJ`u;MQH_N@Anz72@-SV*3hC+&aNM=L9MPCTWh07QbhVHS*b5KxG3P z62`8bX5cE*bxFQ-xjz(n5_spr$!*OQC=wehavqb2%57caY)Ytftu7SJz;oKj$CH7M zbxUqu@Mrb(gNdrZP}?;S$m_84PSi4!k@OBFBQiYt8W73;)aiMy+vQ}an2z+W;tzcd z`~q<*qSqB34o4mloL)z#@_0H@>R{dY~SB&AGglPp$a+*MjHHZ2+ zb-&%lj4-SF4Jtf4FV z3&KoDjb5JGQByb^Ld1pgHSaTM-ZegZEWo0c1~*^55X6W>i9e<@fFONW(*=R8BWvDqeONd)Sx+qm`>!yT5-3Y2>BjwYJ>Fc;f-5DZ3Pe)b;Yb5sK30_- z2Mr}u431_;9BPkQ08kaAqo9*$;qg)}f{b@0>`>adVW{ib%Y-R{ClkTCnvm+MEV$={=LkqrM;!f*ZGjp>C z1YV-A?yR`SjOyhzNxd>@tmd;^jvZ~xLD3TyDPmF#-B|q27o)latgIHbN}1i6y#DJX z`Qtpih*?2mis=M*Qm+e~{@XYy0ibgyS;cKaZEL_$k4ToZ(**$cBinb`t;Q7nzjyiG zF?qZzGJJZlH`@1NrkclAw{n45Z&S0X2L_dH@tm&rtT$Qp00=Vxr3G=2ihvuhxI@%K{(XC1T@X33s!t%^ws?vIbAx>m0Mm0;Q{x^LILmSz@V&$?xr7NVYM>G!|o#<}$SqR{V zky&TjZDh>W`aGP5%sRC$L62Aj)enV4Lm;og{cm6?`>_i_)D(L7P@-_McoLlrSqel= zZP!H)6eOm}X2R-k0}(H#uL?2WwHmWTyQ~jEPQIY$t7p06?oV@DV^hnX4GSB(zhZCw zu!ECk-v3qFJJyqm%zgVL0PgCldrao01&G#(|!FT88^k>!g&py{-l@0 zTf|}hx$}hDU+ND$tpz$;O-Iz!dar>P^)gbJ_vyBgjIUUa>}R=%jmA{{Ch1jL&p_UGn<+`j80YDaFf5El_J zl7ovVDr%+<{o}E5@Z~-L?Ah8ItG0hIv=RLmMi##D?tMcLSjfw>0`^z&+}3e|KcT>L z?}by`+ZndC5w*lAzbclbe(n7m_c@1#{p1T@H(;K0f3rs~u3&&rSNM6cDyJnzyqE&z zJ0r5djyNkZQZ6C_*0n_0m}&Pb2a%jCS7CvQ3WB+zPPbI3_VyiKnzV?Dk6>I^vqub3 zmwlzFUYVYx9+9w@>*XY{ZJU(;DvZ-wRK?*uqUS;1B99Y!aSAvI)6n^on*IItw?pw$ zd7<@G+malglnK~8<$ny8EM59~j??%RS4 z6Vs%bEMq+5BqfoZ+WP@r3}C$!K|^t54hwQF)g{qg-Ee#tO9%^$bx>ESUZ#A5dh;|A zkC81bz%fET84y@hwH|Ctoj#Bc>jV)845DL_Y6G43)WCsZQ9P@4!6M{ynJUZ%cpnynBNo^} zRTLydJNsB($6qLv{PCA7HpW2|5}4kff3T~WQLS1mvNx9gaVH)epv5U1$0WnJ=jt9D z_))x?W}wOB{@GzFri&n(0E2AJH+)|&6;&?94U+Q5LS1p;k!YTd+@|Mo>g>U&e90RS-rgpWH$h^!GDmK>~1qhF}RC5}annG_duj-cA6 zyb%C_DN&Vz;itHZxin5V(}5p^|Rvj0}p zdPzWN-1p~+{bw}{$l@WWB$Vi)#I=s)SkYkGyfxml+BX#_S={BRmyLOLhwK4;`LIuiln1`&Ukg&2S5 zORkg-06v%ERjLItX+sa^8;f5kP{)GeexQk;FILB-An$Wg&R=O+p;GcMc@4mb^f7G0 z{WwgT#%_INxaOiFHcRR}YYFta9C_=#*VlGr1XoTukid4Y+_anH%isqDk#sD4p`+cJ!6gli886 z8G!mKWh>C+sh5)>Ar1_9Klx~vaTtBCkQ;AN+!ata6Fm}G@(#H@moH*uHt)k}HTFCN zV9Rl!4zMp9+>O8KzcNIPANtMw-k5I32m zm9ez6G&NVw!HM>t5c+Abuy}Z!2U&Ue&Kf#S=j>%l5XoOkO9PQnWr|6rpo}GEBAh&q zDqzemeuLO?Pj=j)8X#Kz#+W@4MT{ck`Re&A?EUOQceIY>MjCy6xguLft96-H;~Kq8 zNWT?Ov5<1V}>X_tr4WT+q=X@;+|UBQie^auF+=Bab%Ge9Gb7wr|?-Z+Tka*PhZ zYd!-ecw9ZC=5#~h?pwM;Gn57WOo<$D2eZ|4-)hkMrecB8$A0tpYF}PqFQkcSJZy^L zi>goW1RU!0Xe1citEdaW9I0IKp$0*CvRN@U8qe{e%0@8o`hcaX0s~L>UYvJX;9?h(noPsEDNWF4@0r zm|nlaF4yllnC;zZ^y5#A0AHrSiR-t>8SUUTu044C119N<$SAwzxHWp;7shPYmy?~UbPeA!x3;cUZb4BXW@I{byZA!7)!5h%t1|s?zTaxL75q}{XH858+0EQEhHqfh z81p|M#!d%;v+g=T4(A0AdGgfa1gLam?uV>rS_sdCC@i$H;ahwupMX?EBVj~_g*7o{ zrdMA0g%;Pl?TZ9pQ7Wd_SfGEy8818?;s$)dRSu`t&WKkBvy#eKyu8R2cw^8=DczQ| zc=5vaoH>05$V+h=g0AiFd7n#|{M#iLSjSH2#_>x^eiU9inUya{fn>a8cGnN-PwVi%@aCa4 zoi0XOkx{r1S~#l06kW+h<<#r#&b z*BhRQo@lty#%W!Bsby^wQsxgcPI^U=$n_68MNkV`LTs=Cr(5AHV~)Y>Os(u7pmYZO zRXZKSFgdGn)EOXrtb}YyDiCt0e?1))yk0>eS)E1#1bRDcyc=M_rKx2)Pp2$KFi0CM z_5Dj1U9iOz3qVIjiU9+0Gab+~Jr587mBi|D?~_0+JB0QPO`=U|@-DH|;wajg$(0_h zd3D!?5)(2?wRDy%MybyFX_e)RpD{#bdR?5blfBYVF>z@|j(=!i@nE)V3NTtSORIKy z644@2f}U#o_tUk$@)T`G^YEjntDT*C$4KCT=!nAd7V|Nii|o+EJzcg2MASZ~;vSMjjI2t0a|)8BA3P zEo1(Q_0Y{Ya+?{i=Fe7meT^Wxz#1!s)&InOPluD)ES`;tA&sZpsV!Zxty#r zUC4+mN5t|-*GmY7fk%B4EdNwh2)Rd$IP&8>(`1UuM?Ixn6~!0hg^4Nv+~3^vZUd0l z-|}$>l#hgeY2n)C@v=`W(p3CW4-+I9%_|XVOQ(-;t zW`eFZTQCr>>u-rSdr8p4g1p{yX;zYP~KJQn4=^DzEHX^gm zdQa84Ew0KTM`z9hk__2JzzoHH)K@G*4==8m5{eunn72B&njzfm0FlJT0;{{Fd&f6O z9gly7^12}Szx9pI$SKFpJ}qp|G$xwIy@hOUrkk3?MUbwjbb3x^F6O%V=dPS`b}wP7XhngK|-W@mBt1*JsD!zfD_f8ok_d}-_MnXx@Q(^M9KhG zRGS$GjmgG}1y}ca(=2-A7oxm!hT8~_shXMk!2`XHC8=9NLT(!zU{K}z z5mhye$g95^IkV5X@=+5iB@QL&R?T3a6?!;Wur}M1H=cg`3knxeZNx->iGnOzs9Zq= zEK)}K;M=k)jRaj6dtm3H7sOkV(DqvvPb8p1Kl*we>@h zEyvFR3nfl;3e)&S=-h3u=D>p+J?M*sm2?HeJ$2i6b?9rcyNE5TrGRwmxR3Xq+T~Qq zoX00oTt9!$0f@6L6_o-->79uXs7!m-p;QF<)+QaxMNZ;KQZz^xnn#KjdFeGjgNr_% z@;a8wg(}@xf#w%$L)AybTC2|XQUtf{vx{*lDi)JrpY6*oG5Nu@VPU{Lw$9}hwdG&x z`=JJijR&(;BeOe6{Tbivjwpp)6ct!2sI}!SgQ*ca@aR71V*mhDSy?ILBVDbDr=IDE ziW)}fUwY}woSItY)K~A0+G7UrY5nP+O1qy7vz7Nqk`5{vvZd!{_VxjB28S|xOL+M$ zIeoU(h0Rf82$19;1URwkTGArJ)v&WU`z-$&dDw2cMeW2ymCY+cqwf7mpcxC@%+`h@ zRF=q(RdRAetgMpXQC@nN(p9t~@AE6_6L0Tpqu?lvB_GuJt;!(Qi(5to(|@_Y@~wE) zY7BRV&}&NK9;mW*qa|SI|Aq=Ghn+X)Fps*%apRazrK+mXnI}Ca%kS-@hbm#1Nk8M| zZTcL7<|M(x?DGuqiJ6GRV*pWM1$N5-_J38a1a@i<5uDOJJo z_xz4$#*2V^nbwo=7UA`4fanQ(ot@_ro?YM<0IlwTCO(aWS!0(vn@K=E@AIzZEDVt3 z5GtoHhIG?rKcuLB#vH{)(eLNu(3k$TkB2^Hi;GU~k5frFzZEXN5lR1}*mPBbfSv7P z`2@Xj4dbXI7eG0{)r1An;H*q&2=4um%r_~K(-1=+!`D~q>`Mgf+lgWet}GwA!E|Iy z@}cVvRU@PKs(^4u4D_8wjoD{#qjIQWfqqF#CCSSxW9n4Mx$#>Rfs&Q3F2Kx>Z{krq zmSfD43-b5(2d&UUV_tudsWb8<3c5j-mR<-H&b`w#VLk6%2OJ?d{9y3~;GdidbW#>& z0jBYdKT1gX7^N-9OQ`@2B54irV$LoEHWZ_|Znx!F*mULbYas{)@^Ay5zUGoHg)Ra`fjw zWp;qbeYrn|9b2DS1UC!y#&0LeVgy`e)8ni>Ub~R~zqx{a_lHs5@^! z;%!A^p4Ps8%X{if_B?k~Dv5`{HJ6f-liNP4;_}S_X2dlYwie9Xm$~tZY^z5tdJS=- z-%q_~+9387yXUHde{Npp1m)<)5E@hBa{gf%?2aW>&zEoSxJyorqn=*38sT#@oT@Bp ze8VB?&~YREc0^gtm-MgXgrE75gMP+p=;OY2Z;a`__AgWJk~b&bjW=rxuLE>?nm`W0 z)1}kLsYenr)$$T;maniOoFAr*WV!kuuifChGC$|lxhRIiPe31Llp?)&^NB|}!(_M-xS_mj9V?p7f*9mg&a{1LGBzjta z4@nY;6S-rrv5RunI@dBCJ%eZ9rjr z3S3=7l4roSC{gA7c7#Gd-?CQfdtnQED%Z6Vs9fGtD`glr(s?b?f-8o^`s!c_es`&< z`9ZJWFz_ zmw_ku<=2W~9_XSAs+Jb19}CbI=CBX}a@$PR)ZsQm`3XFNnYC;KZw|V3?JNgEG*mZ> z#4QK#iAm;Fz1+tsyG&W4EyftMSPL0*zkG;r8+oS0!N_5U|Fh0k3H)oR4Vbm{OqgGK zSMR?yDJW!!fX`gh*ny`%D20P&)zGv&DySpxFQqS85XPDgWery{#J5H=>h5+&=q2Dt$NN)>t%3HG%sS$I6 z+7q@58AK!gR$h!)Sl8VpU~DDIW-`vKd8fpMdM(3^c1Khr9mbmhoL8`2&0@y6w;$Ql zXYm8D<$3AeC9`ms6d$$4hmar!dT9pHssBZDa>3zQy@CpW?1=gSaf%0rI_5jR@ z4SYJ+hK@7~A$`);sHHXQ-sX->jB@qXC6J{671k+ITByA$)j{?@`P6>MjEwT{&Y?9B z(-D4XGnR=jEC~IGGvB+;iGk%>!1oh6pW9prWiI$2hn9cg-o*Ham-pQ;!44nPM+Bf- zrvfmt>3P<~zjBT-yN3rbXs!RIxY+d64C=(+Q^zOjFk8mhDBm6Na9c8!($%|f33NPE zoBJG#2G?-$fy{24gG(#fHkud}RR6V4Atfr**L-<~1eh!)_rze#&aZlx7=b}-EhYmt zuJV&0qZgs>(m(LYeR>s|!(iskO?hfS`x)J)UYpG;pkX|dS1GISZ1b7eHu9@@4ULfH z5vL#s33iSg4%!D3C#1*o#Po9fg^lC#@=3wV0eWfubfB7vJtUyx%|NjLulmgO=?3;I zCp+%~^WW9Sq0jnR83a%7aKO}rk-u;r1Ad7yNv;ZHP`YbZLB!Q@u+>cUx`3ZjvX_Y| z=CQIpr!p{gPQRoSERc8{l)Ghxgg7i5Kl7#*te36hkSvzgA%!SVl{eOaB6bv1p(kw+%tpj=!Zp; z5O_ zeX%X`vzt};fPkKGYj618R8&*f%wmzxV2+7KJUS;5`Vru(A>@_w@7vJIyo z>SWVl(j0%lq!(DnWNR1LzGtNbW5UQ_c&Z%U9JI7U;I23_z!r6C>v_192@30K;*qoE zOx;QJH_zYUX+YFc!zMv*s%9Z3MhJV!uOb%@J4oDlCA~ZSZ#iFM-gK7fApo`y`iobz z1ktDS%K&Ur`OdeO=-Zz1*1HIT*@U?vt;MFNhbbqqX>a+2zEuc4kknQ#rHSptYJ-}fZb#1{B zT08;M(qDjtzs50pc3dZHn0a9JUl-di(|N$8aq3W(4y`tdBvPLnU@g_M&a@9pQ7ktL zi;?0nk=kwRTezCjPm*snPVP#S!@&Tn8}I?0+f)EEcAYlT)OyXuPy z<1|)koR6Cd3j;QFRka4WKwXF$!eRNl=^=2I5B+= zcRCCD1N6Y^64+1SV7UBw%nING{HnNIfy9o-@}EVljMU$7646F~Fs8p}OI$9`*xcv2 zMb;`}G>Q{hCMF)bxE)g;@AX`Z1R6UmqoJ})k0gIH(S?B5Qok}kB9NE^VRqVa6n-|{vo2#{M8jRTKBW%ocpj?540G>o zvfwm==U7NLz5Eznu2Ex$|H1|aC{@zYG0z7r&`^}nslY%#77(e~d@{0?{QTIE*3p^U za=@n=JiS-e8i4xjyiFEXH*tDyt+@E}xColoECgUzMvcZhyK~$fQ>hX?f@p$71(yjm z;E@{C5Za;QW|VlO9Qj3iCZ&P~=WE?W%GYpAQ^463^}D$-57seZ{hJ>7|C!+A+k+<0 z(Vi>o#9M-YKO3Y1108w;g9fS70D~N&wo`^8f0FRLVNkF>^;L%HP`+cbJP5`0q{njL z<^4aRzA~(;=L`4HhmdZN?iT585IKN^Al=;|NQrbKDcvC;B@NP@B8@ahKtfWa;g0_9 z{ogM>elRwB&#YPNt(loQUiB5bVwf)3I6MD&9^sI>XLr^*YLzbf;WO{c%FSVB7K zmZ0`FBZIu-vOh5Ep9CtV*>PcJ$%xhW`s z$!VF52~4{2|1F#ZoRv3c3(a`z*Za>((L>!9@1_=#oWmTFP|He4ijOq(?cEgRc49~o z()hB=+1S`Fzr`Q>q>E=pVFcPm2nEzhLl^(;z0{w%U{<<^WpIs#YAz8Owx*$Bnm3`Pl*tkwKM@Iv*uOaeh%itjFT1;+^DRxhq0dhtn|d5u z$>LAGB+x={e1)MVG2GPA4;bV@NevxE*rU-@*ERp-^=xYcTd9uA8fl)vUjdc;r zO6)%<1S1|m=%A(UlZ?7~l0=)pBT!!a+^;*0G}a3K_EnYYKk+jNHYO3|<8=7; z$$OPkpvHI`FoDHNc6TTQzPy8Pdxk~cZ+2d?I0+!fZ51(lLa>sMdz3ruGR)|(2!s+l zxnEI8JWkLJTo5|%8x~h<-iaQX-1z_$Q^&afGYgy97%4ILs^san28p@3)@)F{vX#6n zascYZY?Pz9uY^{*NY@TKd1GRWgq zm0$pL_b2K)gVEgh7zrS{l?)iMnNDkC&tF_WgFV-8`p%z%5NE*pzN7(`IX3ZFG)7Oq zvqP%1m}TW(6YYb$WHpH0=m?+DMCiB>*EDhm5{M3mB!0R^u>amhv`=z=YQLl-A_6VL zPy$F!;sLVfvr9N&MgD3=t+T%IcYZ%&#^1Q;6eN)YPxoC?9&7= zr+WZ(b#XDk&N{M$5XV2IfMTf4fx-%SyE66Eox_rgZMd;hSbpxhcj-)#P^-|1FanS0ovWeql?D zbgX%UUU?F-HLU<~PTa12$8*boxrh>Jw!0juuH?Ed!senFBH(aw9cE;}2THG6QUF?* z%o7r9x^B7x45(C+F@eW41^+4yn4}t={Vj~2ai;LP|KKy1+XXruaH`g|J5n$*g6yyk zKX|N6c5;CS!M~qAz~WDp#o{Ys-wS-`aTn6+JfqejRh~!5v*DXVl|FC6dblJ*!uqGW=8ILe-)(Z|DXFJZ&q4dpw32!zicK!3 zJ*zgM)@1HKW-%7%%v!dEoK@h#Jk0QLm1}h~L=W5y-N6V^QIJ1}*`Z9bYKd;1`iH%TNZziL8j706l? zV%8hxn-74_@{Z^2H<%!qVln*vIA9S0%T-1QQ26uX<%O%lM4V2?2AF@0LfKzHCVebr zrr^adat(|?xVl!~;mYZ3b<4+^(n1#C1O5xHhJd4Or7hN;J$qoEpPVC;5jU?f6$FgB zZSlvKY9m^Jk5qt#YjIm2!Iv8k=*1z62nEmqN3jF=y3i>s^iHo8_wp|Iua3=q>k`~q&QrpJvXOzf7BO}oZwzfkWi$=i3MT=2V# zmO~M8iZ_SC+Y|gKwNiomRW~8?{MbUr*HYjWEYw%Eh!PcBFSI0WZZ5y3dT_aN?SqH( z295|6SO3?vbngTE!{w2_%~lLh5zDyKe|A19sZ!6D*r2cRy!7M>5DRjAk2H3{rA%*5E&d#s z{#2(S*~F2}@B;n$U(s_PeA`{F^$AgN^}iX{X&^5OL4w1GG6yn(FP zYWbJ#0NW+q)K^|3Jz4_|tRr0vN%^hh@!=`#?iu6oVHEkO$F8el1Zq!QgE;#gWh2E$9Wjf%Ro>N3&q8pQPm}b>`X-=6?NRC*VLsYB5OzI+hoO zY2r&E@b)`_r`A+*H4Trwf59joF){tvvnzNZLu=kS_K>4B@>8(e(a`+@RHYhoMJL~* z)t7?96;eG~f=)j=Zot$qtAoHxhL0ZbaI@U)gj`$jTjF0=Iqr8}0Rd(xIUUgNC@{$a zSA#6?u=`ijCA0&hq)&K`0_udco$p{B2K5m)N7k!ipk3-GArncqod)in0y+UlyQZEw z)jj%Gei9tfN`1*ofvv4C5jiLY2Aew#gKjKc3L2|e#bYdMO?wfXJ+odK&&?qMxwC+M z{bJqMj7$a&MZnnnE4)@9-o*h#xF@Fola^66Yu>Z6aX2lZh{+pHLb}Y^(~N?8I^((( zZ~BKn&R_|gp97KjmrFYC&X})*Xw=}u1*%!UtDwrenZXS5z}$O29SwKGxcBT0@_?6a zNyfX9cG}M<_|5RRQ$$_6ACo)nmq*6KHFscx{dmrPHFMGn^P(vb`vmy!3woq!R2-`X z9y@#Y-nr$`^hU>ngrK$fLGuy&sfxnfLLgG(wd?@sUkys|<(+Vag*H(nGLED}qRi*T z#yLg7^A{z0xxQSv4`P`Dz-*Ne!7AMcAMiv6IW$_Y#BxT3T=yNKrjm4ty_Q`g%o(`c zfCh7`FB06CQ#RE8J8`kagS8&}n&cw9;5YWa&vdsS@aPe!cGi-kIpUXo4ES<%Ehd(F z@x8>M+vGIn54r7U@$TgkXLr^CJWsL5x)4}{;{vS-^NA^irwbbPY}7!TSZq_W9)DQB zm9k!SDC4~UjD)qV(VIX&+L1NGL1$T}A#=Ihp-KM;b}&h8bndjNYro&fk3dwBn!$1z zY<#*5g0q;d6UT69(x35uz2WCJ8XkV;HbJ|Sb+mIM_H_rHj+C-4mL$Y&U`s{~XW2=v zaL+c*O230L_x6YHTb09f_iqaG6Nrzh>G6;eZJY=FFE+m0*IMJ)*-g%dmT9JBLMdbv z3K!KW*k$MZZlxQkBWYsDGr}mGDSvBM=~q-Bfq_vQlZ3OUIv}*geRf(7F#&4y_AvpI zg|h+#D2JcK5{{s~un(e1#`3LN;X4_iXukKk{i(R{86_2^nj{h#i(Wt1Dr4j*uJ)6I zHw-tV+eF8|T8Av;lX3h`Zulrl69tL!C%z^Bi}tg*Z|OG=q?t7gdukRGMo0@S1i4pO z5K6HK_lfSi3#6`%ULF|uYr^gj8p??g(L*}iNQ)hHUNY}?wl{8FikLEFU50hWzA*7@ zK^)&dd4)(2KA5Muy)#h!Ew+TIpyEhG?Br5Mj}wI;M(7bB=UeodmG35*N=>_5@AAOF zvOWf28XaNJ{oS6`u#5M2I)wF}E{KQEplhJPf{Uclv9~)Iay+96grpuG2M?>A;$hKo zst%Qf^q%23n?abLrGr&a1(ySn&>-ty&hl)*eB|#RF^I5UVch@9nzenf&+O-(3{$X; z);W{ahXf_$jhf^t^evRZxrMpT4ytHkgh3g{@$vH9o$9x-x>%f?LT6*2^x(elAIH_X zqOKvE65=&5L1l({U?DQz4>t))U3}Vg{8eb{l;!QdrWwaq$qaD1EGa4Rt?t~Ad1O;v z6@qUp1utgiHdA!gPY$l)?{mitZ!oMHDgEpA@0`^-ylJ^wp-If}Av}>H9tgvHD5|YBKmQm>qB_w#MV5HTgpWm zZcp(CkpC_0#Lhc?h>$n#QWH{FFHY}KxT(dj#shD1>-=L){rp<*q>kbs9$vF2pW2A1 zedt@y5J!V2KXZG~q{xWHnW*zO{<%7CKVrps=KFK^92gl?vY^!@1k6AoK#Gcwe(48X zma}1*74vE8N)5e@!Olk2^^3Rzs1x$?p*y5HKWl_u?So?&F!N;Qn1JtfuxyVW_02dwVYMSS5z_ ziwahifg>GrMJDDi#PJmvWYV~(gHGQ5(@XCdL|VD!9UnC9*h0jK5})Z3)8PTEhO2|L zx-)K+8x#)KoBLq2T645iu6|GqPvSv#Lu;$cQ9E#4L9mW*tYwu%CsK!5*6^fBf!qPI z4xDSxC&ZrK98o_+ysA^zk5=c(cA;~cP=gOmCO8;e76(NDN3_l5R0CEXM*;;7osrw>L*%u zJ<6?z3gTWi)%NDY zRtHQ+)kv&RT&!{-inbV+-HfqvsJW89{$b*_73A{JYjzq;x8DjcPe0`EgMazvf<7h4 zb`$3<1k&4uCXqK4Y#cz=T4hBC+4AqtO76M9rE@1cd|Fl3 z(NTcd^_XVWkD$()K3hR3MhW?1rPSft@hCtwa_mWnMHy4EeGjP_snAxk>0G)v#mb7^ z>P9F@vR2zBMtx&Bk&z!>I1anLS&p@ZBQexuj^oP->h{FAw!NBUtiBWL^(s^byI>Ak zn&r{Ez(jo~L0&QgUrsxF*Cj{0+a`0g5>Ez@9l8tT7dok{JECl-fs@5o;*G#l^ zcl5p&?sTu{^6@$3%hAo_*5aqtr~?|VuMgm76Tz0<@b1n2J?6Vh_+GJ`Ok}GZ*qbu6 z9Ip@|rP--B?bQk-d8NC8U^Ka47Xjh5Ce0rZLjx?M{jkyfh!z=nV=Gs1<*JNX?sO3|Xw7 zm3>k&RP?_KMDJ6QBWjF1k5D(0t3(e{C&xl^bi9O9gGPjyOO63?T5HR$j1UW{o96Hf zLApwne`n?70-iK^B1TYfPg%U|du3XDX+Dfj>V$}>OvWTADqiHrIlDTm{0=Ihb@r2} zZz#*)69}m1uso!WuUOC4EO&Lp5ga0JU`hrzvb?TB7*Z&>3g{!U_gbs;dw^+HcGXcV z^CmMh9jKjM@z_q;9EI|5{da)q)}cb;sQP(ovTHbO$bEcfFkavAFB$h80RexG zj~En{aab8Q%~XRr+?#^^iwdfmumPRpV8W3fTIV&9p5F2GKB)K|{y=NVG#hf9n}y{iWx-e9a2~l%Sm{ogpxl(X1ixD zQ4;BGP)zprcOefJ0PVt1XL(@rFEoR%eJprwY`Qx90rY;b8vBR>D4+fuj(?X#godu4 z_rQmJE}};x)S0}+(nOn%pUdWQUMa`C9dr0IG)zPJVVbY_4j&yEvH53#w6j`z%

K zsEGfLEyuNoOSo<`u3~(7Oc}pDF4V&P?(QDpI(Fr@pZFCnBuffB6lKG9d0h?_5O&jAzIj^fjhZ_agP`3tOLI((c~48httTFqi+qEyonSx8;i>!GN4Tu zD(8<^M45x6pbvYu^I)lD6tS(HzG_g8S`4A1vjeS@#^!5!;@%8??`vC!r4szdZ?B$@ z<>sF63&uEzQ$VIe29rFg@j^~U&`Tt+!>TH}mb-(!51#0zmJ?Q1f;^KnG2#8~hdF)k z!M3oMrf7*1RG&}>?x>j;Ff{*{{6@G^a9WMKd}3rV)W=H zxQ{M$N_vHM%b2QuOBwz+%g1S7(aZi*1avEz0^OhA4_nN8Br2B?Sg(E|SjLndlAXz* zfii-6OA|Ppl%QO8tS9tIr5+3EMCdl)^6u4JJSmv=>93dbDI`I^^$7;3<(2#?Gpe{O zp8#W{ZWFe+xc8q|_4Vs9Piy=|$tghj170{Bpm|XnoYi43ds#!@cveOe!zrvu{@ThJ zdtymhwS#Ug-c4eV%VF9x>ovKmI8kb-u1fLsj-Qem2tWlAIdTd$7j9%)oPQ@71lG&= z!DLOM*#P|T2@!j<6c}Yed=ovq;|`fjs)1O@Gn$>oEo_)Q&E4tOL+<4Lf{Po0fnURO zsEGChPUQQ{Y@7z11A@;cdVP;J!YFE9b3%YI_;Obb51S;_4&o=lYDh2=dJFOBJ{xR2 zMRS9jbNtB4HP?@UM96`JiRnb~yDRpCBL7^RNT6Xni6V^puNwohfxT|?c!a>OXiXHU z#fR1^JVJSE8l;Y)UCvB%rw_U|OH=1Zx|d zi={ajkn?jO!MoiSl%g#gAWPh+QR2@x(5*G=nl^o#E^nB@k!4EYVcl_1xcmw z^L0c74&$mEWm(L8?|=KAuSVG0S9EWW$Gv2)e*fg-HD8C~_q(};f)b!oEW530W~ILuKIKSZdyi^cooBoE;|E3RQBuYgT2=5 zcbg&!>~~9*el(FYJYKVGV`=ZKb3q5v8-DU?JYbIS*a~8*4*h287I^{ zLQ}e-p$x5Yc~d7FgL6kAX&9?`&W-pq!|&_fE<&K_p%eq}#}DX%IaDnT=*)rtYEd9( z`>Hq6ykWTiO^q94P5?O-4luCQH&|jWK(^4Gn5DLh6ft@}b|t}EC42(N3X`vekn?e! zTG8+Bpy5Cc4cbY?xb+pUC%yt1nfbQhsc^)LGV1vGK5p2ugh-hL*4MN8{y!~%)~H2t zd<9thvMh|uAYv_!)cgpS`RciM{+&D(4nF!;(fQkZoIq)UOYZji<5KhUZNTpaMLp?40@b2h#r>&>XdQ~fYea_94-2~qW>4s1=)hf0tjNKIcq`<=GlM~w zcb6kNz}eJ%VFczr9DnG=O8DK4>)H6vqro>j8#%s{)4{Ugz_`Eat7a+b7VofXvt%hZ zkSCMwGQuj`o^kZlA@}%-n0}&wKU2jjZ~*?2&mn^-y89QG9|}71akO!a2MMw%&A?bykhJJKpA7n_SpA)+&HJhCwtTx^F-C3 zV~APeog$U=b4)5~?#7#aJp}-jI5BHo>X~r^s5X_UR+RI$V6DM8YYu+Kz`Dp~o)hCt<9p zs0f3>6cxkOMj#<0mT(0KpyDt6(s)tUuCQ+dnpb}AlHsbk6W5$H&rXD6h0jK)<0@m7 zZhbaZct&E9}qb~|>w_fttP zD3L_o5W;JCso>qd3c@J&TP?dTX94YT$R0B>#rs8_R%g~|@U$ANKz0QRNPQz>m+z73cRnCW!hYP7K<|Cy zXyA$hNWYUZwfua9M~^;M4-UlYHn925;G?T#vq@CRwA6S%f#flH34e_fvL<%>kzR+B z*)DUR6;)@$X)RnTE%FtG>%hTz5MXQDD$huXRk2>!Z^>{FV}{B&HHnhPUfm@PE&V#~&!R~i|rd0eHfsg9fB8o!^E0KMVO`;OZ(yyt0*U=~E z--a9JH@grZx*e32m0%}f5}WjbTP`;yL~CDjuKMDD)hl|`moF>i0Zn2;=xV=QYFg6aK2bPW zi{G~5<6CcA>(|!VFn%C{!N420Ej7LK0oKWDABgww7yP6s3SSj8al?w+GVSa>9xhx8 zti9|jo6GvKFY<$^@&wtZL(jcLde7%iN2)R{{ z_54oPIWSMDSR`M3v>6^JIwARRd%LCQX-FP261YR}X-F0hx;zRe zaP$;>`=pAAY(mQB%s{Gjm$4AfO)95D;wN!=XWq^%!{0k`_RZ#*f_j!ox^nktlUG|J zO4ED?-%%jxSTeM?=f?0T_TwGN-p`>RFw!?)30-JoV+%;qOK}y!y8C9JO=$vS7;VnSjgq+-f3Y_ z#kcMgF(j4sB@OY!{G@rxpIZN$g{@$2BvhBfYI}T+H0(*wRpi-MNy&#_K|BIKMMOku zEYJ@-sU@g${E541z8IxYn`J;l-z$A&JfPUU=-m%B?Sj8RO?(GgK0L)#fNCQ?FVhhE zTIY#vEgu^+{NtJFksl3&4pbgcAb+#m?>zLCz=T{Nm6hK6oCm9wdgi%aQ~@{oUyc#M zd97m={1CnuHy#6HQj|_1ck(QR$|RHIo0guk9KBb9r3SiT>oA(hi4czrbRV;F1+;H`9ljF10C zkHE|;E)L+y9Pyv~z4Y-Pp;xc0H}b>5Ng#A{piF6x0f*i=c(kFVNqwJ+PSIDbYw(*+ zP_atmQ=%9R8VuG_=AYOWE4yW%_|;^-BI2;>hj_yfLtW$qx@P?2LTZFAV24k)2D;4V zKYEvUY)^OxyVtm0z~vrtsLnk+S_v`X@#@fbf#k|W3A$K@hL*e6LL5yiVS=ktOu^s) zFO}Tbs{p^6-uqFCg!tba57FDnwOQlr?H#KE9ZeLkj6#RBpV*b_h~;5DK!#DUOn1LaNqz)0tAZ51$mf z;{)9ggq-4uzlew^IBh``=3a$2xP&Xo?|c?wlA&7z5%tZ1Yv<`05TM1~Z zHy~ic;?ip<)?rJb(3Q<-B zVu?`!*z7sCc5n05*~aT)q;UOX#KP71(-(I6psczi5K zar5w}Ol>;?!5IL1`T90)rOg!{d+ei~^RdeO+z!-OV2*+CVEw)@-_@9zMd%B$9 z#|P;GIL&rOE$H!ujQAdv28^Negwr9m1tqBNI|XIv>^gK*gRiVHT@6=qn1YP7u32);)@$$zo}Igr4O5gg4FW zZ2)-@j0HJfvHb_u&pIvr1`OXnEESy6r1;=W3R?PwiVHvR9Z6S*=H78M zI)_`D?x-&NumkK}1%AUwhAS_?;$Q&XgX*sp0F= z%Wofa4yNfQ1UJekmk#qN&9i2|WJeB0es5V; zI?P~8o?hZZ9-m|it~E#1=hC82m4^^*@$OzEl_ZqB;L#0HVc-}$w zeifr&Doxw;qE7K;NapJ4+b;5YvLNWSXCywevnv=-nDT6e$01nP(`fNQLVJ-?Nl~|O zhHnE9KVR@OI|-609LmIpLoiTT$r%G19ofH!mW{3FALu&EpVQb?eyQPz)};0{q`ty2 zoXJps?eM)Q%;UDnk)n9I$ku|iC1{-L>~!UM)sal?@Kt^`&o>sbuBRg#VfQq-1}P)XXi{`%#33ATy08bT`C9?Xk3wDL(q|-(9~XSP6!ryuj40g4%h@sHcw?yV-uRezJbp zmcm@L6sv^+QZ$s1*X{+tPGf%w6cp;3!J2CQna*bY7-LzHk`H8^58{B7IO@QJpkc3{ zj`mL)e`ITp;VkWPun`=}isCm^6saUeMH~rbPa*#ul&D1WmDzx_>A%_1gyZa-`1@MP1iY{M`P4i-Mk0g4-Mz@7HywGdw|DY#}F*cW-p ziZs$B9`DcP*AX~@-kifAqBM7)TzjDg0rdaW_qg_R>xI<)I-OB}Ue`BlOy>@)fhT=~ zS`yhI0oG9~N5G-GdAoU#x)_EYutt(7kA$)}sj=<^I6r5ET1& zyo-X-AykuydRd9nl5q9?`86UgPTn6b5rRgg9xMGOzl61WKyA^{5LXrP!+sx(refsW z)n?g={}Way=z|5EQ3JuuWM~LDg)bLWKE5YkA7b8KkuW5Ip^y5Whe@TYFVY+S2pE~c z2pJ&RW7=m1TG!HCF!unuDUH|C!RtA0RAk8(YPSX}1AZ{--14Dx!%G@SyrREeKrRF# zLG33&DGbo4A>O&NG#R|WnM#0S^@NTPxNY=&VlHyjlN!Xo_~lmMEjCY}G2KU?A!OQo zyw|r^T0RY)v>DNQQ%>YuYYV-_fowb@rIME)mcbjE%Bk64r{6RcgfeoSQlU9z>(+)& z)1;q{6I2uxI0O2$?3W}u?FLJ7Ej?k+>1)!^? zqA`f8(ywq5t9bdX$}kiq(_cD%Fxmu-7RtQwQnR5dzISTr`T04YzX-z2TnTnaNm-$Z zpp+7m?WPvYVZOfTd5d+nJF0XAF1oBME$(UtT$nOf00GF25X;Grk@fJO^flmp z7M8$&ROaHW{ldOqo|hIyngwBH<=C6Y6cJ)W4)kLjdLhx=3cjKST$Xg3C!p)0$s<1{ zM-7q=k#YGQK@tLIBnEQ+UKa!<;=Nv%r!6-`d7Qxd~x5EHKJ(MkE zn&vEt^eI`0OwFgBqtmPR%0vMv_7(_Znc-wlA%us`oH6)Yd6I;CbPeonyVP;Y|3shfxB3M6jR_4Xg^S_XE6magY#aHU9$gc?Peq5al1d`bd` z+@v3N;tEl!VOdsY8G9-Qt@Tp+zm#Roz>75d%Oj&2h7Sgl7RAt#E6>%vzw;l&QX^*$5$26UWUt@lO&W5 z5(zd!nC(;)(eG&EkBf4L74~ZE62EcBb0zb_I0p%P_|U$vL3_Iu1X?AgeCpVoz5Nk& ziDBt7NlbWBP0KPFCD-2v;cOfx86(oBe;h1jW#mqp%U$5Q1|pR~4q}xZR*(1vHJy)y zDi8?=5U!YXm!;eCgo$&duWFgNlD6E#eJ3w2a4a=6gq0lr|9(J=--C$kQ1Y*jK6y9h z75T%LNODVu{mYmhDJ)Ae*Oct2EFLBOY54c=A6wE(RJF~pXgYI$E_AOnM0;enwmq9p z-eq5EFPUb0mRLu(n>HS8s%}h8rZA_gfm=>GJ@%b^hetQ8$g<3yn7!S_dy;ZgS$0Ox zH9;SF0>aD>8VbwCUulL{DXdrbe)=ykauvA)LF%PC|$ zVDCKYq=^UL?1^{#v3FQxA`0TqpX#&)HXfI_%a?RX-AQU@6O?1w(G^uddAEMG1EdQ{ z-CG~v*Bm0bR$@U>pDxL-!p;ENhjgq>S4+$v=bL|)5>yJ>D87mz<>LH1bajj$ z(E*8od#)@S|6Cgzl#wRs#Xa3skp>hQ18t7<&rvPlhs>T>@CGxb$kDl>#_Ip0w-E8s z`^;)MNKsWKA5-6u0$LXw>^-IoNta{R?}yhj?B5R)5<8R;8gSt`^h|;;w)@T&XjMEO zKl7)|(Z%Yfq4FmL5z#lbvs{p|1x3xbJ-(Wp zEncO-Vslr5`1?b{!I&;g@WCJmNcvZO0kR4p+V}vEPhQ%%%2Es(3rBcTG!Pg?JrV`r zI7-T1DixcMPM$A&@{(nFQ2}=VA~!lbq!#-ST^^E%&YDcI%h%AP>HgHvzd<=!ug)rP z6e>8t8-u{A{TjRIuABxd=&7-D4H3iniO}&)SwqU+{%)50(65)mu@nL<55edA=y}^# zZf&#Ijd%2=(gX0K{UTd7_>*+4XNdulj7jwt=m;}2T3y6yxNO-LpIz8q^QJfKu|i8R zNa_>n(ZjX*5!z~ALKD$n8OT*?BNfbrxP|y{TmtVG=pbV${+@%e)o;WEb-(F}aUqGC zLYqf>P2iNS{$ftsWBInz(7Z^3loZL_@(cwh!CjH@bj`fmf!Dzd1s;0CVmD)3I#=$^ z-7>~&EJvv{F=VoYb$BntB-Sm42PN|N_QFU!EyF%GY|`0PlK*WpSw~Y@gWsVOXdRV2 z=Pr&UD67*nPzXt)EtSkove82E#XLrxouae;;Z4=78 ztx?P`9~_MiSeV)QmY%VYGs5T%OC6UmnzHai%0rOsWmQOAow`gydW&rNEHTE@q`_%p zZOz(P>j8jIE{&$Y>J|X~*4O9N5rpFa_zV(SkyXPH5doy60hb&d<5ks*O^`(cj6FafKKAtF zxEC6Z7fp-bo$0(;)i$||1rc1;U2mtt*>o+^0O}k%1Q3|gNK4%N>D6UhXK)pLdPo&K zjKbwd#2y+AR9lS(Vn|)DA%LsS{9MAIah$PbWd*>6z8Az2=OHJ(x});>P$@He8M2;Q z)QNC|wp2)l0PK8frRE)zYEf92gHr7DcW-hHI)|Qh7b5NZBFAT%)Je}U!iPW493{h5 zT2-9{L5fac%Gzy9d$x$k=d#gM`MWzlQ$*0OC_J^oBG;uK;S_&_%9>pgOHrpd!ZY;w zXNLV}+f<^rUyx0en&JH>B!w1klR{68hdiX ze2&R!q=HG3ST+6FOWmBFYyc9v{Uz7cEfXqW>ayTJ&{%G&oN%qHons4G8tE0u0;iYFgNmT?=m6dzbTFf74$xB^+Ol8EGm{Vd=!@>S9WxkdHY7N2Dbf|W4G9~bv% z+hO#RU$+&-Bs!c*;EPL!6!Ew7Csd^-HGyJh-a|*FuCD(4SfFbpC;!-_^XoydBj3zk z_U8N6Wt*GOiU0uy>TCtbe6xJ<{P~T6^@1CMcYX&3%@f|}^>zz3=@WHon^?aA zty^(e#DEZqrjV^2X#c)_w9PPYrw!tHuYy`<1x9(5v_P*lZOpGiNZjoq{PsX<1iADp zf5UPycItzN(R~zdSr%Z=ST2sw7Nvs9MFKkJq&*TmC=D(I()l3Q`jHV|i2=w~<^p3( zKfYEBdw1d~4J)4fh5$)o{wrn!xqA%w;FgUqx4hfqz3yKho&S+T{7Z+-`iSAbo5wU% z6v8sp@ju}uJNNiT2g38Q3PVytgLuLgc4Q>du|z~nGN9pT{-VYQ&F5nCZQL0s;2?J7hXx10pl+kR0{iUxkBeiEQY0IEIUuHIz?Q^5V*T5W*%ZNSgg z*7nd|P;2*(L9_U1_Dq-5`k0%JJhX&0JYEhl6=jrsH?T8L>?w>Cb=m3XwNR3^u;0VY z9|*)6b^!|!VJ_zKY8 z+Ru3+w91d4OXTXALbFKPl#rdgPMXv|3Jr)fGZTWVWs1~uTwZ4k%4R5hFjj?d8f8^F z+uGzc3Z#hl3#`3PrSJ{XG5Oq~j?ugzK`GHOGiZ~18*u8arA_gW&h&~HC0GMb`2Fs5 zO7H_1#SrQpDPTD&j~*dU7RV2t2v00;dt|h>q37*aQ=1&Voz?bOeG|I>8aY3T?7L6M zhA(w>uW(Yzo3ccep-sBlznV1#j<6~&aM1o^P#B*Bw9=(T3u_!Mt%lRuiW}R*hZoBx z``bp#vhhuOm&^2fnFaz3THL_3T-Y3ZO;w^+SHQ=G$A~| z!riQeTW$dB=lvZx#?H?drG6+$Fq4LqSenBhPPuhk3748cSZ4DI4@~Sg?#oYL(WLP` zyX(a0@eZVjIqtXN5dz5Rj7V*oK_hbi|BBBdNE8>S`nIat-p=RcG-tywNH*0N^kePm z4S`aKBV{iv^8**>`t?wiZ7M&F&%mFMRQZjXsP7oPNh%t~xgvgH`G{top2(BHxqF8@ zI+D@s=GW!)zTGzI+T~vDdSUQmRovb_+PNNX$X>A8d)g}HT`&#=1}uL2sm`qQCRg-t zvDxI+coYGo79AG6phE+5bQ~o@V50yK4wI9+{KQS===SQY*wdGxwdCs|c%Kk~k;i~P z=~?DXmdk+815?QWLCXNPY{FKIqaoJ(_LK|j8z29T14Rgwx#xQWkRw1qLKYA$+nM@` z8u{23<(k}dAqTtsRb6e7oA7PAnVwo0cs;&94tEGXn0tA!%E{cUzV)|n46=Mgr1HAu zy^@7va@hKu{z>~$ep6GH>@;{{1G_;VBxLE2c6^W49wb1VjQjTbBrT^DMmNpv^rEQ_=IDh~7yTl>E* z=&5wnf~76TokVX&vu(w?-?-b)o9${`<#LO!-7-ObisblWdwO~wiG%F6HHna3=1r;` zbH1L{J0otutgPMt2_$|DK$@zyF!Fv3nc^g6T0*c0?1+0N=%~Kt)qd7hSwU-Sdtn^! zf8(+a={QZ9a{R0w29TqWT85+-+n#@rXm0ZI$TBO(*?L(=cxnQ~K~m>CBtT&J`$Hz@ zP;+rE*5V(F&UpCJ1j-?9)cAa#F8ob_w(KVnSrg0N2X)lCy84Q+UO#;dXoR0HAV4ya zFob?jZNa<96csq)9d#{`KN~QEB7-i6&vhpoXs^Il!ln$IXHU|FKLYfDI-3ToWr&I7ki};lhi6v3yGB3) zExta(OKWcqqy7?HLrg2&(u|b@?zKab`kcLAcpKxm3Q;ZjLvlhgmZ6vFHyAvhcs}n4mk( zXA$RMMo#qAw@5>0^JuPk#b>`_jD-Z)RT6nT+t&##v+_}fTlw`BOr z4UAv}K=Ayl3B0~Vua(!C&3#aKoD^UZdNz98YfH-ZC>@$+(Wv`Qw~oDkgb88))jA;w zUCqe#lGeyoRg_npjHLrgz=am@)8ZHFo%a9?xIcQ3rwNpjnl0~#A79P*`SC>95E@lu zG^cpF=Fn&{)si}OK88eqZw2wYo-Ti{Fs~+8iSVirPbzfW@q(sTU0x_&GOj}cxT(P( zy!o?{?N#H!n&Vrg+r|jpQsn?EES3M~s{sT){c`!jkvwfgdpKYWg7TCYCZ`K|iPFnq zFiJ}m0-%rdT|)|dxOjk=OffJd{oLz`BJy5GNGs8>6n?=^?9g}w-FXQL14sh_caK2S zHIV>Y`13#x7zYlM$_dBu94G~LpcJAvZ3X}q43NCO`S$Hyi#rH&jF3}Rr^b*0cb@^J zOo^~cFJGzFwC8M!7E|CL<6l`wffxZWKkh8lr@ zgu{iP_wv)Y@${r}?oYoj0k0w(v(28Chi9aPkT5`X!Ke)eNB|4v-Xa6+(`&6i?lIVu zK;Q#*@p~>}S;g>Hc~^v(dCXCKH6>{l^5v+Dtq))rg(Pd)I{{H|P&b_tf7l9Ow=7M; z{T`o30iDcVt>sV1i3!-;0CM;3i1BP5qxFQon)3ytYPX+Huq=3?p%&l0#pr>M&+Wt; z096B6%U;wf1iSTY%@K0{%oyLMgVk-MCW?5l{*KLG{($tXvGibc0+)G1FqybNeSH*W zxzYJRVQ4tX$B;CVPJ^pn*sdgJ84L|_Iqfq862}YpoPHhVqGd???x|s796^;9i~-o? zyJ=)-83#Js z?ihWgkA4uj!f&;!QEYvmp)}J)78;z9gTqJ6(+q(SUaZd?iRO}Y0?scL$M5Z(m;zHd z@;fA=28Vf|07r@#I?@>wq|)KGB@gX2Z^sEzzamBD)RVKH$CrY^_AJECwUkR|8RNfp zC(&fTEOii5m6PkHLHKd<@xzt=_a$^1Sm8xyE+j)N-DvU4|n8)cNQO~FCA9c zpezI>xbQQqxQ7om`gs6YnScoe3=|Dhc=1V9NhL(hZehI^uZs5VhBjU&t>w;o${+|h z3@JBMah-b4M8rO*B>DK(T`v&Z21pi9|9DM6GpK{BihP6GeMS>aqUkHjFQ5T?gaEh^ z0A-TX=hSPNhv7NgdTfmx@Ygq{0y>IwqzO}IF+mmlZ>CsJ8C?-IVA;*Pp;N`md`!v zn@E!^`f2jgV4BZURruksvy*UR-=Lc~HnGG~v7+1L&n`*F`xVmk1iW&5s%KbtXA)dx z#PQRKjC{5lZxlBEH(52jprK>}(>FEK(Gzk;AfxsF#Csd?f^3in%g(uU?j@LaY^P@& zS}k9QRK_{SDVYmfcQQ!20iM+%R6)*3(3aeBO%;;umD8#OP~B}sWtZ&DJnuhs!USW) z4ilv%&oGH6!yYlvi<$cI%9N$5f_MDbVl4eB8->^M-&uZ>mkvtb^GiVt+c12z_>%`_ z&m*l(SFmdPd2pq4NJK=|fv8IO3h`c1=4>eqRAifzm_hI3zoNl{Emi>>3#+hwFA5ro8ydh+V?%y_c%-E^ zT+qX{<jF2~Zy&02ug5 zd^wBLyZl*LSof}n^y!@23l_xp3*T9KUQqW6#f4;N1!mgD!2|V0U{9?zo=2CbUR}@I zp4(|R_q=`np}dsR-5qsNDF1oMJ~9|-8(26P-wk%o8o&yjyLewU_e-R*hWk>RX(Fcfhtqr zg*7uQ$6(t_HWCca0Br6#>CS%&F*JlCEBq!FT~Ae|Ck?5p2wa*e8!7doL|Nt~1K!NN z{co#rK1V zr5^~#wa%?9n0Ee>KWAKrT1NQ#Kpj>Q-SK2OfIev>-m3*S8UZK}6{-7w?_PG}XpJ6p z-rGYix42y|kCm#+gVZ0pyv2+!J+9;=l+huf!}AtnGv8@k0`i0H@!+b_6&K1U|L^U7 zOoG34MLhOfY_>Cne*@aY%^bl_=^x(dgxt6 z-(_N-b&@03)QsHdhl){{zc_+N?;|8fDdny%nFfSVVF#J1se(qkDTaTqQrM{M%4Msu zoi`Vz--NHe-HY<~9sXA@Y71EINgQf7POxlHaj{+=MOY4E+u4v#x{Y6XeUtYXAX83r z^%a%q1JA&vfhCASn`^_DIXOfY-`E0e8nJOKo>28HFmw$ize*8d_SNk!v8^{pd-d{< zoy(ua;uWB*Mhi=^Q}yncg6A8y&9LNu`Aeey2lNf#3Or?hi6}fu&_*UTi@MyL6=rT< zXZ38q(IlT-;qi@jx;CAwMy?fU4M#{Xjf@c1w3a6|KmX5NX_`Q-a-}8lFbiHK zhU0D=fHDKeL_f)f+lIYyZ)Fo5IWV^Ys9upJ#D*|6R2>>k+|7rF4Xg!QA9{I`MN4U7 ztm*JPJS^;ukp2%-XB`k#*R63tI;9(=yE_D=C5G+>N$HZ1Zs~@hq)WO%LQ+6L=@1l$ zkd|(^+xNTQeeeG;bLO0V_F8+b=lL!8SG)#v%leqWB|0gNZ+1tkf?wAi`2@vvP6w2G z-8N7!4&{uF#k=#NFRt$YI=K28-`f{A7D_L1|L^)TBn68~8#eRpG6m8r#+* zC_b|3O@n>Y$xyIYetVXT^fzbSQZJ&>5G@{&<7Dbn zVS(&B`||Y2vJCoErFsqnP23pMP}fjb-9PoN1|L_I@)IW9bwA&mf<6sciCAE(W&@Hs zF8LirMivr^r>8IuD-g$fRUA# zD-MA|`2RMO)0rsH$tK9EJ)xm5Ky9fn-UAl)$sMcx{9MBd2FLbzabc|Xm_eiy4(7io zCHjdsI~iTLWgq4|BM75#0*LvfvX`B;RBbIR$*B-fIThe%rVcWCd{sj-g3!Z#JXfD& zj)5Fgq;Ve36B3KmQ>S|KmUO=3A4kU z;rMr&Ew3^^<;&p90+7%>m& zMC2EU4w2T!H}`eTR~e_NY?wZM-fu@9nIy&i22&mY(Ajq7KhGwEjP1N{}?+WVnAg= zz3mlIQzo*K*^oLRKyGrSflq@}`xtugae#83iN`;AmDPv0K&+C?Ow+I@@qTIpc;0|y6U1+!l^&A$&s^811BtV$EgfHU$>%=Y+A#?l$qfa)^&YniRb zV|Pffr-R^a!`)ScQk1`uSl%!9L6Xg(rP|JSo+i(&m-yar0&UIo-8Cz``>`d+emXox zBrFyWbPv7R7ahyR%Hh$HM`T1(G^X@N;E*i%*H7QraoHOcy5$X|vGBX(cgi_`7k;-Q zs`>8|de_%V#gb}S?V81|jP(5qvVNI3Wb7@fia`WQ>T`3Ii)P}G^?IdWxnh~~HRFs@ z&@H%$Rwwf8va0|LLYxIp5j9CpMRInOY5RyNp0=GCohojrYF!PjROnXwZdIeOSo;Wp z*!%jYEl4YUS<8t;w=-W`oms=2h{833gC1p?&0xlOVm!k~ z*Z0l#TDncEZc!;7AATSfYW}(P;PXLYM8uyXEnIROH2El}$8- zVqz2&YB!m?kJ7jdW*zg#-`vinja2Cr*UOAV%@~9u<#fX!pKJ`k_mfT2E{0b{jKGgr zr&$wgFR~4K3ZurFSxIqqKOvdugcn6r38iiMH4gTHwbU1fBTZh{zKEg!~ANDwbdlYPh+aGo; z?Bz|RAh9tVuOtCwtTE%dPLd`~cKM?i5l))enJeIUtt?Kp$OAv%KLvq(Le%rYJm(wWTwAZmauUiu(7071nJAWb|*!_}iWM6KH#S8;6<5#S&HRxaa&@+_`Z;Wh@6aIT`=!%T# zhZXI6Un`m_^yzU zU2j~^lR|#wqrvl*p&a|Fy868(%rHP%lp^)@XxT1PWmp`r93Y!>{&2HiG5;Pp1^zHVIRsgga}QU%`GS-CX`*qr zWI$-Lj=kYkEe3J(++mu3nxAwYjbVh8vT^kC*OWc-#MONVBmCXC(1hay{YcX7t%vfg z@KHlgKIcdE%DlrvCDJ}ztme>-k=BGwT}1X3XioaNx_{Sw5vpL}4GW28wbZ{`qC@Bb zT9uTWYv05LBdPu60i_tY>h36}1<6a1^i8|i<{G0WQ@Y3(6=A z8WOy&JxVE-CJgKK+Pjj&b(9w1(^stF{Wrm`!d&qiJgALq?zuZ$p_)osZ4;sR)Z*}6 zq^c=Zx2DMduu!KuP3t<1<&^`5(K{Dcf+4jBY!gGw^HUPX`yCsIw z4ubz~$2yuZ^K=8eMTaY&o`L48mzRvSG$dQP$%e(E)#8cMB2bIg&Q$5JW>*^ zLx`^?>U~@vP=%t(#O2yDGfe4eOKH_8UditvTwGM)w#BbG@+^$tW|6!Hgx~)gKUnzd3-Tul#3H^ z!hiQd^?}uv*XeIU^Ult%r?iA~1HvqleyHUL*=Dw{HhVh>hB$00`TZ{BS$kR7_>&~l zqmN&o%Blx>+>MBZB)Q2tKkxW+EBxIe_h%TX`L8L+{ltVPsJ*$ic`yN?lbAO_z=8tK zd=Z7Tr;_nSm`P9W^p4|^`K0S)Y=5jdepNUOt8xhDU^CMA`Jn9jw6cNcQdEoT-wkq3 zRd+y}1*yyB(b+#2GYp!ulcuFDL7(X6>%7LY@{d}gDZ;6{yV*fUaF($=GD+=$G@a|q zi2!_cbgqp8l8jUCRnF1&)-iMUh}ni`1B%_=ydyTfTHBM^S^oF3HPdxSB5U^$qt8uK zU>A3AVi+&#kpM}5M#iVm4e&(AY{F^4NgcS%lQ+I_TI3;rJ=@vzRekz@2fFax;2ikH z)wXSwmkM4u@KGzvXzvdX;hj1L){U3E$2p#8()#<`Z;mN7j^oRt5SdKAws}|#3O`Kv zduiX>z4n5Gb2v2Gmyoc|Zno=S>Y72lP`|9_M)6;&*vm5`*kUzpd+bD2^YVap0^Crj zyq<|1T%K13@YzS3t*&IRZTV(KvolWK$QYaP1&NCR}1idrz;%AOS-JnFvf6lxi zomM?f(N5Q&srx0x%ek9m1~2qVW}1C?Kt&I3^=%W`uw1dWnHm<>94W^E3yX)yn6(Grpfua zwd92T^>1%BHe6d4L*B}MXYcCQ&Py6b%Fr^0HlNcX4Nzd|=_#Uo=N?9v^mZdJbji6t zLuGo&c6&v7>lt`ExEGE0+Chl~vD9AE%nW|7_~fse?LVg^{3@c}0wS)mm#OaJG{xM- z+(-GA=O*Uom(E41IgKpIosie_Upu`FmRcQ2otEj>Tig^91j$vZL?R3VH{y{iRhshT za(6)Ak*t~*dskF>b@A$(_pITQsV!~@Sy4w-`$nxsZY|hDhfjY&h3|*Egu}#&I%_m zwWXa!>6j#$bZ#BLvd+Q$J&ZG;Bw&QMNbo_$V{3nD@g`m}yago|xrd+$Q@K1n5Qeki zx-?yi2x@w}w)O_imJug`6imHp5`Gt7Q*nGmRXw&ft?14#Z5NJjbx2=x3ws82goYYE zWzC|xTi|2LPlJ(elKcl&UAF;?C#F;PkbJ(ye^FnRfh*^7S_R2f@{RE zbgyl^e|I^z7os(XwnzR2Rj2C>Tq}ISVUFJPstcpArEX3V{k-N(x66aE>|%nGpMKm4 zZJ_AHrk`z-gYS;V0m~f~jB{Ko))LHO>{wlL7ZCHUtBLo_D^t;+99ZNCd*U{?`#H$+ zPqJkRx5dGe6MNht;zrs}|c&bX4`gyw9|Hg#=_TVO2;p8t5GhVxgWf)u~ z*?cG!4dzL$PITk$tZh%a^V^xOaM)5iCHiMs3-4SVxVQVhLu$zlt5oyF-_IoHiH}_S zd~BRC&XA=~gL+*a9OpQrZOEbK;qASPyfGpigTV#SNb04c@&BeB;m7^+HM7f5%I>-O=?@043<$8pS9awrFE<({ zOi&%R(4vjkPBpEWY2X+L+=rhkgC6qlZg*i!kCaVs1RHO#XJ63X4SlX z-2bJ9jB#}PZ=1B#N`YXI&`5cFXw&Zaq8pI?RsvQphv$F<+zySMYJAi-wE;9o<7^*_h6jJ z=6kx?WnstHQ4Hah4Ynm;YL8vIRFj6T>1+VXpH{O`=4 znsQ-20q#LN0yXi!e%!Vma5ZHy)OUcIQ}CdD-x~*p!@zwsg+oPFuEz-FcIPEU1b`B_ zK44hg^%EfBTzJoQe?4{exZmyXX|$Ps`I!E;4K|JzPH&Fqp(6bqqKQu`z3yabXb(*h znBfl-M=Q~q;nlQL-uv=VYe$GCf~ADcOB6OKWnVgt%&4xfsT^7BzT-bATq1+<5l{UF zdtGyMRBF6Mvz>lp_x{#OQbHkxtAX;G@nC9ttTCN#M}Jym`�*t5;1l9p|9o$gB=s#=}fKmx_P%g)Z zFbTTI>ktBk2W^NfLfaZT+;O{IYj!ltT;T1>dg<~zLdEiiH+9p>>|X>O`|dA68yBwE z?4>{=N==P}E6n}Hj5*2f9zi^iC=aCTAp~1IO9xQEzkIZ>UUwI5zYm8&p?O{XM=Egi z!tL(X2Xy%nGTw?reEY@^+!h^AF=?NwQ&-o*0I#CciyPC^>(jw7ux+pW7><&RbM^V? zfCV;|Y+$5tC83(C^djRs^E;aq14t0yoW-U>gljV@F+}589eQ2}CzYEdU1@RiAbDqT z^EFC)*)*TJu`{`%EvPEn^!)TqpLF^?A+8enalN|M??yhI2X>06|`r;zKv^GIi zU+?oeIcif6%8I=m#AEqlIc;x^v>m$~iZr`uH$*(4J&0zY52Ej1<*+7wUYSdP@(_-; zcE$1cf;+StGqt^i8A3gMpqshcsy|nhWeF+#6)*NG+&(I2#4``{F?BR+>JoM9CXaNg zYs(^$OPdX>kE>+i7*el&X&_7@dAjJmOH!If)je|GS8N0ez1|pANf>1{#1Wt)y~!w> z5m61h^LW#C6DO=`H&=z$8x0hs7ZxP1YDvf347Ps7^HFKMjsTTio@WlK%pxFbht6_4 zPg1nFdMltDtmT;HbnpD7KG^+Bx0Am0D@7^ivjxfOhfwF+27- zD72#R1zPz&85!|>dx{PAln82m0X=~xj7qhb!)W#ryqmlW@>bx_K7N0PgNvRpRlerx z@iKmYDme%nv7&AYn&7*Yjn)eV7wDa&k}_3ZR!xCTm`8@b$<8PO1Kaoi-NlmL0zv1J zPSL8`GMpg&bcMzRi`UL&WsD9Ev;&{BzQK3XR3mk-PKA~B)eMqd{J9b64;MV! z_PsdA#hO>{=m)xeZ3B_or;o{|>WDeqGH4NLt6^$pTh_5S;RfeJg#TXR^w7Q-sDK|j zJGivXE`0Qzot8d7pMRdacz9fq0`;BU*b(X&R(XEhenVkUb=;51KIao{qGRpF@3ugS zV|Rl56SO|6bdA=7Ik0$n@haC%}T;-?yJa zz+A`)GGMKD74>j$!$W(;8$I-)VB)=^l+zdA6bg106^0nZ`4688W$a!L^aOn62eS+_ z*h4Iykwq-TRGl;06%d-3V4T z+?c)t-QLInFxcztqNvo`@WC0r@TsBEUvkF_+K^h#K^UOrxNW8bbHdNlbri`ysKD<- zc@MtB?#r_C{*jkAOsTI(2v94k484CvtMsaouC!_W6%R~`l-M_0Jb`ca ztkltY?ZTuwZa|h3?U~2fqaUCWSt!v34w{X;EfOuYMq0DqLj-4Kg_K35-ccNKV`zs(?h@wUTZVCvN!g<1vZ-FdlppW_yRaHybKIacl|K6e<^ybt0=gNL- z-YVx}`y?xe#`VovIA9UOXL8-Ex%$4Xt_RR7IyyDwC~sCHrUJ0RoRg|55sIsQTer*A zii*C12bKgXIdm^CZH3*A+huR(M#L|-AqDyysE5>(Y~GV6|A-{{V8S6%<*+s#Nl4~B5w9ye^*ro z?6?p1LO9O+X#o9tAmJRu-82eUs7WQn<;CA*&`X8q2W`^U!8l9d#ONn<#uh> z-s*|%urJs|PXqn)ARi3Ey8Yqb_n5wH*{d6g!3O~?;F5+!mKm{)9Do2*nU1@DtXG@q zhypGp90`e(wKb%)w1;Z6Bre2;)VSwidEsdckfjDnBESP8rXOx%wHUP@Dhf96P#yKe zG8GIqO%-)_KjY#IRn0Q~3)?}Bf(K-YJo`}YKoC4IqwzJF?Tu@5r44MEfGrf*YyVjM z4oPV#}S)d|=mlKaY3SylQEhJmQhhe8&> z*Se0X)+eC?Af{VIjZxy-h<#)3?9?7pDf~Pq z@CipjszTbM5abN2q4W(k3@JkH*i(gjapGhI!KF$y+nbe+Zdj!J1?E z2OVc4`PVWFKx$FA*sxKi_2ZwX1%O3ELpF4KG_W4Lf>kh8)!%?JeV3h=RK~!IGmwPw z3jU9uhF*Dzp)~_C@}KiM*wLe@m)oBaz_)W+d2g@ZhzJyZmIKIlGm@Lp4myKsO}A@MDufTipz=uJ6IO;~p!~o#62VW2sH1gy@a8o7Mn40E-sRfBbm`(pQZV}V$^t+U0N@0e0AW;@Q(O5V*$8a><@ni{Jy&vn zpSYJmRh8=rJusT(2*US85F+yU}uPB*PWkv!l(n~yYdkz+6WLT5S7W%1Yl#(f(z^c2&OaX8boUzy9` z5x_tUjiP*K75(B?x}u!f4>V!4sUbgb5>cR$NEqNM#>N4cZ0PTdD1^TL2w-vo7U3-$ zV-KvJ<`f4EZ%GFE5$jEZA z^}$t*jp1S!cacLGCEmjS!(~Cvg|swta=lI+t*G>il6l$Q?SFhW1I8EaFGnC@1k>!* zWV;UDeLZZ^R+?ST`WgIGN?^=oEe>4WKFPi}5KoWdrQw*q0k9art-PKpjWpN=3Um46 z-bW#6fOPzHpga88PP?YF)r;+y+iy{9szIy7%A0`=P&>=dI zV#qmI;4rbN1pF4aM<~Hwdw*OW8AVmq!=-=!mZB}ZO9D#^&T%b{LHPq%2BzSr4a*B8 zZmb}0q4>m*OLU=zkjT`l0cZGX;>=Jmj3zbXrP<_?#~4{ zsDNxWLFV`)A)T$^4cB3p8pE^1h-8(N;4vt%JS~ZKyu&*8zBeYO{^R-WkK$G$<;-7e z{^c%@;o0bkuPL$j7cH)7f==+?Zt=Nx{5&n}A_sux4iDT|)%ZZD_9vU0h=?K(f)>P_ zBQjLIqkErW{_{Q;JxhI|r%^tL-8C#te3|pKzfs z5W~1J|MIFfHw z$p4dA`J6z6od(fZP^EeL%SK#Dppg?fZgV<-6(n0MvQnbCJN@}p<|=PC?&CNtIY}6! zmm0zZhWpLVGFRF(6@I`RNd&L2{RHl?0%I765-U#ny;LA~%ESP0b!9F9gasP0g`oIY z&i=hRSZYD85+6OxwU7I!J3LaOY~wK>MTSgC^SWY+3UX(H3i6XD0El^eVevx(Xv2$Q zZ7L1%(f>hHzKaD^1Ax7~I8xBU7Zv+93z9a_U3+M2@oFBiA+GRRb?||Ca>@IR@U(wn z3zn58oQGR~*29`zNj^Q( zWGS6_SJY%UYiNNB?g*+JiY@IE#ZvIn5Gr?@=DHz2TqziPFAa*BURlP`?A50em~t5! zeqH#Bj?%38_-i93WH)5McHvcto~kg1kL4zDuM}%UEGOXO9|cjbb9Z*m&cX%X-_B_+ z1A0@8X9q;D-tE$moB5Qy>1n=!d1C~r-te$HfXM&6q)P^g)BrPf9-|8KKcUdn(fk3xT)_dGdC=n}lqFY8p*H zZgu_Y6=W8e4l9m!HGh<7=0D&M2Mg20!n;YM_y5Vl#xKX0DCne>xMg1pB>&8s)_^x| z^lrkD>1R*}1_gt$jxs>A!@_XD3k{A73W@G@%b!m89zV|izMt}r;lxJ|GiU^8x})wW z*a%o}7Y8!0*>WKt&x!Ki;@Reg=$U38QgXyG@TR_a%_dI8QkPDZtR04|-fK;zPd z9@o9X?L|S`y@|{)N?KI{Av#75P0$4&a14QS0-N5iopQG!LevOgUf6Y@5DBfWg`&}| zhH5YJV^JlhExaQ$RpjmpgCsbwvbtz?yrw?QO6`y150+EwEMHok{}Ehjp-{ zQyz_3M<}Y`jwzcv1vVl=^pG~nx%v_#YO!U(A>~uV7tG9^2|g5UtH45ojRMYYOT~la z<%z<1yH&oTgO+1*2DFG_p!h)U@^drOq7C0QbpJH*zUL!C`@J_wB>Orm0iMYSaSt5a z?PVA$^`meGCt&^A7DTLKoBQR=pO}9do{_~DW6RoXNfE6~d-^@!jzqCshoWI2w!`Dw zT!gFek7F8CnWUZ;OR1ZAL%un>6KM%>Z^TftdMt|NbKPbfFbA8A}`Ye3Q%gn>%~rx-wVtLv>5%(5uXoY}X4 z9SXGF^3M}x!_TYJP@noGznS`03=lDZ=SXY{7mS4Qb>>N8xt+v|9V51XPSu4K-}u{C zUAu5&*UNJLT)_ap$u>WRE6Dfiz>0@q>Whx&m+kdw3cYQmLFG}ptq2T|yFF|N!6i*( zut=UJ5@MX4=#5cb;Uqiszbf1V)hO0wOFh_uxEUGSpOGxKwSP zh+rlG$?Z#~bGWGQB!e?b8nGdlw1VgR=}D%mz5q^^!kD5QpHxk*)tb`9&l5ke z#{*wpdb)66?!I+pRjIe=k~^)nSRh3R+}oa=HMv5c(N};zj!iw>2M2d{_S04}tQL0J zJA%RWlj{-ha!qWtD{E>;dohx$&U(B_8=aE!tCuY8SFcyRz=7lF`rJ>@$Ch^tacvF> zSjKW8f5YykU7qkh7k5~wst?wsV{5hkV%ynxClN1v0dF;cZn`aqb@FH=`k;XsM_`Sab$S1ICD zdky{CDG)7Y+0I(dmxb!M1=4wt@~Q2d!)|7(|5TU}X$m}{pfFwrkRg zsswd}G`+&aZy#}f7ph(tCN|a|O$+$k=1m%^SVORxZV%~Ez+s2iHh2jqz^|@`GY7gt z3ucn5{(`jl#EykuKk*)9U>S_)i9(>z+l`7~hzIKMca;+(Qa5XP}|sG4*2MIM(ca z3t_chaf?pJr-;x#4F9d}QfQIz=~>c%SZyYCsK#7Y^^#tDdTEplq0% zr+xagl2L`FGXazeWI>;U-6*nH0i?^|6y!0bdYKs5vb4Jk>1@E2i3gD4>$P2grOuB9 zZXPH&iPh(K*|bR1L)YW42EObEK8Jejr7L*EV^suKOT;9c5Z&BB8D;@7=|#j@GY@ z2L^Pf-rT@z>nR)@>~0?g1$DkTB-k*bm7zh8aBl^w@)(}IK`R0*5nWqF zHqMlXT-nTqC!W;4%=p9H{wt3z9j2A((%J7{P{h(Rt0&&IWjm-43{pCf?0S6TKe<+_ zr!>q>iU82BSa?wN4(9=u^CJaz~moL_B?<3?2%{xI&+PPMkdDXWq}W@ z#*Cu-j_%?|uE&0`lR2EV^`Bd}agM+5#!j-L`GMibdqKF_*`HxJuAoRgs^T8|!O;gj!-!Vs^K#iV#oLEzH6jULs5fgwEoX`5*yIFoqu+Y8 zVj_bzzOH@=3Vq1w5h-TafF%F78_L;%s3s1t3gXKX`seEQ2P|Au0 z8t=yUg4yIt1%H&xgazPN(WWrvHx1CxCFA9yxBToU`}1n3RN+7eF=;~H%L`BOnF`Ym zzm9f=OiM?023L6_Z&h{9;VN0WdbBvzSap4bbQM7cN~R_9IPS-}paZ2XCMiwb=Nw($ z7Rd2gEnOdfC%>9zZ7iJ;krPxc-m)?5OoMZ9Y~}?Y#WcX&;b9>Ti7a#m<1;X}azBWa+Dkm>w~@bvkrS*S(BDQ&e|f#B1?-42Q9mPD^W02Zci5cxgxtG z(gN_@<*BSR`NR-k;5M??V^#? zuT&O=l92(h#SG5KQjSnp-q?7#e}O!Ma#sAydN-oSpZA>*2$R9sJ2}0z;iZn$tz7L^ zwv?lFL`B-y)4PXVEKk+lk{|!z%zl-E^YR8do4I*In%urARw2(iwai?b9JsRK@l;=< z)~{7Mz>zdB$25gy6bD2Q-~hmgq&mZ|s*IB_Gqc10gKtbmy6|hbTqZC>ljOfjF*HQ2 zx7nn`KJj6GD$H^H$;7E_mo1@q3Pxk1w`TyK{f-X>^mrOIOQ76zisdZXC6c#%USH>C zD!(<$OOl=Dd~(`r7Z9e>nPkQJB?h%fp1Zh?=Pp%kstYv(8Ap|M+-LDn6)CP70F4dp=wPo0k2uc48Rp_|70MnaF_rWqo{ew{H;dsG#VcZ=|zJ zWb~_ok(8GVcwfY3>;ZBVZg)rH5=_Gdh%mKLdO2F4>#??OcFgu`^_ZkFP59V4|8}6D zUk;I?&WSl?s3moD25JXWI{K$Lv(}R~B?#Io1TiiNHY_jIlchm#wCJxST67Z*;%ZFkW-fHt!imF{r zSKDuR7dV?Z+x$9CsvUtf7d1Ryi$*cb1#5C2pf(J_UpD%m1o?&1k1lqdpsA+(wzqRD(kv4wyUoF6sG6*uZ$yP~+hdpcSZH~tnCC4xQGcVsTl!SbCF?3Rx}(LH1L?wc%cR zBxj=)d4j@sEP1pTCtK0Lv+es<0?HRfM$Vx}->V!;Z1j!p`SY=WzM{k3YP9z^e#;%H zKyNPD)~p`T&60?+?~Q=Hj544oDmEwLA(&4iq8{Ego(mD6OyXES`A8x&I^)>?>^}!| z^r^vFvhgOVXML;Akru)f*l>kBaTy?-_Y0fLB-d{L=I^n|(R&TH&nBYhg-<(H6`)?q zRoO5?kXd7f&j_e6(f<(sqrNZ)eYeCYWy}0{j?4T&3`ug-#}Dqu)H`JQ(wYiN5Rs%Xh0WiI6S*{c$m;x zjxRphCh=3d%`ZT^LX0HMoAu#SSZ7Yj5HHO7>D-|Hnf0-ey0IzsV!vUR z-1zV(7dLU5%Jbn~8=T6enXG%KZ5XY~;=w8IpPYk^PG|Z(t3pI_7K;m@7eJtIicf&b zuda$nPZHGb-x&4g2cD9r3)qtYS*n-US-eX{U~6Kaw$seCG@CB-{rqap+O|%$Hs4CN zEvr?@gnSt$Z=Ql&(QHnvxnA0<|pb?*j_C@5%K}8NkJ=+D@zMdD` z3Q#k@9?f+4V6ypv_6z^jX93LJJ-Qr@@{g_FHPiIR?W}Cs#KxS=*&{w{bsyc<2AN$_ ztMdZa_Fu|$IqQgTe>Run*UnPaug4<&E!is|+jm;sv^T~j{NntnYq>TmRk_k`-!F$QmaX&9Uv?3ZqoBU>r8IilD#w>ZGji9Ib{ zp05GfPbfEqjjuRC(Oz9!l_=1d`gY)nvrjkPC;9&3IMN#%yBr^0SDzpIpciCY3BzgW zjP#r=GI-03)!mb*SO4w(kXv-lA$XZl#v5BcSU6?R>ZAthenpE*AN8jCqWz{1 z6p;g`yu8`zlv7p!2@XZlU5!IRlR7v6y97`#AcVoLgq*cw5~vbINl#)KQ$dr{ly1y7UhGu(u& zDb5es%IMI`dO_HlAm4-;-W`$!9*?T5ub#1YYZk53{_%ZN|7D5_p6l1OGgIGUf!$w5 zMk|i-%D77ChcB=Y6=y1XOauI1zfMFs5eM z_}ip2nZfhYp>?pQXEf1DiRK*@o%tkiObe8}xxlU!BS!zW&{LL1@)&aWG%8HujK;8$ zo@u?cHDhcX*l&wIS<`p)BX6XI={M)5yh`!&-#HoQ$TQY0bFdR!k@7`?KPoM5F334;_bh=xmdx;j95F!iz#={FnlhPwq1l}7 zN_Zz{K(wB{f6L34FC^rHy|jxeED~hVV`$V~ulO!X+RX~t9T8!6_SI1QAI$M89TD1i zHk*MP8j(;*|47S41S_$}` zUY36_Ob)=9gzbwZZ!TAX#K*PphVQgL2`Igma{*XrGDax<*mvqcm&=xD$>DW}UC?*a zV+77;=6$AR-YEh(26@%BjH<=4oJAO%_54Q6B@znQwe&@bve$&yF8oYGjgOrglZ(Dc zLaprBVoic)MSVE7>zN1s#toqkuQ$U*(2M3llLV9$!PK)j9KmKE@eGV;IWn#$!HctG zMOlIOr&%t;)R9wXrD#6oA9n_koUS#U1|oOX#9ol_ZK3Old4IjT&Y(UiiUsL#i=*3W z+$B@{GGqh$FaXoOHWLIT93z;zF4lxbiB|sC}J%Nvk(P8 z1S$tx8!?2m9oTM(FvU|dutP>T%}AzE=6%JbmZ>1B+U5OiIKJ5uDSK39Z(#~sZ)g^n7ylj~{zAa}^?5k> zbA+~|o0Dyf6#Vc!Tz|Ueb`}TNJWbScX*qH=FuBlIS{;OA`6BNlP@hkwjO^;XUZ&b? zjiIAg-H-d4sz(X?Tn5`oZ=7?4$2fw#QynGq%3X~z`{8Uw^@eXVA*0N*$JP8(MnLzL zeys7Qiy7bi2VRp=sngzz!_wW|fpn~S`zX4r>+s>J(QZ#0vBP(S*WgY-GMc$(a95pM z6yc=i=9tKHP=zDk$!vN+GW0g=1c}7Y&spiq3PU8WUwSdcHt)|%&G?d_8%T3bC6FX0 z?tI8s!4p%Q;B5KmWvq{Oy1Q;u;NcyUGLfAl_-(m`AST+7{M|pPSPjYF!LL@9+mNd2 zCilA$w&`|aOMSJ;xb2~p_?2q^HI{`B^?^C6BAMX8+Cfp0 z?V_pOD+0;=aN?7MEn7P`Cl&@_OgYVZM8by9>9^qq!gRi}S{ zw|boWxO>3R7uDyIft7K#P*WU<>|j^_OFm0II)h`J3lGAu^sA;dBlyQc>qSviF#MtE zfH`*zsb)V%w2qFpmJGRIMS)(OuAr8xRxJDMkx1D1!)VJ0-UH z8iA10qQ09YZf!mK5mb*zS9;!4ECN0-ruV-R)29$Dwak;Jj@O zRiU+wjph6cpUCmvekC7+R(@bHF4^K01@EkwkmC{u6_cvi^uc<*E?C!EC+91)vSEZG zf#>_3)GL1|u$9Uay+qZP$54H2)3rEIheK;RuCHy%%f5ZGO?f3DFh09iH}wN0LuCd- z`Mqk6-Te*I!!IN1*FI%+{goHlU0Bz$gF%X_SRmr;dVKFOsYzY>`u+|BgQ#MRd?aZQ zHajCzm^9bveLgokW7X{`sw(E4Ws!dEOMjQK>j&9$zfj`XTd3aLk@bqB{{MFeKGCq% zsW_jibmD63IBDi(UY-M4;OW+#LN+J~P;1d7h%MQqT*Zvo2Xw#a8x=WcmFQ|r85^HN zby*WPFjvhQa@8`B2{S~4y1W%`f_nlIMg;itCf}M@Ca-w;ze>9JN2;dy)_|hGDl^-9 z5;H+jZvipw&m$p*TkmoY#GG0!qa4w;KLy2mAb~&>=Y3N=E!YWp{+upL zuDQxVKF^mx=7jKZaq)!h?OFFpB!y(jDx{^QYSJ6n37a6iyru^N(9fp zDf?j{%Dm`9KEq?5pWNA{CTO2`uyZlIkwcFB`u227!(i#t&DPyJpCHLqADD_6ms@?| zq3l5}opsfuq`F3B+|uTz1A}v`tgd#&fstXFB21F{{h>2kWcXw3%knv)knt)Tg@)^l zHE*Ly#M~)`fB>Z}6ZaT*qk8-KS^K4K2i~t_eE%+oHcj{3X+vI(CwQ26etl z>~gLwWS37*ci4quDe9RBtco$CBGFRmJqdWo6kCEq)8<8Cm{lLNbB=!(j8>N)!>2wU zq-YIs0%tJOP}ErXv5A|@>xxPizX3i7lf7c^;!k1SIt@_LcTSJXg)DdHP+$Y@E>i4qG{l6K~qk>`IJe1%T_Xptr-DGgon3c0^8S^&FuUs5hE3iqBe(fpH2 z_99#&VFJ6N^PiuwX@wm1gu`S;b;NlbdU{L}b%~(DWp{fek(j0WQC$xeI1&$Oi316zT?yqtoU>bK4Lqm2wnG%xbY0!O)O2hIf zgwLQ}<-MV0Kh6mw4`y|OQp5ffage z5x-|kY3(%JJT*1aL|#nt_FpUAT5#I$FHFXkzH(HYxsV}yWwOWVv>EhS4oyGbrBHa} zN*C4hBRqt}vbMKBwdi?K?QH*^VZsl|4V1h$vWi{V=AW&^ymN36HtxH4&Q|@ z(50qXtt*t)q&tY<45aCro$!617xhXu3EgVcOi|mrUh3?c|FT)~p7eR0if^uGpGOcU zD|pX0WcV^qFW&Gnm9)^sb0z4Wf@MkpzcQtK(f#alUA8>hod%Gk1s_QQh6Q_lAJNwv zzuZnWvMk2N*pZX08^6S}*}3A(uOd~vysB;|;@anH#I9*Pa@(A5Hb~|_2Nt}}eEq!W z_;T0$$(0|(by00iV1X7aRXfw#ET*Xq)!d*Lh6`xh5AOk5btER?bi1!msD$fYT@ia8 zn;|fDa_xm8WJijnyT0YpAI-!{Hv4(VivQtfo&AogFJjdlt z6v~TZcJYocJTEM&D2pC_qM~6kKmP$@WA);_{ES9bMjVa{lc}b3*|J1Vda_@5a8q+c zHIC3ySp~c7n$y*5j|L5yoxR6OFU@FY_{vXTdVx0detjtdVB?r&ygpOHPX_H@5qiE%cJr7Bx`+C%JI5G`GvsWK9`^N=EK$G1Z@cs{cEywu&d-C&y%J`1xzZYM9Aw{)3<$YjK~;6&suN z%G*xM-Bi*qLJ6Ci`ikZ?Dx^>{l9E@l1NO)PcR@uc1AOSz#^f!0N$$fUbXKPl z_`J7Rio@Qp;CxVZ)qH7R%Gnc0GZ!IhKKC~6YmNoBrd4pV@?gt%zxvlEQ1cfb-wro? zJgMZ2`e!!*!FNJ6T1`gDY7@1&N6~OOnHO9&IpLWm-)4D4SDR{hcCKz9R+Qpm1Q31` zug)HZSkYz_?%UUy){n^S?YT~CgZGOX8j~}!BO@i0ZpY??xXy!*5wb~|0`m>+b|evB zl6#+4P+ot+S8KTmFMRPlN_h4>+15ID!yII`nw}=uk_C^<(<)@Iv8or$XQqp_>Q(9JVoZK{IuL|x0(qbg+hJp zr!s;GlrKiXzj$-<0fYLP)9IY1wX{i|Gef3Rm~f<4roNw0Vq!e7EYh0z)T+-{C!7Ja zDe-k6CugM=zjpJbqtrd`n-GOHM%Vjz+_2j%$TW$%Uw5u@`2-CR*e=u)+IfwbD)z}4 z^#PHs|9)7Kk}Cph6d`RN;pa9{mai%37GAVeFN1|LXsv~6o|%2H!<33ukLoY)(mCCW zeM0XBd=1^-DFaH`c#J@aBrF@Cxy)+kbxO)LtV)vfWw40x#lZ*Uluq|{E`H5AwQk`CI^ zTr)_?tVYSf$}27&0bq)g-+GF#eK)Vp)n7aVX>k$XfdyB5c)z5QQYf2WN@{sc0+7RQ zb?enPFzJB_vHUy2et3%1I?)0(4S;yx+|U&+Hys~$9QbBqR`}F;HniwLFnKI;s;6^4 zDISP$Q~9>}-CwFB?D%2y7+$uECG&&Wl3ug|_O;025U{8GR$W(1gK%yyeOgY6AVT$J z!aS=kb;<)P$uY=7=DZC2{p7U>Qc>wd4CCl@_&*zocK|COLS^19Vk+iFOiQyYjfZ1*mmdb-5bSVqkxU-%sNOQJ z<&e{F@2&mBd_{YV1wF^-KNZTjB6d@hhEi`K{0@CAl|O9(@;vPJqVh`C&0|xxpjn{E3OCcs1%VA05@DTGgVzO;OSaSAVE!+;3$k2WpoGd zRAaI+anV}=iq#?g3AeVLRKNibn2-!IHJWiBUc#NJiP8>1U$P}iaK2^83@8K&(33JT zF@LWQ@UTm|vZ*j0N>2QS+J&Rod)%1w*ed7ao?Om_d(oc)fo86%<5H?&peYG(e!qQ> z(+<6nfPWtFhjEn|I_G*`8+*v=k*|ZPpsmJ&VlkkrtxIrXWI@A_lwQWu!4Jn<$qGx{ zfrjOoe?QbO8~dFU1ek@qA558+pamNXY;U>L80irmMD?@lfq9aCVe0rW5#LA0Ij7jF zWWsUExXs$gD#)=n+e*x4V2B1n4uE>9Kjs1v7+ID`0&{gWFUDr-97O43LKO{9AR7 z=eK&U&o(*wdlI?$Wm4Y{w`4uHGe1k6!K$3WcR+xTSKPZf_ir~R*PrMej7|`Xoje4M zsm7$|M(B6K0=yX3`i&Y`pmca8C7*o&J;o}R7!;Xd#U&$5{#FV%Ci3+|`dCCaph5tu zS;e2U*&`U^`dUHz%OU{r#Ly6^RY=#%3X?Zp{Z4;eGq?WsN3VLH z*S&P*$Mf9u;8kwYfn)2^?&th@;`X-(e#Cryz`^lDlF4g`l;9dRV7NCQosZ>}+AuFO zfL@;)nk1vmPzDgR@NlK~_#s^4UAyQ3MzD!iVgLh{qCr*l5D+3qeK#h%#oN2KZ9$(x zSH!bP0p1_QG2GsGrn>_9*i|PtsKY}{yl*CHlBgon8-V->9^P&9ODpL+n&xa#$9stp zAVFn_m&gZYm0rH(p-KpZWKmw~nYu1DMv$sh&)W9zQ$B_lq7z92uSd3AFMhMX?Xse( zLxd%s9No$hu*vx0#Q@PDznt;!?H7wJVdi^0#P-vR$jmzYPPQ^p8fRhoaP zZ*A^!?r^)g)n`GZloI;Mpl(_dVCIR~Q3I;E6Iq>)dV%Y*XRD)dyy6B&HycI}RdgT| zzf3hrZYhgDA?%spojyHo7;Qo)@H8K%2CRPeFH(F(9?kWq`lBCR#S<6^irkGR|pJH=Fmq^Ov5yBQQ?15s(a*= zfWw}m%*e+5E*OGH7sQF$PB}FNpzrY*@8!(|U4@-4_YOVFG-}qIfXNIbL;~_oL3>nY zB71;LHcyj^?$wg(QcuOQLTs_W@Ma zYzX{~Ru6o&w^VfZWh-*bxUG+DAn?x`UMNe}TUwt5NZn=l9Yi8je36?fzMpe6LcpqH z-`@d2Ljz!SKp`IyD1F}QNd+c%`amX5FbIK322S?@$5jHBbj00s_|oMk*|STmOQ1mw z6vpKWfL&_69iRxNrX8g%XP06%#de1~olI?WEuZ56b#li~ig>2wRYaIbo;wn+&I2d+ z$gow!`%h-N?fZL)f&B4NRUDvlywCu>fCRic00|W^UR{~UakO<1GvDuIWRv`U;IY@4 zZF+%aB7w+Lx{3jlueAMPSxz^~G4aZr1suU#Sd0beY6rk50x);`7QAADANB=>zyd_K z!FY7?@&h%DhD63YMD2HGEb=gDuz=PtO2_9Z;Id1Xg{PyMX}nRuLCx08~`9 z(m*qekmc~tgjTIwKB7b{F+p+CS<(o0e$w;9T?4W0W<=uA5CrIx3=LHz+T}EI50mGDU280dd z^`$%EZKL^vuU|h~0ORf-j@=zO(3@rWaYB;)G)`;eW@h*Ab-)?pXahPg9};t_@flQ* zJG?gGf1O%>V{Q!NWgw!GO|gXQeJe2_dVc$7SdcO`9E`0Ay!jiIF-_~a!!eup|lj=bG_%eeoUhVd-P8u;9*P5Xq<{d z03q~r_l0?{ECo_PoekhUjrpR%Id6V*RC)1G_>%+SY{1~~=0igppNrslb05xW-**0B zxV>RBV(Fn_C!p_4(36WsH!O95S+z}6U413a9~IL42%@9gd(8-{?UIablHZ*pl`SQO zNsB<}09FEm%yxK==C4BMxS0WlwBdE4_3PtvU~+G1)p^zq&4N;1GuAtx2P_$o3kDpI z_2)>=);|E_WGq9pZLgDTAs6@!*VX}pWRK;Tnz24z2ViqUE*1+6!2qOqd&+Z{>zfsr z8h9cHIc1s_F+%A;z47kqP1_a9=W@;qv=^iR3)Ouer~oK+^UY*e;1m<2D~EJ9Zjb_E zNfZZKKqduHhXBSq4+LKCOq+cA(J)_Q^g=@00Ju+xfoc{cO&@k+awDHPU1A-f%(U%Ma$uZCX$r^<3pO)A5C<-_Ex4A)e&GuN!1T!hXmdp%yn#W@d3z2v9rcK}nyezCCbz)C;Dj=Vod z=nbSNlsX}R^W;DQrpBo$ORE=2t5V1S(z%pH1;&vgS8AB*FL1l*Ta-A&wi*IP^$2Am zKvQ^)i_`xpv`*xQJ@6jrqL~h-X4)gz|;*XUN704S8R-I_OGVg`^2y z88qZ^w?;4zYH#1=tDj*W{W?T6Q{d|m5qjI`NnRKluM(Pw+4f#OHPrM z>-+GZq_+cVcL5MYLz?m0NC`352XP8Nf@x07i2iP#KuT8aPnAQY zv_{6!GcXd&&aIH4$3f*k?^gM2Oq-l>K?)i*(E85=m3~LZ=lMLM#rt*9_zD@<{K;Jq z;bM2Kk@R0o{ZovD5h-o!(zg-|z1Zgk<5PTfmkf$5h~pUD`WC9_?=Hm1TF3=RZL;WB zH*hRV9CU1ys$|oPB;5ZTrlIw)7|i8Vium9#a*A)T!IT^Lp&-#bkvZSpAyz@1P6X57 zMK|!3X4Tg}yaaS>9fY z1(>I~d1Tb`w0Ys7y?D_0A_vdQx( zBUCNvHO4^0i+VQG`+^Ci{u0=P4#flr?|4nr+s2->G4wceKd}}AsXPqS6?aUNy17_NXs4rdN0A6q}58(f;o>Q2QA} z&r+G&?bj%KXbx1)L6`_BYiqH*RmTF_E6f?@ux>*qkp6|J(W~g0MKxHe^A*L=ErpSS zhoMHjxBdOKtTCLrh)|WVidUe9g^URp8}0om&=D*nS|mbb1XR%(B1e7IF%Djr~>`Dhx4?RY@yW6HlEVr~o)AX!UH@Bzz$-Rkd0Vsd< z9Q9HHoQaQuVbTw_UnFQkgYwwV# zA+@aJmU8!WVL9xe9eR6Z0mC^^25tZe(*d;HDItFT$2~ef^meLVlvf;3z&_asJqYNI zfR}6cyqGbn!Z0Jbxjs0I^AD+RSx|}ERMtU>l}^`6Qx;Gx>;1%^C1%W0PG1y?J39K4 z7cx(fWvYwi;2KbiMjjeju)9?3ss>&$q(J`_QIzTlnWW zZLZD_m1;(bN`@jNhz~2B*fy9M;=*n_GUw zNsh3vZq*qh;RgZ&xulSBWEUIpekFS9q5akACwV$ALgrXMn8C2SeC;LKAlXWwKr<&} zJ5eZH|3x`tmnnXUf-(w3&FC@RxLLyBqE!x5sxB9!s0hAFW2&7zCd~(-BHWk`7`3LK z=9d9AsF_>z)e#XXUv{W#1m3W8$53OLcYD z4tMa!lE#aq`Qr^vK1`Rh5l6pX=YR{e-(P-1eDk*-co2sAiADD#z8wbN&Rm^T!o_ay zx8Jz^-6}e)^bg(ovu_C+b5mLerD>yPOacS$(TdnVVjj4f>IJ zngpTDmNUjxFr09^q}5No%v!8OcEmqF6$eefx!h|o^uKmnDEJi%oo9zMA8m}J)kir_ zVq=%TyjNaYqQF*LTCr2jy1?H1B1%Jb#%Z9|^GpJCNC2&c%0R8Uh6X`s>k4QcD>lNTcOMxJgf6$IN@EWE|9q3B z^uIdt`4Cmknlv<1X_$s*_YIi;Qhy2}YW2JJ{-ReBMD*rl>eVw2OO3LizbZQUm^dpV zX#!`DPA}Ku#3&j$7u}tGd=}hEFyNcob$<_P=E_P+_DVOpp<-8CMOmksyb#FjG((o} z?_OfVTK&k_chhRT8B;`bi2=dKF~2=TLI zU7J7{2$`0I&Hr0y_(&jwXc_pQTJqn)6kNnOL{m1;2k9@_;am%C?w+aDtYc$i zCeKC1#QZm>*oT}=I8>FIt959>6&NFP_wd~`Ul5E~mL3%qGh!y4LAIONBaN%HY>(wz zSKj!JyCcm8!X05gL$5h8s6Utqr6_)_ZfR??Z?=2{I{5{`!Yx;=4&UyAiA^{|@`(B7 z=4Pvbg9t@9Ze%X__tmRc78Vv~Zyw_eYJWWOZk;-tG5F1E!^fRA!p_cKQqt7YV%uz~ zpRjpu%Dr`VN$Q_!?8k{p-eFwT*w{GhY)o}SJ$Z0;d402e>D^gx@3m1lVTD0GRGpTV z_IK3z%WySo2xo@!0-J8Xo}ppoqIUhc=0`K_k9*CwBIWL$K?apGJ0~B9%zVG-v9CRW z`aZs~TJQ~B+&;T37Fe{HJt zS~;rM_!4?-s#5xh!iGO>%IzsQ-j=+`b-T%LC9Fn^)j0QwI#=9)Eq`f=HKLFu^Npfb zXE)WB%%gdkqxzQ`iG5i?H8nhv9Z06y{5NwS4U0>dL$VDrhe7$Ef#YQI1XHHRAD`wd z9|*8S5k*P2T#A&XT*ukGl*G{f7$ZYVSnHzl=}{&X|5hEDvhNoy)_q-Qy%uXVYZNqL z(rxkJY;1It6}l7=V^h91WS7Zc^O02n4)HS9K z&d`H9QFg+$XHI`o_~30$vvY7Pu*+HWR-I;0rj2cqU1ms^_|%#09ipD;FC4CTC&#qD z<|W;$$?snUGB8-~`)x86M@2HAal^^{O*mmKPg~1~ZO0S_aF~aFuddRJ!fW+En#>Fr z^{&qktvd^6oO-u5qKhvS1WUec&7Rre6I0XE*YBM}dw%kZKZa5Q!^!yk_it{|4xy~E zlOWkD{NF;_PbOFQuG>IhH8wI1ardEMt!M3KBzZs2`)0`r<82P?4JVhtASNc3elc6M zXXUQ(M8x*hjL=f7rU%NCCr^f|cmMpUWyBO?{$@lf7J|EKm_LGl(fQiZ&8>h~L_#;g zTci`ktwE37BnkwI=3HyLhkL@Awq=zbd$)TO`mAMToutW{o8P>`K+NhuYj6;S01GvA zAp+mfz>}3ie1~8 zk1rgFT$a7QbqmRu)uKImq^rF<{hD*uGb6YU8dpSYtD@s`3NRBm;n#k*7Z=`_i|Rtr za7Rx+zqZqj2^kN$&OTe<5;Gu^x!DbO+4x#wl2b_^SIeZ4PCg7oJJE019j9Z7Z<`I@65Da zWWQrkJh$;XU9A}kR??J2Za(Rlcv1>Kzqn|cGo%Bral}?|>RyFyw??9e{JFgL6t=d7 zgNbAWJvEqR6$HkY3rDXSk+IW}W_%kuikC~|4|Z?bp-xCcC^7za7~_9+jW7h0W324# zFdDDD405*aRjvKHw=j{K)rwB9yk}A+rdwFIu(0r#4!#}snqJ~;M77ny>2`fKKMjRh z^LA%mwN;P3f9+`d)z#}N-Q)8XA?xY&#nLU;`P!ci2b&I1B+^?r2{MlPP_4U<&yx)0 zG((nZ)?=6NdFemAWhgmFhJ`mX)6gaGAA%%g(A3o*`iPTwtH@iCVztsFq@>wzuC8J)uir9J zgFr|v-?kG2rZMg`5s(gMfRCY&5h!5oL4ZXJwE-yLTFeOYdYZbh>XYt39d{+hnwbQWs5{lDs7`9*L&r1-9lBpd;EFbjX zTL8mWAb#p+`q@Cj`XB)e2_{<*WtY_BKQvg!CRjw0*n2@i@6pdjG1y0+7Uz-=cRsIw zTKAhHs)O)Z2T^mNrw5+WqrhkQLLJft_%hPCW0FzNI83A8&}4^E5kyE+JIb>p1h2gk zjwdL1St3amN4!R|_R{HLL->Mv+STib`*`$$_#JRn>l8cRa)l9F_w3GnSHCJh9 z3u+3*t`yvR6%$~#^5%^}CjIbplCag^uRrNI7S@w3VC$2VQMuy@e9q|g{V{RmSwbUxPdQzBt27^s4rnqIgrJaYJC#w`gC+xOOT+n_H zyo}fXl8{uD6cNvoyc0*3bVWB5@0OsFu*A8@eyfSen9sh-n)u3DdLw->lTB$_J(*FD z%^Q4P`I4oWeUq_H_aJrQ>q202U~{BTqYwP%!=>QE+CbRbytly}GQqksMR{=3K-1tA z`tFpM*fA80X&T+zn}e+V%nd9bnfaJ-nc0~kOjs-=OzuqLA9BBa`e6EjMe|B?e68n3Kd)e3L;_?ofB=h?Tr`z4e-Pjdc`coX?JzhnJl15Q1M* z4^{w&!Vhfn=NRUW=HPSgF7GKcvM{nbg*u^spo7|lWj6YJMM@L!iJ@t`iL6nxUC*88 zTdun;)7n#b6U*h|U+=ryyQmRg`+tS!*5@{vd^Rcny(~K?E0Pb+zlLr@v$P%b7OStK zD`Om^j__AQ8Qu|cCN47gGUO-^y}K;hFRHfqZh>#%YGI~NJQJ$-v&AGvpiW@f!f)v& zKe!~geWj+`D7i6NAsLp;1L2+SDzyglSQpwpx1KVlui4O%)1iVB&oLpS=XmEt>ONFP z*V@%))lO6?)d*W7=a$;D9hR-zwv2yQbpNh;wXwCLv-f6=?to}ZbMAX_hTzPTywni%PammbtG*;h-?1cA=}f_7i~%V2mc2?41XYgDLy(LN6lW%RqaFsYl&tFYBj$Vv4tRorXHtm z>p*9ZXVcz5>(L#nkNA(0j-0WdV)J1;5Eu~d5|Sh~C&n9e`K8ex2TXzwi>p*xZs=E1u!==hkXgU8t;L~kwPlG2-GyKm zyPfpIm_y?8f6kxeIE&BBKoIkn(53R;5!S5o7HY@bJ=%5C-`z<{o+-o}#YWjp1nwWJ z9L$yzp)}fu$m?@FgOhr<)y9)ED7qVZioMR_8~=%wjRw61y~R3Z2Y1}`CvJBZ$9kJ_ z+wW&6s)a?}hYru5mcM9yW6I;Sp1s<#i(EWdrZf;1x}pB_qqFi4_wUZFP@dQXsus`8 zTaWGjbH^KxBaN}*q>;63zPqwB@6b_A50ef@(?1ROCya^B{o4NKcaks3a-kOF z;C}Pv;WJ{#<}+Jj50#xQ~N#A1k4ggik12TGBDOmFHQ1zm+Kz|4Q4)9!n$Ik5-bAbOJUJh zMH+goD6j>z_-RlUB|;} zFi}@)X)ro)3E-vufBSIT2m5YK@0l`%Ty1s&5eS4+L*}fl4LxKbI)0&#bZB_E%<=v# zjcV%dbjFt7(!yeH-|eQut3^yeK!ArQzr6cL5Y|Yhpho#j6S8{bmGVu^rk;#L!{x)Tky}2FiMMn|x+ezR9bZTK{-KhZ#+xgtO>Di#q0SKyf*;4iNJoKuQn~(2# zh{=s#uN5$nVL4vw{o=gCT4!2T7H;5I9kxcL$H5&pH_c%l*(4aB!+6PXqn$5(#9BYz zYqK0pWIK?zd>lEkfu}FcI0@{Y|3v!w-q)Y%uq5R%jhCO@CMUQ*0NIjZg5vDGn#pC< zMg~qUo14u4;GO%3m6KyhJ`2g+5FI%oCLy`jhdlRxBTe_DGqSX>8>l)WVt&2!1CPPdW$EJ1Z$oEv|>( zw4hThFF;?#0p%*lqNMG`TL89!0Dl=ts8{9@6d4)0C^tLsvExAWh1+KJmudcY94V1) z#6UY)zn4X~dP$9GX#_bJY@57vB>5nE(z%?suX}_+TJ1}=06NI_@t_`hz>wlkyp!;l=c%&<>yZ=#y})%obU zjj++EH=Dft&7|9G%ebC=)EWlpR1%CHP@|`#^XcK^k&`?omLx?{#?)>8->y(YPcgsb6)qzdM=~Qucb$vZ4#t$dLID)#I3x4k0GJo(y?dR}} zsae8uBYJx+9#vYqodRYOPS=dCVNI5#3-;cL6k<}sdBzpp`x^cW(VlDn(`Lj!)Q<=% zJ<-R(0)S?Ex1QG|53CbN5`jj0Yw!H$&_LE->G^IO$E+qfQ?s&Qnk;3ow%465vkrCh zCx8FK4foNVWKz)%p$OZn)|^zQqQv?YjRsyJhO%sr)Yd~R$zL1cQ@dve5NnQ|hQSnw zz_KlW#*jt+m=%Asv;` z2cQ+eXIJ!ZiG1@B6BidRS2BQI88^OXvdRy;AgVgce^G?6-8t6BKH4A@MHXClbkVcg z$9=_HE|kt9n`yi6t!Uz9k$h&QXvEQ-G_Y<_o%XG@?1)mSaJ)pL7;rC64i(Rlie{cZ zG;cud@3*kAK_yxoDX!Lg2UOcHE3(DGYE6q`t~--AH$Fr%fQfdSI=1Aehgrqxl!abL z>@v7-enYMJOq(NRb92*onKMaI=uRUv=;@J1NOLcI^vz^3OJRd=4YF)RHitOo7Fg@@ zy@4zm2pb4N@=abXOD6$3c=_7eN@F1xaIl@3Q~LPI2jrN4(;{U-rT2=$=UVx2iBcNK9xOxOF{NMWs5{~nV&2N6Cvd* zbJZ-WwZOW~_t-^qN*t7mfm)N#F1}o2U?oK$V~EFcxbKg1-de|RSJM`FG`@^lH6m(6 z4^lU8uU2(8qdXaND!b4*!%0wAs+yj0Jj3o6wC?2j%@YD`>XiiCexGj$?3E=XND!yg#6^SeA* zdTzg#a%dN$w(A4IfI#o_NSQ1M9qn8}fp^ApIl8CNF{`Zw#>IIcWQmI(G6(~X)S_Cj zZ)F$=J{A_TW+8@3^FMY~^O?SDLDTDbjjg(wDu;} z@0u)L*NwFLFfHfnhJ{vK*H~YUD8LIni_eBKZ;dL~X}2EAsnsl8O~S$KDFd+jBd5cE z^f^*=rX3pG!-ZwJpxHAe0fnc#sdP8JN%8Ts*_Y~FxvBSh@H@! zi!={8$oLr$ML^W9c}zbI1-fnELLG(kAY+0!04B+2F-6pT*r<0mH?P^Z?D-xHs#rq7 zrh=GF&u-Jo&DSd#UpNlxOa^2?68xit1fV##IaQ|x@5-^7=4o4gp3&phMSCE;8Uf`v zu1AegC_p7a#!Udg%>O45mY#d?+uZj|QQn-Wd2L@8z|W@a>i|Q@A0ss%C^6hQyTaUK z1Re#{Aovd``l@8}xdjAf?CY==bfkTjk-p-74V#|3RRER+$cnD1<=EKR__==kUfY^K zgI1j-se?;DCks_@tVoNSo|burap_~&mYtJBwZ@V@O%M!6+n=vHY+AlOU@3b9^op8B z#}oN8&~`Jhx)d3e`no5|o9eZ_jSb6_PB3iRzZ$SLP3RP$3oxyWp`ycU6VeT*2DHPK zX*~x~-zyhn?D-zTx%;_xsYM%il#iJIdXo0t!pQ9cAP1-I%Xl=^7-P|!gTuQ6?Y65A zhJoBd?gtAk$fc&09P&~sUu;T`U!Ql&n(P;@UpH7-T6$vhw;SUyl;gzshpiUOZuSnQ zg%kKyp94?$9tEo<_~WL>^R%GsY-~XEwtMg*#H3IiAOA1(=1L>QP9t8V_g+Q@QInd( z_<{Z)gp?iol#VTGY^qKHT$3qfpt`#H%uCeIq-oKfmrU|m6r>#0F$&+>P6RMdz|fD_ z9tC=}7%~yLOz|y#ea}=gzt0rWQuu1ZignB{c#h?UDNdvgr#(|k&AOx)>lL=d&O)Z&fz@(tHP zOW#wiUPE_L?cTDP-J_bKpX*L=@Km7QGYk__;>d2aLx9^OIaF$~$|o#Lj`1S^t5OFa z4tJg5!3#B+^}YO+#ET*TJb)c;TX|DoCM{}P<>+0L2cAzHxR--Nx? zFqb;Ir{4X6gzVqEU+eI4bDiBG-pzaA8jU*gZw&zIe$;(DuH)&piPd;9| zUG8YF52iUDJ`Nb9L1q7?{nN15qU>jlgG15Y+8}crRH?xDtmD1kh1BJ+``Y<@p?>mP zlLcW6YN@|7LtHnrj=MP(#W+t+)H!0k9YE#}{~Z%3A-&e?ub-}r{UDq+EhE2JJYei^ zfub~fGd!$$gO4CYokOXF&V;GD8iOD7N&;1d&>>t-k(F{1ESV`pd{LC~F&fUy1qQ-GE6%DqIGa2a#Nv@cE5ITm|zxEiv4#%Ws#8>@4@u~aFUyzkC6?ZHNQ1Jwz2ZR zROZ3?@cTCl7i&dnf+Q5_nNxKC!EN99yAjih5J)zo+T`}HoB>3;tg1f8<$z zfkZD0gEF4~ofD={=>J@XHo^Ac3k-FrLW>GOU=S^=P_4xV>JGAIh>Z6_@iGois-1CWR4+=>i0}v zE^jbF#?=bETgY2;R)5BvI?-D}0URKw2ZMRZqJyyTh6e`+d%fk+KmkM4trE2pi$9l{ zljxqT556EaK_A7lW@i@}iOgfl83FR*Ht#pxia=B@_A@=$IpLVQ z3xsCoq?oET-c#?=+Vb$c7G{NmV{ro}9|wNbf}Y)|iRCQ+%IfDI2g~ZaFS?qL#-LzQ z>idC@?8=b!s#B4`sdj#0R%d7R5+Lq9$Y1kZa+1r&!lPV3jgox}z@DgpL*y1&l|I1y zqXPAKnF0HeEY6vq%h*y)kH|%H(dbaH5hUAw;#KFrH-XyF{>_i}G3}Vf z*yCgY3SCFf0^(0@KQ;-UTdyAyMH0xUGmTDANnlyyw$rf?X}z(15b#0gAgIuv)xTJi zU^xY$EA|zn1E>gLv0;jvp4iox;~`dnEq13LGiyYFzM-czP;~&vaRJtS_tI|eJeV`e zTO4Grmh&SnyUxjT=%he1!9v5rQmz#O;->;=2+z+#+?}fSworkpWJvl9?Wfafj}Iqa zy!I1@r}Ji`gH=8NZ~FeNkyij@ZR%Yf0jB6z2mjQ&tXJQDavB-jf0?!jV@MXo*0f(>PEQN)VFe(D|M$ItdR3GM2a{ z>C+0TJB~FfR0muPS2$`OnHG-yS_;gPQwXNi15(&?R%4)td!Pi%^Aas=+jeunN2U^; zHD35tndx!#F8G38<>zp*`h9;gh0+h^qyl|PQzH6+p%`F6bxo+!V~8SNYU<+$#&lYH zzYc+3;(jn6!^aN+qhSEtWV^H#e<4EuwYBm#{V5q57fZIlsNB!LUPUcW{_(?}hakew zz*MxF&=pV7@$^HbXMhq!MU`#62{X~V6fP?k|BTxwf)e?tGid=?tspt*RKU0x0X*!T zvRS!)Ezm1rPrVATR#m>3ENg}!Tr#l|00qEt0woD2S-_XQ<$5LZO+#dK5-E?IIyzv44o6r7F9?_XqPLIMr^V-Npkc~@`3X4F{BFM zQ}AOfEm%7oZPN`*l3(6JXxgWvYjFZ?c3s#s~u7 zJ0qeND zf}!=Xi7JVDfKhuhY=^D`%_Z)0vs%adiXy>cYS)bh{)3y8pnVRvNupMY)&FnBBke;u z-eQ{aNLcww!5h$!3PPHE?8pGo~@SR;5I39|1jV#8a2c2YQKm^nIrLM9b4&ue{F@*u1_?ZQUgjKqO&+GWUJ8aZL*5>t^!@L5M;K zWT0(cVyXb~v?xJO*ed2%URBT0CJZPvDFeG}mVaw)y^a@9gGmkH{RpFnUAA6`0a`rk zku8lc;|Br;rD>GUPmDu;7|VlJpUVK-iW02g)Xt8#rLYOp(8i8lBU(GzrC4z^2+(Bn zNJ>O$VRzVLsUwk?L{JnVu-B+&#TE`p>Q?cTzM{k|=@^Zv#0cO9WXhF>vI~g;qunpl zBC$W>{$0-;Ks0@UUIu{@KK=&wnW$zJy-OZaf>d6V=5ie`-8%lYqc~8ME)lT*#^?+H z7;7(@v68QD;9!^ivh;eL542hcyHS9&O9Qf;J^lXS$QL{CtkHKQk;{CCEZ_(LFT59T z9xyyY4Xi5zG#((3%!<`t@wR;pz+$rtH7$2u|MD9HER<7w?7)u-8~hl+h>arp^0SPZ zB9{VsXc-!*u-*E|9-r}BKtQ(kXIG7Kz-h)LU{_SIo6q5I!RQs?+gn{{0P9YI!aD?@ zo=9L<|1Q$yLb}#d0H=O7l0Wk(;0U#OC|AK>`7ifD2OKG8Tyz1NUx5cSC`f<;oS%Xi zV9cT-4+1KkVK)L6pU?svb89h;2?y5sPvz+!(M9kd9Du&!0rF1-^bsgqTmqK$x8w&v zlu(pF|6)yBML;gEWB>MG29yHjECEzuA;aoVJr5880%asY03Vb1?>#BN%M(BofD(%- zY9JtcVCrzxK(4<7H)Mf<(0@CV1D#9%0#jQrROj%&owre)=}?^|hyjxNDF1J6WlVWyT!}NvNIv+L8Uou~O82~7nJ^l9wVB{Et zGe6tjlOicWuYf=d0`)OaJP}lb-T2=l*DHH_S_s>>01<;gRm>3#&?NtSn&pd-FN&*6 zc*ZV&=SbsIYms%C-6Uz{I=BVNhN8HR( ztK1K}&a@;^o)?(d_AU6b3CrWSAlgm>^WU{lO*6X*1L0wrBFt0YYvxy%XpD*erC9(Q zb_4x@ErlPSVNVdhH$%Wp^Y4R{ORYPw;ABm$Wh@4oHSPs1=^Dnr>PH0_M2_D z0-h%sDf+L4o7U#hLT;^D?=LTZP>mFg0S0TW7sUjtRx_0P%PwiLm%-zQ%tQr-b@y8z zQ``oUY&+iH-L|FV%OyT!8%d;&E6z#QC{FHbsJ8sLsp7fu!n>jI(gM+-LFun=h-_5B z6!y_+J*98>jp;p;&1iJrI5_BXZtiC&c4KnwTHUbV&6JX8!4pK-_^(HxCwWaufIy*H z78Ywpx6rlqY)1D5 zn&tb}!J+=a!Gyu{j5h1G3)nLFI3L-nT~xf@j+T~_qET#n)wuc;(P~g@S6$u`c5~v- zL0eVNWMb7hjVmDE#O{B8I1k-Jyh1LRq3boVJ9uY^+}4EA2_Yb?_j|Y@@16u{N>UFo zv@y?~{(Ib7IyE_|36#~E#J_>q%xn~G;FSK0pDQ7}dt-3nQQNwG5>Y%+-(@$gKfXsI z@i@Vm7bH5-Zu4TfqW&)Z^vA~oPN(0RuNP~V^RCBY@4nqEF83d;9$&1kT&uGnM$!?w zKu$N6P}ia?cE$|AHewlRm8^so@Aa$QeQBtVVW7ltCO$r}yO%ec^r&&IU z3k_$GKmBk1XtjEUfp#I&z5&_tNtIol0gLo-b3Ht%&Nr&o%tZ znR_t6zmH)IMIy93dBjKd*b`d{5G-|^?=^tqJ@>dT*BIBe{XYP`0Og;v^IX9e^wxU( zu;D}nKOUHMwfCdF%0b)m!TdrdZ-&!eDj?rXG4{42@?#Qzni&H|s=Er*@5>BJDu~CU@$~#8`EfFSJ{yRxgdHv^F`Vz+1Csd#68pD_&|lpTKeOX^ z=VuwNuy`b{UpNAb~GtgK#_i}Ht9x=z+S(Jh&ESfx5#uNoXufWmE) zh;~2E%~_!ii2`gNOI?@i)Z7E9##Dh;qLxw=zL~kn55v6GvzkQ1e46MGO{mjGRMr~- z9<$y4W24UN?6~f7^AbZ)1R+IkF&(6f&)daOK-Mfe-?|g z=UjdHqNrXzP@?f#fU$0w!{{dOiz2WQLq)z38Ool!dh3Ka6-FeF6GjGB@@@u4`s&)) zTRBabEQiAm2RZ^5+%j&4mit1*==N)U_RQ2v`n;E3iQnYvI|kbY=s^2VYi`z!ehzRB zoQwb!9bk8b-THEF(-xd#eb!m4K1McQto&C<{w5Ax8`ayC=z)$aKm2~TWou`A?wj zvVF1g$1d>;EP&zWT?0`e(W}N+=;(oqt1|-qIX2KL1d92s=QLa2$5hzOKQfD)^-Ojsp85YuJGgepA z(zYSJX=#lvBi2rUO`H1ev-Zjf@zLpWJz+$tfi0Vn>LQ@|G-1Ib-!9x^-tHLY(0{P# zbdU+~4>a%1GXgGeZ-JS_z}!e2KP|oL-v8_a`5Hfuvgtq}9|ij0cgXC*6Mk|0k|~?j zB^+ZOeD0fZkgp~SLykbJgLG8bWq1ykTr3%W;z+Fbi0nab=w1*JcdNs(r$z}Ig8I?m z*$nvzPpbnl@jIABUSAmL2v1?cE$^6;V&O16ukWJumi8`Re;DI4cMnly*1(w?n7z7U z)HB&xFmV9EDKb(6W{7zAELCgZq7^7|IKnJCMln8@Xhwx0nr6aMqlLa`PTsc2fBPs#J1_DV- zrz-=_gvZj{MsYYZ-pc@}?r8!gixFQHx4pRFhyA}azqq$39kkACrExS!@3;y&%RZ(2 z(jYj0*Q)bH{NDMJ+}ATk;uaVK#Oa25*r-+^J!prOG&;C&tW61vF9stW4M=38qHMjV_BH_-q$y^W1E5`qeR+FeM#C8VW@h5I*S6F>`T8-N(}ox(H4+tz;jpJea{+w;${6xR13nh;m%-W<;b4eNxXYs(ajytfZ_H5He0BxSpH;a&Iir!3vl*3nVPW6`S zf*AAr_7<$|TM?vYF%;EQp4vus(u3%DE+LYQ{u&w^Er%3Si7h5B74~nDz1|~36@H}H zg5Ux;8;}Te(!xw0Sf7T`u6nvne;`UzFG<8-Ire;I+EIa26)4nm;G?zhnqzqB``D>L zMP;h@W-Ff|WtUqAEAwdljTF& z=H9+i@(_SPY_VK!K}T%Z431W_cA|97LodXy=q`Y zMdDov95v_5fCnColX0<)lQHym1om$#KVxIgr$2sc>bLiGOdl3IE!j&@RS9m;;zNqiIjtg3c9*`f(}Q8^+(RimXOMefoF%3dHU!Ct~d39 zKC^zly%e%tnZlM)+)Zw2X1!6|z%LPmFwEL`US!+HaV+eV>E`^#1KB*-lA{q-!w>#@ zUJj{g2_9|~a#j5P0s8@9vr|=BZ<8}V^NTxJa%~sDl`R0odD;I_JMcv067OEp&_~U_ z%|Lo>-ysFSV$6||=VQr=SxKYB#07{iX=%fm#io_jVtS;CFb1GhmD#ON?$g zk)E6{+4?ZHr6%!8@qrJs`Ub;e28s)s&q$Y5lP^|My4+_;g(pAwe-{Vq^A;uuy7c{% zi!J567S?cK+VrL~SnIA_MHw-d9_G19?kzt1#S!Nv-RX^oyAqu-`g=Wc_Hi(A+;o6R z{B+!l$Ves3(=&Z8TN$BJP8?hrmy4V*LBE9skJW_WN#3?JoLnoDT%Ii+NAnj{M^?!% zo^Nlxwi<|jX~0pjT~l+=UZl%PNe%avCw1c(^R!>IQ&~uTH?k{2>-%e?V-4ngQ0eV` z`YkQ}wO-vhCBdb`opNk%0s~Ad))?yL*Nj9^zLEp~FM5=u~N?eugMcW+GEyn}%Exz&76X_P#!A{~*`BnjFF!G<4MiB-CW@oNU6ycSFduvU z{%qx*M*IV{FFtdb>taihGEK8+)8y86HSz#>1*3<+`^UkiE@0@#gJvGjzHjL52W@T6 z{VRD5=ipbSOUPDwy(QNaeD1pC?Bul7twsFl6F$k+mH)t9>bvZnWn=z={JK?hTRpDks9+ipG z2~05F7s>o@$=emRA=GNMC{a-dF(M%ovEC zClV|Ok=mT?e1K|ReT*LZJtj9aoK>6iTUj8j>7Z&%%QC;g=ukRXaWi)NrtEH{Bqj|w z^2y1+^PIV@@y6J2`V6z=A!y<9d$qU=TR%}s$n}GU^NOV@?<%J660F0S#`(5v_4>Nn zG*yfzUStexpBydSN02@rpRuD6z1jvdSM{=dy7{%|7 z=wsJcsRRTTzv#Dw8oDj!+*F*lc1X_@$Q!;c$F{VW6*%g*5&~~|QSNYGz zV~EhoDc+qiqS(p|Hak~&-|L-Yk?`MY3wdGRBo^;3$fx^fM70R1`T9_2%{%7&gCG!E2&v(Q_SZOdVR zzuEusjq=<&v_HeXsxXJCN{SV^zx&eNruglmovwwoahFzkG7glt-1KY*zHnV+%apf& zTwdRy?`>D?D}Q5DS#R!?9?8K`4bu_OKv%KQtL)p5m2uP4A-(O5cFPSv{Dgdfu6!7|)W$M0}W5DVx zdgE%AxA3@G(zvW;dg&`>w|f6eQJWx{N~>(IpN3^ptcPuFi6R_r3zYrz)96<4K{;`o zY;pb73{a;#_Sj5ySC?lq5fc&uN4dSsn>7)+!Ya|Dtag zb(JtnrR414EScJ~fK4ZCvq~BZIBV!H{Lu9oj)H93nW`ys`fSmdnKm3)`q%Qr(mw$} z?TnqU*W^p#=@-sPBkqk_*`iIus*XEbJ5#%pZvISV*jpR+Oyf3bkTPyz_qhq;hJ`Ab z{_KHwP07VU=Cx>y)eYIA+v0@r1Fqv{&DsSS{YB7=?g0pi3OV8~4nPxj^MmL68|`S$ zzXI^N#V-@hyx;VYPF&XPnsvt_x%6{|Lizs7H%*Jey79&hM0iM4Y>oU|41USSa=MQ9 zsot4yekmt@#>>af!C{R@O(G=JsN_N^>%-0Tr3luF3`W10V>Xz-L2Zfgr*i0#gHs^bl%=WKKmv^S18-{gkM9&s31MAurTX$>L z=6%~+D@KI}aFY<2X@j-(^@yINbb2%DMZt7w&;8cxsIZ2;D*AOeOm8TLLP;p*=7=ix z$nnYRU0Z;e=a#J|z-K@IGpQ&&Q-*+7$EToY?M#LW!rs#!*_V}6JoB}#m`s?T8?No0 zFFtLu*k6JPAuapF!O(#6 z`#a4mh`7`z2ep0Wog$5=caXi;^ARoALtL!YcC=nga@L~DZ0zNWzI8_;&YigBd#SY! zyBCjbfszR)0uG77GmVRhVfAY+pZ!1pkw#&aIWM4E(g3_^AWa9nA)HzSh9#fAmPZ}l zbdvdkBdH{<;@6kF_b+XMSZ{EyYGIv^+%UA-FZ15b#IKx?MFk< z)~N2yUYYt`74HlFxhNo+DX^bVEH#9|BjU>qTWreK(uO+eeDinogqFU$G^p#T23hh8 zq_Jz1AOpceVu=SQa?8{1%XUv+Zq+;;{}Ctbo=zdWCq#91czD}Vxd#{4n_8x(I`lez zy!+2z>vL5r(Uk5wY4#BV-m(!LA&ggCo_GTXD+90h;-!E|e`&GocGI zLO#^pz&ScAu?WtY#p8HhYVb&J#E#sIv7nnVVVnMdt)9C`iwC*9`~tnC=25cMA6P$^ z-y^7S@|(BH(tKI_1@x~|PER8?huOE;NmZlDL~k;dCIz!6LYU?hoMt$x-5p|sO2O>x zlEvi*Q&54T{k!)yWNX(Y^OeuHzI6y6aJetH6s+e%nDQLxrds@Jik@o!qWJS;*E0fb z*EX$~>NVNC3)kA&Ok0ibW`YKLqhamcM9*8~V%?GVcjsL#-oD=J0D<5s8Wd)*Gw{d; zzLVMQP?LvFjVoR07izM=gk0i*v?=-xYPiBzrvkt@SbnVa+F?uA=y4l3qIANzl0rW;nsGm0F2_JP-1N%Hd%VP zfE}~gH1u5C#Y?=g=k^E*D;n=2H`LA^MP`(#zUd>(RVM1UJ!lx`kyA70XtGt%oF~ZW zaYKBxxc3vLbLw2SLnrRSy!4=|co+H~mQQOcwDg548gS?H4xs|TcmR{JlX#|OulU8c2EO-8=jhT`J(Bwa6a^T&;@O+Q?75@JP&(( zcSee}RLwOF6F zQ(m3}S%=@kJ5>M_ugNPWJ48$jvxQGVCq#%;q#WJ1mQV>wwRhdVYQ96Q*vNH9N7Zi@ zH5>A^B`wFMb*q)pC ziQMPPb#I-xn>iV5_1);h&+xB_t+hW4VY2~8#u~FF*?#z;@Ge84)C1!6VUSms-UdJX zhnZ-8dWJ`GpMw{5#>HME($M*MEn(oyk2Oif|3tByqtbWfpAt>m2_l%^OCgk;`ok}S zAD;BRS|uYDT$+N;&}sll`Sjvv^o@Oo!)DT3GrgP)C#A)0x0?rC>?e>U>miD9>mwQM87C}mZ{%Eq&5R+W)gn`@~@^O&evmjEr z*PF4&opmYS$olB#`in*CJLcTFoYZlCV@>CMs#TJmrq+ZW5F3DTX-*)Xxt=ct-6A57OX>_BxyGbl#&%rb!1)-64 zLTfrkzxoZKzI-f6CwiQNh8gKqNh6}(gAhYAxBV&-73DPNO@0e^Od~qG_E@B3vVG?c z7l9Ly6X(}8))XC;>agwD)`4Nfz=w@rFyAoCqY~xxnxcuaceY!ruVP6@s&kdP^u0>5 zLfw{qH`e-xx#aCQihIcpq`s-7!UGmXSPny3?R9n*(<}>bOUK$uix!10d{-;e6Zj-XcVL zFiG3KJ$s9BH=r5^>&Am>ho771Z_*~~;A#!?o?Ka3$qU0kpWFss%BavvoDOVfh~TQB zD1$5YBC0no9ABAIdVJLoo#4&uq>kpkY;HK}p%29jS4`JiXSYybM3<*0CJ;aeX7kDup( zVJC;Thg2pJPIgFx7s~So4n1!NoIE`VC$yV&Y9`*CsWq&(5FUQ!>#0?@9{n8u$%apO z+ROz27Q-}p18X8_(+7=W2T zeA3_vm)xM+7>Zq@Y2FI!ol%B3udZ$2TQMr1y0z0G0nQh_q=&aw9HmYhbUU`;+;QpH zgm&bM&h$eT1eb$$RZ)+KWybhZz10ri9+a-fNQ(o3pERggp&8~`mZNonze0FuPlh!*eCQlIL zyxLM+G#Eo+0fZ??3Q+&tdRdz#Je177D@y6~P0%99zZp-AT zS{CW_SN~zxpJ@%x_@7d|mNbT%H@O3-de1mL)_(!WQ=P*gw0RUa22o?vvps1+m+s`3geiUm7GVP(HWi$ zi6UpGrc$a+x#(-{0)Q=Y(<`3oJKxWGJP$E~Ed9ZJWqN*KFk?Xa-GB9$wcQ`FMAFB9 zi&FW;6gPwp6L%ChN`>mAA>mzx&>G)O7v5EHmvP;$S^^_cLv=$al z3lxsBnBqn<{s&WU0oBzP^m`*9AxKIn-QC^N-QC^Y9g4Jc#}A~tOIrVwfPi#|q;z-P z4bS_$_by#7T`oOmpEG;rJ2Riz2gK+IOvr$BUm9~mFX_dOA`_zWi8KERR_$=e;#!Q@ z8eL6`)^Bktom=P@#ft88>jr@OEfGR!D zu!lR}qFgq^H!{Zl40i6Lq>AE2wMsW)kIIN%v8@dY_5(Q$Fy-uL+QV{5tn zCHEEo0jxtk7u`lLyKV%5%QXLJ#@1ht^ENK7QRa?dUv>pJ1lpsMRITKjr`?ni4lbIbn z^|qrX7?h3J8(jYx z^bJkTtwrC-S8xR4GPW#Ma%bUUSbwejc(}Zz-8DNL)%Fx{_IQ;!QGDRq>6kOu#)YoB zW`AYQR$zLd1YqIHrbb-2L%M4qX9!A_B%{) zk_WcsT*dWj$>Pp~O~Afhqt>dN(BYq{prgm(J~`dY+i|x>Hra}B0;US<4OQTMK6GHr zRkR%h_d>9$WM-PS56?n0WRwreVO#bV{V^nHbzXmw9hS z;#annc7~8wPPzEHzp4hmc+i(l)b2e`Y%}Y`&qz%JYfDAz8Acg|Q zmRg9}Q{=GiE!H5<2!|Ce_DKo1Jo!&2FH_0{xqy>N7MWegSDD5csbw)i*)uAtX}3`i z!XPN&Y@C}ofx$qb|C1a!wWp#un>E$YK{Ufwzvg^pNLBYD>P)xzsed$(x7)not8F7M z5d4nd0wia_`3dH)7>8ViQdbYNE(K+m;Iox){nQeL4F(Vca3g3K060tfl zgpJL(IS*(=aHZ>ZdSVg%^@kfribbx-d)7eEJrEvKauU_y+gx2J=rLF#T3vU7s}!1u9AMIgBrhn_D4?v=`#i2KAZq$pQz0WIzz%g^=uy*&FZS< zW5)$ulqznF@ki4|m5i274&LgWYiCf|-TDOoTU9ao)L?DE{#T=1twu}MT;q`4f(4NF z0{Tlr_5!ETYUNDhC#M5?66uWq*-XdZcu321UFxT1LN&VcXDJA5ww;2S}JX>!anSseI z10cX45vN>}exBkz5C`YpGthM-eE7x;!F9jjCSt31tU(5CF-my1wu|e+5PUStl28j3 z!P5ovfwS_xsY{D_*qR9z@a~QBP)2zT3o49Hk@tUl4X^V$Ha1f?Px=pLwnvAMn0}!K zQj^xXmjhg|d6^dQMd9H`vh_5iE+@UDq!+E>;T~|~)vi3~@ivWT?k)5OO;-Ig5~92A zrE2>G!=tkAB90auaj>WNPGXd5XKz}S&{k4GRt^&#nlz-s2&RkPxfAL%(q6PC4Uv+z zEOM>HKM^s7Yzt|3T>lJoKf8J2irW_Nv6~~UjtrOUIEhx()TaO#f#06)>2A4zhmnm8 zK)_nI!A~(U!4p7BdFT_dXfQp`K-_rKq;9SXdmjt)_^1IKj}r_`+<3QXa=3w@tF*8UJYu$Y&_j$dIpyQA4hH5b0kFnQ{s1w=BlqF zjuSCnI(n@|0Qh9Yvj|10jsQJEMT3Bw%@^WEQHY^GW*~(D{NYqp$Q%_`G5Z}l$nnI* z9>;_*(5=~f&h{1e-0?=m!2Fcn2%+J>nO6B0`c6l#%$!sU)zh1i4#yuSzpNPOXZ;<( zgwlKPFRlvJ>S8(DB6zNy1Qv8fOLxJlzbS3%+bi*HSB!hkR~d zCjet&^n)P|11i>nV<*sy@>^ycifZ(WHRI9cdo0RJU4^1~toOA@C;kG=0>~!DCy2C(xkDA$h57Gjm1Hn8?6eyz@@~=FoF9-4e{x z`S}x4P5-_sQ~@9jKujiS0L_=v>`iYV2k6M^*nr%d;WN8{iQ7zBAE{tHgY$2w=hZ)l6)j9g_C7dydmdz9{Eq}W%aICtv<{}mVP%WiI?l)z5v9DI<+n-Bm zz(vhx7y%pxEEJQfU@0ZlpiVNe&0~&UvpVW%;oBO9&V3pw3$jYs>(=UZcxY|jLpK^X z2ZgdJ%YY3A!#V$jy{?DCJ;A5iJu!o&I{T=0dQ#oXqr~no^C4{SQ|X)W)D2lf4D`7= zaTKByS*B!7!(^twxfo&p3w7UY1F_4)WC-8p&9-lBv|4p1ZQym-X>;HZi+}6nUQ>_; zE#PL>z~IqBZG5GMi)pmkp{JOw!|hNqE|0hIPnECQj8w4#lutWCbB?G43E&BI&D>o* z(><7qzp5WH?&qs354SGXJ-QWaLUJGO;l@M3qz&somX)>@22xfI4)YWV4$}?amBjV_ zgPSShxUL6X^xCI~$E!`8KxHvEy`1n_bUlah489^MX8?J;e0O&fSQ+LZ6!% zAdk&FAvi?zfHyVK6xRFjp^`9iS6%40AI-1Dy83 zCXOL}n@0r8>3;obFp*o+4DkVZ-uz@zcsR@HAl>OkB7iMBN)2zY^5*-jn>QzNQl4&v zHjxbDssq$FM3Uw9te2AG#p1o4$`6Gd{3?R4!LjH#K;kV zU0c*+{$4|r?}|YUuFyCrX_t1no#~#rzg;^059w6#F@pap3qX9NfI7kFw`#t=Y~I`{ zJ^>e2P6A^wqMzvQbQegIEz9a2T4y!iro0v&k4mn4lD`^ zH}?zY<~&j#-?`RgO@pzS@3kolU*_#u@=oCnvsgG#soRh-n7=A_$s8yx&IDY}O-|PM za2$2?^Bw(L#^~+kp@?zt($J8QMr`xkqr+k9WA{E0H}DQQSqGRryd93gFHzKZ1=j%z z{#)vL%X&Ya0rIzRd3dr;U3mFQtG4h~R;P8tc9Ub(X$4~?5W~E8Y5W99(IL7T4mO=Dv}HwNC})H@IeUB6nnmJsGr4v&|4 zULSQKtNt#O^9*B=qUD)I3{R-%$^lvPmciLZVk=Qce|{{%(g^8cNV{Lg!uy2UI>7^k z?+h$~x2ntDl7{K20;>MRRPuw?lZT92(#78EZ?PF+ODZ=La|#N+6w12q@vL@S&9-X` z4K}6or{5i}ZwnQ->5l%n8}a;pWgyUH8=m^#SB^OrUG~UPN#Zzbb{C@$^1XJu=V5Pl zPsg1Z=5@gKN}(UPft16Y{7CJp zKq6B|K3-Tkz3Re@hE7U#oz~WK8$*j;BCy3kB&cs0z7@?4ek?=9=4spEW>LX~`vf&A zIMig{enaVd1+Av`&+q#BWPkRjJl9D#5w-_g2yO(q4yMRg3EGK^jwAFa7F+Cvrdn^d zAOD3^7|1It7podbYaIPdz-Vo|*-?y;aJT!G$DyuW3>~q5`QTu};MdD#{bzE7MEy#%uqZEwGjf+!3D!L9BElddIIVPV2+0x26>AJSag zzdAb1@=Fy$_<|W`MK&u;5-CdIR%({BLEdMxt;q)q={$)sC?5N({X$#Qx|>G@Xp%3c zV^xsXxbnd0I-D&4b<~Bbq_;Sxsx0kmaWPq;ZDYf^<3=epoDnJU-or=cuIKTct0)!Klx-j!aP5G76)GJyvpvlh@akQ8YqWVnj@s zI=unY#~#stR;^|nbeqx9Fi`kNmcnSh%wN??>l!T!+1IQ;0>{2|JweP8w7xoVvjw({ z)*7uDX;f2U{3Uu?-AuhWV#bJPHF|XywnLHF&|Ghir>`%U4dA%_#eoQ_@ulJ2DbV^| zRu4gYAREg-GkF)$%Z%(N=- z*kXe;zq*Jk?q8F4rdFqM|TL;s+-j~|g^s9@m(uK!& z?oc`QTXG(Uld{;`qp3=jhLbi80Ixo>waoh2FEnz#!y~=b-uT&j=MPK^Uy@Bftps~= zMNBU>qeVZ;{DSwLebBhdbaioEg6GQSC;0ETyCRMyXk?);H*0pF112bJ{$oz#PxoB@ z+i`W>Lp9s}zB<);U8^}}I5V9k-&J%^%wt=K|1M1hayJ??J*m@JM5%qsE{5_IqDE1G zhg>3Vi%(9-y^d^S>;6FduORELVT?K+fzNY%VJL#i<#O(HW!^CKr@)odsDN00kBQ%r zZ<>V#;jQuJgQdCT7zRV^ho<4PQP2q^tVQrq@b~5WAYFe))pSFm63R4@DS= zzp#~VSyFC#?=@X%x+WH6Jpt}86z*FFB#y&^A^uO)1k}WDSnD$3t_71XEJBy9H3`!E zguiGDUAJl4Zqh|91yyO5G?tly}>gL1j zJ)kn67ArH?UB?h*mJp4nT@%D%3)SSfEo-=DDMYsl_lD)O)bpL)s5xz-Sm|_SZw>*0 zq9Bkwp|~w6wAOwGRU~ITP4Awn(t4WHBM{Cm?|*3c+PbVhJTnjdwb_Ed9On@gmYP_8 z8fC5$C3?Y|W)YGE>3~zrfD5|+jLXWj+S3&MBR7ZO9rh#%8m)%w!o}RKJUD`LTU!3; zQob49qewRCePi+ao9z?PLMyNTPv+~Dr_2S%R5nAA^Jixtj?S1)j$c$7A@k2$20Wv^iM@-(j4 z_1IB%h>#OYW}PjLBL7b$rW*T9B@62tCHzR&RDame*v`^n?>X@82)FEx;3~MVck>xX#wS1|GoO$RcBM%6wXZ z`tY9p+js6nb=7F1slT1HU)6*&%%(!wVz<8u<81u4x3vmdl;P)ylMmTz^E~UpyuS)O z+sc&7iJ2Kf4dnLH6(B7|+_LdhB@jl@E2rd(aw=U`7;La^Xn>N-sk)1~zicj;NHD-$ zt9c0>PP+)JcPmusAa`0Dpkk57Ky3aO-{Pv>ar+IGhzsS<`XsUCg$^x+BnDX!Z^#jE z8P_CeRN)*NYXW{-}`ejI0TNV_qT!&a;2+s6f}o?rj- zLVVBUg9Lnyo=O*`6OVmv#$ve-xr0t!{ArsNDYOIOrs(a|g$Ce}V8o0GJo-{GB0yNE zY_9XF4N&8p3fd?w_WJw!v+!r(t&vT(oWBbzgh}>NA>Dn*>OFf*z|Z!R~uDw~k_>6ZZton))gu~O9BDgTXG;86<@X*Y<8RO@F1OCHhu zDTTIEY8_VeeY;bpTyxYhpEJT(OyLL!)YSfr{p^WoXd0jDm8Pn-POJd7@Fx zbV-R3*`}njITE7s|KL0NnybW+xjVTsFQbZ?A`Tj_4AIf)wK^jBUuR^^DSR)%#UrTJ zxZT{1Gvuf@Y074TRGgxNyPjG-o7QrfQ4>o_%r!sG;CB-7U_gLC1gd>zavJsFI+9s zDDL)FuD}NO+K-(>np6ir8|=k^AY|OuwByfS=C;s+CgmtI1E|zcrn9xc+8J z@|fMLJ($|XUJ0w=hF&MxDQ*I~wW!Zkd0 z--ZF7|G0vQXy6+S;+8!tJXV(NPQ(Rj4+Urc7 zmX=js82Z(HfW-*x?ZW%^I+bRs_z}|l?9t*CEPs?&uGRE3#%C6sj+79}^xv>v{xall z*ds?o_S!{apPjT~xx&R*l{IpV({xeiwr|j_5on->)?x$AwiN~kak*j|ZC`fkM6Gk>HmIZLx2^$hC{*OTIyj6l-9*#vt$hvR4qb_+M)3CUObtm zWk8(uptPo`pA_S)PBn@vqwUaRNH$sIrlqyA%`c0zUogAOK=V&{-hVFFen}~HcJBws zQ}z4mN1^XeVi*0JJA;j#o*w*}K5=U?ed+Mk{;pJ3-}4t}&cvctVxNvhFEY<%X=@tS z?U-!rjlayOLUOuzg@p~xu4@s$GkOc8F+w9yWgv_+boq_R%`0&Kc5)lu{i&a+Y6%6? zS8rNEM3802&Begg8ycP0qoH;h9R75j{itwKDl9JYK{)*B|gc4;&!e%-rF z_BfHmDDaP*Znjcww0lD_b%tBlITHQI;NZWtBH>aDHZB2%#9ZcRA8aS@*A3VNALFYH-ZV2Qc{od z-mK2s!h2@+9$PN7;*>1#leI;K`pmSzi*rD-G@@|CbdYX zG%NNAj}`gv1YdXaN`1tORCt+i5TxLAH)`ysE5IfSN>muvWYqfT$YeXSc6M^rh2ymM z1=ry@Kq5QR62c@%Q_7q4qwMa^wqX8XztCy?7zE+FStq&>wYyV7ii5gdXdlHhoPytq?Fbeif{M@Y3l z8>DM!R#g_(eqY^%qNLd$#RLs9!mZIxG?C}T$O#7-Bf>+T>qnWoSiV+D zc8Ga~-(MvDdnY2)QNr@VK1&#<_40986?_%e2xI)MIAwQg<%>@{4F-vr2*-a!`EST) z424cV%$9J=H_9TyolV1OyLs7l6-lIjf)+ZAEKjM&j^jQLAEAH^q1Ll@zq9Fh&xkxzVy%_&kB?M zt@zXHU|vDx1Di>H7A{uhSJKQSGj6Y;=eD8Gy2MFIprG``WM~3OiTCbv+zUZpiWwm!)qQ_$_TM7{6LQ-(kx<}kgOG&ATGN2wLjp*1ZE#52ql!nA|`9D{lu6hk3CiAO>k%Aeu1`VAI>5S6* z(6z1U$;$Br1>~e)b*Qb21)xy$zUc20r8fjV=vKG!#6~@v zH@k_RH2%?IcG5J=l~EZPzA4&TMYVguanE}W0`bWTy}c~Ty#9-d^z0&0pM!U3hxG&y zP8_z}H)fDJrMI{1&V*h;puFbkT5owsqwB6n5*id~hJw6t*b-Kpvqkh|G(j08pZR?q zY@<-?1bJoCO-w``9k;-Evs0z_obK>bq$&r_p(JA&-0dmYpM^E5%pQCw70j+2=I77l z#l^))!DT^ThkW@6zN5aMF}# z%}P@qWw#Po1tfpdafxXM_$_0q0$?MfELapNX+`oYIuSvk4j7LGb^8$HtfRW>n3`36~P4 z_n*;1`!y+_Cv=t@hGW<8a)(w5AL59*Rx_sJeY2R*ly>225kr z`?1qd3nLNJi=mISe<^$ZC@H76bq*aMmx^$6;q6N}G_Q<2T&u;GZfnM_jgAf!Ftu(tkX&okTYRs+d}qS^68ch#6wFry10G!; zD%&sw-jU*4Jlx9F2Q;6UUY|aL-}QK*pgxJ|YNpvHL}ja& zy;Znt!)f=+?QO07($mLbf0b0MiQmXgtjG{uJVCn8Jz8kd2{M~umfmVI!+TSEKUHYf zoIxGp$e^`VtMN@&j+7Y!7q2Hu?tB5L)1_OwBz%I8>Qwu(#kj0GW=)=8eM8oRUTg1h zv<2~mQs9la^Z*Lo37^yMPciBj+{BltC#zaiV+`|j%G9%7ppu?DyZhOCD=Ed?5ZmOR zIckE2`Ij=oJiKP01%i1yie@?AzGdgEvqWudTyzpOZdxqljVkfRWnjP!jajL?c%N&2 z)$wkvL>oKs8U~LG8sE19WkD`6o3P1&0=J;Fv<8n_EceBwan_AyYiO8cOwOFe2CiOV z##&An*9y_9mU6m(+&38E>wIT|@I~Z{h)-U_Z5b(-y4*j`E6v*I-Q~Y;;95>3vc2-+ zHrsX@4t>@xFe3i>%TT~jh+v9#vwQDQ1R-KlGj1(;zOu3LIuQ?Ad8mq8pcE5+dC8pj z0T~&rI|%A*MYkVAyS1=u(>iJRbX@N)>V<@e#e~x=ieP8#PjcjTJGl?}BicoNDj_WN z9Tn#aqw?aJM8HNzL&?jx%0|B7UZQ-&$c-RbJ^Op6tUH8ArKHvqLjZKFC93ZwR73OG z4;Vdv_uOWcaA<15d;KqHCRXhaoSFvdHyZLkIpqa#?j}`TW$NkaT<7##x6U@{d(rch z)V^T8L62SMX6M=iABXE+&n-cS4Kq?|##2@u@e}+k%%7dhxBjiKqO=q@@UecRW@<*& zFm^?eHe^PYU%{46Uf$7w*85KyjdQ5!8q?qDcOJd!1M`u;h6bW%!SL!6?U5 ziv0RN9Iq#TYzESFv%exx3)2MmcXMx5-oh)AGlR3JNa2FaYh5TZxnR`PPqs3l+}+R5 zfnmi84%V56EPW&i&3^Xi#`#St!e>83A`30W0D`K3u8<)%aQwvBA& z3$Ebg55uWOAzvqtru|yG2v|JMKa)MvmEcVV2oS~^3~<&6oM0kGMu8gpnu!XHf!8M- zgVkl*|^d;Z= zYj&u2d1(INvo-Si*ay^w5jZa49UV-0{~#@>ZBPbh_tcmyuygE8rt|KshT1!LP0W@| z*dAI5cmJpZmAR!ho*nWOMuO|NXFg}5{qRH^nJWcteD%653;CVu!Wp~VYZtpQWOZ#3 zuPn8D))zhS2nc-SF25kEsnu9xe$>QiUi|OrKIiq47)fY`+k12oWGXgGu*4aIp)z%H zjMlL4nToEeXpy>5*4nVpJpHL6$nXYCxoE?~4GsSWX8zVVtmo={#Sd%`xawPH=UV4( zXu^m!)dqEMb#+nncOl(+{v1TNXw@A>lIT6_UL8Fq*AJ7^30dO(|E%Nh#zx{rE5XzRKV({V=3TOfQxxISP+9k< zB-03E*-CX=oAIA%KAK#dE;IV+S56-N;yJM&KXTdOx9?WFW%NmW7A9c)0Jp9G5!Mh*(%|Zs7Pk5MlP0hJsPCJ%Ic-d3MEbXw%7Yf8S_8 zCS%3igq*PwTHq_1AQNv?QpzLHCEYJQF&#pMx#dKI4>O6PcIaydok23%$g!Fr{o#WY zd3gWH4MNz7S4m~>5j+B{m33}Qx>Cte-ve#cnO8|Q(X~CMY1UoJ-r-i7sn;P-(0jJ? z{l*0cy4g@fWrUZ@%P@$yZDRYUS9sB5jLDk+Dhv3{_|*+B8i57FoN6&6^TbD*(%nE- z{tFj!MrN)32R!#O?{6j7$Frt4i`xirrPVV+j2HuQntWPyyx0?XJ6E#n0W8#N*q*m; zl=6Aanuc@BRZNbHS~YJm^Uz*AKa9||Fr{o!N>7P9>!%>Xv4!n%4y+~MCnZwE@?yUa z)w%sA&w$J}Ecf3q^Y>euj0`I)+#oX--eI0?G-RL|T}Mx@*R@h&a5FQGZ%|r^8PX?* zWp9d2cfRnHwk;6t^sX z)W8yj&P9tyNJ&oAb)B#+oBHmXh(`9AmfOyb{KEm69UHQMkrKtCpJ0MCP@YYkP4@Y@ zpKPmmZiygLPNxI>XI~#Z#z+O0cZ)I+;4Zq_322kY2e{NZcg}X+42br)i}*Q}!Ok2Y zYpeH;K-@fGl2Tlr9$u_2;n^pNs0s`=JA%n*_1-v#@!xyH=?y6zZVYH~we2Qfl;_xf z6_lO+$2rAf$Po>T99$@yE@a3w59kH{?EH#IcH}(eLlB5zyK=za2twTVW}BkB9+S;j z>sLz6t!Z0uqD>ak4amkvB$3|^4ayBNGCkL;L*Z!Y=2{Y`%8{DQMUZLIn<>9gHzZ(S z)BiD@R@>OZ7KMY3OICC(t`g6`t;Hw<7HB@|Cpd0x!h(T#A8;Qa5H}BDDOtY!w%rAz zX)w@apXCg9wnboWFjVKF6Iw#}P&6>1XlcUSNH707vg||4s7}9Hq}99bKYXQVFpPKY zAH7=~{;e#?IA?WEEZvKk{Oza(&d6>pAF+^#Sin;~!WZ zT7I8#H)mtOZ{}mKm{TPVNZ)#HX@o2jMf@Kc)@n^A*}Zz_u1pVAq}fF$h47!)5l++E z=a+S^R6jNbd@d+K==bbY{UMKO^6OdKP@~0$aoC=3y6G^jM@U5UOBY+)ffY3zWSK|} zR7Q-EAMJ}8%of!d)7q(?Rdg71%pXVv4kA(=&)YUMp8O)y!tS~+tZLwQf^C{7QlDo? zC&w6DZ!a7Q$Ca7ukQf|vdr!W~ZMQ&)sn?_RTvE^bc)9=Al!y${$1Y9DB2SS09`3nl zYM&@$9%E9U&#`d0zN!))KeV3PnQg@U^iMU!{^a{%f11qSD^)|()w7+Z=!bpO(!+L3 z)ZX6Tnf>F16^5fToqg(>CyGyB`h)xPk4h!Vr)Ji#_CoBv8Sd1ZZfW`Rhb^(cz%GDnZav8WHhMW)p+ za?vh3WQhf>2D4qPMCm-`vhul_Pne4Qeq}rm%4Cxpm#U7Gy{h%KsC2$mu%((~%d1Sr zNS7E{KlHATSVSUBx|L)vsq!q3# z&wGtT@@7Mnh&0(`iTAKo)-eCSdXOAZyUNoSbv0IG2|kK^rKHt*6A~`rZu(%P#C5Bg z9QN~DXYn8>9^7{JP}|Yz2;cr(aK9+ETgmYNGizJ24@NBf#D-^AcbywwKqLFe-a#9d z8M_R(9BpB}eH~sTiK#Y-Ed|o;Po14bbqR=={|<{Pqt#@}Tzmgfws4S$eaiA<1%(%D z8b!f@wccBq9Hzj^`Ja&_A-Ktlt&)vQCFZ7MC4~Bwm#-&!>bQ^i89S1y{X*!f&E{Ak z0(-GyB4IWs+@)$o1YMv)E*nr%q$4~%y;~;5q4`mSgC!{=^X8W%00X#ICTI5N#l>Hn zn?t1<8ax{)!v7d(H^|UE4%T+d0ipuoJ-(4DWPP>psW)!GEKqX?)I`%MbK_zl$S_@o z)d$ESE|fJPBD0*R0zKN6=x;9Qy1&^FfFdv%QEo0tF+t!mTY*Zed6&(HQk}0Q7kRYH zeB*>vBKREL-zvV2C|fnwu&X&s3uN-_}~&+GspP}>ZehcNwE`dSC03Y*SYdxTWoI>&jGu>WBTv` z>l)?aqDCC8g6e}5N=3>$lQ=Wa(25eMG}e$R#-J)j#Mz#I&*^;LN44T=?Rqy|^c>W# z94$GVpcW4Ox!$-?lEmpAt&O62wKlb8<9u3Vln|gs$M@0FEn_7uYbLBg@;bz1IYm2N zy&c2n1_k=HMsn`&oiQD3G>2m*)|^Yj-iZz#AoJLN;PYS(;J>>xcX(Lbep9C`g8cS* zJBSY1dlb9aBH@@UeCZY=2Mm^xo2Gx75w;cs02FNe~I!X)Qtvn}Pxi+@bU>+GUShW~E4>p`fk} z;gDwDSq83&`S_HS7%jE_uB>iXiHpWCv3g0hbV}c)>K8HL!9|D_Id^>+Yx8e&Fh3lm z3r)JEW5EXXS?Z?9{<=hqP+{VavPi?jw`P*|47IqQpmx~bzV+Y8Aw$Q9?Z{(bj83mjlH%im+cjx`(;hqQ{u8YgTRSuTOm#j;N zf`b1PA?F&_j6t7G{y$>@oQ1uq4v9KTV@uD_cP8{o0(iPQHTFvf>p$k^QpCygW|Aoq zVS~>vRSZTXg?#>OLTH~XaPRN8drUyd;3siYC11w(_g@9q8`NmG2RkM7?R64kIK>Lx z%W>(KmOd8okl&@&E_quTH%W&7qbX0%A8ac2Tp9X8`ew(q}vv&}&{ zOmq~&;!=7;T5)m_eg#rtfB$8%Xn3ZGWbHGd4oa<-#=v^mFWjUl;+|an_=zn=6<<$X z`l3zO`~I^}K?|0B7C?VgZrF)Gm@hQR`3y6=r2H%~Aal4+;R=%vXAvK6(%@mAdOyBS zf<1(6EK3>D3xKR_|CFV+i+pfKQL(Za>wwS$rhq{EJ*%QX?=Y9@bH|I>nH0R_UMYjD zqOHo(A99-~$f7uww|;iZ71?(?@G6;u+j&_jSQIDtFuGJ~ly(Uf#&6XBsFn5>A z+R}=sOH22+Ga(D~ByjQ1(ul-T`*+qryEp$uQcOQGnNY{pS-iq_!At?J3h2ReDN{s! z1E^IXx;k5_MiCE6Ji@1-&Tkb4!`ha$wm3i9z1yz{o0lYX@wy%xWBxFHU;XB+!!ASo z(UmPFq+isOtZ3ljDpAg5n8V)iwoleQ+f_(a$aN(&8*%D>lWB@bTj`r&9PWV~IAw)( zMFEoGy7!iAW5rM%rA>C;Orsb#{YA#|Oqlf{PgiaB;YCPX>^!v}|BhZsYM+-P>0`yp zEyX4a5Nd3M4Ze}gvuVgkPyo|MaycUj6ndTnAQy2Ya^0$Nq4-I>4S}z5GFC7QPYg>tPd^3+ysZF~M+NpXsd404WrOevHNJLMwj!*2YcLc?Tv zWI#*jj4vZg!?@LP1rCvv*}3GmkyMh`2*Ld%^9J;M!)yCNc&@cK2uPO_3rs3Qc`R#} zskP5jP8g7DEI>2W*b%TBve6rxsDi>xdB%r*L*Ny3Wm~Am}=78(6*Er7sR*m%gX@ZdM2``5`no zLKKuc=XG94$`0S19pm8-*z`~q52Of=$HhV{#?T*0e+E9_1U{4p*fC2{tHllDtXXlJ zY{0CYc;z;Wga_E#xcrFdznGEgdDXw|nvqH11PUov?DAA-)Qh2SSbkso#aQ#kOFdpx zRw__$q!q!$*z@gT=9UhyAotg0O>6i!Z&~y+XYsgZ70MDgm6bzyTv?m@)?>_fAhm_P z&iGUqW25g8xal;@hJ1zmmOGs{QMmu;s%<2t@b(k(u~!=)^gH8sJ6Vjl6)AfDC@pvW zQCg|)C}p`N*YEse%+b+FfmgcgldTQD6S%j2=d!Y_WICjKS_zJYCYaMX0jB~C6$BQw zMRm(VL@y57!EG{(F>7|9us7ctV48eYo%pNn+qbXZ4f#=oT~=B;x5Iw&-JvZ zMIvHe-_9VN4xyPQ-NJ&Cx~DYzUs2PlKpu`(_n<)Wv;C3xNB!vdG+dnADbdrT6pKrG?J#N(b4x-W85p!Q zh*gAy=k>1b$Pd0lFkmGf-js?Z#^p%@ z!&26f5r2(^#p}jisNIFDbHa^d_`5(F-xV1ky_XOA`n*tWm-99r&~Bc4zjZ}nAdtyP z&{{qDKElv-`sT;BkRmTb2WcffsH?KL!cBG1jMDGrjxz}Bi6 zSRcj2x)X@WYInU1S{8*rl zyB-+0R=^2is)nPHSoHb;h=qE(hVLhA+niPH7iuYMC{83*DvZ_FpPV{*yz}Y^d3YVp zQrQ9VT+S_~a+P;x5f|shRc&qkclcc5l#wkh{TqT)QVzaVv%_AlA*_+yi5!96{gT(_ zu5m){x{0nAR<5u6FOqF8GKThgnORRVKV&iV#)+KMFj=t4gTo&UF(Xzl>a5Un9@&Rd z0NNVUO%@B(Ot}V&HAWFg(R--`g{2X%7Q4S70w#8M3aYVjVe}Cv+t*?KQWL7Uq(tgs zTJ?2YZ*R}~7m;+hWD#VFp~3X{%Ja)L?(@rC$NuOE?^OofG(kx7vdNkl)P&jKyK!sq zQZFD&iy5@%XeMd#&mh1TJG_a4qR@i{@6}fj79?1pN>8+M66*?aRl-G`OgXz(byvoV zh5Q6XNFGMFP1hwZ_g?{ku!+-S-)LRp@O$uxf{Y9`o#~wiaMAv3yH|~eS@*w>z|&M> zw+49kag1z3a39Bap+8$$Dv(#nCcJK!gY&;ISEY*KhZ&Dw|U;Jv@%!K=l<$quOFiZhjtg<09Yq_{_Fq zb^k%1kHjMGjWgkXVJW`QN2MBWh2nYbvjm*s$zjGyUL_4FRF|G~I^0{}jt_hc?-b9U zoWVr4aDn#kvlAqW={8S2xj(a;7n4Q=k>&aXs7pqFHEVe4z4<7a(&S`i4GCYq&CP;| z-w;{a-q$$4w2YO#QhMu0FP%GV*z>;P!T%F1!Q+Gi#a_Gj3(cyUl8T`F2%QzcTl(&& z5m8}sf+c2m@QaoxC@W5(e|2s66y=3Kl$ZNS?M*e8P)CZ4^s552u)k+Jef-`__jh0C zE)NUqF~2pZjwoCn4)2@9tSf!dz5U0%ztG?5@8-d3jnUCzw;-X4DKB5AA&+c0H>RTq z`Vmlxlsh{%RFEE?Z7BXLe0}|QI55A{e)dI+zpc20ul&;p+cr36Z>G^~ltQ4Mt-EOe-p4E5W(ct%G4<-~A*8XzkT?oGG zS6@T@+cbSyI8Z}uJ97COax00z;)j3R1Gb2|I!HXFsm8{kk2jh2>am`-pK7eotK0L! zdhF)EtpAzr%i`hHku3%jHf~s;)%MbAJQmMSH_&a8e=b#q@x6*i5Ht+9AlpzJ#0D&v zF#vnX9vRgZDqicm=-Y2Ede_GT9@_ ztMV%3R_2@|eSEUo<#d`ZJuF5FO2V6$6HtInp8Awl7njkx%6m|3RO#C-BOmW5vIVpU zpi*HZrL3KS1~pKZVM4#bF}qOe>S>e|6a^FH7$8^J&(S0i%Y8{6{K{;fLf--!;(VuI zq7|zka&3`!0A|A0JFzYVEzEqOp#kj;dX%!^Xrf|*T!Pf<6*x0-e_?yM7NMB>?w`hM zm$NNpb#eK(mN~<>7he41)rQEbf<(#5;8hY9OcOyMau6BMA2dDx%K{KXfr7aJK!)Yg z0Hdyjol?jb0|pl+OM{#Lf_~mhYzFlS8Ch%F^>V|_|B&3(lXc2daI!ZGXOKlf63=b& z35tQ?+K>N^zBFkUF+H3w*VG{}ZD^rPalewqC~$K&f=WdnBuT&@c`&qjj4chfx{qs! zA$x`b6#zz9{P(=KcaR1O0`NdcvdoFL-mU+lC=_iCK3QQmm&b?dxG2R6Dt>C3mf2L0 zz9XU@O_CmxmuH2soh7P?!{^CriBhhyM6|w@qDSg_ zD&$q1O}w7?&oO)MbT7k}iD`KZPDxo<9m}zEUo53#*?55hN*inU<; z;m#|AM}Z}zUGh~VCbS5&H?{tJO&~`CLldcnDE|Ty1_5!p76sFJAaefF@*v5jEd^}S zgU@r6Hs&V;-ST*s@be6`weXUWxI;nn4B`5ngfcH>UEUZfhudMHr>vtu!|G#e$KvMH z^;r1t_b#9(JA@4g|BKzMD3|wYm!m z5>KU+)s>sGL{|Ston}B)(XkNNe15;^>E;y1c{bmKYIGs(~j_ zLG-4WuU|q*$t-8AfCRY+y#%kkD_iKN{(Kl7>1sq4V&HwOh8|ATSUdjRhA#L7S3h;R zQGYQG8tuP6d5)-dD+=;&k2+-?nZV#u6cejIFX*9X3$SxxzQMXRM;LSD;7Ce3clP)6 z+^RF**_GsK-r8DBklq@l!UgrCj7(|r8hUUxI%ppI-%&G-?(oy}{CSBTYIeGw$C{>o zZ$)GKn(U!JWjQ=P-N~(#PmNPo zQ_>&a8rE}uJv_{lY$}2r2xdCA>ECeh|FP$*U@U3&^f)UsOK9R8w?6zXx+1Cm88ky{ zaT6(7>~$>WGSNg|M!ATQ;M_6M-J4jkCwi&=)*OER2Bsn~#l+c{;o;shIqf&bOQR zKoL{6$dXJ7*~)oJ|M+o6G=s8eAcnwh@fVinzsI<_J8@?25+FQqte%e%|jt=bT|? z_TFn#6YrWj#yxWdBYWl49A|0%=G zDYp72mWJDJYfU7H^#V}|LGmgvTzL;sLtxV7l~G?(ZTU5oytDh6GRHbu3m>-dGs6FY z1B@fdbmJZ*Te}+-yz~%4M1I`^gKWB?c1NK9%~buHh}G!O@pls=`8>!$B5Ngi&Pyl>V!@Q9uM zcShtq;Jp%i3fka*+l}f+4r8%?s}f@3#^J9iMA|Ee_w$MgEXyx%0FL(I!}J{VvI8`h zJ|Y0_@2?+sIYdZ6o0R1aEC(kiK<=2pNGyhMJ+a^39O2CO@guga)t0fYsC8`sYpk%Gu?q2=JIV) ze9oM&Cz8QwHx1M=M^%@l@{Vi16?)OO%4+?hTYAC5T$SXm<@ z1xl=};LRR1k@LWWkCTz&kRZOFu9_6z`O)gJ`PRzn-@_URI*;LwS$hnN2Jv z{+F~Oa^7OSYYST|lH`P`Pev+=I4m4BVruh63HGNzn15@bsR3kAKr~TWpFC5p*^#O8 zbyDeIm*Ic!De=ZNn0HTscF$N>6E8y2NucC zD6KGA#ZXUEkG&4O09d=`+I8jRF8IbF5Wp2*A;2L;fK8n zw>))nq6TUCsbZz!r5Ersp0JH_29+u^$pW3|!bL5&@mnU&|1hDq*J*HE?9zqdBEV$? z)SQ4$QOtNET?GeFQO zQQ0*G8YmD}A~2E6ySe2&krZ>F=bHNO1mG-qo`@|={CS$)GCWj4dz&}$sB=TtxPB{L zCX2}a-|CR8L@@AYG9k$|W|?VS(?vs#h?Cex(N-4BLN#7`pTyS!Y-%S<7akfvfr|qC z4$Ihf$Ad;k=8zN@ck>~&o;Ol#n2AzxD_!KSS(b+PqvI&w$4>sl3rwSLb+%?BL(ToQ z5``{E1ue&777KT*9J5N1vpO}{dR43M($lYwadH@nRR>QRZ+Z7*!y!MtLZFO=N`G?3 zcyA#*+V5?A$%MeIAA;2>Vjbf5u`Ep<7!GrN(;{sq#(e}UvH^u|)Fv6x3M=KV^=d5!mRlnCX6T9GC zqq<#$S!vq%SA7p1{VmCR+DHw=;h|o?K{CQ8N?qMM;ylzKf!B)D;IEgZEtuj2MjO#L z2~;gL(Bfy9rfQWMTHE>^2LmOu#YMyEwfkoh?3x8}pr`NE4%QR~jY&{>fI{g&zR+LKv$#Gitu zaMt{1N~49WX~v8tT8_NG)1A-#?4%M80Vt;#_NJBLj&|T{a{k+WZx+U&z)$Ywi~+J{ zNI(E9t!a?8XZ$+O4xS96&*%yz9v-`n7Gn@7hPS@;wa0Ta#@JJ?!H|OuJ9Cn z>PCQN_Em}e9b>@f!!`0Lb${6V7TCvuE4Pn<*$z)t6-)yH5_`Qu^w>m+@$v7MZx6q# z6}HY0iKwRebiV-}3MbQ1!*Wzo!P{UfA!6FdH}9@uOt9x0MvI$!X8(d2e}iPDDx;QY z$r{SBW#z_8>?!npjPo5&5^jpbG5=u?f@bOS?3a6WW=I^XB@|%4Of%8CN%Lk)WaSP< zH?jdexmB7BPd3YRqkhLf(Z!|DN39VhIk7n}nV+Ofe(W;%6QfNGk}Gu{}}_v=VpFjw(>Pi=0)_ zru~#gmNwm;u_kX$;eU@F%Nsf-uAOm=|34ZG+eeQ9U^4*GJ8OU3#A;c~$30Eru#pXM zsQKoCg7ro*uKRf5^*aB&kL>f8;ZyS`uhVtvxE>EdPaR6%L!L{nSEuohNUY?on!p?Cn$5{PF;OQKgZQ; z&;za+ry7ey1oOXbLw+W%WFk-hA5>t#srcM{$=F(JxdlWOR+V~@ab#|))W!v(< zU9v^g{6|*Ao!_~9ym%Ga_`;O(v5~%?Jjgs8PzZO?dcCrO)o)g+bL0QM7sg6){`vX= zVvHxq)N$ES$DbEe9_A=Vb9F9M7yojF1XMp*YJOIYryeYl12{K0hc~K`_kyuUWfF&^ zz85=f8lI-%CzK+`NzsNHnmAdPC3lX6*&ZnXr)Bw~N*i3kRHiGYcB5JB9;Ok*|9T!h zhEj}(;8Tb1Ml9Emmgz0`6S7v{ihfKaK#MS`s01m^JeXA@2^{1nNL|>!zye>?_8=MB z<8@W06GD-sEK)qY|K0FL4p|lT-*jsrAK8aU)@VKB+Z`K|40y-Ha}qm?Jccx=!hC{i z3d$}^BWy2mq_7&>b{LQ;cje*n{=4e6fS&Hy|?bv;ROxURPp<14bRY>lf!DRfsiPS1B~?FXpSL{zn9 zB>qpuh!$>lb2W1)g(%Fr4V9-am>NoiV!iruPK9;GB}TZ%bwsb zbZ2nw?T31zQ*2&T`|;}P2KX362$D=Jo}(ec9vvM;e*JoQbQDx8ClCdNrQ7@U12*gg zC7*s#S?^xY*%&Jpq!6(TOL0!%5|d_lcYz#!6FxfJSQj|1ei>$a$Bg-4b%xDj6y=z#0B<@8RkBCaZi^mNQ&!%fFid{Ud28QqCCMd;>l_ zjLj0P51+n20etV)MfWNXam-}R0M~jzol7Z;dCXRaI^8f6VsSm2^VqH#T&BQxq7173 zB9CRrVt;>Y{&9IG*{9P{zhT1m6ih%re6(}$;e%twN?~wE>|v5EZf@?B{}92sKJR8W zEJO^4H|(UPg*O2B%q)f9X`G5@zhz~iFQ9_4@fz1o1^(Xn5n`m7?FtVZxdP9-Y)bNF zac=z#Bn8G~>WujOiaYnZj$gB}CUosxeh^m@-IZDt0a_&z)`bV&x!F_NxmWuWVh<=! zdeXTtVa!)~;P9%{385MqxQfzV-WDUH?>y0lia6I9V}A}ahyGF6cj4vAI{gB1$e5mv zx8w$B4@_DI#Gd98cJpp1^ItIL{fNa)^EDNuG4NX#kJwes3rw;DjLbEfMBig&XC}%} zdz76o<3+6l1N@fC4QSB@{jxJrNbBGIY%mk52V_hw_);71arwI_N^q655woH1k~OSH z?-}jw>`u+SPEebbmm1)l%R}}Fr>1ikM>zHhu&2A7Rx_3xE}iX!5TR~ey4Tz1rYEut zO=2M60)}9}D68(!YOL#c7AmV1RY96h7~m199FjX$mocN-PZB&NJub2!9vhiUcuNNshxf* zXJaO4!$ZgAhv-8eq7Oyq0!$C^3u+YIqg0-VLA4C(o9C-yl)q?VFvGRTnALA$?os0R zm2-PUb0^dZWGeNJ#*7Qmln|{eE4`wlxjfebwfLV#I1>m1AcyzF(< z^$1LZjeqSe46d!RSRKMlgF1-n=6Wp>B;w@u5c||5S#H(X-g9T*ezQm?L-Qg6*&+h~ zw31FiJm`;{_zwsGXU)}dx=xIZue|_eXDGfd(%fceaW!V91bdPo0g`-mae!#0vmCzeZ8KF&A}$ za;X6@E5SX4k8j>G>6F~IA&ep8)$Pjlx{2nujN?cY0!4tRjvlhZMW1lw1& ziy%1iU9`qZ-iFoCZaVUk&6{F#eH|uX;e@IC+J~JegNAr`odEp_0CEFc-HfnC>(|{S zDwl1Z9z65xgm>_OfWt8ddT4HUWDSxrr1@!PcGs@^zr!#=0FIBm0JPnTtUA_4H9Zvv| z#eM^`$Dwwkba!`IO&fHINhe1gO9^k8MJG&ZJq6PuNWK$I233Zvj-ADh4J5KAc`yDv zc(_~NAPq(cOW4l5^<0Cka9M;ZFB?LDsTd#_z9}x<`0Z&6QKl;JbwzYdfo2GSd%8L| z7o~`ASCYIk-~j zbV>+OEL2bz-_|x*2tZLFuH$M7f*xywF&^H}|0c2>;4jVQ4EJ9wmGon$G^-W!%dQkx z4A06Z#Xn(hQ}7#3Q-Tx%5T*cnxG1L(j`U1Ozw`C!@+PD#s_ z%7;rQU@;{RDl1A65|nwq$;YwuDsUrf_rBqv7~`}k7x;3qxRARTF4>iN(Y z8%3g4h6qlJC&haUYnz|Q+<%~~uPl!0a%TGCF88zz=(MKy{9AAp>|+0pX{S^krsPlX z@gox7E3+EH}RhU(=E&$Ax^FSnNWBhfz7mH^hE; z5lXd?MRY0iK3R5ltxD$_EQS5%F#q@NFGFFX&cY zF;h1G(Kgq1xc5hwq>L=_ja?!>51AGXI2)yaAI%6=VXv+)vaUxI_hV%!tS^a5s&6xm z`;4sAT@zNASbNM(m5gC5?#FAo5I#+hc8bGsEQVQ}N-zr%u?PHiI+HL%*{O1L^nI*? zdSVGA4 z0GPT{0ez~`W)K<6k;^ro9TZR4UM@{}H&T+f>6|d77}wVx?ZG{8FB!l$*u9WU|o3#Xz&|&djaBZ%vY{q>2K2nuY^02-I~fW7FOx(iBu`6Vy;@e(2+a01~F}xb>hFuoRGI zsAkBUA>)dL>&)@cL6L)p`8yUVbjnE<&Dv*cbTf!hZ&B}!JOybr&|_VT))oM zB07=5-%H_HgMfiRzV*lo6Dm;hf{nGD9Pj!aKRrD@3(M%mdbxLdYZ$3S_A0j2S8~Vk z|0gUErkAVWhHG;A&#ySqB1r}optrQ66JOCbFYq2wfBR+Kf1`-+Is-aCh)g-K4?LWi zPg7FU0NV$h_Wc>A*y+Rc!FC|r6(O%LR|HHdNEhxa<{trZ7nbPY%H_pBiSW<+lDYw; zemnLrN(em6)e3qs`qZ|yzVW>a_#XD?%h98=9?Vbw2_W^IxIo}m$U7XSFACudz7Y}y z1OJ|v14bCb2L??_su)(^M=E`H6DUFGfL6_%6wg>23x9uq0ko*yaG?K5PX4d!zjl9? zYL_==0s%OOM0jQ+xH|M|6(#bnvKgZq3gI&2@B#0~tJ7AxYHI3= zG?qxWU?4MSY#pc;Kg!=Au|kVYZ#BkNV=i6$^$tsmF=?Q1C@KC|!ZMI(o;@9^L)h9j z=}b?bkJu|I=f9KQbTq0Vz+q1%9b=2fJ_H}^FVam9>d*A_1j;F2B+i}toi=HOG$F7P@6%(097CNbT@7#j|?>=WAb z>>&h07QK~BlEnVTKj%FoY``+w;0)mPEY{O%scc)w7UHXRnb|KYIP0v~9Ue)No!`NS zkTsG^MS~Z_uV|jv=BEAawE&Vrv{*!600FubGY(GHC*+V0rhd%7STbGsw)#a_72clzf2RnUubU zi$;Ze#UMod6^k3;0B4aq7TxQGH2=#mZ{nFxjtTzm368PK|9cW2H33R-wiJ0!i!0!j zgHS+DrHVQw%!Ai+Sl8=LC1PxRTE?j|ASr{6j^_ru zzFvd`*erN15se4_p4dxIq*A`O+D^{WV3GYI*tSZb8YAG#D`(!I#f-PRo#=Y{3_N|$ zN1gX)-$bci3A>4bOu56OG|qT!`#zxS0ni1#jjHe`$P7-Hc=%k@4Tt9sD%p_g_a!hv zGHF8Ma0B=QC5k?O6Y<>fmKsq4lGf~w1xd^7PgcDz?to{7rmA;m^Z8++CJ2RZy|U3I zz5q2SYieODMvk(e5qTE@RMIJf?+yHA4Yt5` z#>NJ;RuRE=!*9c`DdXGTKBHAfJS9r(YqhnT55lS)v7;a>P9@rnv zW?gtj@?{L;1gvPtQ{!C#qh@7CLuRqU=t}s+Y$uYGE)%K%pHn5ipDgtr;XV95M@1Q? z8uXL-NM19})b^xwr0efIlUJ?tzBiUmT;;+2xp2TRLve@R*z>AyYdU^)>64t$75S@j zp;23Y>~to8#`kAhQ8umnq@<1qF-0cCK9TuI`X<35L1}`|zgEfruLYP|4xmFFKhwXa z(`!ZpX)xF9P{dN9fO>P7Wxa-r^J2y>C=#2ygQih;TJ^kJ_)Lua^}luEI828Pn@Eu; z#pKVo!I*}4eI4~toVxEC)EtD_*ycb`;WpSsk z>KKZ_cX4s($GNw%hfrFZY6}=yjnUALHC(@}aok#kvLJ@dk_Z+dc~QkjG)ljhRE?`F z!YhCOvcWjU&ybr=i71WeC%{9%aH9wh#!xi9nQimL)SyqDnYSpMQWFl^anihKN|w=* zEB0HRJxUbPNLjM|oTbLK@=(Rjsv%bld@CCcF9frGQsi{iqr7ua)~7m0)jbtV#;?=LxB; zn(TVJ0-%}a_UHRtpDb!ASt5haS-h)YDlx-F##7spt!B#3^&y-vz^Ow%CC7nnt>EzC ztV5fjZ`JopC-0}_Y|9@~Byei)GboD`B<65-WHeI7j<8)sR?t1&fxZ7 zuuvbL0x<&F*^~&~?@^j46@<$t$u}wT3$Kd@Z$vT$ zS{o?qt?n~&~fhU-tKlwr6|q7AyO1?Dc8Zp&!Wk3@D?P zNlar|sF!Z^Ln3kOx_P{8yT)WO19570U9HE=EiLm6vM;6~*vGiIfA{{C6M)D^8mr!N z+#SM*t8WaoE>z|@bmpv%c?~5Ss@Yv3;v#~XG;Pv_w z(n5&=6`&$Db~J_*t&%PsO@Ro5keD@O0@@+|Xx-KLllG%AVp-71>x$T zJ89uktHkxm#od1!=aXdOv5Rwf<(f5lov~_32(R$@6EN*hl4W~+6^;D%IS~X4hJL*IqTBPm zBYSc2xO9}B`Qm{|7AkO)pcNY)Xyb|p5N)TX=OpYn2DgcKrc_kS;4IxdcAXC9Dt$q{1?2XxBNSTUzuhyD03I4_!3U8+`_fgJlIN3B^jK@x??TZO(^ zdUZc?U8G0&wN^nLjRrS?^H+pFZv+x@uLVv5KCMB+snJ!D(8A} zZZyM1*8c=Ghz{XV*v{3hM z*?5kBdIT#LWX*{aOnAR{hGt&}hN-O$tj;c0IQ?gZaGsiPa^H743};NygWEWkD4Gy**1Zv1u0<3Ubp?M!8YHyi9^St?0+O%Bsi- z@yZm5iQ?pO3hIaEGxGyul8O8##hMuZtxq|~YDUaI2rAi}FT zK@0#99bPzqB;UXAsXD*R`G?n@XGwc@-JI8a|755i8-LgwFTs@n`b5R!3xjmBM6cR# zUYg0HzAfU!jk+AuK7@k~%&=FBxyTCwu>F2xflG~42v;c+r_v@07#8*AC6IR$YaQdD zyhO=EJx+;}0bcxh=Yy^6Uo4H}VfNeJvCIfkVoF=J}!%=;Q@W_BtF7CS9kqbZA0teCP z+Z3n+`*NK%QdEzPQNxBd9D27L8#9sn48WO*czEc~CN8oP^|N%rpSp*Azr{;rqd;kT z77z|L3kmx77U?ZTio6ONX;Y>7%-21PU%mgWUjW_s7*C?F*`o&+7f=yPZNLV%Xg#go zHvKd5;Tz?SrTNjt3fh!_q7TjYyJ zrbd)Ru!|SG8k9E=LF({KwSJ^*Z-=BEC}i}fzw;I+3IvFJx%Zm1Optu^J3R8%i6|$b zc>sy(gb7Mi%XZ}QyAc!)tst~;RBmOj%E`h9BfB(X5t@W&xbOx+E(?Lt3~^)xXo9Lb zSB?MNe&4;^xB$<(+JosGCIn!OJjp>SVL~;!-1>|l1l>bVIP0`_11#~}gyzuiUID|9(`54*)*5p~GSj*rZOOx|&P+u&P4B`~vrwVcf zM?HnVT7sp*$~Lk1by$?VXTcmATP(J}F7QM44!|OLGaR=#Pgn_j;&50r8h;c__PHIU z-+PzBpOhA#dw6Uif!%Irn2MpeJTm0nCoS|(B(FtERb%Q>_zl{-)JOx=IA#e&RMY>O z?YIpWr@btjrT$t|Acuq_M2&RZP4lt}=0(tv9aF}|4F?sw%f|q0=4Cr}+q~8c(wHvB zbKoblv?0qP$DPTDhIJ{yjM#^C)U#(-q2c`x84I@)Kne-(3m^D=qmja3zQ7DJ;sS2h z_QLr8dyK!Qo8I^An~K%om)-e%GxIZ&Jvm3+{4QZ98!p&Iz-f1OGGcNSBw(PxcCPOb z*a3$EyfyzWl9CT{xU#@4AHXjzu3KUuo>6UHtC}-MDeA1`l&~Ut{PHH#|M|OYY1xUD zmGEhWW`*uM5K#E(o6%n{&7a{R?_8PcytvCVmzJB!5`Q*;=*tR?Zud^@|CS}-G~FY% zhmdA4yaPb+3cmY!FM6$$EFLR30Vv7Yh=^|?O$g@&wdlFEa4NDG_y|ieP|w~f=WaOw!RGu z+rE_m$`+Ui7`b8sMu+YAwg-A-xJ2@c<2soPwe6lG?pG=`wEIsQ$eLoCJ0I3Ryj}xw ze!oIM{)BA?S%05Fp|&K`H~+jv!LX;CGV2m z%LBkGcbyHKkmG_5>dbr)?KQ8RS6Dhc=v6Y4o<5Yp?e1_pDbm;~B8~o_Owyeviby!x zhsEOGF`E4b>i%l?;!2{nd8M7f1l{PnVnjVq6E(26>)QT;0d1oxk)R|(2qU5q6R;F~ z<4*N|43ehbsGpl}OVe$2;GF*%!F?L1`OfIvu{m7Ko5wiJ$_;+cEm6)G`y2Udf9)kz zrg9c34A9U*0czrRqSyKbN-C-ov!RCj=YNjy(NeXa2DT33i}2W^!1pTW{MsQ&Cc&7b zTWlU=P4-cCPW+^R2^}{eY)%0-MrXuW{!vA7pxLczR~vd0*Q`?d?Qrt$`S$MV%#jPs zI;U@jnc7~oZhmr;N!;jJs4t%%pzh6G;8m$B9foJ)P?E(_Bwj`(eT8NpW`ln_aY>TD z4a51IFql|cPMZAd%zT;C%KF;CQxT%f!fKu|K(h{;J7rFv0^`>fF}BGc?AKY{6K5VQkfhc8vLtIvIzdT~ zRRcP0(0=*06O7X#>#+`jICD!hZZ}}U7!c;F?Ny%OU+Yc#^E8L zZ;eX9ERtuq2}E$LRvGTi7GjHqD^7I5O_k0m2%W@}m~aP|n1>ZA$Sg?&bZ)-w9oCt0 zM-;N?ojK{aSq?|8SK;$;Y$>4JsWEOoW)>p0vIbGyUX~W)(Djp+%clgA?5f12dFI5h z@W~n(pTWm)SS+maDx**BKsJoi!9O5rV>Il&EO$$eEn7@FJv}rVL<8zFk4%}+0m9;n zsGZ?R-y|VCj1RG;UmkgCG~6swrX)!O$%KT1SQW#+fP{o_UQlqQP3P~bUc?L+()^{3 zw7_W8_7^D+&S-~KKF0b`Z9CsJn$=RPf702|86jtWCdpoj_Ez4>u%ym3AZ`2q7!@LSdVAv(O6(U@7Pff}n1b{um$L6#tH{pG>Go%Zv4qkuZ$ z`V}}HF_P)It!p!JgwI+3e7vB_EYT1y`WU1n!#O=tupa|Fc=V3*DK$ak2|Cc7Ypv+$ zb{|15TQ*h=y{b2u8li@7pww7F3B@HLnh)B=08>ph9y^@SXUo&umKsHW|8_l^Ec)4a zgb86DJMgDGKi2NH29Ds&vt}MB`cRoH6W*w)s;axXHug-MIQTgHHNSS>{Y^?&jfec? zhhE7Id)d;Iy+|Cd;g7%o zN-{ldQv7~il6|I!PFbv102Lu#;=IxxQbpzb`2hl`s*L*L=>1!s+yWXJYKzFNudogN zypv}i`vHy3joDTE?`|y8BR~j`kuBci))vo?zndsf0BEmSUCV5jIUoJ>yd?Sk*L;QV zjRo;=!KpdVpvN#s7MeSNc^a`)c|wBzeg8DX2pCt_3hjYvLx3+^Vek>&u4*5X z(y-^mI&Mw()b5fGY=m*sT3^tEdh;5XEaL-0(BMh;bEHg^GNU-C_jJ_t)_E2i;c}o1nFSq0qem>B%hW2FgOGE z6PsNofgr-6_KTlBg>#9ajo*5 zA|K@e6BIzcqe*kz-~NwD$r}y|YW)vq%8I#A4YTjVY8-MqY<#aKj0g)+A4U$2-ezITKv|W(oZ&Nh=E;!zVI33 zHQ1#|aomviQw)@kQjzr+P(f@J#1Br=6#+Q3}Ap z8$1U>$-wAFug-l`(xsYr(%`Mct6px`Z+@3~D;XW3)VQi5o3l7(V!uZ4br=E)(uXgF zZYxC_$h-!$>}o8D1h}H-q#3{2;;BeB^ozZn5qV$In?4n>7CR-Wj>Tejei1933+8H= zUu+Q?Yr42AD?%#homN-8*JeNdNey@n5uvYXed{36QaQ--hM=refF1*Qz61i6>_}0u zzW|)-HR_KO`(~AaP5YTBk2Y0$?rO(wtsxZ>vGQbTgOQK$9p*k2DIa03!gJF5R$D+; zo}~^ODYB*^#>2b1{_}|(SG~oS)Vp?RF0bF;4m-mS0G!Sr?$PeYlfS`+4r-^k4f@7k?} z64&{1V{RSS0h~BJ18nyoh$J@*^d8Mn{wA9&7t+&fba%%=d@oBTP>gVdA7A{BvZyCGRa6wYEgPIpEc}kG1GF-?H z_eD^tR1eH%b#(aJE+l{fQEOj0KmF@N>aY~~yBlw@d^Mu)bFrne#z;toO*S?gLQfo- zJPXtebFn9cGc%YPc8$po2=+EVp&;9r0OJXhJmi1XAO#6_!A(}I#fo6G~ukOu%yYoA6+C8d;u;7m@@<- zRH8H(mq9NHP{NTD5Qdh5wER<78!BTsK^pU;VRk`MSPr{Lf4Q zATVYs-*RNNL_wcFX-G^ozQmH_KUCr5gp~uDR;xEZ)(E?guPN}Pc@LWp4@4E zk8E(Y!EN|iB0p8D3oZ+*=8rQWx_G+8$%p4!J>+?kHzajMk zb|pm4!{_zWTrDyoTRJ(4K{7r28&9?YexOSf3_}7h%TCDuU0VV!US4|i1IbfzqwmrI zEtt=l=q*nLNB`MG#ok*urlMIy%mcw>4qYC zkM=f8W-I^O2m$Nn<-xCUjf#O;8$cOaqD8D<8e-e5loez9MMAgRJ4>SNfNJQ?#kDQDcd zZ**TIXx4p=nG+3fZ1jBIcjiQ(*D+-*cBQmt+J1jQ>N6;Enk~-iH%$e36Iod>P?Ox$$EVp*0vWy`8^%?@KB>Up;CLHK5|OV zc!ev#p-H^%>pWpM5&z3)eEfh@6Knf{4TaB*Su=@ZTw0b^n~6EwyBRx6G_WZEXOQ4f zIpgaklpwp}8VC2}<=I{)(WLgaiq@4Nc3{VeO`<@H2n2WKp_ERL1_scZo{b^K4T};n zdNkN`XMwSb$e&_?q5q)xZXMcJ&*xkaj5EdhR`$sz7qzG~qtiJDE3bN5+jInX)e~g& zh(!U_R@>@hGn5g3^9sm;YI1})IayE`*?my;if5JZszVT_o{$_Gs>?2B77l;w!i zrr!)~68(GnlRYxR!QxclS7aVI_AlDHH56%JWBsJ@Eo`Jiu+X-m?IgA0to0jlS~1z^ z>@C7r^vL%Sz{!{>`d{{_h`&RtB>DCJdsRwBj2mW%VG`WF6LQR{VF-}F6Y@3PLHRPq zd}QDD-+rh@>E*kzNTm&B0^^>FYJ6l_j zWO%z$p+T%}5GJxihDE!+omg5n#Fv9!m+b!YFlW^jORm_Z@T-v$x92pK&+To;B29jW zKvwc}gbekisG#JU7FAqFy`YFLOc@gy^mduNtceQ0%JkOtAzz~(-6o?f-;?ER)!Ncr z6n=Rac{!=FuQfFsShA(QLU=8XTjzH`hpW-5#*ZE?bzp1=69jT$GC0gT8@-u)IOlXJ zoN+}QMM(ZVc^`AD>rRys>HBhiBM0RZ*8Vv8|Lynp$z#Q>F{&Rn1>#x}iNH>w1v~D) z)R-lw=bzQ=9B7lAv=nV>s0lJA9@d;!J-Kp6FMbxh>u$MM_rP-}&040{UpRV!z?{HG;<+5|H5wyos-#ROp z@WCtM&XJPbO6%>e`yqLUw9LYeoFLU7N>S!UE?YoAeb0=!K&e3KTajO;yZGg>{%$v1 zq*HYtV6%X33cN@bw&%=%L?(%Ew{^hblu6W(v3F8-4R;IE?!NCcVxsTNOi5|?9RUKC zr`scb=428yVzlmqq**pa2tWP^7?22T^Yi^$_mwXOv=o=ve^moBYRE_mbs{d3d>J0Zgb_9v-U)O`ex05CFtiI0YK238-AoED+ zYxBf&#mGe!5QdJ9_Bszp56SB=y}2yKAOML3lkMa;sV$Cn=^`XicpzW?{%)h^8tRke z{7n`Z-1al#%{y#%L?>n&bP6yc=6pi{XC-DffK(%w8yXrQHN@-{6 z`WhQnI%GUL}7x}Rzo}DdO+*n!z0bsl#?Y( zn{B`aS?9NB?d}rj8*6%n)ZqH%c^yoD%@Fwl#I;{tS{VJA6c?v6PhHZ{<)>AfOijTk zWFVI~CjAI+XDEh|9BzlBgLoqysaYejCvYBp}`_+dOFD3BJc_? zB0qse$ol_UfFErM0|Z;k&UX)MuAd6ls;1(tn*3>t!X8liJ=CxG*(OK!w&KOFnj)+G zv!og5ZVZuB>&y;5Bcbp~a78c4vJNo~fPzkCiq)@&{|~7-Fd;(LzlbEExehbno_so0 z+KC4_*LdVvv+wx9e6wJyJe2?clncrjr|(k|?iy8ZdrwRutSDQSR+id)RWlo~a_$hF zcNO%0WNfP}6sErgQN)B+HalH84OCwxJ}~p%Q|@I3Su#75zuc?W#7b`eHh~Wb7jfXM zrXAjxx5MYlzHR<11q^F0TB|F0IVG^_u7u-zQ-!fWkxgCraXdst2s3?qHW>SRn;tOl zYv(R@Nd>g~YO69VE;Xu#Rt((O)=zyelPcyO8vguOqD>FPm)5MXi~;!f@8f0f78gEF z1W1UqrAv$I*eSiSKv{(;+_$!(2^kys^5%G6(3S1w9xHeJd)f^Ph6ytn8m(3VS~l`9 z?%0F<-x@laxr1_Z;`>0Z&Jthl1D9vnu25JUak6_k(Hay1_!@CJiVMzoiG%G~8!K+y zec~9ak$Nyu=Z&2{FCB~Xks6pK@G?Hr*Lr5wGfNutz3gkhSPGr-0yFO*@PrMozs`^X z5g)EZz1bxR%SazViT2mY@6i}wm^a!?0@$#2902sd274g?6IBY^%!S*+M|(TYi^tM< ziCBy<)HhfW`#-Fcs#VPfW+E){y?AE(>xBiBVJnH+32m2_8vZrmt$hK3 z1NW9$FDHfU>KMtoD4#uA@^`_2P z%#G3y`y_So<#}hu;JCko*T_)vQvqt;T50HUtZx)ZnW@}~;RbWGvVCfOF8haKbgeQW zs;#G+%qbp$(y=s03posInEqj(ok1)P-z5$x0N%V~l#Q*Ag&(dOKW@_QQo3P}TC^Is>s&kvAX+>pCt zsg|rk0n`!?PiMg3EKUIV?7o05OP4?8{8f%JEsFi8+SPhJC33> zx&)Wj(sJV&>cOk89sk9$c5-GFDDgZuJs-^1BqdMG{|1Pd3&_~;=8le*N&9uY0GK@I zF#yPSMd5&uM^N$W>ZbH;R96)3*2;zA!?rdYmw4D;S7*sa;SZM?P9t&80`{X5<9y9WA5-r$$3mBt7+C#fYa3H}r_}`l=1L%O1j72SZPH z@xGEF(j2dU*HgQMgb0B8M~+B$D@1Gd_M|gq1_RLOQ^vyPq-n*-YGYsij{wO#E3J7N zPF2=S^Zna{g2RsZ9UL}Jay;>4{@Er8$uxI4FB6xd{jqybw;;2lT>8@{UdkK1!Pc%A zrbG^{L~-AL*@EcYZpZg~_wTv+zn+4#Bwl>}=iB1MyUWsw?e^QNeUPUT%FOnb2z8yK zb7D*Emn>d_iWT8|b&_0Y z7B(vBlPE=|Y_MOB{Z9dA#}NTz-lghz$*c z=obGc29Ow6r2=I(Vsxwl4kQ1UkHdLwKF1UJ1Aa{rC>)R(W#-?w%Zn!XLU(l!Mw0DK zhPW3&+*E$7*$j2NsJiZ+WEXo9IG^|km5YrubsR&2t%70~CrgajhktEQp4q&3_1UMo zjOIMFE7Xq_r@H-K(!ry2MLtZH0^_8bbQZe)u-0)KlY!$&tSAbe`2L$EP~D{TC96CA z+khbS`^|j@0fv%h*fSf!h~xLAcK(SMXEsBuGv9J!@!@1>17q1hteAS|Q1IId-C=2l z8b98YzVP=ht^i9dl7&Dgm*GoK8yzvWu&XRv)pDCIiXnwyx3zj180J!OZU(-^$7f&K z70g09wCJ2BEA&T-3xYHi&(9i+H#0llDrr}=}ZIFEWeUEOgTe0_aw zm@G!9P^E)t}0O*Kj)dKLj1CBe=8T{e_DPCIKbfrY!@y&D?Ot(~!DCP#4 zkF9AOu?_4p$|!npnR38wQJb*Qb9dW$2e?MWAar??EwSs5v3HYqEc#v%({k&gd!J3u z?49F5v5~Q6=i^@HeLqthXd50O!np}g-~}HRB+UTm&J*&qq{vD^N#E*{3_&@Hz096O zd4l$5s%pRHn{bvg><6B=6gQC`W&+iQIFZGo;z5UVaa%#s=e5sD&6h*dHM9 zJ83W5co-Axc=B=?{g%ZOi$fr^eUuxK@JD{rVB+1s0mtSmln)uDKH>PerTS$R1(net zHCP`4_;!o4iZX!K>*=M8BLtUr!znHFsB~x7`<9}gC&$A${bASNEAlVh`=^n!0YH8S z))-q_{i?<0KprMRB|-%%!3be9hEamg3A(KTv+<+c+8xg$Wxq?@r<|DRZc@{K6GrSu zJX*~g)3c>oFf7~UDS8eP1DIO&KXN)9y9w=W$1U${#RNa^F=M7&gH3Kl)ZOKUN7JR; z><^H31&Vch8nunIO}8y4Lu_nVx#H(9DpLM|T3*iGZ;qEE46iz{#StBg2AdpNSq-ok z-VEtg`H3YVvZ*{_bt*tEX;b)ZRQvPRnWda9V|~1m#Us8EdGlC<9WWPT0u@q>lqk&Mnz+M zV*`fhHEP3|9TvN7o1q{o#AhslxrtysJCDT=Ry!BFctr9lsT=SSP8CCQ;(@7N&vedA z^RG|}m`8S4?sFjBcK+*UYPN^=*QzP&M#ZB=EJ}FYQ%41*mCUG+GEO;ghwvm zcK?9%3BG?23)d9)3ERM;vOU`yaP#l~5%tz_Q9j@MFc!Q;!Jt7vNu?VF0YSPOq`Q`m zMOsC=K_r$C>5iqBPU&1=K|myyT2|@i8T@>IujgNO+54WEGbgWeon_FBXK48P?`=Rb zsR-*yY5}oi%$#Jl!OOzy{XFiW*LKp7(aIfL zBTh#_B4*calEykE<+mboj-}V`|L1jutcRc@9n3@pb#p-WuTKRgeK`dTGU9Upt?Q-1X`^{i~DE2^}3|i5et|Lt*lRc2j6$S;csO=iJ$vlMEWL&iZV3-utNhs z_qP-#!Jlo}F(A_FV+LiN2yzD`GR?Ot8nJDWIuyOQt2b-FA)@szROBu|83Ka68ptd3 z6B;i->#wW0`CC3E-5TPMTSGG7eU0#A@2l$cBdWUlWl-K}3N)h3Cg<{e- zZ%_y|GRNz)vi(zr$rF8m5O&@JIFezvwX~{hZh$70@s9lski`OJ)c!H$yu#b5MIr7D z?pH9g2jO2{JTk-5_><=+)Ib2X8}O^;;Xb8IY^hPt+qKs*>~`|c4vvmotUo+f@pbHA zP06*EUK3fRPl$^l978lcWqNfppf~LgRn}wf= zZ|Tvs12_ma!0mX+esN(rsi+vFk%yIgqE`obJq}BzGw2Za$NBm!xPXKALh@0w>Q?-O z?dF!ppqMvbXYfWa5jXJ)0rjhGE>e!JDjcz;@?lwI4Wq?+=+ngUhzd_mPe8x&n&x=D zBxmRGY|ZKTWuvwF-FLc=OA~K~O?5qumAy_UT>viJwV~Gs#8>CchKBd4dUE8dt1YZ0 zBw~2!Xw%8|^kzTL7&@?Xkm(o?ZKF1C8mim9)pQ($_P+p`cwOzY&`zuEQyEIRast!M zphpoKsk-Gl56U+WSl#j;7ME>U#8V4b8Pf|A_|T8(naWjb4U;pPGp zT}y3MdTBDfiX$h;VvF@3qgwhAbLjzxC;%eO!hKYnpmxo4`qP{BV4VdLHRcb#2aP-x6=BcRM8M|J}(XIKApH>0~fGa+Z6{LME4(zCl z3JK-7zpN4-wQh0f=}D)+wt8Q4SJ}d7gy@35S-375!+k!lxw`aFyi8|!Y~WjIu`Sj5 zzfPH(Hw5f|{q41N$gPU6;>lCV&kh9bD%V3Phy5)bOU-v~d8liOr{~0VX8^sFpE*qJ ziF1x|dIBYHe;U^1Z?lo{#`htZ@I`DkMETRvu_c9o>Ubg(coaR6 zp!bn?WH90*tP5x=fJj+oyt#x9fKS*G^$+H(#!%ZGi^kL|mv*tVn>U z@rk_UT*$<+v&BlZ*a*+CAr;-jSjmfrHAkS#@?7(vI_sgM;8I1CrsV&gALA=(zyXTQ zm!~?9?*nc+=g(rQ_}s|Ccl|26}hb-`y_^ zjs{WzCg{x1i?OyAT47p^%fch^gBY3xK5wghwo+hlmse^I|Ge(WW0^zzVl3teZ(t)@dtP<+{GP)tw77-?AC%$cFJ`_JNOTV=1=J56oZ4&WKGCTV{s zI~;3+9D{##Ie{waLSzdr7QkX25(WDeRm*d6>eZ z{{QaKuh>54lhxN(uS-iohm{tIc@KbvQV9U6@f5|F${)@Bb503}r~1Kf36%#~e;n~QCIIjk)z2UMHY;N4WW?7* z%>$w)!J{k5m6;2PLB7%CUDc)RHmoS#@5Hj@fc^5UwX!5`yF{Pt-Em^uciJ~x&zCRd zqbTuzL$POh8G5j?U8j^t{|e`4Z7#h_t}cft9y7^(-aeo|z^o4Ojj#IkSN?uvd!h6I z16bCgR~Fm#F-0hGRu8b%6cqhVv0fpqpTU~|fV}}4Ur}YT^a##8IFasT^LsA> z(af&%w@HmU1v?LBAAG4a59_ulLyG=0k9w?kz?`af0A z*1CAu>*#3Rir7r$exP$Q;6}1~K&z}nW@s3pTW^B-{m)gE^De!O;T6zu zlhKT+)_axE_wc`m|HHmInQ>oFwlR#!@kY`;GUHYxD%ZJsNTtWb!BTfPW*IVmv{+}oE99LLkz~Xq7^918`fWLj0sD7KLtXX?F`n%_KiEkp`?Qi#K z3V;V+o^cOd82)6Iq?zdAI!23uG7uhZR~3tGosf`rrgx`p`Ft^R>wp5}VV}jHGaq8h zf)hFxkFRwsOyrYCcqE9@u~j;nBvO9vhyP}6Wc1RaGkgFQ<(gHVQZ@nx5c)vVJLy0m zw`Q8W77t<%r|e&Zv1wJ32e;3A!XadYc!`Nkr$zSdq#=@}V%l}Fprle3{Xo>&B>nW% zPYm&^>gsrq@{>5KMC)IMB!s2dVW$;>JA3u zdpZHgS+in6x5Z7kd2LKJS5Z+D{CCHm*Z$b2^Sht~@_C_??KI6#y<&uzMSwp4{lc27 z={sOY4>2GYqa+B1RUR%^e*Nz{A~*$&C$|Czq*$bM$l8`d%-?})IU))pXy&0%)L^ef z!Y_{)%GJcnmKEMU2fo1kyt_LWgcPiu=0Vu)j~~v7A|!YKy<}NSsxa1~@39Fn`~18m zn|=@NW!oLHC#RVvoP@DwvO!rLT*CY6)_B6^Ulr!3Yma;j!evB-AO#XJ*WrfaUf9Qf z^u0L0j?fEzYnZx&z|{db#v0Jej(5z~fRWf}v2x)K2SkhsY3?%sGS8TEoJhd=@Q5A& z3+(K0C}x>XCAnk)%Y1K<*6qL&BSR|>eL|UO1E=m(WRCi0iI8|o-uu_o+jsHs8HmR% z_n_;!%6QPb&3>O$h0UQ@yIP&%!n<0#g><-&3qP~nQNQ~FS7ZWoOdnq-iJlSMDkrPc z&*X8#!#VcFYs%G}hiV8!KRKLYw!IScEGp$pmI;KaXS3%JjEa;F1q_aTyPIh_Pu1D@POz3U#tH2oPq}W zO7fKZ<~>|qJX=%T4wQ>0%GhasD651Kg`&|dDq514ecfYE%~BOpB`p~Z4XbN^I|G@- zU~b>!!BgLVRl~2Jd!h0wNbHJY9r^{sLMyWU+H;i^a{Y9Va>fMLk*t8#Ls`T;aIDAy z*&MMZS?sml`d5Ba`tnWklfKhxiuFED8-2`5i+h8>W zG{1#N;JO%eaB4wW;oj&*fekAycM+T-6RQf~6Z?8kKNw7qhBUGl@D#8VGac>XOJ0Md zZAyuOZjqN~>p5y2Y4m75kDq_)zdr_8uQ^*IJKM4Ty;5Y+cucjua$U z8s;aHBYuT%l3r##%uoBYs3LXejXo6#37e6k8}D@|bCsd)ejVt$SlP%2BuKrqSGt6T z^Mp99v~8<&k6(qphEWny;P+jG+^Rlmv%m7>s;vS1%6VWqJ?O99P@#1;u72pJ0xCgW zIOY#-su86S-M##Sw^M(sZS{9)-As$&2xVpYG=@v@VjA>W1*jafA`I&1n@4UF;jtwC zE<-fZde>KZOrKd2)iN8Ud1yZ?bDhKob75>9koTxQh+W1lUPOafu}9M7WjZSBj8*$( zS!2=p!2!6=glr*;BcJYgL%VORp)@%i80fe=KF(a3s-@hgdGHa($m#NEnj_F%=%DM- z3)RQB68|rH%Eg9=t)RuM&!F=?d9G&A&sH$5k1BrhGG;}#4w=|{2f_u5@*N*8zR0So zwFi;uv9m{)m9bmOIGoH41l>g{CJ-qDK6@ddf}-)aPthY_kdb17GkJL(PC)oWymm(u zUZu4W^a;9jdRn+q2+_~dj}T7b4y>&WOcn-{StmhLcdrU9pqY#;UAtSXEA)6wqeRoa z+2<)UVaorn>(%<{9yvCK<>k?+6e;Bu{p{vC{&frF>T4iJ#Tx(~l_DrCt1+2MU8w?S zSj4onv}HoF5k77x?zzjuk$2XwJW4m7F|h}V`|lD36PS10UhpFuFzdJthS_77o_yVu z;eI-UXy}Qls}=l&+#nYyK~S6Q7|{6bzX=f2`pG^IX&$g}-|%r%>bilHDOeN_Lcy)# zl--8-QCjw(ga#}G&_tif+cb3nFf@9qClWLQxbtT>hbu+3Lje%P=T!i@$Esm9&QUNp zD}a^cIINjh=`{_L;;)f_yeb|sO{T~h=0o?&lUx_f-lBHVHWZ8YbXw;W6oc50gY*xeTsej<uT};{J0K^cMq(PY7#g@YvXm{r`}!X?Q5&`vN0<0>wK_i;6*t71UT+SirEN z$>(5ewM(8-vac`7hrZ1djfUhF~s2AUFrffp(h8cOLv8 za@ha8Is=>La!ajcPNFJUR?@;ezwHK>e`zunsd6MS}`P*Z)@J4KW#Oy zBnKBhb6A1%?@~zQ6FI3n4i2C`0w&P$Pycc?O?8!G#3emwVB$sxiIE4`>$4%{5Bp*=Se0=Xmn$!zf-nad>Av^+apSSYf8;*OL%N9H!n`0pV zk&e+;__MOOT|!=6j+cMH>zFzVFo;H`*5c$s@7=pvw!XPWd(6nCeh(K8_+e0xOpWr@YOVStTnLt1dKX5o(`lBmW#mt>H^+>Dr|{E*TqUBVC1 zWNU1*+G0P{_<5xDynZz%zHd{{P9QN+{&eYq$JND-gnnT}Z*R0UrLv89bpmlzt*aiK zI_B{HRoe#vdsUu7sR;K!-?U3c&13H9yq>JFTi`rOZ=FrZ`S{UJ6TW=RYy^g`8sLih z8@R2lcicM|Fm9y1lkkR+&{Z{P&C-)z;Mq^;+&Qw?c+<{jBj^=IXv`{-#$Pucxcp9D z1Cmhc_VpT+kr6BDeAxm=FOQv2!R(8?Pydk-FJO4hXnQaHOO4C%XuoKtU&gIL2j5Ii z>1DP^_xwLBz>OOILFsmKxCy>Lq#NJwV#|9aZu6-iq!Tw$esg1>&onhIan*VU%Ag`OZ! zKNWoKtAAt3n^77_KoCV%X^%@7WMGQPym~i3&m+y*^leyKPOnijMyyO#HZTz0(*Gfa zzF<=}J{s_>r@dtAV;727R$-_>)!;XIDLiFAGV=I5tRSUNw=jsTyapkWh=T6wXf7yJWYVDCMe~kKA-3 z(!;DU=F8h0_SY8n&@d`mw13D;9I%}e5RCGm%hD>IoXE!dslWucV2hKD9^S{M?D~1~ zQk+dDPTbO(@ZN8=ZakD)LYUbG<%~?YW;_;AlWTOqB63;)Qu?jOLEy+$0*Y1#JhqcF z-gg*!ok1}RBIyrsRcVc{8UarC?gQ9;D3%GX^k7^s zonp{8z6xcZU3b&wv;7p?J2M9QlonBtkXmcT^7|Y{)_=lMjqvta9CY|DFeETh@;5h2 z^JG|mS4&V#+5{+4eNCDDU1q=Yyxp-&q?#GBdDIG z(=3k+purP;xxuMh7W+7mZ1}M*OQrGU%&q;PH zIX9(<5m-}>>#;s9H9hP{5ADo@5j2Be+37{sL`LjqEvCu^;{nz|gH4-A?_nbcVi3Hb zfaB{`k=|t{VpmUc{FL{;k%72W6sbw1yq+s*;= z4s{eGfR-Ajz{wAmyd-hNoawVOqsAU;(Ua_o`YZwVX|<{k9kt@0jZSf%F?<|@2)UrA z<&HmT!;7?78|IHkRkTahw1~prSH7$20;6u?q$MFHxN`YX*g2CwKk^T^xBe4BzB(7x zs~h%<8;QxJ*iMO>(&RwkwO_^^Y7X}eKW`!+Y)qevre=b9)K#6W{L)5k&$Rxh5m>El zoKvIyM(QT$|{y|DKAukxPQIVB8YER&RH6n^?e5zJ#0Nog%aY`?Wv{J^m z?OO@$EO$jQByik2xm-8q_E77h>A$VN?$vXoRH<83{>KM>=M zZ9X@2>LGMu%4%(hin9o1E=Ps5Cn(h|(Vp23Iy<6T^n4IaU~=f(zc<(uCCvjye?|pm zSYNKF{KVDJ>Qod=Lq(UgZpxl@kj)~Lt827w&3U0IMySvp3+k(&7lX1Uq&mfJvVlwg zkT!w9Nf?@(t042aPIvG?^2>lDCv(c)h-VU<+4jk}o?qOQ-VIxV0+u90Rzp<__+9qn zm0>GG)w>J)wcDg=U6>6DM5I6w}W_YLTZu}jS>l3{KS5`SLhGHf)okTqo3f;|nje^d3A=Tp3%z*hgetXLGHZuY{a z{5<0*Ihv3@%W#rg`wK)I;ZjU&w)>r=%babBegWD zusK%8CX21*_L1DHt{%N4+ZUf6*>r#Z>qiuW*qUk1#VGyvc%#7obHYd{%CxNJY(fBn1|@(R8=K4y)u*;CZIOj&m^nME#-qLdzJE;<zu~Y%8jzuj>n!Y z#qAP3Urm_$P-zM0sP0;}+R_%x549+3w3EbB7RBN_);PS+mY4-duKUrPq)I&Rl+6Af zhq6ve*Xx#euUIaBZPwxwf-1vdaU(izsm*#q82rG)K(6Dd;I?l$wE+PKTOvL`J?yDg z&QI13=Z4NttcIWL1q+h*HJz_Y7ZG+jLEti9uTV9o8+eB)7iVC+O_>`{s9nw5>FxH3 zU*BNwx-N4Mb>_sbhJ~Xn%9^KS*BqRRX_VRZ*IIO&X7&$jcVwvt%{t9r26!%C!OQ9Q zSAJS@RLEJi--J7+`z%Ij{bv`vtJh!;_3S3}O!sNB&T2TdTRyWw4{y@Em}$Vw37Q#O z>t{obqH3(`?Nky_^J{&*uWA>U!dVr4eE5&=`26x+sJZ{sIdHByq!YQBW&zZxf$!g$ zqexqEy<*Ps*)M-ykL)$={s}8^ZLsI0Kr?N)dyi*DRO6=gl-8w|aR_F0_hpZLA{Fsy;cq|bsG?F3 z`%7~CmYR7UwYcUP>QmHC{-I4_ zey$WjiWdyUf#7b*m2xOT_ZXGu`f)upJ&vt<@#C={aPZb79R!w`^kO zKe5g%9YEpPYH%QiGGZrk2ggdEoHl!SUA|muOu}il5D%CY2Q<%((#oC&b z2o9d+W@G^=@u;+)1G6cdVtj9~#cxLjx}R#u{A*kx3Z3G$_w&~ArVh+0LMq5)2^BR<*uS9Rv>TTj6tC5;t5g=1r21|#` zmC2|EH%X17UnU3ci6V*SAX{NwFMS6-J0oBnjcWAh8ipU*&lYUR8U4kdn6@Tm`xevq z%wA)rFm`G)v|2krz%z;kikjYkS#Bu&gB>>1V^-<>@<~K@4>qlYaf2xHSQ5%cWSeu_ z>fV{D(^dDf)fseR4k9E})X*Kw=VNdBfXzO(f_sogvBYr8PO_#~D==^er-LRmGWCM( zrE_5vV}8G_cy@O4)vw1sb0z|hfM$`mTdDwL41yHPmPvq0QOP*-?`ybKR77^bdGC%> zwZ;mk-pZvNjD2oa(dR5|sUsD!c7ldwp6BRs^U^12!}++xFNR{4NEQ#st!Gs+8&=xYT&rX{3dK6O_m&Ee&O-qK1SL+&)tm#(jTvx!K~5HG1q0wWECag8VwOcBjP%=xa+=QYo>8Ez7~Y|C9N;r{qm zYvt{2u$Pa8tqv3i*jH5Rae1~nbW{(;wmb8~P&)rSDKA*MYeORgXCkrTtFE!a{w4HV7m z5&H#$`TTjmqtLP1e9An?8Sy7-2?yc$=JQ!daekW_H{9L1N71)d+@uT(!lzr~dR0R%h3?{F9 zguPTdVZx~CoTV=3pv(|>vltAxCv~fk=|&?N4c@ysrM0MII|W|>IO@yXn5of)-Le<3 zEEDq>?L|Tw(>#*)ZQ=;(t%DZPqtY0UvtCX;YX-M5DM!~y6Nb5i={dQW)Z8Yk#f`wg zYk&E?lK>S+Nh4r&_RMe5ety&L0P32pCUR$^8q#;@=Qg2KCeohKT!jb%rx|tkFfwMI z5jTJE(;`Wjsx-v)pYM~Ncr1I^(U)73fFOYKU8Lj{PieOe`||Z;cK!~L=oD1V#CfKOk40Y71$!Bs{hkr$GfsNB+Y}) z*diPamvY-_kmi}ILj+Qtfgz^S8XT~B#8BERU^8?`sv-JVz)tAl?K9LXx)$wPh8Xs% zeE+vEzrffg^K4$q$vptVW~E&&kQFQZ8GrbTr$>WW?^o=0Ad%+WwsQ@z?Vs+fb=)gv zMar-BP(^_t#Z$)BZ7q4hsHe!ZM=pQsOKLFsVNtcu;%juUwP@{t&3kGA;fJi`eQRD! znNH!mdR(GY84^59nSw`U(X>+?=9qM89x`Kl2DoiP!&0!FuxBg^c%K{9cY{E%=V&~; z;P{o@4SC>-A|VfiYi?9Gtdi2F)IbblI)?;dL$GIK z?5DqF<9G?0_V4HHEw?@ZP$&aa&jlb)!5@Sb_7Ee(1V!jC$;{T*?L^C&|q|L zoeUR<88CB7qE5bxN?omxq`40uf^fnA9e%D#FhA@nw$NP0TBdwV(omQ^T|@z_mn z6|Uu6YV%rXsn>{4q=jQ+UvgZ+n_2w1U*8~pKdbwIxD)wk9q z-C`Rws9{A;Gm2v7^cRrS0gau-Wt~?4w{Q9aYt!W%g5CT3?Kw4_MBit6eq2yGQj1|< z>o8Yq;L8E!0;VmztNsD*F9&FI12@EXVSm4#R~3ZGbB=E8I8Yf%cW$6}Pxgl9Jq1rW zdnullBFSt^FSqYsW*g-#kNnD1&hK3MQ_y9pW1CI%*am2Zp>OYt0^HDzw*=3oIFhcT z{UwRL_6O0)GF?6JdBnV0G`b;7TH;w|7lf0v_m(se)S(CjAeE?Y8<^i_KphVm%M) zsD+E*dvl+mXPBMG!hOA9M+Zo=Q^RN-#5rjM^=s?Rzh%(WsbdNP_SRC6#Y4ZluY;4z zi)^!TaLbe_!tv=`>&};fXkvP)8?!;QQQSSgw$?75I)k#D?!%t^e2B%-KeNw(*iUoReX-O@ zg83F8=1O!;q1#;Lex<@&7EbzeYbHmX$YwQPU1|FiWp4grw{iL&tCq@4(M*+&{9;*0J&Sy zlBu~2zi>bwfndEdGpxow$a#$JC}O9fcZl5U^2BOU^hn`o$AbcUd8XupK-G_ZmdGm} zFmV3(u4$%h#R`he2)4#e_7}&z*8R`hHDgxie43G)p4zx!cKfHT8TZ7r4mGd@oI_ad z@p6vV!uF32lcO~z|Ly!~WUA%nDUXed_Vj=)7{Q&h=5&6#11`>9St}IJH1n&e92xpy zFH{Eb{Q(K|*e#bNRkb{(=Eri$Ss4?YMyc{t2(mV)HgpGA?!<{QqHWM}e z>ZYe~WSM;!&;a?I*R`8 zphf#*nuKBd!@&_42fJvi$eQ;Z2Up;eY)z#nPyGEnT#Q@W9Z~E?sRU~mKdOsjsk#H7 zbeu6+IMqICb#E%|lx4QpEWVhY*1?F@UwVVgE{F-LEc53?Os#-!)q%aTrSu+r>EPgi zvKJ^AxM9$mD{h6mj{806J!F(~)V1vAt6t)qR7gCq{{PnybFjY0@F8n^Z{ zuL|*KCo?ZnE;lkK7s`f}sm02Om>D*fX?0%vf1SHO_%bnE{e>k@JaNPeQmSU=mzW{? zM~U*Y0ev13Ml6s;(dIv&IGQzMMDnhyF24c>eTHbojtm`8-^=}!bc_ngj8qGA?6o^F zuQgZ`)aag#fJ}(5ap4#B7eSr!`KxFBtHe>8e@yF$$gL))@=~*hY6U2=a}^G%k~Vt9 zw4KUZE-<#U{)!Q@43F`Hwr~5q^!Z<^l&d97y2e0RzxMg#F|wAYi#ncl-aZE)H^1}h z;Gi)3?H;B6PN7Oqc_ELnnXrwQ24jp#Hp|i%`}r)SDoyXVbFGcfky6vGyI^!}5ZPv&Otl}v z|B#n#=DLjaJmvLSg7ET-#A*i^{+;e+c_vWRFnN<0{@bN{d52Raw;Eb1U_XitC=a0- z&w5M0W7>W*-7PwrdcycJS2*8ocY}S<0(ixCPW!kxIC)c&*{M15Qeqc{hudSLv4C}< z^{N?w)Ox|e5=zRXLo{)NcXTEV?y;OH>VPUG!yqLDH<^6@W z$ZjaZyhjo^(Ux*q$zp9=8`-!}mc+u-PW(HTJpE{r7}iAffL34QlO{86#>YE4%nAMI z8bEP$ZW$!uz5XnBBA(C)dJ#yS6@qTs#k;^xFpCu~Ue@aQGZ)>+m)5)WK^uyzrliid zNeC0YbdgIH1m&J$gnsKu6e;JF+lU>@4Y1w;rrpi%m3n<@qVkg%S0_eQG?4 z84eCMAjT64oVG)h%~uzvdty3;E9wcrqfWxC?_hP<@_dazBbe>dcyd8bfm0a44E0OyyAlMbes~Wx`H>t?xVUK9-+;i z74_=^330%sEf+#qh|s@B`aDxd9|i>TczNg4$v6A*EMR&$hIjWiIVflh*~f*_#Z6cX zP|f%nm(OjINN|%xgm=52zn=?B@^;^U(Ce+@>r*b^G^L@k5w8GhnvrTMF@XQL8SBSU zG4GlA_%6Zy$vw_WZbh(b;C$f7qSOnuKMsXC?+s3xB%WO_b*iq~-w!(_%VX4sUiAu> zG{9s0@HcJ>=NrEgPZ3Jr3VzxnxbJk8$DH{khgx`lkk|XK)Wy<+&7H5@LcY2{0EVAn zW^)5BbU-Ps=B?$26wV*^E9h}$BO+N@INNP2>y2N^q z_-L|hq`5KJqLs;Jz~E+KPnHCikC<%*hoDcOHD@%o>YY?JCAlhH)_Vg~$(b4lI^6!G z36KP=CP8du|JIBCxgm0x4Enx+exZv~l|_||+Y%7i4yB$>Uwt5b3j~Rj@1%g~1*Hd( zrvH|{Uag|fQBkQ<{IH0Q=RzSmbGphB2}HW z+(5h<^ALbrm_F$GiPM(zxf3}k!1awEqMU+~zFiycWX;KqJ&V|i#%!FogK=ti>>wJR zbA=`va!W`1gZ)5d=Be5q1dvW7r1!Eh)Cas zi)dGrgAyN@C91*JSQ^=_*kJ!%jh+H=)Ah9@0}&x8+z>}FJt?~^Fo23-w)rxTKZ9SQ z5=aI?aUvvV!qL{5r|rDwse8O zKn@tF8u_~jK*nv!ZbnEYC^nW4Sb|Ncu#A!3j+rWTn@b%^1^%@U;_RNvLQVV=92^=) zIZ1I%mnXCg2-P3Xs=V28pop$4i(~Vs_6857N4gY_)x$+ln(hf;e5?nT4(kdXZc|H$ zexJeNZT$YPMmMu(UX5=9==(-^Zq?51&to^6_Vy8r8yP$`-GBrClzoH zu8Z;~kt`$*^F<@R(($!U(_$A1h%H^k%4A$z&FA&QJrDe3jZeZsP{#FU^sen(7Ar~V zJNiBcZ-(D_G$@451F@1z|K?3C7Gig7^Cm`%Df=EL5dN&J1lk*v^dBqvg*d(wN;(iE zAJ}WLlS1~PI4>dH-@|$hD_Ll0)vSw4D-s9zv8V0g)1QvRb?W11XKTQQ;)&TXfY`bi zQmSj}?GuI8VzsI#@GZ#>bz^n$#bN7SPKOM{HE~f(`r1Ha1n-xWUA3T((s{ zeYRMxDhq;?4pSZ71OrnClQ&|Qm1lmn=Yo7Wb-e|~e<8%R9N>H$IoxTiaOhVSGWF0NjGH0!M@rIz8XKcYnu|mD1xC zJF)B7Kp8@pWy8S{mtO9>daO`7Mt)Z}haV@oeY?L-lK-35ofP&IO%5~xzwK5y=Q@%$AB<^Q?*wrp4OXB`i-DV#%0Mf9KPJpR?(S)VOSTn8HJ9O`aFi;L) z{uzMm=_>xMzxE`7Ng~ECY+WQUPcXT!U))>b4s>!5qP zkimR^ZjlA1#p5+AmYG}qZ|5`*ZCFU@i*B$F?-9oo>uL%a4%uHV2mCnlK&R`qoac}e zMQr>Mw}b=r-FjIQO`VXVDjW2P@X2VR&gMtFpU7w$WZ;9%9x8sWZ~2*Da}=e6KJ9uX z%6nsd4q~p>t55~XvicDUxkZT}$4}r97YeQq?P;u#@WEc@){xUw*4xeXQDBgNJX&>? zXJEQSPmqV9BCBz6cps|~BnR0$%H?Z4UuSn3>j=`Tl1!9W@+#GSSpry24AJAWb*-fq z>bddJPvTZcS89DgcYvl)Dd=1oNP-|)EO`L0JF%RbCI?gYmOx zh4Q?kZX}ICl>L})RxZ|IO`kfvzUMZp^3zCHU)Sj`F!B5 z2)$ROJ^zM(XC4Zp2{14;bOfD_<|&FE3y=B|e@&IBy)5xvATZo}O%eetFV-is)?otN z6Dr5i36-tZO9lNpyY`#SJ05x!Zvsw|tSK98BD>fmfzhT2F2H>Q;A-~Ts1gDD*c=1p zqn~c!#iuR7!TViAr*N@}*304yf4#);3_tB@!~CpgBIgwV*VB3d9Ba%%X&J}7OUUK) z)p&d0=GMemcHWi3+EZKVSKpodAmafqL0Miz7J|c-@DPbJi62tqSq|K9 z;Oj>iKRGJO$Ol3%cKi|a@$|+h05o#eh`)Aj{Mt}Ljt>?|?P+u52t1X`^O1vPS_tTh z6DevD735xxqo1vk%8fU=@&@3e*=o7MFPFbLtDUoq&h!ZGulKX^I{{}FINdv~#y*G7 z<3_=I0Tur10}#?z=ylIljjV6_j&az5J*Fd_Ye5UV7BpNng0|#qCm}#2PL4G9VCx_q zTVMdB>=4>~f!W*`Gmj~()44}hq&c21nhQuQuMUj8F_0Qa5*U*1IiIUl{6%r|1Pvy1 z&BA3e^2vSgPQWfd>Jx>Z<$vH3Q2Z-kLTTD9P7mcu8uqkL&wO&rmlkviVp?2Ch|XBLcso| zdx9^?oo-tLz~t4rO7rpe3}5wuB-Y1ci|0`cg3K$x3j8r`zC1Xc%y&OPdjGoNx0`US z8Q*;$@t?X=OT-N3U>%fCM^ndx0|DX)$b?8aG;_b-!gHTC1PHw8AG#0tq`wDUd()^# zNF2pdeaA5(mGzH!)sE@lSt_Ey>r2R4?p-~TX8?Z!u4&;H8edf^!OhCv$;EP&0KKiL zjR9kAx-8lYS!(J=jDX*U0@!X4g3mckC$*NijUYFXz#%tu{s>~l-`(+F1~$qNo0l@9 z8a&D$GM@{4{+Ie;gsFfgSqE_w0cPgWMJR%BKCM;4GN8-Jb~F zTIBc}05=13(IN`M=+pKG?kk}Ht~Zof-Xbb;QN1>d1kxTNHd$tP8WNx?pkFTVBLN(w zHb}*PV3N|jH7cuLTcGP+TySw-HKxQL1Tc>h% zq=H@(tmSsKk-fOkJapCu%45_WT!z$W^hP!Vzx%1SZAxKn2+n%SJl1O zf|V;_MBb=@{b)~+od8*wREQ=A1U+o0xqD%|@JE_o`m{x!k>I}KMEP3B^HmFz!~`(|fnLA~ zuHY&?n-ToSuYG&0yx&OeVR6n^1J5nANcdu&U9qdc-!EyR)dRufzq zeq>Z!UrzBaZYc(30Bym^S7UjRsLsYTQanO^{R1aTw&pqMbUcqu!F%Ff|1*7JJo*Jq z`A9Rku|5-fvgqV2srqa}|AYsvLzJt^ONWQFs^G$hS@ftZo2urMy_ z@VpB_RH?DkfCNa}ATLQ&TvqJ8kBX1NG@gO~eu3)HGxUDypsA3*MRbmXGvUNSNuRBj zJ8}I5aQN3>m_@1Fp^&T*8fLkRV-wmaDBWWg-p$9w#mL%Znnw@5Gqb6s3-n-l-z9eOJ2IRiNSEre=9r;?bTvqp%f|ZkzLdgD3OxHl zobj0Jt5sL)f3MMIzw9NSKT^v*KD?3HH|d}yIOu-;AofJ{=X@vMz{URXZfl#0-kcjG z${3O-Xs-`Qx-zInt~?y5Gn_O_a|@mgE0{&NED$UcFv)qTqGPG==hp&UoQmNpZl07c zSXOX2KTy%&^t7yb&7#039~v z`ZKwH3r&`Emwz9>)Uci#;)cQdeH@&!o;M`Mbh`R^za)nLEIzLzTF`THDW*`rmh0u8#>vgTW?p z&_WqSZj0U@u^2YVa`<=Ha6J|e+#r5%(1Ut&wJ+jSIRsZbdz9y{S3(0gk+QN1=O6Rk z8mIh#Dpr3L_;3HL*kPl=!Ng(fX>Qe4LzBUE69Upq34B!ii*fuf2T`3A~!wII(U6jGkzSl)HW;<%og zPUku&;I*(ZB4)+}?qzb6y{W_bBZx<&T|=7si&fWMKOvSICZw-kH6_ZkBx*j_%>N~p z{f9J$l~jW+>*EdZ%oI(&A`A7f&%T)>Nu1P%_7AWIW!#_B2x-w6s$P_>aXU&&JfZat6?n5B*T*7frY)n9lmytoIkra*p5 zBaLE7XUe~U!!!acsH1~m)O{y$bWUl*Nef6$0v86v5gwk9Ep5#FTpNLm2vE?2bh+_7 zDH^0xOw`EjH}%(nxEZ&gCoc|;hr8>0xQ5bKd1TN$aFA3)a?h|j48OI_I~8TX8%N}* z?_N~igFszNd86zS!>PDb3uD1MPxJ=YeGAK0SNs3EyYgr@w=Mp8ie8o~R|mATsFD&v zN{m(1bR#w7wiV%e<{+rHDq1x)RdajQloUY-YMy#^h@nk!V{9t7iC&aM%j2q2s%YQI z{p+o_)?4q-x9N)o9XnR{*@Y`h132LB? z9t4d#ie??$&u#IXzYMhM2CH;W19*Zc62*5QoF`0pPUi6O+CW2)M-rtc?+pPj2U)k$ zIwWa<66AJ+3cyO)(er0pGZ>pUY)uY8kgq0SGCxoztZejs^|_i~SRB|s5rZKf+)fcw|;}&PrZn6m-C3B>#NjnHiya*uBMiXh> z%xq1N`{*BV@Gl`iKoTG!@VN!vBW<*t1pL#daWmh6cpL=#!mac^pfAYx7I2awCqa;J z7G+&r3=;7mQFEEEmjy(MXcY~lfU_Td&WDeuo^bvYyHDO0Ek{YBE}s~@!z|M zK@iFutXuEcp{f!f7M$I+3KIxgNc#kEWX%TXhCpisjQTI$w%>M8CDF&IhzG|M($HF* z_w|M23Tfa_sF1aDgP}#}TMSyWG}%T|fgrkH*U?s#&YHaAnZ=;Jy|GH2+6L#?14>(V zwtXbDFk2K{LRixp484v(9y)vaS)TK;67q{$EUXjXFy>|OfXAS@*C69;gHDzt-!hLD z^m~9UBj4AD9DcL3DPyCfdo@@<=!u@$rbnqi)L?%N zFdUSS1N6i;uI{3`UT(>yb@Qps;lcv_3r*9#GWr%7OT9Pmv4ts8a_;g(T6Cvw8iSU! zN7VwHQA(0l4w+)c&v=izuIn^?t4NBKuIe!wvA9&rx>1_&b(1hz$mIrQ64s2Zl^be# zjj6Y8Iaj`XUP|e_^iI`0Cj3`pfGMc3ni}zF{*TAY5kL~VU*e3??bJK*5i@6pt}<7P z)pp)H_SMta$5e`v$Fa8T2{Xn)D zTp{-VS>Pi2zbYbepkEk$*O5NvmDIel2zA%}sIB;UccH2XBaX> zmfCV+-~}qH-rXFme*1`HLPCO8E@5qddmUQq`|JFVGm#ho#MGdZRhqj_tw9BMK za7D$KN}}0qJN5P7751ba6GnFeI$QX0^Lm9zJ@CtwXf30alrla;(qjn?rtBRZ9qk}a zSd3)!%>u_V2yUmReUZwR<1UL1(b|e1EgIK9x=r~-+gobb+S-bXi&whq6rqjdI5-!; zYo$ALc@-?h_|yk^gse2Vx4XN0myGzjb^k{E)JB;8J8y)Wq!He%IA2kkoX#qLO2@-f zZH_w4Uw+g)!S(yNxm|6^wu{&Ytf_1i8>ynTvFNJ+O6M&a@$iXAwy@=Cz?1tcD;D~oYI1gk@37Sd*8jXQ(~0_~ zHO1&85{a$B&aA}V$s#&2+-ovhpXn${8;`mC7Bs95Bmu;*KV#hL$!Q_u;>39J;w(YU zi~UE8bESg**Py*w_M5v4CCgm3t-_N{bn={kj`h*X!t^WYgX04H47|`XAMy*Onafhe zXUH}^f5g8yfc-{{tfjkZD`v1_lNTZsM)qj+FzF6UQHu}BHgB;zzGR!Diqbr=QH?We zV|OAa8`v@d1_M*_+G?rz_4bAHWRv7n;X^*+KX-W&E07 zV&Go{9}U7y9@Mtv51G+a(jtN6Y}0^lquNzCgRVXb2@ z=CtKdM_2({c-d@;R8lNX8}pJvOKrhFSm>ji3{a?$2eNGoW$i07QkuNpXi)wuj%wxU zE+-q=92cMsL)|iR-)+J2oB`B2@xw2~m4(Nb+T=d%V*OdnJ}4O^W$LJW@L)f9#l1E* z{S+62V8&Sv$6Uplt6V@T%aU!vxOD>ohWD{HGP5i>#})_rX_%AHkE)R9XG6giFR!Mo(n4vN8Qd0k3io;C-|expkgKNaQ`VRt8J`IBa+l=;IM> zj+9@u#yjmh*vGrU%*MS$zW;1lvGp#?^?<*X#=1gPOLZgA%G|83&vtjwtT*B!y{VwRQkPJNs+h=}$@*Z(M z+^ugrbH!z*Y>p)tU|8g+X}FN}?D6#AtB2Us`QQ_TI#bjTW<2EX5U_{vroFYrG-K5q zsq@n;mtC-z8WjIRT8n)>wg~Jf2X3EzDy~E%Nzy62B-1uVIL>!|zsmw$)=E z$zPLLclAimSamR&u`Vo@Pz$y}k=gHQ?~8b08!9`Q4Ke>wrJsnb?yfv9pSpqCUR`G@@R~ zf6=j*|6PyvP0UHFS_Y*!fybn$NWel9%oZvh;o*J2%&Aem1Y=3*Ert^3McZ*!c2=|c#6HIWCP$hBsQ+W&_T=dT{3{cqO) a<(t^{k#MoZb#9{w2u^1(b`3VZ$^QguH%deR literal 0 HcmV?d00001 diff --git a/doc/images/se2_interp_slerp.png b/doc/images/se2_interp_slerp.png new file mode 100644 index 0000000000000000000000000000000000000000..7aff8d26bd59777179fffdd096b706a3a973f32c GIT binary patch literal 74792 zcmeFZ^;?u*6fZgmiim)S0uq8CARr}OBGMqBbTAQLNw>7bfCxhlLx<8GLk=a< zQqm1~58rd{Ie)+;)>?yHN%jqe?dJ-_Wlv0S=)Q#TNJW41$I4N8sv%i+@48V&y z+}euCfP>SA-^c$@CM2<@je^HlEPlA+Z;Bz1<|k}EBw|n44Vq6fv!rhY1^wIRm_5C5 z19IEzU(*#fWNv?$0;?JyGSTQ)@!i^gOCO>Vb=9X9b%XN`R_)fm^5aQEZYl`m@v~+K zsqCj4-~Aa^1BkzVWS9sbss6-|^Xi!mDclaYM=bP9GM89Nl3++Y{2seWgus)G5Ssg6BxxOF zSz-eh>4jtN=Ta4jQ$&+4k}Xm>-mD3|OCJ@DXGVHLdGguh8G(7$?suUdQI79~N3aQA zjpsO6-bx83&Gs5%K@f|Ex@Kt(POUy;ku=Q0CpS_Hk6<>gB`0%gt}o+!PP$;KTV_&p zAKHp8Gq8cw1>=ay5pf zhHqP?AS6i{3S-zhXBRDZ866+hgib3oN@UP+ylZ_%@qkqx!VpvbNkz&kUoR(IbylT7 z&HRVpXj00n86|jjM)vGCrMF_ktyX9rTpaHq#%*`)uWkxf;0&W|E7%pL*Y#PH^#Y?vf{jbB7Cu3%)D=UiN+wqgTx(wBa(j{b zb^NR9^BW4EmfGdb5=wn72+EcjS{cF_0-icDSTnH8-kv1aP2X%+vPddZuAnIulj~MM z%eBjH#n>cK#puPyCX^?9iD60n8%>dL`m`^`HC8EhmScwPLhTk)4%-529KDm|a!PO7 zbA>ULL?+$mUOIRiGq-1A>RI1EsGF#> zsGX`Ut3On4P}@_VQllx18LhV7u?`-&H9|VdJMwANth7u#Hb>wt{E4Qq3(2VFEbS2u&`7O0-I!=0vP)p&z!d^{Sv9%s=o&u^8)i-8~ zN*^>`_xSs8)n&b5Ommb7HCH0`?W(Q0m3H!5*YD7*>a05BkH#hQbJA#OksO_zv%@HyB6q zSMkqT_|Bf^1QrA~|3S1FCe|j(CBhTAp*&-)MOHf8Rxq1~R-;A?h-EDqEt*PF^s`Ax zG!I&&O1&%sX^TupqRJHz!d6G<+2#!UIjg2sqxsUd`EvT@)jwJr0*g<#9;~V@?DuL< z3ij9ZdCa!8npgCgYt|PAultU3@q6%R=!Q+z*Cn5k9{Ccb1UJb`Oi)>@c4>cPWn`e?6BBhR^-{1))Xnp6GF3vh4C{?_(^5Xm;}6;a+qCZ;Wla ze(J>&re`Z}inZ*lw|+BjDthrLt_ZGNARbjESJiMBGW*F~wvyJd5$MLi-|3zq3v5`Y z`6_43&qAr=spW)ySvj9Q<8ZIyc7Jc5INy5FJi!h`nRi$k2T0 z(Y*dj^Jac_^`Dua5xDjm6q;i+*;L&^Pm6Yo{uXG!XEhu2NDR4kpoUZLm^7>M?RGxw z&&SXsWzg$O>k5Cxs1*fHOMk+$3g0!9?UK)H9hQ+PiYsD^Irv#yC0emtU3!ZgRR8-t z7kWurk(j7aGgi)rU@NpeG&}C96BE9iMio!Z4*uMFCU`TyT&dxl;ZG87zNpes`h13! zSfMMjIBrsVI?&nnZ_0M$HtFH#!@HSIV&mh`$*GgV*^-U{*7TAFT8FF+x+RnOwgd%_ zBvST#!;HH7Zsz6orgL$HPc*lW&JKz6_o`hNYWEHbv0br~?6hVC{7`?EYjme|XQ~wK z-3U_dx?WoB>aIkuy&b2n5Egao+dd>LdDJLi!tJ<}vCy!7G_y7LSYKG^oc7<(ma>0b z^DV2v+)=SK4IXJ1?rU9#4(IMWszdn+1B)5Fm&FHO!Gmh<#=jg){?%OVF~!w)Y5JL6 zmWikz2V7=5>NwPzw_7fs7wv7#B&{1LHOTu_@@VeoPh`53@ET@b^cGZ7nHl(gTXmL$jnpst^1~ncqlM=D-^wTj!JgKo9|Jm>UQO=aj|}Cs zwNG%_v!m-($P6z4kiz>QtL+4Vkln}p#d@DP3}6+6+F44=S=HXc+0EF|93u1f4Xuo& zy_2((siV~gXIepaE`j))_rNGxh@7OjntR&Dj9)b6k{Hy#Aa$X&zW}{*0uB4% z*LQmS8CdsO6seT&)4mZ3UFgO#<3B-0vSAlf*TwqzoOYbGv^^$t!=0WF5&eDg^=yH# z3PLJISXJWV_i}sSE0;8o00>rLJ}7+suT_7Y61Pw6<)4zB!r+qQrbTtjzW2YQ^8g}WuHZ@y4u{2rY#FAq~;NjPmV zq#m*6B@S((>S-X@-{riUqfqOSTH0O>rTytY-n-Wl!yS6>Qdisw8o$+Mq;PSy?y|Wy!N2TT>(0 z;qa^k>lOdks#}mQ7`L}j{~l1(&XW)NKQsytJVn!$WZo&-ce~8M;=XA_19=M6z?x@f z&VkjOn3&k#cjieg)?=69{^lH{?%ZZlMy}YHlAdl`hdSj*vb1mV&^XG6y2RCpip&61B|USmD^`0-Wiin$Y6r_!vhGUa5%?xVDC=guOF0ddj+$WJo2#NVezO! z!Ur~W4s%DM1A8I^E;B&iR`x=91Ky=yr0p`$CZ<`q@&*;~rdy79sHZ*g`P%S%_t=)>gDA+M*zV zB;c`VK5FeDQafdA-(9r(;gCQB(l(ps;CsWS0S~Vf?$*22A8IVNZq!XCIYWbsIfC*e zN+Jim6a+rA*?MRsce&YE=B&|_gq?!n(5-iRp&dUWqs*7`EemLGqgA507_Eo0%49l< zT+`l9_~@)J`wZ`lWgnSMos}-M2fh~Px2rQB*h^Gu!G=7S(!uu6Wqokx-2r2)QvO0r zdyxP^0b6pb6z-gD)mWaX4z%#Nk|8^CsR$XKRmOyFh~zJHn{ky=w4AiztJTmIl}{~@ zeDb7`n;Jh{p)ia!mzS-max*_@Hi4$+2k)D?BjNUC>6|Q8f(5v6lEzf6GIXY1S!2S{ zs?04gV#);0#h9*C@-G7iB8e>iw{r&~8{jNNZ9iwoo)o5;AP+-ktmUmsQ`E+$_EUvf z(>82r9Z_l)suQmX2(#-%DX`hHmn`5-ZF&0oHtMkl8*8yAi4H(h-@y2@-O%k0R2Oi* zobeiOQMgP#{}eJaa=|@g+*MdqREjP;>ifb=8C8P9QR@?+>d`T|CWVeLkkf|mroWwR~6P7J;(g1 z-#)9Mpx){s+hg&`cDP4;OAuUS}6Wc*lNszBJPw;Gb$tPj zU;N(lba}+k{^OOEm4z~EUtfc9xWU2S9g3X(>M%Ri%+C+`EOX@O8!1n`8}sF3W;cHQ zdVMbKj5{XyY{+E>xsjrjPu&65#FA37cKPVleYHY$AfEFl4=5yBuSQR4%IJ--eU)uic?;{M}<)^ic%dwJ%rBn;q4Fc;W3u{wjc{oRKp}1q)(BY6H*KPL-PkfN)Sm<2z*hLyUKW?9~R`o|6HIK}MjPZm~ ztjY`|xON%V+6TUVLUHt+zxtS>&;S^7hB?<9__xamR_&N2-}= z$HN~A8v`|b!Xf^!_BZ3A-dK?8!}j)e?>U-ui%&pf=tHML;qrID;LEf|V22P0tLZGj zKX};-QvBHsX0IQFwW)VB-hey+anTN0zg-23ea(=cpil+c;dx=vG?g`;*zs&(KchMz8Qz_Vx` zUEBujmLeT^|G)r$Y9Bj4De<_A{&VFSvLlzwc z=Z^R-^1(xh4P$O4!Muk7dC=(vFmis)A;g%5*81?)OkLAXgniNc7eMsNPxSJ5LF_

WTqs5lY|MW#4K%+d}0l zb6kw}rwiLx&j(d*@Ou&m%}4Ohg4bOxe433Jg00BZiUw1qT=`o(XVk_ znh&NiIG7{gi)_S+61zNxSIr8o`aIGvQ2Ubfo8tJa>FR92?{bgY@1XIhVY@YyB=e;A zeen)E0jo7sZpem@x)KHfK~ocXd(FdPdFu*6V~%%e7;S7(QtB*X>* zSO98r)c?D|@w0j7{@rOXQFkGyRz1$AHmkbJY$h|6_?{(;isU{E%7`GYJT(@NjHH1T zukd7LMHSLaj0eCMv8s>=tLD)xwpCo(Bxv4&C>n?64D z@mpJ((HsVRLGFq!|9`Af0Yd$sTW0N%+A44EeO?DzrBFJ41OljYYHh-Z4C-h{3 z+-3gnx6eW0?kBNleaqjDu$wur+XF>2F5_Kpjr94-BomN*8cZv|Xw%z}k#VtR#mvrb zuFY)9=eEW|7{A)~;K}&cpiOev*#81CJJkdyhY&i>NAZ;op=g@X{|V4`q`QX-cm?<% z)fEfM>K&+J$MWC0?y{VIGaw`05t-^1i|s4FP3h13pOVAaqv2MHk^#-g-6*q)Kee&) zY_<0w8lc7jIwaGl6{fhGtTd%@xkDh&02mnLzFsfSwHuQ$w59NK`bhekw2}1}{BD~^ zgv}QJ4J-K`+H~gzv6cPJH4haQxtcf1evlbDIKw*tDPby~X7M4ALAd3|jnxk4T8V{A zOJY8azFUI?!#ejLhP64?h^#h%Rh_XegonzKvs*9G;N9r5FgN}v1@sn)NPG^!a9r2o z$@wjaQH2$BaJzOB@L_D}b?RhC+T1M*m3s%*INF@z7Zq)|xBcWM1j6^}7_bWiR5fYG zjlF$kK>P%d@qRg^(cb>WdADUyUntFlw?NIhh-A453-X~4akB!DFWkB5d1_h#5-W9- zNJo47*M5{C2B(zjjrUnpocdJiz>liEmlvYMeAnSs>B&?OIp0=2)#g`9UwcKYw~52K^255{zT=4kc}Kr+fs?9oXX z+x1v;$0_{CmJoa5!Tf;F8TX^FBh~vF`T@|N&|gS@WEcJ!fTmUK@y$VAvl@*{;(@r= z;$NgN%Y%int8YY!sVlaR-6BaDI7_tWKB;F(ODjGt#a}@Ozp>GM=FJ zh3FZC)QX_FlQ{`C8PAkKzV8bmXK!p$>ArKLYemyg2d-v9%m-lu=1MPGk{0 zx{e_JE{{^et;9(*Zu2;sLjV1X&|Idx4B%t zl%!o<1mf1Wfka(e;cWPM-Nq12(0!a2VgtbsIcqU*ldWK0Do@vS{2M>AUIfMYmia#^ zIg*wfW0iWQsc1B=D_-&^LJ&D9lz*DGxMzeHa)I~-43J&-L?#=o#~M*MEs&U41^#8b zN(k%tk~28uv<8 z892iD9f>Y8t1dxWsv0QGnC5naA=gZwj0*EH3|Bi5pK>v2jSf%tc~$x++ekm~&;!LU_cG1e;4!1@z79G)QNKO~NM z0}mYDyqBwE{)*WD>ui)mwiR#!g?ZAi=|<|M_r`9`lfOe=7=AKu^VnrPag^%&#aP%sG#-xn5^J z9eyjts;u$b{s-%o$_t)4C)nh6KyxicdZZm|e>>&)!7En74C+YXm{CuzN7VwA2~-h$ zy@m7?xVE@BBKURkUcOAI$%U9(Avmq zl1Ss)SzOUf4lSd_@uL*~QAKmCk` z++w{AxC5IOMyn6Ppxf!xJ3a;D zLJ>5-Wln0_YjrvMpt{DRIu5xTyN&9mA$P&NAEsxZ=@%m~5a*aoh=$w>)wpa9!Pv;- z(H|r0KIFiGUCHm_8To^$!v%o!^Y5O2SwGBb3vr~{@v#VpkUs^hLyu9J`@REt?ye7E zEaWaZ{QToPjA1r$X`mNqtQWyQC~d&4Li^O_eJC1xf6FpL|EU;nZm3)F@g0BSZc zpnK`13~w8=Ed*PJ)z8QbV@9DSWdkj=3ENX#i4e|LKw;7(Kqk(?-SJy6-VS5Vr{JVc zf*5BCX063*o@X!>*FE9y2iAj~4?ll&7cZOwOlUlKG<)HY!8FQ(9Symwbx*cJ&Inr? zAfDztO}KnR;}bUN_}LdrypT^I$I3yQWkC*_*#9EspubZeQR~w|Joo-Dh5t|d8wDCC z0ym^F3z}Dz)k6Ewis03KOIAPmi{@3}coWlzhD+)EN@txE#Yiww26DG#92ew|Vm!b^ zpQ3^RC2+4bSp^M!Y|anp?#xMObIA3$?j?dK>+YihpnDOFN&|sPNl-(fl%jW4U?|rS z2FP7fpe0OXC=FfX?1aXRi6~PA8_+{;MS(@Tp1if&d`HA#2I}m##`Eb3*3%nc0CAZM zX2T1*ayD)`oHE=(4bm?pUiut11^Uj*R4^cwlu*n!!DfKCCdMqw5;{=eBDgW0pL_vy%Q zVJL{MDaZ%GJ6>MD!}t}L<@g$J2H^nWCm>#c68=7h`0h2aJBFC?ns{Cu5P$uT7+{N! zSwN?Nm<2<8>zepGhM3~NH%kCw(24*`2#UbO@}U2ea~p;N^nCy6;oh##PJIk?DYNUY zCy{^SwJdj;sP77@z|XH1{NmqdQtvB4F8*UmNt{y$eqN}4GIyoxSR=lTJ1BNNQx>mE zgS7L+O6KJnC^%LD00FpdkfK2260NdSvmy=s#}q_)&7Nh166=+x{ttEH82viw;;K7A zWtzyl(rbgH{-ved^ngtcaR!fHL3PNmjj#IWO&*duwSE+BDe#9&S=c060 zf?wIQMh-fF9zyQ=u@Pf(3+6#kV?vV#AuoJ$nmI#8rzQHocQws#@v5+gft-e>L9NZx zoP-kpr#j!3neHY%WFYU-*|5zp6sP5SZvL9ulETY5gCL3CHjOk?ckuF6!+mGx*b ziF(PD@A}Yws%L{lc9==(I+}JxfNw@>&WKx^f@9YMFJLT60bj1|Pxd>1);l+nGiiR@ zRV`7dWHFxb^$=oW;VJ@(OH{ zDpuypkR;f}fCR;DPnFn=`98b@3aEmo5kchi?XoZvuo<_J%Q#-SxB5jYIWP(663kJpQBb6pI4pbkxQ~M(wMBK?htlH-?=usyadi%O#uHTY7hy?ez6N>u44Gu(2^H_n z9aRhtUw{_Enw0~UpzE9BIwiaMcLwg_7Vnp~FO?b(*iJ5wZ0{teC#2dZu9qYY_$X~P z8IqDNl4RZ^o@~&a{dcQi+}u?ok_NnP$Km9!Cip@4_yMuU8pFwYQ=;0B%HWgw<#uPC zzb+>zqIiC<7=#}3=KPW+ji1rpb=-?76lGdjHnVvH*4p{oYjHo&@wqoS>4}4kZ9Js0v>CBRFTuE0cQD9+s-{1N3ljFwM-T{S|B{>F}4I}YY zjR)wL=03<@oU$MkRZM0b5SD6VB0sslke?jB7z)Mbw&eKUB_zG z{qTb`zUf?{%WUy<-P~9_MN!a8qdzSMu4`^B? ziW?Dqc>f-zhg{-i{1Lh!%Si8aC`*pU`W#6wcH~4yXLuS*Ehr?$0d^a9XSTuGPzf_` zdnP>y+cmr@1go|?R@L1Wb{IO_WaxW!WNsn7>rpVi6lNH2+Oep7DY;eCQM`I?co`Pb zneO&wrR%)@yfdmZncK04Z5JiRhL5kp-s3gLN*CKFU%}jT9JafUa^=_4oW1g8PFPGR zi5EMi7yR(*<+(BVNjVqYbfF6j-gR@Bcl<`z)#ld1wU3>zMiDME>u17P2V7c>WNoak zf1fu98?1uG$5do2FMU0OFx>Y%CO zs?v(zTQRq2@Bb_8q0()Bl7FQ}NELl`<_B7RzUx(s3p7c3N=W-8W$)KY83+Yc!x}na z*Upjn&sqAH8~J`ZjTg2c3=dmPtqr*>)y*a7_49Gmth0M;3F1lA{S-UKrK6jwnhJVy zQ0ty?zTjuGo;CWTet{a;K1dCia$4l@tM^{2<6?;IEGAu~3A-IQ_?$27W*q6Yyhn<4 zFBNOx?_Us>JpCV5Yccx6>;(|;>=5Wyt?)jMN`Y+7lbSRfaj&5wol0%?)C3hPgo1Tn z-W%nfEQ#F-(?g>xTl=`Z6)DNQyhV=7*UQUhb1!R7EI=G+JHn(C&Uif~gFT9q-6YI9 zQVTCm3+{+`EI%TSacfXm*TJmVEWP1nxmm?wET#Q}ju?}7j)IutIjO2a5%dj2x-1wn zleT>Zl$wXlQD7-`A$=BYdr#xaW{5t$@-}?&$U*<)d}Zm}V@E_=tMuV_zoTu?yfg+; zWT*aWTSZ>7k-J6$X%oYg89#Rl#}XZaW`*IpCXekG+~lLjAf}c)gCy@+>Cj1SuU^Av zh;GXsg2$-&7&_Ns^!Ggx;F*p43?6f5W}fK03Ba?SrooB)Nnukg?&E0MXt7IE;+VNB zA3>LH_V#mJKiZZ4uBs-srXw$8RLDZediPQfAKkz}54GFGICB!oK%CRcVxN7Yw*ghh z80zv5hYcOx4ZIsCzj2p3iJ6l&Z?$DlJBFo4CG^SHJm;u4^1CZhpt0nXNkUvOzG**- z&oNP1whr2}?S9NhZ5OkK;px$3TwKz#m#!zj$ZqXOmIUUNu;Vvjinda141^}Xzf{ha zvvyu!q5A7B%fo`vr%7?np0L;26;?^RcWy8zNLOZs^o!OV&5mVVz!X5V*qC@C>;|IW zuYhUK!VuX8c6*<~^FJKGqbgHGc0Skd$5I!3?dm+Q_x_E&dr+cK_6!zFU~@Ff+Lj%m zT+Dhj!^EVF?#-GyA2pmL_R3(YNsI3R4(b|^R{VjV&%$do9|d|$+vkyK0#E4voZSy{ z&2(`#y4NWq#zKcYUp%{RF$1Rat)IWicQe>N9}45%ZP@NQt|q7FpFwDQp01nquzO@s z-@9WYbd7e(zHeSO`ozjl1}z5$kb^VvpN%zZ3iT4#tftcQMPAz zs}Rx{ICs4lV+|$>3t>z0SyOnyjp{Zves*=yG)3)1#r$9~%+RKS5|~AeW)pfgK5;xnk+{YVUE^|Ocy(20pBRcaS*s4bT+sI%Ei$>D z)$pe7(X9fWaW3-vshCrP{(Vf1o-T~^boYZm5`i;L+7R&uTcG$J>|DgyJd5q>Y`Qvv zr-UtZ+Fv1U=Gf^l2x8#M>Wu5L$g|9|v@}r=s`#3Gww%hH@~H&rV6pm{r^R&}1h+mC z*!Z1Q@x77R*|<8VNlq?vQ)B6h;P3W3vp<{_RhDNs`9o$KMofJ6y1#Goa~{bA;z_P7 zR3umWUPp|L#uuqG-SGt4=&Kzun?uwtdhR^J=Ob^=nj=B+*$>UGOz#T|j~%I#emAfW zv9-PEQZhA>?=!Ri&NXw4O2)g%=i;W3DyBXt6||hXK#mqFFmOrVxrry?Wj2c<$W!6- zd2okbTg6G=W55eU6G2Zk%_jg1W}bkcVLJu(O*T~biru;vbI+IUyG4&=D_KyeVViE{ z^UnY#gU(}N=t5_W({5tb1hcVF+CFz?OpeS_UaF+Y&PI%kjpd+%;7mSi ze5bz_9mDu;2aK@^L^hzn{sj6`tMCyqNzh@3p50KezL2e++fd?U5%YuaPL3JX7j$!( zp2ewMH(5sZG92Nt2{kE| zdQ}HiHLs1raKzUmdq)Q!!s1k{hQc(TIZp(yD$gG24k_))$73H*y(%!1yc|ctG?b0O+)_<=p((wWO1r&2cAC zOt9yYDMLoo2b<~RRHsj^r>PWKOKbmGS( zd)carPLgK@j3+$rDZu~jH10ke;>fMMq=OS+4^s>lDn^fGOEj$d%{CmNw+AvRSNid9 zR=5-jdQXg4yQWP`5GC7;*-TkT_9n0{H=b>jX~HeSn1P-t2)s^C_S(t!7UPx|yT*R% zWxaB&Ye!h*aEV9lwS16}X5ynbq&1W|j9@2FQ&n9aeByLiB$ux{a5)lxaW+hxz4JD{ zkD`OCBPz8em@L9&WcpzOGMoz*3r~>plb^xiV~c5%5wU&|ZotxKzmuK3j-KPAC}cvc z^7J{*D=udC#KF@J%L{YpXuNFn2M%uys_Z#x9J`M*S&Rf<+KCM7_{EH2x+kmZuTeVA zRHQhrS4!zGn3PkbThdJq%bnC{n6$QcGYL3O3tJ87mOmKdNj&mN3k9uLUUcZJUqL~CI z@9jkMy@zdIR$uu%wOj^D1atiwTy#9-U`;{fpJ-j}Z#B(@e8nf*h=a8uxZmr%WAePe zpqlq5p-L8EE|RhKC~ozp7R3aQw6vdFB|4ipmZA$B@vIsO=Ov&UinI#lledgSp&O8f zQgu)7*WRQz5fgIVe4$&#_~AzCmZJ!DmG;SkPavNCD%t<0fq-G1_(4ZOF9BGv^MIKB z?6EYx$?SgKSg2pReua71WL3$-X35_97K5)YM|&vD0t=d>9;zIU6;vo2+R9Bi%Wcbw&I7#UC6pj|l1v(I&WPX)BkZ8%M zYqHu?9*`h5`^jkNt~fZN_w`kFQ*mFuMT{-SSV|&7ad-GwpjDPnIt)_zZ0) zO^8^fdV37*z`E;JrR?lzh;Hs%)h&&|857FMW}V||Ea~Cw{5`10(oLhH+Uy7DGgqmxI>h)r9n)-^tmW_fC*@I*RSvK57U3-e{2PBl7(XWXZzO8 zR*H3Jyc8B!z94*wiWghSH%-={HqhoxetpmloYN6arnHMXrh=#lJuV_K5j39B!@vMrD_YH|t@jnDkHlBo23&HXTGf=EOT^C}=xi>J3>O_SEq%P0!1t)#7=ip7`cn z7%mcdUr*N;3gx;Vm1Mi{B&Rl6d%DkXfTXPls>wa;)Nw90>v?w6(XrX}%{`DUZtVcJ zS|^>;pi?u_O|v~SePb;2e+7MBe?%Vj<8UrAc5>pqebjO*9=(adg>{9SJ*%+3TRLzT z5amWokm}`@1mBaIrbE7xFxg;j9!_m8bwnmRqZwJ@LlIGwbNu2)!M+XKKHvi>xxJDr z7wFT8bwhjpiQ3VPSzEi>E~RV=N^TGpkdm zBXG1082ET&E;Q8qUIyzi?5YN5sqb0xmnNkK zCXluk>l(lTkapC^sdCD;@OrXB-}NE(K4`k| z`@CX8ej)e4MC9x)sh9hH?f4^Nr^S%X+u6aPrl!joUcF_ez(o00=a79HlfWLz#=Dn# zK_WEy<(}bjc_Kw-H)DOc#hdU2gi&C~Buu?9g+qaj)psBQ!*9EFP+K?-YwR&H_Achi z9rJPn=pr1w)=9h|fYf0y0nIcJjW@5du*s@y%6PGe>-JIo>C1}% z@nAB}##aK1I@e^KJ}NQ0sDZ~Gts!5}wz%8B!gc#b;tNJM-W9Mvgpp~mxb~1Ry~!~y z**aT3S=r>8>=l9}5_<>uEWs z4wZQO4XslU_}difu-l53BWnEOJF*qfV{Kyue_S$YwMNum7?hx@jGm_3C5)q0v_54ta5tTDEr;(}2y*)X`|6(j?(U!^DaMGbwDRA^9Lg)K*xw${V#la`r zQKAI9m$Q|VM0~feeULKy?X!@O1p#C7Amdem$dCsbA`z-A36iZY`hI2dWF4T^{iaD7 zJBE1ok*j^LcV_`U`y`lf@-s=FbZQz;T%7CUln~H`NE0+g+HxPwyq94M%AzhfZpO|V z;?zY>sE@mD@!%4YoAwUnNVkey)hqgtu}|#I4CR3OLf8%ci9(cJ#H}B={WF6`8|Ccv zTI-`(=(_u|wGB$#?3euzeX1&Q3~z?L*OYE?Z=I_95n!Ic$8O?HxK2=b#bj% zI3N7QS$<3Hu~Hj4RR+yf;gX3$JKZUU0#nzkHIrumP!ssrnMSxu^1|2TM`y^Wc=RCh$ze)iIA4y(4J?h(X;Ez0teXkttEy5q>*Q!944gU zi!|*q_f*m;W^eP__`10n)AgJsXLG{Xnin`HfCUoIs%)&(d)W>7))15BZ6c@N@g%qf zt@4XQzv|kR4Q*{`?~SOoJM@NEgcY#(xyu;y8zI*%jV zikhr6W05-^@77~vVX@!F^WffO9NcZ)(2hes12i&MMj?LE;0z6IoSPwStvzwyE`JkT z`2>DIW(B`OlqTwnlnSNx73&$`x4f0KhNiq9bhr)Ml`*}6H(2PK$9rMw_m`R81UP4E zpR>5NXi?3c5~U;3jyEoj@orzSK8S6p>jBOE(se73DW~k3W+L^57hV%rIOWeAQ*U!B zix^7+5Ji%rlsG&_>WTOfr;;7yxFa!YnU!yO*-N7QH9wOt<2?YtxP)I>HEje&x>Geq zUAOrvQ#>v`DE0Ou`!gz0n~~Jq+wQ@{TqRyJ*`vV+3Ki2oKZQjS#yL&Yen!sN>oy2= zku+zQa_Yo=$o}QB4^yq^Pvfd{n~L4`IjWp3Q+_!)8(XFUb$O(nGU-^Ok#mJKAIpAD zwvBFbE;oXeTN%V2pXn+?My=bwa`H3@dCVOdB4-kp4!TBWOVM<@B$?Iib<8u0eCxXl z4XMl@v_2Bv(IvEkN6A7j@@op=6R_>IhqHA;U2rv)o8rIEe8H!AQEA~MF[^&@ip z*vub^N2(BcF>;zpBwY61rqGkMDZ7e}7~Lu~eN!l&(`CKK0;O%_a7=K*7i!nz^F2Pr zHRAa))8#)>UUz@U$(gF0Q`%bHgCld<7Mv-19p5Q(gzF5fy`kLHBkQZJx$*^Yh7V~q z5c~Qk$g^y^8$%Jr9Su;;!ryt14nRi%Y!|q0aN7IToqVJzCGwbi>9ia!=+xf-JSAC9 zM~8Cb@8~+$7Xm4|0TI++RUvLup!CARbTNCo#>tS0V$cKb)9i@ikcYC&K613O(B0B} z2M)FUY+PRMyA-P$Dt+(dOp&XGR&_XENAvA(H^!JI0q})LYP~}dA>Bbgpiudvv>i@pgYzcwtBQ`#9Xsfn|y)!QkhB!bHcA`Y`U=@~?uYQg*jvFpAM<=HB>k%J;uP0+v6FWyd5cW$+J<0L zrF`L^H#mlMuHbBNE0G?H3ZW@rJsufMbT#bDba7+;25^2jz+eCmTFDe2zNVt&u9`NH z>}54D#{O#e0W>IjQ2B~E#_b)trqtVwQ-tC5?nB3o1PW-FB2;6tNHlNIh8QLg3O+z( z2Mr5_E$M=dlNDXXmK@%1f8c-7r*y63YLWbnb>20+E1SqEfHx?!!=qBe$RfCw=Yuy@ z9Tp;%HGSLMGeGSK;BP2ioi^e|weRMH!zN0{QKQ5lDiZ$%QH^vF>}NSsiN1Hl7ga}4emB5L#rk6V9UP} zjoyod2+X2H=3_DI6J*Er##3W*qtNgUUh0q0`&ts|^9L04uz zK-9#mjdjD(jBeSbgqzMaZ;a^j8%SJS#^u_3vqxyty1H#Xx;zc;Vkqc+N02T|zFEna zIzW8)%)_S6^lPmAm`Bj}5uI1MnHu?y?MJRu%$uG!I!41O68jBfc6#Fv?&N7y5VNN9 zfzOe9JcMjP<)+A*FPJR^{ZNL?MTz_^dbx9B%lB%AKB>!x2<0N z&$9r!sQ-(os|>4hiPm7y-O?f5-5?Fp-5}lFt%9VqfNV^qVf>@x}Lrn9bbx`CYlK{lfky5!^UA7)lH1v0Q_Z2HUpJ zT()Oip1B-wmZtw|WB3&S<7MPv6bqjYSvv6E>5Zfd*(f8}l}9CWo(7~vafwL<%w-SN zMdqa(d;vnFcKO`L#U#f1T#Qc*^-e-#2JQAa3tK~F6ei=c{e?LZGlTA9i|w(IDCKsH zkx;a4=wBgpQTxO=M>Y{hWWp5Iv?6+abHRXxyG>W)9oTi>3z z_%XE!GB53K!9o&RJZ9p*qUSGlYJ8K2y8J2ghS&2Ex)P8jcOLQ&13gTlJvcZ`CJA2e zJl!i>#7Zfj=#`ayM|B=I!)2$*03Sl6Y61Q}d-kQ@RHsj~{=!>HP)rL$$S+&kdf7(IRN12P+3O6kvTF1DZpD5fxsJn@ zUsgxGwIxiit;7fgbVa{P5niDFVlWEHQ6}aqiJ-mI@e==&MAbaKQCHEAdi zxc6g-)FJW-=h&|Cy8_K1+3)ebe%_2=p@ZD;t&#B|00#5+jP;-eq7m=@Svc60S!P=K z{JLFCBTBzn;L?(qd(o>I$GlH;v8oCcsQ0Q>xA@-+5?%B>WPosZ6IEMJp=C%SXzN!j zs>Ohtk&Rc@Fk{X2k^I{bLZw*qjaPYrHVEIftS$?1Md+PHeZ4(tShcR{3xSBX>n~HvJeSwY4`nsDNcE%j;+9cC*h#bQ=lP?aQGrBdMa0ZC z`SS{Pn1oDq^%yT}wp<}Q^W&e#sW&#t(Bj125e*(K+gU-608j2%X}w+E1|n5eIKN;0 zt+w;t{OUCPo-Ke#0LS= zdVA#gF!vmNE_AY4OkXw%$xankF_!#7#xOy*oTW8?fFaV8a(jZBs4LUQGOsXyRp?Bi zBq5)j2?3D(vTaIe0wk~^S~`0vud8ce203Q?PV!TD{V3|Ek4>&UA>T80U9T&JIYzgJ zM>9(B=iPNbQm;E)S#XvbwJF_r%PfFDd=<>Jw^79TcR`E)fTO-AEuLvPU+vYl*EFz4 zE`#ZACe+zfGt|5NH>rqR#%?$~D++4!vwr1x^O#fpcMepu@$U4v4)~(W9F!n2VV}z< z?ujy<+Gk$S&J8kik?^VP!8geit;q`7%u3*{fMVd}ybO8>xSHSl1J#(pn@E1}-ikyu zlc!48+Hp^Y%;;9nCxuE5PCtA#j>+& zz)-dj$YNfRV14VT`WPAvKhkzZXr_>7ivJ>|B$~{9ES7{bR>bzWy=A&?>vyMjbg9FI zt+0Vr@c_d33?C2+$ZpvIm5rL|Z*lHS=NoV0n^3g3vy&DV*H0=Rt~x&-1Oku!uz~_` z@-Moo3(V4u8pwJ~dWk;&zwT9c*x_dAv_Rmt>`?~Q#>U>(tl-eE|2o^z&V8&JCTWWZ zXbot*kAZ@tY-x2;3;;uHsG8~EG}MxROI3sy-dB;!Fx+VN6mu{nQK(7n{ccT|M*5S7 z&@-MZnisnDUXx2e<@SQe?BkEjBBg?(dudb(R>SJm1DrbROTE5yygJ+nf!n@BeE|pT zB(1q@*SVvHMYDAvlTIsGS{`V#%sbQs4s++IstdXfj_vV!!H`pRcz;Vf=XWu(C$Dz;g+i@wMfP zaEyCu0z4?P05BxqdzJUpT8rsmoeTo!rf~AEwpuf7aE|Tv59`%CL&tlSm$gpwUZ;6p*p?c8 ze-}0y^JJZj3?yDUTm^fX{nM7O z0YqxeZzEfbw1F&Tn?$LOxig1K1`tUN3$7N0O$7z9U#+9HR$@6{>)_BT%)gS`~lWeyz7?In)8`(~knwfM0geJq&LtbD-e;ZGjCmFKSQ;3=& z__djTfhzpoQ6K*R*lk4`4BJ&_(W`T01o7!FZp>@Z${2C=Cy^!G#)P-$*jxB2DtG6s z>2QWKg)L`Up4gLD`SiVd;$kW%&_R>i95tNvJ(h*{>Fuzi!25gujVf z5yu*&E4fK>5(ljB`37Z(;@_34&EH~0T0K|P2<9eY{>G<1;A+6ry}Jn;kkBKK^EWck zmdrIu0apXvc3vZFir$6Ie8OiPjJ*pF`3|BR*X`ytl$3k5%j|ux`p?E$GU{74o3UPC zg(i#*9hL^k%cd)9*W9gmO)Sx(<3}rJs-_k5Go>NSnTFF>98u9v1sllk8^)K*gi1T$>TKeYmHbU4RJU+ ztJ?gni-0rgZ(J$DrXs2DA69nTIz&atlqOU#FcXYc#^BKv5^K{ZUX0zgI>Gm!(319T zQDSwT(BgHmISaTnov*&3`_eec#XchY;)0RzlQ8XYeuOaT9xu{#$!n zTb;`HE*sZNJJ)|C0`w|Sh@^F2?PSG{@&0%q{M2*Mb28f?FVBvWuVnG_1raV`+j>dp;1D2sQ=|+%Zpr$i zOu&s4ON(hh_N`m=1fB^mr!~E}*oc+g!pr^Wn^p;Qplr+{6dy=nt#J;#Fb z;Tyc4l_!6{8avc;e`Q8M?1lp6BaMx*f+IedqQ~pv@}ObH8b{>4P~^{GPZP$WBz&!w z+Ne*xlJHeB=cXWz_`8qLO}Zdf=MfEQ-%i)YxYbT*XSId>!i!%EZ|xXaQbKH>e;wH{Im+FF=Wqmlh-g3v(NuQVmvXB%Ydx)DQCDH+QtUD832$ zL@2KtXuA9ISldV2zU0ZL^2LY3tpsI#eCBy#Iq~}8*7*I6FO9+v%Z;(1{Opf4quGr* z#wQh}x$T*!u0o{XSqS<%&QWplVzu6^dDnT^-vTNcW*3;(4uRn?K-p0=-;p-bP|W38>F=>=zAv z9)E%TI8^}7jkRNbqfWt3n67WNUp8Vk7VIw2eT}DX$9)=R#^>kvzg`nFmV^2tekv@xpUd*bXsS~_?TcuWb3FQ$@b4_>S3Uck zq|JA0&*L~nExeP_w>@IN7&;l= zGe|azf{;E>xw0P?#9rlri%Ax#ZTz(Yuc>gi97;0 zsCV`fJE6q@)*Jj^dL0SDytq{*I1$tL)=8t068)ANDIMmW&%oEGC?y2JH-lGQ#I?!< z8d)pKFLI-YxcMG^@Pgk<+KGo#>=)uv5E5O$3wo;P6e3p;Ww20=P-15KCs<{g^r7AJ zXuM+c2qleLyV$o87BQ~)W&F~Kp;=1K40~OCkYkog%BAaXO=lV{Q3} zU!|_xcKbQFLq#>0IMdVqCw{G`NM^miW_p<$eq!QyB7ISY7%Dt^MV%8XbnyPcf+hS`!)kk!jJSC9Iu z>p0B&KFKCwg0Kv(NPk3DOF$}#k47GCr}S`Mj+Q;38Es-}sl(eq8HY=eG>Et*!#jQ7 zHkoDX6TVJ^(qn66R4TVTmg9Z+@+gthE!N^zk!=<8vQJqo#u(d9zuSaj`n8r~1 zM_$HD?64%0N^kbOyu*dONxP$?w#-U9{2I%>OCE~uKH726c>BFiaQQMBk#tL$R zjUV;0xhc>f|MtOb0L$}Gg;$Xhm3Cf!r6{i!rzPWETs@DH$SZOzlfSP1BEpiA)K)0L zvXZmBdco3Kcx#TW-LU7Wv;9I6PA@hUw^+RvJHtgU7J z*D+=O0SM2(_uuCst{lNx?=DBExZLQ-*A@G@AyQhhCb zdDLT8Rg32PLZ=Gn)h)_c>72rJeNm#{4=(;Q1%_B%0^i9pfr5rb5Y^Dmf~Y$XL;BIT^um(1(wts-8&bUc{??8msWh zVTMuiqKu^b&=We4N)v^zZiKdrsd#kc?ln0fZbkb8nU(mw5tAa6FJdMHBRFF=YD|Xi zg^F6X(u_m*>ep={XkFtC5}+M7`UiyaErerMs> zL6TB(BAMz7t0U@lajBr|eFW{VdCX@rD$;ddl$+_tbsrI z;e{pM^k}W=%Z^83K`#zZrarO?qHL!8f&J;5%WzBs&sSHgLEatl-w!+C=W8QW!gUm! zO3_}N^Zb+zQ9)?XpT#{PsXW?&FB9j}tYUgv&v>f&I(hW4yFXpsCvRln-L_xnKOj(` z{TsiXvKD4jaS`dn^-cwa;Ty45^Bg3On6mdcleyJuu>vrZn8Gcq9HuXzd{!CMR6i#f zFy^cVhai6(lg6m6R^BIIf%B%W++(>RZ~XRiQRNIBSpZi-)@T@6wKD}WK22yw|JapE zM4t$m_4d>^Bjm^Y0br=Q+;!ThSc}sdEekVcbM^{Zqvv~jkD;OE zUuxx;LKn*>zvJN==yu6YH3eq68;)G7PilkRy9`k;#JSDbhY@`)+C zeHHz_M*AR&8gG)>wisoC?Od2AEuF+Nvrc^|a`2M1X?5>=*j!`$PjMQBZa286C_6 zNtGVU?{TALML+o`zo>UTP+DY4x(dJc3yh(+`a3vRrSSEKO~D>{=hg)86#C5vc%An2 zYL0amLL#4QlQx&dJ%xLLb+ZU*#82*%5EJKvvfBF7Zfsx7`pHy6+=Ah)l#a&_vWA)w z(iaNx8G^8$hcLT)uzXhrMnS@EeYD+gD4!}Dqe?osuuOzenx(C2i^S;mmP!z=b=-s1f7oa@`X3MZHgpA0h5`mp-xBl zCBabg+LgM&FhKM{BD~A5=ikSg9O>N!7K5;CK#T~)X7Vd%*bvKPtjP7ZhfXQV>R>x( zwF6}%--vC?wh@kbBB%apdkVC;r*SLx8i$g!Z^Pt3>;0u?DC$Ob)cJ4#_cRO}3TwNw z>IAKx)fxju&fr?TgSxU(20iOd(wp}`j5y6MseMjwyU@>uIS-cxa^(~JUM&NL0h5@s{aM)m1JTcpiT_hhV^q zKOK8=HGO$~qFAAiCcozTK^F*YQ;LUGFQ|6kdk|SBWXZOK8=gFA^bx=w0=aJC9u7ImO zMq>v1+uzUU+@ubXjeq$7B-j4$a9@`~O#wRlvmRyOhB_uX7LI9dRpVJ^bn7<49Ux=J zAYP-BL*Dboya5|6s8zWt^jZ}9LOx|;uAe&P&nH$kUw6~o+{uB3y4D+pSWzW5StC;3 zrT0VBMVSHBSazYER~@lKc`dNZj;%%pEcDjISpFiW?8(eIWzqHZQ!*Pa+oM}E`kXH2 z;wS`IWr!4TA{}It3fdFhX}Ts3?#ZY18hWvNFuYcTX@*MAly8+a{P9&6 z^%4~&%u;@+hi91PG|-TAWFa9jx0;-mdg7Yyo`3~{uc!+8_bKg)Y1b=P*UKkZSFQIv z8-3W(YMM!W^hJaotGVy|?-$JIiZqa71&Lm6Stg@~6M6-?^t7`^Es2QV5nILJ1 zFK*`i=|blI^}`+IP!)Y##7g{rFjx(YlBBc&wH|NfzriALe~ zsNmm0ZL~fp8rwjZ)UyxW&haX;Cy<8FsMl8*dXolI4vb2d-XgxC1q2uxS9)@Yii+k| z2dQyDZpg@B(t8cs>FvLs`Xf?0Lef|9ex*`Od99-O=gF)W>F=$(%uI=(kZiL38mFTl zQaJ+TU`h+5az%u~iBpufCCiX@?h$8G#}8=cB+{N87z02zUU*EXDWMfBlo0forkZnO z6qF(~+2cDl`0|UG1oP0P@4$e`wKE|R;DjWCbWFKm@11mRoN%omfBsCJ>4YfW>a&f1i@~^4*FMO7O>LgoKszfa9fT-=C(y zGAfOAeP1D;$Gb|78KfHe#MP9&#AMyo%+tQL7lMo+-^shv4H5B(G2$k=NUtFcWT# z1#MUL%~d^rcc|mo93gmoy(z=XHfO)&0`IjX#?%YA!$e-|EsLQc0UTPN4EnIfbHk|< zC|}iAdu^gxA<}i1nTpxHI-D9y&^5bP{*eK$V#AT0jZgS6r)M^f+l?DKbx5&cVWg(B z<=qOH9#l=rHp;a;t;at&7))g&dd@>Wo73A>CuR{N?O8H+{a#$18R73F2ecY9o@F+! zf2r5>`u;_*Z)5n4U*#on_r}-!nC>Ye73v>U@kYjyZOXUldz5hSxXq8}1vt3zNm6E1 zfB)7t9H?C`xBSg|Ttg4)KUYN>?~r|hEY|z`*GEoJZx|Zo?P+b@mSnOAj1IE2Xdc@fJV7@4d&btrt5bvQACgT zZ`ixQe8s2n&FJ|@E@skl#Pr5J0R6SJh#t|t9MS+xf%;X=z@qamo8rAM0guAt%8HU0 z>>Dk-SP=$LQuO~V7Z6d(%6#>18eM>THZD`+&Hjcfvajp@3W#u=mgmqWx!FU(D0>cK zgItc0sl9LXQM09fo=2v4-o3H2S32<#3F+L$<@wDJ*^uI5u_SJ_c!$^GMwt)Jm-d!p zp~8RJaU)Xm(Rw$JXkc102zvBBa!Z7YxG(z z9Y)~(gXszX#x7r}97T={;KW|MDTci#L1T)%&_7-FtL0hmUfP6ycPgZ|mlOGGfXJ?4 zZXtGJS-e?vuBGGp6Y=gWOOjHOvU_9hXc&^00()~moH_Cw9i^U!CsroKOFBpB93xh= ze5{F9dHe3HY7twv&OAOGZETA5AiAky`wcr?Dh(L-zkbEtsHkJR?YJJ4?TOM++|d48 z6B!HYx;n`m03r1o0QnLT)OZ=^2%bt8Q;VbNro~62wKR*M1!=c^rr6BO`ql~1l z5R-9vR*_PUL;ciuH*tRhcr4k%_qjz8+1cIlO3`l=0zXz;V@BbbK%TcpGyAm5@_hze z+`<+kNN6;Hnn^c1ESw;8v|bKP5hj12B4{KwNWqim@89!tHh(?`2OOMVey~;cXxy&r9yh)Sn#srM=_YmDXP7MN&Nj*-3)FdmtUY|C7?mbC^(kIlOXo^Z~x4E)d&T{#VFlj&E zgSGn~bHX0j>iO%-hQH9*z2lh;X;(KJ>vx;7hU_kTdG^bYc{7~stbgOMf)Ig zL!~ul);$wH|J0Q8lxiGKZk~`RX&;+=ElpHq4{fgPU4riO-Dw2LA6!Kx8+j=}2rO7Q z^mJ_3b)q=C)vXP$vx9m&H%&aC`kQ{ocsvt5TzDCmD4~qL(d%+prI70SO&>|4DEDo5 zQFQo(tiX#R-k1w?j{xBx@MOE_tA4T3M6Y;RsKRI@JDx^n_A2rxHQoY;Z`@776!wa2QfRv77rdc!F=z5+fxuy113|D zFCAvZprk(aJ`hOh6^Lt4j99nFdtY?Px5M?08AgMY-M?u5ErotvcV_O;2A z$;57_yYXFU*z+JEH*I3EbfjBlQV;+UXlsA=BCd)++n|%NVi!HjCv-+D6qO3&diPM5 ztC)%lcmAW1Icq3iT6899b@lGyi{1U~Z|}=lfDJL4-2_W z^W9oULLv}`@VkMTo5~&xPr4f$ufQfN1K$<87k}_Wo^^b>r_tpmQtmByM%J1k2jOcz zsTzk0Rs^MR>4BZ0VQuZX?`~Ben359dPbe#J_+;mL0~RG1mywQXQ%3Y{X&10(Qj9}a zkY}d!j2IV_ITX~wyJ)dG*JPQ9YwE>I1|Aqh=39bX2e5$ja%`~Tr@RU-Bz*aTfslLg z8$D#Kz%62?y)Gwa{j1saj;PNr1xyNZN{Mzze!B~|t|TQ_6>I)LZ!{M#Ez1iX0Riu8 zllF@;1>$6k`;SlG^Wd6X=_*@{Kk7Y%9N#97K@1vk=} zfe_kE;5lMK`f?WMF7x5;kxkeYjRI3OOK!qv-U}Xsj)!9LZ-W}@d1lHsN^AH|Wt9XF zCxKT6X!;nrh@DWdM;Bz->BtD15>?|%^;I#u9g5tbVvRkX|P}JfQ=&f$$`aKQBD z^~G+EjrH$TtHwLmjFjsxGH`I$!Y=r;A*?AvFD4*-R%Hg*l=mOS?gB~P>vG50Vyt`2 z=85Q{CTbwpW%)*W9Kh5&_8e`G3N}4HD6pW^s@Vck^v`;L@{y3-8hrllYOR$~Fc~ox zHc6kN+AT7FMC?VJ#yh$2Rtar+8LZZXxDuMKZtJb%Q>}mg@7sWK7)<6oAqN8t5!083 zhIdC!FyG@=#&cO33E?`)Un>UJZbyZ5rSf}I;3TmK;sl zg-C5}3(Kf6c5#b~-YA9NUmsf0)BS2_X|}eT?0EkPnbX@q+&pd*u$_BlRm^WKIQdF1 zzj8&yQ~kYN1=)rlT)-K-%}CgZDr5>F^dpyi{9aC9*vlNnaAVl|6YXG!92%QjazKqs0v=1<#sMB~4$VV(EX=94b6zjSR z{bVCoLw0Ey7%zs@KAA9(s#mDl#e^59F12{OPSI(V=Vm{f1Y_nocz+F(fpPEHa$CWa z-4LdTQn{e!gn)xzmhr|taa=v8&Mj(>Nz zGn_6*{v+!lq^mP0c7M`96E{`JSTb+Q*O$ZXkNBYs`L90WAlz2n)Y>m3Ft)zAV|@n| ziHXm_z%)|gOP{IS2_Xw{!Zm1mkZmJdm*(v9Wyl} zV^x*Pe5>w0O*h7qCXg-4zfT9|PMJPzzG6-@;qQu|m*JAm0;%j&9_`^KuS0|7`yjgw z8nTwEXIRt3vbe29&-$^IzLh`qylCF@qGA*08D0Cu-ri_{L(aDIPVBkyHi}DhTJXq8 zt=1(41i~e~510i6FWd}Rgu^v0CbCrx32Y#0=X7YHzG*-Ntu!&W;)9VcwC0c0XN;qnpqYk!A$nH+Is&sUAHCBZ- zZOC-x?VI=7M&AoSbv@o2Gcb5R_y`MtQzT9ST4%mu*Fj!3B}uBeX0rdX$J|kfc&VX0 z`40&9i)X&X2iqecY~d-WsW~-UfcD|Dq;tzFZlns{x?G@a%~eaSTHEE+CEfWqH-j9) zxA*lt575}pr0E!Y|3I6l91B#hjj$k51tBXI5!>4O-Cx(X!a;$~I=xwq1ZLvVJ4*%% zkpz=nNp-rAE-@`UG%KU(TJ!MrKRY0=d3I@K?LJVA`c(o9F9s>1cwhaXH7 zVffwM@q-?=8?*^i_KfH5eBsiFFA6LAb_5Um=;5$S>>Ep>dZj&2@=KyXcp%Mb^tTIQ zeBi&C2R{wXen2-gKw+~&qs_=2>H@YN60*-a;u|Monj+N^q(udF!e2e$x%f4xil&r9 z*@}F=(Qs1IXF@3-en;NUZ-JU6-out%YZOGRkm`JP z_C%FlzSGn!l8T+dYI=t;nVTO9AtbRvf>sg0efkuE-qK>@kk>}?ZYUYWi5!QrE!PR0 zI8oprrS;lXz=9Jrk%xm@K2L5yr^-!*a{5_c^WTT2kfnn%@ac^%l~zeSDk?uFl{d~XQPfnwuabvp z3B`1Mm*A$xF&(Ge9;0QHe}wQSzQYI$K6MqRFkrE@^BB*+kZN7&%Dl%8PJn!eq{!IV zkj1j-eYt#&MQQf0U!hxNq55q{)i#(Bq`M-0c)y~I8@1+cTC>Ngr^%D=SZJ*%%+UQN z*Jv&&DFTkCWM=ln>aXjHPeJU*fp>ANf$^ABVBA!nV(?bZ+c#U3*C+QxUA+8~%83|; z80PaE7O)-B2h0YdG{qG68~=#%aUF#*d_=gdXnM4SWhIH{{QM|nnKvr($U`YszvDvs zUp!IRdx=x`xP4n;mw&8nKzXHwm7wxF*G=QKFx35D0MXp=iy z46gmBrc{iT`94p|DMpiCks+~Lehy3{cI~*MK53OuMD<$EqYYp3=LB1}5j{1N?^#h4 z%*qNN>CU8TItF|v8{dPs=i#@Ks06Ij)BX`^+OQ>q_fGy)lYO+35ZP4-2IXXFQ_PQe znTdtL!6fid#!3UY(J>~}bvE|=D~+R9MGSY6e|X>4O&h_V1fsdA8T&fE#e-?wgo1RC zBgn|`?R>`t=`YyYHm!lKNBKXTwRt)RiI3Bv!SfK+SRIUV{Sq@ft>z;qrNx;zd23^c z9Tu`Y+Umnc?CzP60ldY$JT4wJ9a(j3{RYdM>kwJ&0l)z`Ml3g?jLrYL9(pPXgO(<8 z_UgDf3K83V<#0#T>PXKJ1u;ZCfJq4n>Sdd+GrkBW!bZQH7#cXMo>$FB)3Hlz($TwM{uE~M$XPn7Das8=hK%jC>H z6DVlRe(tOU&kMe0iT!}RZ z_NypaN0w|zPm~LvGhetQ!V5K-&xL%7c?-Fcy8hxp*AnZVh9pf*?(Q%EbN-4e3dW+$ z_*Zw&)$?I$>!4tj-S;Wt_Rr5BAJ8v{@l~1Gi!~IM<4Pd}{wNZ(lfJ%%#Xq@jWgEpR zbRXB)CJW968M(Nt+-Q@M3|x9TY3HB8`ud);YEBj&7l9s4MY@w}1@qIy*3OT)Ln&rb zqZpX&P(=QWHU=j_K|qAli5C`j_tx}R2bbaz<7xhF*;{JZ7$K}Ka?vb@MTAdmC?CZR zJp=zd=W#sbZeMlmV>_?r_K3v@{yJGi%XpmOEO;Vx=t;SLY>G8kymLuKK{0@+b#}UK5a3L(n|?6&oPrmV0NNg4$j#1{?mvHDqgG=R4l$BK8Y=BIb$}*Amouu$75*vkfhGU`-&Gbnq zDwZ0iJ$1garyVe#iXr(*vse!_k3`zZ8DKn~Zuye)$yMpPvYRvIV>{BDb$=o-*TB}3 zdbzdb-R3(JGbu;@Mo38!RrH?TtdGMA&G?ouDe3y&Tj<*V`d&kWcykK{xA=ZX6bKOM z{2(U`_A-UhKJt zI@l6n%PS>*%!Jb>X@mmV^<5<)X-G#xq<{o7>(4b|SENKnKF{F8igM|}otoZ5UtI9M z)IB|;X9bA8cGB9`v=`-L=M-PGaGBiN1L&Uj1%9xL%k&pWj*U`TQy;m@9>`jzBH?MD(>^UI+o5Df@C8fHYLpKaMP? z=tS;qlmsFoum=VwupjmHv9qp^TN;<)ZvuTTb%jx@^Fx~jXq3!1r16-ad7rDU_(l;q zfyEG~SZ>~SS5u!Xd8ZaG@skZ?S-~`D%SgZq_%P;rHu6eag~m_=cLclY+J$bc*`9t_F(95G2F!7i`Q*5p?J7oi#TMver!!h$UK9M5zS=Q z_rB2VjoDgU1&_(O`{Xh(v>#SKC&_mrxUqQ}1)-hBkHtITI&w9e@0fsE@~s-HD-M%t zos9z}@LJ;i$7j_wpzGG+{0^t;A2jU>9VX2H(#}(BL*d^BKj3!Ug8nW0*}FS$9tYDo zwhS)kCigf?0$|LHXt3vwNC&jV%!d$AKKo!~0c7%VIvyex{GpT@KVD5ufX|gh21a-{ zJU6a3Trm-LE$g3W@nwtGZN%=JWm%nWwr|wxd>(uYlD5uYoppL__8ptzDA9yHDBfLx zs5cA}5{#?c-rn~diAahb@+W*sDZ$e8;@v3mQ-s^>P^UMViWuC91(x5jK>#6SsR}Qa zHj*N5>MaWQfJGb&e!Q%yR&Hds#(`cyfGI;naiq|df#>0mHNJ1C_TzNMca$$*fWGSLT_%dN3t~2FLQBmRqC$J zIIqD`kuS|-7v7cAZnV04oL>OadXTh%FON%o38q0G;el2yES$o3Iv#8@fQpG zhq-l0m{hxm=GV^PIPJ!9&zn|0ak6+sKo9UVb^6N(t7khqT^%t^^XrhJkRfW8abGC~Cc><~Jw)Uj`Ic5mU*WD`yIT5d1G^W|l8 zi}4w0u@B{8t!tquq$wC-|Aw~$C>@~aRdWDi^Erjp*!EbEWj8|Gu(sk+Y>#_U5>P{Y zcqXR|xx`U)KfE6;C}Ot4#l6W6og5H-_)Z%GGIhY#sjFDK0GwUu6xfYUh@N2;F&3ce7i=28T`M5zqthzq{Id2 zDA4|Sys2?n%7!FvJI@UKn16tti|}h{_~Xm&jYflJRfiK@DshBMu7c@VbbEO{CyIyH)^Q4+;-ht zlz55n6~m3vmD;>Vb|%m6%aG(QLmXy!j^4#(2o{xDEO2d)Dc`Hvl5fscF&W4*<;#c^ zkDdC$R-`y(VBU95oIPuda&q2oO|*W8O{u81@2#&7y!M0NPEFKQGOxQ$sGkZQyEH22 z<;x{^Y;7aC*WzsbWeu+P7eY{wCnSwsX|ROM9r;pKF0-_xhwMr*L*Rv1S0Q|AMx%`` zfNkt#$XMj9d|(e0;s>d{@ugu@-a-Ne{q}UXvAnAIqecD$CY0wDDWy!rXiLYTJ@K3( zBn^Mt#<(@or!UANqdcA&gmZDCNXH)Eeg`M^be1vT$dg8qk~gJQ$Z}-8 zw8p(}!71?h@2jig54ETEwqlhSKe3|rURv84d!Ba3gIMIUKr*Y`Xu;TeS949YIYV6gvUB=_sDieV5>pQbf!FM zUnc$)DLQTXuPX@$2m7V3Gr^eaf1aF#cq1MnH2AC4*g)?e;3wnBVdNymG?quhF}ZjX zGonrY^b&QOHmfR*D5)&l6`zkUG*~ta{pP3eRb93N3z?E3*}ggEopq) zxP=F9*QhIR<)vUb6+8Kk^3%j$M2OU>yY^2 z(}gU@*jys5g<$yA%>VHQiXidK^Q$tAv_VzCC@f}dY16to^HN;@ZUF@^z20Ws9lTqv z<&X=xu|D&gJ!BAVIq-QO#cFw^mp(cikR=ZDj==n61LZP;cEXQNoY?cJAx<1m$iw0> zg9P4@<+U@ZZ@BZZ@TzcF zbm=gj@4DJ(YCGoM?wA zyNl#YOWVdEAN~}h;=ahjkj1hFHLYHdtm`Dt%X>nCD_;+a2dWOT%1g7WOE;Dek6GTo z;?${;W);Pu-0&AkS88s)@&9vhM?Vrq^}iK#H03+FZYurxcV0@kBmu9|tnvM^mw>Fi zQiYF@0KbYlm0#7TIkKdRdYbE!wTEK3)4Y_gqFL}{n?(iT(%{mSl3;X|87v4W+u8~^ z{(PnEZ6A0NRhG!QuZI+u)WhDVqM4T?LUEInPTc!>{`Q#6)#)ZyD!l6-$RaFS^MLZ@ z59}38E)6%jbeo=^V<2HhZ%gOmKmnI9PF;cV;+-CW4OBVjuT(K0kS%x;l1nJdZTcE#pL@_4p(+SmHvlxp zl${uDaOh%@mVY`Quexd3!LX^N23dYV#9$a#Mm^67JskaQvs_Vi<>F#cj?(UZE?r!N0rIhZHl9KLjDUpW~ zknR?cMi43KGkN#^&N)B)=cVgf&zfV7ao6zQy64*F9yUkA`S0Y&vURsDH>?U>=@=Oa z-r4U>me<5vG%QAA&&`R{)P zYV=`=y;v4bRq+R`{-2LGm6e5ci4du;H)4{Q2klCfwURF!oQcpn$tv4P$5cxJTEFLtwLp zL2>j7d-}Q3>ia_=3CYK^I-Xu7#(_|HUVfYeyS=4wL7D%4+G%n>s2XF$KR3M$a`9lv zG{6I*Bo0)vW5;Xy9?u0sKClMiZ12R%FmmkAbR@p(s=wEol|n(egw@M53Kq}5MRWVA zXiBcD3)KvCq=P_M|JyU05}KxpE7TGEwMM16cZg!>y0 zA2fi9F<%d`&_?GGxg`I)pg77?f%mN=D-;H3aF?uOWG*kkCnj6`#boJs{`oI|Vpx83{C7uFGFd&tLgCD|njFDsbm=0hQGyqV@sq4NM$ADFhVSfZ+lU2k-cZbOx+RQ!;a6Jv|6qeD?%5%s(+op@_>0)2YCgtvy)x>Xu zZpFK;Z>8Gzq!9?^-Cwn~-U&zJH!uH&gPB{f%7zOA*m|b4>ug!l&dMW#6{XOhxR!hId3Cy|>$1J;z-a zQ%D1Zal^5C3`>*P3HkU0#|1GE^Y8GkuDYMa&%c1?gegEL$`+K`}@e{u)4FB}|t0&5VtZv>i;cy3>Bx@pXA3C$==?V%aKnGJ*NK)Il{mNRd6Lrgm^YekC-R3bRdP=vhFMVhU(e-l z^mkqBUC@YIiB>rjubrC@^SA(W&k@`w@tjq-gS&0<--jEgAcM(i?>fXgGP0#?zMUXo z?>2k}aBt2_#S)Ym&|K?p5~Gbe6k(0{r;A5&IeU;{oOUH$9Xr@li5Lr1?d~2bKAJxZ z&z8f+{Q2Ri*=*Hzv(dj}`AZ=-u49kn>7P8kBnpgWqAXk>!E=)W*a@ZCWO5=LXTiAyD;E zyp<#*GDf4BE-JHXQ;->UKI`ru7XUI%iGR@F%%6%bHum$?1zGtpweRqz_suW{0f*f(H@^$yth_2V z{~`SJR3@1q;mBu6t^BkOfUdhM&zXc)Q_5^XmxsTg%{ZnR$H&n~hmPxEy?tk<3*DA} z=f1VtG}jz-W=8N5yi82^wW2UTNf5^szz-O&RFrAV<=+eA?L?bzi^whReK!Ju-`8PQ z@YY62X{k~A3@2VLW_Xv54dFj( zuuh0-zkJ=q2s=a2cYe0Njf{*vI=tcCc(dO!lI-r~ygRP-rYOcj{I6&11Pi91fc6l- z(E@s!aX(kumhN0ojX|yaGxFg%p!R$jgqKTn<-z;NJ$gO>hqk!<&^op6$7bl8h!klGYvI1IR!SH@WOM-RSz^jTTK z;Y%)9v@}+A63-Ve#IrhBesf5Jg|cnQVGk$VM#ez3*yZ3bT`Z%MTz2$IcQ#w8wUSXS`c>K4 zj65Bf|3N8?L}+s@?Z|552gV~|VZmco_AfsrpNZ17v>%HWvYj)Pd#^xNL@R1i6rU4P zl#lFgW%Wc|5F5u$>M~rP;Fl0maqtqqOf9;ahUmGCX z*?de)p%L0aJMj&DElL5gR8qdZs*jPw1){W17&F~wLHtYu$&HgU@>fegvc9YXJ&AsK z*W8>O-_JB{aL#r|=a7>rM|O+a2$JNJ@HOF+kCOELg11m*sC9I=JkK`**1Xiu`f-XV zIaL#dmFmMbjnyzHFsB)PML^QR245pl3R0iN3Wj!clJd*#VN`LLSl>Hwx()}Uql+E4 zm#$S9f$Tjn?7c`T8S1jpzIx zuOzQ(_KRncET=as4(c4<9~$T4@nSzj@UT-Mt*@uTIoC*G17$V zvsrA7Zs>}ssYUHY8DVFmKD|>e`Hl(CTL}Nl6=n$~LQ2b@Sa>$;_UY+gaE^-8Asc-YO0uQ8rWDn9LL8)Zx zG$X-VzE^0YM}kZhBf_>&m26HXk^@%dT(G`dN*b2X)FvE#RN5&__Mw%vgbGc}s4G~o zx%II{-0_-IceP{IJ{Ap4Ltmb{@9s*b7{J^jlHOOWIfHGgl17x=Iktydz^Xq;2)a6o zfOxRcY`nol9dota>*-eOjzA8p5bG>p^Rvhp1*gAsKtE`4%5x!<&-MsQ{BHc}$?!;) zzg{h8Qz1zwO%4MNf33sB6ZvMXf3erqRp8+CDo6H#KF!{{igL6Tfb(g8y|v3_U7UScG}|+wJ0{Iq*CV#6YNv zh8!2+`E4No`Fhi65t8;b0y})NJ(Jn6&|;#l>kPr&G_~#OMw@YJWpu5>E{S&ol?G>I z0q!*s!QS{z$G$;l+MZqUI6g+|SYx1&-^K_k$EU(pn~y3(3a^iX6$}sYA|sjz4$Z2J z=l4DsQC?kGajmRoiDsR;HqY)9_U1<-2n#EeS5wxtnXnv7)8nL%=F|oI`Eq;Fp9{YK z2b++9SS!JV)ZhQJTRERTD9GCz3ngo8RP1JIL(NZs@*mVUm-dtqpigJB!VeGn?~V0C zl7eNFQ6=9?Y(BMljA9^+>;e^Fk){c#xsMcXme0sQ8z)%7LVmJ4e0x zI;3Pg6jswwk6~;KWe7c3M1P3Xb<}g0wm{G2FI}G~dQIfkBTMxSQ39!ptmP_(J}(*a zUAn0iTSky9anMRUf6~V^f08h65Td1vHH1?)mch2fe|44XLjXoX2rBRo>zhCm@nPq6 z)1{^2rC7 zoj}s;%*Iuu8|W>|o?c~|7TUn@u{HsZJ4=N+1qlx3&|8=!p=|b0k}6q&mfH%QH6Gei z2x8gh+~)yATZYZRyBIwjGn~brkpG;k9yH1rhvsWK>*^fxE!nRec_-Z@(IOc%(}5LF z1Fyju2gxq)KPQk1-P&xti|P~>r2w}A@DZ);N0yZEfBKu2ZM$_tT8q873mio)NCmCw zhqEKQ2d8pOcXv>Y=D2d~D?AO(y?V@z?|4uNw=Ysg{%m1hlyX21VZwg-&Cf)LN`p!l zk0w=!l{{`Y7SOcJiiHw!ecycl?^!sJCruL-0_}Cuh%(o)&#Y0c$F!=~RvRl@n%23E z0?$mLuT*KH6%s3#t~KhDZd>`9A%aQ=Yz4dxOz(GRoQi6&%_`a#z>hmB&73Pytm-ihx-4eKB3f92+cI@0 zOCM+6?Nr)?2~jH76|R-Uk4r~?oLYXvGNx6KD5|yGcDJ^#V_lpr)ZE5lsgt}>9$a_a z*^1$QqG7(irY>lM5)o=^cwIme>av<)i$6Nsc>jy?`J7UHdDXs#5ADb<)SU`!hYdW^ z22#ek`SV)0MrUHsf^Dh`kCXdN%~;)00Jr_3y_8&WnW_t8_*u9|(x!SPuMT3SxM!8KLGW0ds@Q-WTW?CE>>JqIl z>`n_mZ+Ki*um~98w=6gnWon?p_NFe^(`-}5EDa3^I{komK6)7Jr^}Ma2Zq<%$;02a zM{`DS;-d{N_v<+Peig=0L!_;0gz&Hd)nP)3UR2LCRC#KcswSZtV#2~N??cou1pHw$ zDk)RZ+&yaCVI0%C4Ycht&{?i&Vg)K&saE8O$SU`o$!bZ-zB>3P*w-A_?d{cBJi5wp zF!M_lBqS=jE*qj=W@rp`)dikMbg85J+8MS-8%mW{)1t#|^R0`g*EX+-kOdP_B7Tgd zPwFeV6ecelbQ|#TG7f7F7Qv*eR4q4;D+;_1cCn`XEtp8t+R9Ar6*oKyti zEPrXRJKhK4lfSQJg{d)1Sah;02_fcrdut1{i~Bq?;@q)J@o2QhxNw#SOn8iVND=Yl zMnPig;)?uZwwchhIBVXijYI5sNKuWfGY;0NT@DDnmxL?hs7>?YDR@hP z|MReotj;;wYFj+{Ag3r^+m}^NR84%c`yH#PV@=}~_Z!+!7t%3jO)Y||C|_>Wh-kT+ z=U=cg%BS~_1`8pT;u-H*321O$r51Lro&@fbx46%RBZKI{O7nU5R;jLP*%9WV^&Xr3$@mVTG`qEB%Y(* zu3bvr1=g54rJ;EW!9b^$(Ba@mz;@i?R=qB?NV}|NjKYqaURGrG;jB&C&F?;!16TNp zy*;N$PImm^EaBI0C(F8Ve>pwY*JGWHrk>A-K{%dXJ%U0x*l$d)3iKFzlbOK^mNuGZ zXH$yV8&e}W8`{k0zfuQwR6hR@+Sf3j48v^lpwTXy<8*w@NVB}6(6@g9-SOJ5)PGgr zVFx9Y6Yt?bzNIbu_x;(v`BMa)GPAUkk&~J+{~;|K4p#(xzPc;WK+CH~9a5}T6&O?c zl%Dzkd6LLEBe*$rD%0-fe-zfT8|za%)CZUbpkX;XiBdi!|XtOHD`OjUOx z5`K%536J@2lE1$yM`)&#Yx|~}X&%$St|uUO>$@SHK2T@x-~Zkw2uFFjbznlEu;K4)pWnuhDu}ug{JnZg@!DsOH){F(b)iW} z1*7q*F`i;VbQ|gJjuCIEF>J%^B6)Ev6dr{0Mv+?KkL*Sd9vpGAFa_W(BUC4a_m`C# zX6T2fgzaFV=+-ojNjr7c5*qYmg9}qmb@36zEN#bu(c)xTjzORCucg8Cy4#)F6{iEHkkRj61`fjMC)H4Guipn8(6LNMbQ=pAzxlAkL&MR zH=Pg$6+|wEjo9h(S34WGwlQl^BndsW!u#s$<8PCqc>f67y}#<>^eVgiH>@k{@`Jy{ z=~|IN_jeCLxZ_smXj{709_PgVxMo%By<3kiQz;CzPaphf(_9+UP_|Uu{V^pT27>0F zdUh>i($@n!9*aJx5mKxKEO;n&$3vz0GDJM#{SQa_U)V9l23i+qX8Yei3mozu@;1Nm z+DQP%LbX+u@gS3rH&CB;^!v;cNdB6C?1$4maLiZ-tM5M z6?Ns*8Vfyor_ABXq4+DQ)>9oMG-da?SR2y21l+rPRP+x3Hoc?c+uO|)*bor#IxKBzA@h&!kK9R~+!2He10U!2j4_WH#Wf$oHq}P3bQ6(o+CjcZ<)-MG1B&R1gtns=0;1{_s=&E*X^K#{5CDW$nN?Y%Er}2 z<-?C!o@OF{4qWQ!qOd88IT1v9TC>Rd>3Rr1cb{oIk=_zL&cw%=u zqqxMg#;XF&3^THME4hox1dfj8&;`hj&d7aD^x_UreKMxsN-z!91uVI|=ros{iRV#JBGx!eDHjADl|%v+GB%IrVehoEZ4)&fxG zM-7RF{;(p0$J1@pWq?!2=j-Y1my?&z>CUh0C- z0-hdzx6clDOHG4#J<4>&nyg5zl1+TCu_EDvLgI&k$Si{u`t6;=-*?+DVIfcVENm%v zksO)TE%Kvc`R>UF#q@c5SY#~Kvv&rG#g#EXH_pH!^8cd+c$2^Tod%kObi9V-&*z&z z-(aI|R-*{n7TgTIeX!$*5&0MC2&}K2zy5(&Dvf0@rU%g#WyV@qa!CG4V8$$=Aeblh z_pjC21{=+Ck1NZ;qI9zNq71p;NZsc6eJw?4UZ&N4Df)hFdG}Qpkbj9OCL`*~4e;qV zpDUvi?G3+sLdw<~uN-@*$cP$=V&KmIy)KuEs=oVz*!iW!gC>v^Nv6Vp0gYU-P4nd?_-DO+K!`~P+4J%HMh9Fl9;!=>mrIx)7r;Y*6RbU4 z$==amCLZH6RiB-864+F+rb+Cd*M~K6hyHf8*z7?gPp&)mGvYkK=A{=xtwU|_=j(mq z>&RsaEYXs~62)5yfRyPUU%~5QVL-8|7n3?*=2o?eJEFjI6I*fZ)OGo=h>1Zd0cS~` zUz5wKB~$(!0UJiv$kejKsUPrL)(65{+6xQg(}UiO_F4eaJgtq;tCQz>xR|Pe?vlri16hsHeHDimLC-Rw=`4*dAcC&dN#1<2oKtUPH@+!);goU>;dX}-kbJC>w&&I6KoSLR z|H4_%NdUu${P&9DWr}(EflYu{0L1fX5)19(p}?z&FWZl&O^qTW7fw)n{HEYsM~`3y1^+93ETG&?bu1k-RTn_)>Rh$&RO@2=0}6#h&jtNvTS} zpt?PnrUZJ=IlAzaPzs~5T}C|jTqV+y1;S}m{z|-IvVL6k1`Fub_KOfq3qydSl;@kR zE=736{hv>(bFaaZ?mrVb$Wp+i|9P_`D0;`}w8-sMrbz$_?y@hPC2qJM1DQBd&l7XI zIL1>?7MfcR{M7n52&#Whk#BOuH*O;{3EPVXPU}1b&<*&+I4`8lO$dhRR27{)$Edqc z2$g8j;o?6z;N`)2#=Sk0w+n0AqWm3egh(GnogBZEX&q$m%vr)xJLqps8j zp1FZ2X(DU`0&#O$0xbrI2$;&Wj!_US3nlUJDq~O@^BllX1GqKD!-?d;U(c9973%(P zZsoIa1&pL{UY!pf_^M)M`D|lh=2xmDZv&5VHg$mOhgF#_bq~3%mR0$1M~FhdK&o&> zjxFB((h?`>Y~Nw92qgj!%t1h0NAukdzv9~0=W^O{PX!)DM>?#kUccb$-F($kBeoo` zF z^q5MeUhQ6FiLtR&mCC}yv?loDft_k#@=dflp=y1p)Tm?J=$aImsq~;kZ9a>ui^)2% z^ic_HI+rEFfaDOIn0037&;|i+Vu+%K-mROF7EM~Vr@0hIzzsW>>?p}!#go+JVOlisplSm6w0O@OyZ0rXA@5dX#YlFrPLdT?q1h&a4TW&m*aH%p%t@m;R zR^W>S<gF_erQwox(eS8Eln%@A2tR%N$tT#$c_wXn7?VudxS=M`9{yiQQ3(g{ z_~VXoVz4ksUBqf-ij;9fpl;T}jz^c0GyJ0nCYB*>RS9YFU3wKB)^M|>8Aa>dg440GO5kdt#hj2n|Y zmZFB6WNjGU|I5?P*mxTW2FSG{V3todaElD$4bXh)p5__SsR^vNWy;h6-$(OopdY0L z!tHv_(8tZmE$vM+o5F!rOitoS=!jz`f^`@v20Oi%2*a06(>FR2do155%D8@ERSv!@sVy@=!0t zuFceDtqT0=IqhKz@A%t@&m~)^gh8#w=b#u?lem(72AK&7!U-yy*Z$0uq%x|Q*nkxP zY;uJj_5^ah5;d6^1vGxY+T}ok8nB|p379^n{JSu0deTk1w7K4YT;J?s{G9PS-LSPd zY46yaA)nIxF}Te|2_!){FbDiqWd8#7v$7m13b4lXs@%K4=}O4-zVP}Wj1!A<{Mraw z+3g_s``cWt7@1JnIFQc^r1{9WZzlsv8tDITO*A|G5|$^D#fNG!j8UWsltzUi<)62u zDY^XuY|mQzyqx+9qCJo+@lufLy55v;VO5D+%^^}_XXGXS({rlX>O%vPrdJ$~Z^fY4 z*hK$PEt(2^)#5AAsHo`3_`P`An{S`C|JnK}FoR>ChO)2_x}Ylum7~UI0PBK3Uzy?*l;w$kPlpT|AtL z{%xQV)2`sCN7~A6V_Di^)Ewf4{#UIIi(1p_y@~X_heztXgIdHcCXdGCpR);(Q z`Ls|2AdV+xJzH7Q{;b7wW_b39BqQi(Ehe&(yl=l6$4+)^|~ zegkI=Sp#h&`^X4~N7N*{PUbW?mBEMFSQzN*T`42UBgtwxknC&N+v8rqXB266b~d#7FbD1=O1ptr@SlJl|J`Tk%qUZ zlw?$jMw*WJRXj|rtnKP(6SMqlUa;LaN^f@5PFK{m>W%Fd>8f5~a;)6EnYe~am*)XL zA2A9U5j?O|LbgKmC1+SFzlT`COWS9V?5E zq+^sBC(HN#D-54?q^D{6cy{yK1=jfmzy?VD9@*FBbrh!9IUkMG8f{axwh^yqRc14D z#@HK41*o%RL0d=?3axQ9JHSKW0W2m*?C&uqRY*r+@pYkVBp-!)zfAJ&RtO62+i zC>Cj=zzd6Pt)tiTWUbpx@+Q9EEm^Nx!oW;SP~4N}FuT;5o+pxkXJbw|J|1{CyW^+l zQjdp%-|H;q-x(+b)SrSs);d5sHL!1eo5+I-`GB2@7j9I@cPCvqI*|Q2Vm_a+5-$tw z!wv{u7rOx(;59GI5U5JL4ino@J*>!Vqw+W@d`U+q2qSf#-fj0eAqJdEo{RgmGp3`e+#3V6=8s+Y9=-zoTyl_3zC%s>Cz%sr?Q~{UWPbTWe(m>Nt^KM@hyc zsiBZ*ALDzGiNTv8^ueN|0}Zo!M_0hB1b&UBRi)DCIa)UJFy(QdUvqwPG|h8#b|!}A>nP(Oif)&xeo9j*3h-XOfqBH896I7;=B zM2=)p=%i39tAJy?jXzsXUThg{c9f@dS(t{dCrm=D&lEZR8OstW7&;w)U4;_Gg!e;; z6m9#)dNo{1rnt<}qYoZ0&W=J8%TeK-650bGWeP0T;H zlZ(QxmVqy9X*|qj1&>Z(04jX*R%dZD%}&7PPGvdx&`({>g7E7ztx`-9fi-{`IMfi5$#mJE3#=hLuS(@3I`& zNaZPBVf}m~VZF*v7Nv!pKWXxzl*WjN092W9BQ55v=}&(VbofUVS1d+5mJhy;G_r1c zJOs0MB3TTgJOpoh)O95SvG0EvJJ;X${_(1qJ>RV!1b=E=l2${08n&LgA|U(#_5jZ@ zwjcTCai8Q!OL6MrY_Tz5%OGWw2eWEBAfjYl7z7jFyL6kecg64L*MqD2ZK;XD?B67? z^|-j)LgL;~uO93YIqgm*=20jGk&AkDU=RW$dkCV690OqPK~Kx6gNGuARM@S_tjj-o z6K?C>MQCAYC*2<0_o?feF561HxjkH{lFT4goL-E zmsiu9&vj3(5HsW`)gEd*Znj!+%0u1^+pn#x9~HTYL8_-{ip%Q1U5;IE0>?=9hrNqm zp6MM2b?i!XO@^!hy){W3rrhtRwChLcHbX%8zQ0?rju_m#+4j4FwN?)q+~E*cvS6p8 z1ze7^l==3ai`4v|=YR5_M<()GS{q%-aq0j341;o7aDO-lI}C|Uy~sje3yZLrru0#z zAdT20n1^!OF-}(XoCP^=pmB13`v&FD=cO{=8uhtp3JD8^xG-fxZN|ZQ_3hgIqulal zlS27T(^opAe(6dXRy`(oL>M@jbWmKeCTu{f33L*_+Z~)>L1>raeE60O!1Fi{Z28tJ zD~RQ5WB9h(R^M*H^E-pK6UdYeWSF>#DS|(lKZGiT>%_h#8-A6~Kt@l*YnsB%23X#| zHAY@MAVz5xc4|@HiN*YhJO80%ErXmlfYy1LHCW0VK%*k5b+*?v5bMlP0))du@N#R%3vXwSQ z6xrDahn3Nhh%j2zq$DpA1HnC_y>aV76z5gE*$*ZYXgvogq*!spkL+xCOh{2NW;ur^ zHrq07EgavYSb z7(Ow#!y8zeW`G4aluxh5?O-L~p#3eE09k(^!tu8IuqEZb&hIsNu(z)VR2aVBtKLCT&1_qZ+b!oGWJrO6eNi|Y=I4X-fi!}A7=t9o1G4$J~1zpii5E* z`qaGb!fW`g5ny3>+r!KIN#0antF>R&*mb}vyx)MJzGsL*0{PGCCJx%i z5l$cGNeNIs&F{2ot?`FgmRYCm2QAnLiZwW0u7S#z0&^@QMJ-i{IHWq@Y}f56vcqd! zvWyB1v$buXpb9Ekt=x%x@Dp{uep{_%M;$YPE_dY%iom3i0q7C@r0T%03z~_(+aB=g z^{MK5b=B;>CatYZV_N55-Wl;5-@dUo(GT$?(`8*?_O+bb5p-PPg?BtP@q**$tLzk> zpDHjib|POppwHJA&mXl**XmNc(D*J&0Kjwe$0|=#J_oJcOY_z$U+@`_2E7K%4xsa8 ziPeBG+CKf>(-7>vlb;?Wv(0Y zI~vw%?k)OpY(#m%AEW6iS&&F{UV)46G?zfVdm9r*cHPO!RJMM%1AGyLytna-KY4i3qMn8RsMRIR z0#{d1VN^K`G>xL5fxR#m6$xEFL%zUAyA-6nJa1nTA?d9T(Zj%I25fRoV}JZ_t9z+a z!7T{VUDEa4O>vMxP>;>QR5St=6euS z0P&3HAV+|;Lr}w(V+1fEFRciXRwr#LqpYyY+{BB_GxW6; zmmj$Z{J{T@hXMx!cqCK;C_#+basb3A%nAEju4x?WsT876c{%ks-*(^L0iFBgV-2jc=m1Z#ZsbDyHfL^?*P{fx?s~_HwN%gPQL9yAP9g zwsXdUQ~;m6s63p-Co)8R)HScqU{CL=E3`W=+Mc~)K!4i}>O`wuLK7?Bn?xfpM}dad ztiGyR+iQP8SjF<8kf+6a#l}jwZ%Sm0nFb(4#%Q5`734?9%`I)^Q>!}D~RjAJXc zB^l${IBytvPd5d(zD*s|b$;LxRIjerZ?>Bk{&Ei4mL1$b+SkM3&sPW7?nc1;_Fz@r z#DjJQYo*U8$Xlsn$x~e{Eprd=D&HSmjzAF;t@f#4Wo7PU89dsr|KFqi(PqDZgNgbC zM!iv=K{N}(JD3iO5UyU&+|dBd;QAo(+2W$KSUFV!2CHMp*J(ucWwqL`U;q9_W>A1g z%I=vzCkYFebg2-zUh)lkq}c-5P05>1j=R!K9pyNWe@Jk1 zmE~2P!qz<6UvZGnLT$iM4seexjRw{tO&T#Ry#YZ+=bV?`-YUfgXO%u3a`xs(C-gNA zGD^g&=zxJDzHI;ovDEXfz}gyOKbq}d{0oE&11QLVM81IZmQko7)>E!YqCxz%FW7cT zLh9f;)OB37INP5qM9spT%WCXONAP$j zqEeix!zOZm(hJ-LoX%Z2${c*1lj;(x@`&=}5j$8&8q6b&%xI*5Nr4pNA|+2+ufA}Y z4t9n^%XIkyFjta-DsRd)#YDq(+|#D#BS4JRSL-#*r`vpFII!C*in6SEHrm?(UMTOo zj}PdX2X^F!)lWMjdT?TZcVZ|(^pRJ@x4{~*rw3}7QeAW+DOl(D-w?U5~O9_~=NYw*hF5JP# zn+%Y5{WtkleK;n;w;2JO)hHgI zh}?7#DtIN_5EsUbBSF3MXx^fGFXBe6&UO1Y<&HD7-h9_fq<{&RXkJ% zTl?4cgBXT6M1)I{1om3kOjEt%sc;WzDoK82>etk-MH6?hVsx}xb6ml)g5G?vugT}Q zfi*k(k3TWd&$d-Z@=ngL$e=B5tHBCG0i6 z8KcevK~Vu`bg8c>1kS7lRoL~XNr-csUnD+uKd6Xmu28Y$5E_X@{F;KrjNA1lqBhL# z?$7T#euicvFz6Vxt=*j$A$~rQaQJ2%HQWzi8*sC%IJ9D@5($)O0n08s;6*rN!Zjb2 zXo1$bj2_(SO@>d~9E|B8XqR+c4UrGoEE?iHUCgr;>CdtN8?NH6sA#@!q(eO z{aQNQj@zBDoqg6kMw@^l6O`eOy3SuXKEF~>UP{Re3OKQ^%V@*hd%$uyX+zk#ud#y zaG;_hpRPku=e7s&3*U1kEi)ATG&iL+CPh^kQpbk-pBA8vpL;sPqD?ID-N1qG=7gQD zbQl-J(Loa(9e_Z-%{&|ZQ7-jDIh?Kl0~D@xHdf7dO(dvqx9VcOL8tjN7#CY@uw<@Z ze{`e***mYW*TIh~{?)Hcly|`5-S{O_N44DDG1JnTv82fm{-~x|$2cd{<0R2vQsD(s z!qvixL|NqfYiDYzn@X`PkYO7*7AtFwpuvcR!Q*pe&k5V$Lh&wqB-O#GxQnztli~Bv zjR4Kjz*-~tpEo&7d}8Ev@{27yebK@1AXvBA{|CjK@yUwWgL+8f{WB^ziQ8p&#UYOnf&7T_$u zgM$$vdttW^#Sk8g9OpnLP{*m01dhPj%a#Pi<~$H>^0*Z3t$ zE74J71HwIn;PX3#g7(Y}Gf|4Vjv>ZbB$_OhNO!?g0t#d{^FHdk`-I5yMO623KCrG5 zZ#n!(yRIaiPHx-7B-11@Ref*yO_q2b!1S9VK?piM1o<}pLb zATarA3@Jk=dj7o`J@~^vfl4Q$Pc>;*hYgQAv+!`XMFl5`G=D!krv%-1GjVupa;@DdS!;#=KW`{V8W9uY<#k^)eYh;|zNIH8 z2hx_`zd~6;6+|K% z4n*7aR6f1QUufJ4Cg9|>XySW>e^}pav_YoY|Dpl!+0j!1%C@QL5_BVA4 zhrB@F@@oVbRt5=oZWcjno2&W1*0wk{aHHaP(zmixZ+~^35BA?{#06+igO}1!e z{I117XS#wI;zgFOlKp5KqcBDib5^6_^Y`6L>*;gSC@0fWL%uRslEGH(69{<)%zohb zH+)W9zqA;$c5Z%CEm^RjiDDhm=a_7JE1y8&(CpIcn4T^1zP(rz&H6g(Wu$q5S=@In zi2H^N(0Y3p#-qBLqwd=#+jH)HskvC=R@%l_TEX@NGY;iUPoS@I4`aH;M=>C%GiE|U z2rEOMX^JPYW8`hx(6)?5ipt`S7|&V$GF^e>xUyo<{V6H1q^u7)YSg72H2UALuLi{^ zXJp$l&FRy(&z|ZK8j-DIv|=ohbw+jOTONv!N%+2xvD1+4{o7%}0}lJA&1VprbrH7t zK;LFMI~Cy(C7)jJ4yhR2IWL)YkoT{YC(Vk_vWy!>hI1qz?@Ap@QA!#4bgBwyDsU*-WU5)ry!1ms9I^Wpww!iduvooct0TlAUdcYKBp5R zV6!CXR60`OQ5EQ&$R8QMo!zXqk>ekyF~0(0f(l|Ie_E`H#>?-)jV{{mECi}YCGuyN z{|u-#e`{qBgos}0JY6yf3j^BoQVRuM{11q-+$HP!B z`!&)Mr5IoAHdoEs@ZaMvPn+g&slAnj8A$I#9QF<~2&X#(*5cOLqbB0dD7z8LM<=<_W9H%Xoe&n3SEnEhmcBfD(7;{pC&GA zIWXtu1McscG11wZf=;Z<{;Qc&)sD6SFZp2nPJ*o_BNp1nG2+TCgLrR} zRr*X)zQw~8U%v?th4{e-=70O-k`R6tz`*>QJTS2 zSa)_jIas2RXqs_^Hp7;_O&NfmWvVm;))QnPE>DfzlAsjw1@J`H(3Q0b#FsOlT~bvN zN6)LJLUcxdbU=&eJKReQREqxg&s6|BF}_J-63;(rL`xR@ML6s&r_(^lT(PMQiq~WW z5fRojz|5RTetDh!m`d;Qc*SaFGW#>UkT!KB0@wG|{Nj?=NruE-=b+cQBvC zfe^W+?-EC^`Np`v=2ha6lkfcl3&6c5cmM4;*ca3%We|YOrt@JZ@*Yl#6i{tm-etU} zV&$5IL>170zc_P4*n!$f{Ju1(nyyyBHi5~A+`4gX=zkYkrI%Wl8z11 z(kd4qEx82*RJx@b-np;)y`N{CG0qt0^Z5d7_CMB|Yp%Iw{N|i_b@I{=x`QVD1rp7^ zcEv**!*U~(4MjUEh$BKJD3+CN%GmLw7;`pRyStP67?>UTlth^)=Y zGVhN7@#LSq0TW3V4rsT0?sb21j1PCLqy6$|&gXGkjQ`XLBU(`>P>)icl%T{^kx3R& zJSM;^^AOL|6Z)5!w|);vxfMMV;?F8UYFS?L?N3`(E#A|nVa&|#pH0fks9)8X#pOTQ z3}mX;pQ+_B4rM6)!n)WMs0KF{QVKE z!(y^ldSAtM&%Asxgt?2FrQWn^l~SuTpP6KSKqlC>LZM9I{?q#UAI)h*G?4O`P7l5c zhs^v}N51RLsc?FaZeFcctkvw8330O`xoToM);uXOzx%<(1%G<>r|YYO{Ah22OZU1R zc2?M7pSs;mXiIGA0l4lv6#(o;OLdhPKb1g^SsPpn#rqfe-~_1M2)VBHiScVPs+=wR zrHlD2EVYxVWBy1CLy$gB#Hk6tBg^k#rI0=-f)!ySbEsX1j9{#C>v8XQ-5JR1L_LBO zzM1Dut~ThITMAG>4r|$671t2!ol9&j2`q7Zd_Z~qk<)b=>bTw@#mJ)mr|djMzu1YYiuYvocO;%dg=M(q z5@g9+B^-K;agp4K|8rSdhCLkgg{b zsYV$lmwn)`5WzzF5$c)s677GMVOHie{PE8E*vp`7zH$4YQ6NV|d*o z1`1;6nzuDTzC-ST&-VRoH8)YaeqoZk^?qIhj4>4CPNDxL-zD((0{j^3xv#XjoRE9z z&iT{#+tU5V1cg7hqvJKEQ|b^k#}q*}YfH_NMw~h{cdy)iEB9QH-l~m&n)*jwWkpM2 zSe-i*2Cu6npCUrjJ8>XoSXwI{gWGu+qibk?-#r%l~V8J)mUn$>=}Yg&Ix0 zB9NX1eXZ_Bzg6jdULo#gxiXt@_>5s;RSuUow?+nMq9)SJmYdbv?k?$MzMv2PhR^k; zCghY^U8}RxpDs>dp1o%pgI}#?o<;zAeRIWfdvAg)KuO*B&w0Ed4wStlhEoU@Kp8>LPX(D*P@KXdD6LQznp)9` z<3KOk4*KHhv%Lidg1{-)8cVD5stKRJWEtzvho_J=>bDv1=e{w)RE!K#gX0&C$N}E{{1R<|U|FMe z!~{-8*#dH5KXOmfG_8Std#R5iYY&?z^l#Y_Xdc&4g*iU9+JEfw;6CqO>_;+!_7v2% zor%ffy6}g)cwh!5zaWBOPM6`8iy!YfCew>M^uN@4t@lRhAEaV7i{|k-#;E)`o%rJ7 zuOyo!-e=OMVfGp5lY`mLldZ&xM(_VQZ9}xbZ3K4ExZv#UL2VL9T#AI!naPa@a5~q~ zicDSMbtK78d%41oqAqJ5-#MP1NDd(qIr2ZCB@vFgyKgH5SXqh|-dl2>p2HXc-bY0Y zB2#RIDNnAvGi9_g{5rpVGm<1SR_RGA^qL*|;UIU{QcrV||TRvWdDG zlbPav$7Re`V;mfRLjlNn>fm`h6Vu2}l1CFp2{F%Y6X(1NLonSNf%Y%Sb6PTA&bl#? zKtfw5>-KD%0?`Mv#e(8uD~GQIc05;24=)4^$FEh6feG+#42n_G``?&giMxqP)s9Xe zQO;FM&zrM{q78F)O4u6n{pZ)d|5Q^Ybf156ycSz@74o(KqOHIh)k@Lw4SGbX^5}cf z2M9(+A}5_}6B+!!_Y_oDYa1#S>N!SK-6Q9=?INul=NJxA3fc3jLH_P!Ei6-H_x1hz z6u^v#viOSpC-)l>U&*6W87Ep!X?R-H%;`KmclK}_4lB{--S0(r_O>j~nHg?^2~|G7 zot(Z5nGru0C5iinJhDqlE6tx=ps@HhnA?-4D#o=`&r5>!d4_0*lh5&7M~{pQO!XPt zTN%S18Pr(+kyX1gQb<&1pJi~E1av+k(O^u*lP7o0Vimif(&r6oRgvxj(!486(rZbwUb zjRtIbU5F!*M!-uQo#3?41vZ!H5`1gqqCBiOx zPxp570IzW%Uo34bRAZpz!ZJsrh4vNN$BUh|Y57Y8sR?h{<6pPIIRj-Vx7C^y5%Rbo zdfXTIy}74POYhD8cR@u%aeI3Ks_|=gaH9K_6a;F2s&Ol3K{Jb6VM(mV{s;b_xOaCI z9A#Ktpwh($nfqo?e54XN)w8q2VmgEyu)AyKllznA>d0futER>Qvu`**?OXWzIU;jf zGS1Gr^k_0kYp1b6OOa`bh;qVL4_F>@=ywk7xMt>)d&aCmj!t;XuOBwO+ctdsRDdi+ z*TR0FraAo4F*~C~dG+5SBW$eHxwVON-D8c(^LF(O(DIx3;LZlSeyE1mu8{6uu~j9|KUHf!In5w`x>&HHQ_&AjWuIi@K|pXOiDC#oow zQQxq;?!DsOGBl*Q(nf)LyJBh)x4QVPU14OTuzbLIEaHQJ>5z)oD^6u0q1Y-XGHs$; zYyXf5yR&o*plThbrA9{gCVt1KCoow%p^)EMVj2N~!89s>P)3Pf->*G2hg5x{cNCx6GA6O##}KT&CA@Dcf7)d~ab{ zCeZhNzPE9zZI)6ylq<1PKT%CVNN9P9YU@1_(a|icPk^OD&mvTuh_ab}DZn@RK3#=9 zRo^Dtu5WmK^2Isyrtq9kR$=-fXWLVNCZnhp!Xab2p`{v5O#8hC6+1kX-TKONt=bm@ z#h!8uEe7(`j}H5Hdj!TCjTbVec~X6vwvNfJEJnHvmzt*tshZY~YrWbGSJ)j?6?2n| zj9gyk=uz8P9|cKs$7V31;A=uz`+JXA82UAycs+A-whHCtWgUr9E>n+w$vqlvliuD~ zq|){=N=e|Bq6adyTC3p6nR=?nW?QVFd!B`ld~AIKS@_KnEh!}g4u>jRPR5zuL``9- zMpM)B+DNa+%6uxJeF1vp`6ZKb*}#^Qz(fC1RhTUTvUJgqQVMd`EhoUdAEeHu_?I7L7a29;orZa{^w20t(!QZ#Eq8pvlyU+pWim@}KO!X)R^IT>C%I~B z>uzppMDuG=d(O?taiEO?f#Fu@*5D909{7hhqiotJ#$Uje#fITEHMPgyn3Hotf4<*3 zFq=t@+S;0j^alxT)8dQ6qrqPS<~ZwTh*1-HaTKS1NU zbP3*NL7SI!)`E{XQ8NJ>Lv-F+Z!?%WbN;x7$`XXGdaw=6C3XG~M!FwWJWdfEDm6Nr z`*YUaY#NsM%t2(s$1oHC-BT zEQm8k!CUvt+>7}BmAjzlu@grQZB!`E9Z&CQ*V!-%q_1k>T~k95bLUyAkk z6%6%=uS-3B&hYr9f(ijXGdsCW^ZAoMt_{`WJ;`q7bW%w1jy`cs05Q6TZ1F9Bwj&o$ zKC3r%9_ULeLhHkZpoo>};7?@yP>1jn4RndX4x>Ak1=ZEk0`3~}mvtg)Q+P;BN}+YE@6%f!%Aw92P4 z-CqZ!sSU#r^m(gWz(0GBnjm;A@&Z5KDrwG%HKRn*Z+Oz2G7a;ipf^=D;K^s1Y+__= zqlG+U*BnsV)3Y`05CZ-|XZcenc1<&M_ky@8=I6hDdwbypL$8TY$H0s0<94fgENOnF zVD6$V(0W}KbLB~lF|l;gPZ(iYQxFYE-J!-)GP4{Wj$%pR_6k%{T3j zUpG1x5B7;`Xqd40MXzZU^xMThyXqDGwa53Ksdrc`rtWIzebm*>E-I3pE?eoEiCI~G zc6le8!ST%hbSK}*iDPR((?07h+DoP87Jq7WykKYEr{dDVv(xc9-KcE8jS+YS`KUm@ z9-?^auy63}(&xWP{5n^Y_;Dj%FD2Bi38SVhD3`nj0 zGH8=xyt!%GU|e4x&+jht$mnu{DbsE-u2s)gZ{*=KM!UKcSinbb=i5zPMi!*#iz%qgB@EXZn;cz?7#5&DLyT$2hSK|C8KA4q@+^)k@hZiavGi}ZdX8?=JN#A zT@1qI<;O0iGSde_ZY_z@-qhVc;VGiJiqS<4rq$K;zwyy#h3WKb+hg$qt>A{~v+=jIwoS)n(-Df3W~*zC{|6Bk6^U@V~PzW)VJhu99MtdH#htfDa}jhSyVK;Sx~MG8LewKb-O>AFnS^@ zc`A*!dy;+EgnE;**4H1Xpzt>wBGkDJ3zFtAMao-;v->Nval0qmAi36lvMUF+Ozp5p z9_9odn}*81X?tpxavN3|t1}EmV~U>``R%c#jYiP{AWy)aBT?6-jGSk57c-In_Z9u% zr1uIGsv6FT=k)xW>9t{?uHJ&Vh<6dUhHr4CdSUZ0uZ{4zgC0*)&Rs&V zL+4+phDy^XJ|s9IX6*r z@3iJq6rGr@=5*aqvrM;XqmgRja@|6e%_~@y5kthf*(F@DUA?A*4@_{juQ~G*{@mud z-4pz&yhT*n)0Y2Dhmc>5T`wHZQS|!ik@XF8^eI6?47OX6%dr*4lIM+Q2OVDx z_g4paf(mP!J#~nwDJceFPu)w@)s54THt(0>RNkI1%vUUH=1_hXEOn&KWmYhKZUMS` z4RWBw7>>|>Y3Yw26Q+eG7UD3)pz!UEjMu13N{T(zipuuce%D=yR?qsLa~>M^RgJuJ zt_qR3yfU}B`29{@>1fG-5Jt-vmM9b?~iVxr>)Y!&FUsA+9WBYaI z>l+@wL%ZyDyDgU&q!aai>>KDjd@;2d^|d&phyyhIbo%4i4=#a(7eRrmuitqo@@*z& zrT~rNKL?BNXNg%~U#B4FsIMO&M*u`qfy1F7T>R)G<+HUP(Z{E`8ImYWnf)I9a8L5` z`se^0BNg((L-dYPY2pBo1x&izP`z4{b!dQYPvbCOG#5)2(a2TyPS+iV^DOc8k2JM{ zLQB~UBga!64~OLLg0k<3CV4v=`~kYdW}H=}`@8*Gs;&mLy*pv)IbjttIX%Dt_68H$ zC<|Kjg6m=mxcCt=otF4MU~1o$X( z|MzJgglAIk4pEDo*B1i!I`wRc+lWE@63rDvCrMgh{pkT7gVw_rKwQ(B#a|E7TwluG+56f)EQ>;uXqn=@*|;qI zeZ+90Fj~R0dU<7c9O2|N*dbl&-ZxMdgnnw~w^vZu={2qdK(wG;!!7KwBK9P6+Dk?( z;b+gv$AIHi#7z(bAgD)1#ttXvTDEm~3+&Se&Q4*w!}9tLJBL8O^A(!uByJvNzSAUv z)PBQ|-TbKRc{_Q=H$F37_J>ElyL-#uV!k?$cch9Ny7+|C2Y8sZ_!aT$8f|q4_jVkn z7)_sQt34O;`}vsPt8UzHx|lUxi@(rJI}n{xkML9;~F_ zt)WfhSc?UW;a9|D)~WsZ+kGI#UR;h>VJFwUUxKVzol@zyCA~HtU0gIgv0|X_=||ms z`n#ia^7Hc>dY>5aYeo%nb(R<3VmOa~JsDEpb$w$>XqLiJt7bdh_ShD79CeBWMkCwiw99<#=b;R;) zuzBn6Au^D2jZ?t=GpE5~%lU+}&cfy=ef`T4l{{(5hZx0^lBo_4t&-0MY-Mwnqct_l z|EfQy^^E42(NaIZk^RS}4_`=a#i&dS@Wm~OWH=Uhbu`k6>*;3eYOZJRT-G&RIA9C;IU}2WCxvlul>ks@~ieNmMkyT(AQsHj?DoR zGAT=ydqCfCsk~!{=lsKz1+bH$2~^?FIM>~H`U>RdD7wpbmEb^2Dd;e9d1+vMQYDul zR7jxU?s@59>J*c5v?NPMOn?59AH)|n7T@N;M(Yx|5l?z(q`RM)W$_V| z#p4Y_VexqKX5zca_wF4@PHnnek^CDB+X||T2=otc&83JN#sZw-qZw+$BF!WA40ApR zVCu|kcgJBu_?WtF12Zv|cUN)eZ>#XVrUgk5 zNy)t%n2N`sx~B?vE(|3$=ZLQZx%)I49%ZA|qq5c7n?1Vwbp)hU0zR0Z;knaS_9NMH z^i;-57;jeB0ELJ-sYg<$!KT^S8S;|IV~XyGC)OA0lkm;-D=#~vDStD0MnkEljcdxC zKW`V>`Xcfr%CS5eq*!RJlA3Bxht2thctnn6jI$WuhSeMPfy2I{H7DP->O7JUJW@k&RV*0^u9{_KW!EiQbs$#O93`kZIin6 zQOw>tBnC}w)2DeRcx{Yc4|1?EWy_iCuJ)^i-k_-^+)a9l(aW11YlGGMjf%0*dS%Yd zq*?_sZ8<%Q4IDSECC@(5DpHu|)VX{1OK$n@_Mexey3`!IDrR@tjZBq}js`O13<<|F zlQ^M9e%95m^0&H&}5y&?I5&r?QaH_@)9u>Ug~xW}}3*~xT-VK|m~{FC-Xje3(aXJVBu%s4kwjCSgyHTNxCZ*+fto%+T9o|nq;L9G+Keqaj~Wo7Y_Wfm%D zoR%cq8`#Aly2<_ibj1s=f^Fmb=PGKG~_f@)9xXB_F34>r}qhM zbmzr~{$>_kY+IW+x_s=Y|zNmx#TIk`Jytg(K9dxfV@O{5y zgO}qF3)&<%lyEmLLrI6tmNjKo_vd)^c!fNilUv=p#g^=el|*l)GJw?kEoDLoP|ax- z5g4aaU$~9Sw8|yJSail$BFMpLZ~Z9aG>D2vn}{;#5lv}hLSi?2{2))DmFm8Lol-?> zAbz!N7=R3iW}*{akOHd1TMrM_CD9vZXTMuS=xci~0b|xS%Ex-G4bJx-{l30t)(a9P zUn*DYb$N1J#Q%s-mAljAppOU)F-)R0eJy>+kwk>ni02zhcX=IJgZp zgG^psU-@p<2fV6)lag(C-*EEY_0Z4uaM66NZ4q= z4C#IzZDiy1`r=*=YbM76>Tbs?Eu&?D%$;g7uEoU}D5Jn|sm&3QDIxnBaEJbiz1-Dv zA1{@?EL8Sx(#GO_C&%)(+!)LlV~m^Hy}Zt$6RxPCvS606rUA92@ia^G|(QZ*8pDy=gN{abNe*IQsvtPqxTdE?x%-|=yR4SX{0ltb- zNnQKnPR(~36T8S*x^sbGWoOudPzb)-MsaBcnO8itQ7cq6!yu!kYTHaTDDh}-Elw{Z zpgfTqoHR}w7RS7PqsB)^7#}ST(f?5&*d({x|CXB9@0m2X?sc*j*BT!0!;kIxrFg?t z(SC8wjN|vh$nU4ve{vcw1Jn1qEQeAckpe5z+@EBo&zr$d)5$EhKr6ZPHt@{-67ErI z3zbAZsJQe2!`#xQbvm_E9LkC2c?%haEZHN)z+9=$6?m*J&2`h4K~)@93SR{-4? z8ng{%z#$X1cz%*`qJ&plfArc^7c(*0By4t`b%Q4?_(J=w9}3zQE62wlv{P-5*7GK7 z`-A~@if%sJ)ge!#RU9ZtOSev1d^~=;H}Bm;x+%lv58ws_T?0hedfm}>Mtt{DvORLz zW@^lSLR*>bf7K{9ip@_TX9;-UVXKv9V}~KlG3jPt1SN zQi7vuBS6!lthCvrb~4Yb^v2XEdI%n*S2TT@B`e@$rhb8b&JF6ILiX$-m4_YfY*1Ro zUgOTLdt#+61Le=BxTX@N4j%u^RZGPAH=hTbVuHqUEAtws4FmstSaE8<214HLy)w$i z*|8iki2LlTM8GynqOm^0>jvMh;H?R@>$70S);6K1nXSnWmEXwC?oU{##GQh5u#~^@ zoY3QNPK})X&i^up_+jtZ%W~gpaLnrKgYzA99?R3N_8J)(1ZEi^EMV}|8X`v7(hMHH zfHU{x5TxlsdNG*#m#;7HmSL7h>QB8OAf+T{ZvLiYZhxhycxU6h6lt(BsywJJ!hYjB zTyb_3_?wHQ9F-t4RS*b-p4Wzo9y~}kDUUKd-?kMW17bh&VVHw`>k+G8`Zt% zQ^K42dUiXh6FF}=ZS;6vGNp1?vgMFGZdy&&Z3R5IS}}Fm2{Yp=Nncyk zC6)f(uXJTUdS;)fcf-5MLWI=qR@m2!;i+{N66gD?N2hyl{iWcacW-)sH{@Tc@@uCm zolW;EZE%VYxWa!<&h0_LU3J~TdrI_95N;R}0V==DHh28WD-) z+{1<~MT+!P>pc)|2|Uu(H!Q9(sGTl-#Q=u_Y!*y&o}q>Iy}WEiGUDQVMW`RC49&4b zT3`?Ucw@$r9j6KYgsrD~mSyJHK;LA;+%5<)(6uZ323>-RU*f0vFr~t4gM`pCy&dD8Y+DovY#0J=B*a`71C~IMdRng z#S^E^ky|4y9@vU>vNW{sczf;WtILuOSnONJ@!gTdvSg9udw2PW-i(!?4-WkaLXkJ` z1%)N`t@%sm*mjJh2l}=+D-4}3?sCLv-Ogke4_(`1RXs4~5EzaRJVnrnerQ(! zCv3W(hJf9-4UA1R1pjEZnZ!R?4j%2ohLk+@a4|n!r{Cx)Djk#bBO~S{$r`vqSyz6k z##RT7&bDk49=_?nR|#6g&NyOu-9SB(Ncbg{!r;E=uk!;2@TEpe@Yh2eh?C9`mDF zw*kieZp#|3cYyCWog$)v>uYO9n>M5{8zPc#OLv@lm0yj@I|N*8w?lHpNM+DmA>Fvb z7$ZAj70?u*#FzH=Fep!Q@FZ1o0^aN~j&fnx>ZqwEqbJ9`F!7x-e5|Ds-AnY!ybKe+ zI-`HqLq}Hw>gC9aXRDP+%%b-NPp|rz*8yy%P4(YTfBabFHu^O>S`T}gqQxkO@Jbu_ z)4?slq5`EYLSw7S>qhw9#NR(70duP9-@@F@XHwNu)-%HJePQIwG zKWAV_F`5Cz;iaMT`!Qol^AsEfo)kP@#YI2$i+>vRlp59@J0Hs~JY=Y_>R)gdL4M@% zrhocba)}890MN+0lf=+%qj_TYc(Tsjys%rh#mb6l|CKg(!-enDl(?zJO$M{9dwm+- zyH2%PU)pm{q;E~&hlt#YwCkTLFYFf=ig`UTY9}omE%7W^vdd$f=+&CY%hu3`3@kNu z9kDrA{p{#WrbiGc6o^2Od17l`UiB!{`iNlz0FCc|ecb)BJC2PG4w`|hqIYx(^;A{E zF)Ku`T4Q57ZMhQ>2t@Zn?aX8TV3(36^vciCfBDGSwEg_k^T}zoQ zS19xOs^o-4CblUK@2l}xi=mtR^i2_%PxB&9E8>fmvBSomUAr5nyOH^mUW2CoD!Hps zQ8BM^FEGccut4vN8(M5RPmJo`OAffMzGVFU@$^OSexA+?L1mS$Ighn!2p~YgM2tn8 zt>Gu|=tGY<&^Ld74NNWiH};d}9yPVgO?28tkPET#n0PU61C}z(%C4_?bW`N$*qEaR z)x0T5SV+4GBh9u5E}J+C<;?WQ;%Qc@M#F|*MgXDDx|!~VTX7KqQJlX1i$=xtpcjoB zw?8EdtmU(&*_x*Jn;y+cWDA{|d-Iu<~)F;cZ9h4pWaDx@&LH zvXX=;EmIEtd22QJG}9q%1BV4_1JH!mc~2P|eJy{I1;Qe2e7ZK&u|47|yG2$&$ZqXB75TE!dGRBJdWtsiy`-# z9R#VPJ1$qTq$qSiPZ>S)Pr13w@hZ7POL`o0_oMn32ruHcdT8v;Z9Z+@t1fGr<8l!_ zQ?)4D4~cw-)0MU)6-yeqyx)?T({k=-9@LcnR5qMqC02E3&1C}Zve3t+mbCM9wm$UG zF`(m%kYGWvs!rC1QfyVZ)JZXO7EQ*L?KU9keQBZ3%A>NM{ybwF!gutgt2AzK z_vQxY=MY5Hq}da7c?*yRPyjtYqeeZpthwmL<=wA@c-P&|{6{e0XbzaYOYn;IfaFWq zoLgN<@?W3#N=ziz@RvgFrRa3D5!lL(Z{{O@s2JY9@t1!88y)d0#Vs0nRwmv_506hM z)L!JW*0-huYwuS4{Q*VuPLz{d%Ypp9%UOH;PiEDhh_dPpoEoNUy$*jy@ge64AL%LRTc!TpGD)YJxf%8;oPt6HmDf0$FIj<^5nU}j_F40R z*x!PC;=OXN@Bme(nAehgmi_|y(@(Rx&P0UB;A*!0HlF&h5E_E9>Bq#-@nXL)pJi@C zk#FFtv6+5c#&x~|HI}&UIS^OIYY7_pr-4DxPKYHgS4t3Pu47dIG4;n0F?2nspc=9J zQly|#H|XGn)S)uq4#dQ&0vZ4TwIE&Ar_r?E1n3#hg)}gh;dF1O!N!Bd4Od1{J_or1 zfi+pag)UVS2e_16EtX4Fw2EIcCy9M2V_r|@BEKecp>6mA79ZB!_F8;PO~X7^-_&t8 zx%uFOb|5Tq@t;nv$9dr1A4R{`=~Sni7tU za1D|Fvn7_~s$*V?wr?BWUovy7ufLMG)1fU~T;?wybQHI@Dtfl!tRJ6W>zzn0wUrli z@M{ReP7cnR5^(gJrxg{Gg_EU_nVLSH@+Q6ro=Vb+pp#hUqeaEt$qgqNk;$z&z!fNi zS6G#2>H8fB*~xvNObxY(<-Jt_eu0@ko&ELkOv!}qNJo?wr$Na#yGqu^D2T_lzbwFy z(Bl2!;(vM&`FG0Rpp2O$*Qoe0{*FDr8?7?*L(+_v0A(-f=6Pwyb_%t~2tK!ze+wAR z(3|hC)!`|)_M|cxZ~A@j%rP+quWgNUb^h^bsPvR8LGgG`R~6)=Z#t-8oq1_*XZSPA zhTl6Z+a#Zb`fV>cTn?mdi6z2$6AEK66GIW2eaU?OATlWV>lIT*ybG6b-*j{wue3AL z8Zc%>5qo+;Zv5~_Zk;<}12nGnDJr6##G_znK7ZWge6GKeel<`9G~)#gPY<>mT8QG5 zREX_{-8HRU*3GEM&+txn6MbBnBBIG@z?NJ^@xZ&b1{K#Y^6?kGnoUmi9~wb)a=GZk z+-h5XM-I0DO~F>Lq{Sa`mIWf0;$ z+TA)H8OS2!c?ZsckrBrwok{PEK}V=!MKUm6U4P;>Nc~okbv7hP#3el^DvDT_wtLR4 z7od7#;^MtjTQ-{N$JWBB=H=F*(;F@b1Sk>n*9IH}VK0(|{SB*U07ZhALr&n_cc3?Wr;8Gp|@`RANlv-RZ>qIAi`a&c1dH+tiE zpwb@PLEvh~aEnF}Gl1=Tbh_cgTSWOU{Gj@3j1rSu-Oo20-)+9;YDQJqvjbNdg;xG zjt9w3ae`){=$*OhW~f;+R_I|8biQx$QO48L%e|(k2)}kErF1vS-w8FjTgth5v$h%{ z=;7qbgR#tF{zl;xFjfdqfTJAH7?TZ(f{eG45(?1j@6=dsMJj9)y)8FdJ?O3QMDm8k zsIll4>IH_H-o8QkdxB(m6er?_HW8axCA$Yddl_b(RPv>G;uyOL^;Wa71$ZKKMYQ?0cMBzRw!4$)6oGkN_ z1Z#SP{U5p03W+2-+@Do~qC0kLi|01K*W!x~5q6R%n+b;8(j74~Sj6dASzkI@k%26H zoAc)X`15{+ymtD`^lc8Are2YKL$O*j=_)cR+r#(mZQZ=N>IaW2>o=O$DfUjRSAMqm zFwXCDlCM;5Kcl*`v|S!m+l9Bi>x|&8B)av(Uy24de^i3FQu_g8mR?ts%>`aJ!2A^0$_ZuaVew#4Ka^4X z8}hW)fNqQC6#+8lHLB*l+gB@7w+Mx5>$cb2mvI=;7i2EoExIuG`65}|SdZNRYY)f6 zOTv{+6Yn_7sPbm-E7>pwXT`u|_+c^?vHi%w*ZdP&&$vip1ev=L_>nQ63*N%FxbW>3 zh{!YpF)q4pWb3Mrq{AbDhI;jZEfadU=nD1`gRnsS6jw<3O|hclRS)t7eodi;g@8lE z#s5qZWRe=$VGsG0Yl&k~*OBqs|9wz9#-g_CDun;jZf@Cgw2Flj|T+yA) zM?y*9NQA=?66TckcI_T6Z|H%4Xb*X0QJwLCLrahF?T^V@CK6I_(6!yPFqBM?z*<+g zw0qUwdY{7uHuvb(w#{sQzllwk5C!?$NqlS1u|Jyp`sKk-CVR{5~c|@SfGBU2BhsR+c zRoQ0UWs9`yo+Eg+_J)(AveE84}j3@5)zza zZQ+~}?cXWGmLh-$bV;;{l3uDgD>J?8UB+YhzB&eh{yH<}MC_pXP(b5H%Xf+{3>iyR zjtoP@PTx>f2Z1QOj`%Y`8RqyJ`-E%SM8RM*EL9CU0%(p2;(qJissU1c;ZnMsnit2=!=HU%e zagR|v`4|rABPm+K}HgE@C9tH!?)MG&d-b>#!73=1|wY9BXh@GJd zcD!|+juAVD?=%F47_za?xtaXB4IldjL)>@DC6FV!{Dlrx2hy};VK8P^J72>$$IhJE zL^xf&Oo9q8Ti?i$M#H^#W#Qgi0-{{B+~e1oV7_B1i|yZxdJO);KyCpQK11(4fc3U+ z`G#-fg*oA9ov~E$4Mx1ahED|-08u|*{by#&mn@8QAsQP*Z*i? z_XU%#5vR)aoG_;_IoIb5IFGi}R7I%PPF-WZ2#D8OO#sV#haLqkDz< zqq;Y|kB!pZDiZjZvg-%+-EDzWs+*!|uHoHgmRtR5at#87bix8Htr6XUbnk-n@r{}Kiu zr%#Nerj`0N;R;gKX1>Z*}CMGQV2U#L*>^AC$XuNzL|AM*vFCKw>$ZKT!k+xDKi_QqVhc46FBvxTfgr<BM9x^yx z9*t8eTcM4#xiW@uFSx;x;2jW`nu8oQm^ykX5;vyyl;%lbE0zP_fcg;%8-=l^H&Cxl zOzkT6^?g?f5%OV9ojE$}sY8QHUou=T;0%ogKN%5e1by0dTb0GYIKeSAH>T8(0_Wgg6qx*HV*^83=M+!Q4aE@$ z9TOA`iLo~_(5W)1 z5E69grItK$xO$zo4K_D#BvwM+Aw<|jIoaJY<7e;CzK^sQ!Nbv#>v$z1;56t;K+^!Z zSbOUudFllCYtG1|Wh^_#JT;S={sjmkGeng(WHJ%rLpKR(5RplL6I}j$n|s&G5jU_A zRHjI;&0@3Q_^&KX;#RZbilNN;X!pTHO!AGk$>Dnzc2dUt3pgsBCAKhEEv&whN2qHg zeiqq2pdb`?q^2RTD@g8+htu`us!IV5mcFvhA4dU&>fk}D-P;qV#xl1XJA{MtIRu1l z5_uF)$($Pj{@ne$Z=4R_+a)x`V83I6gQCEHZ1wZk@o(8CEZKTp^Hr|vi9|R!yd3bz zcpmCCLn9h1;6PY}xH~YQ;K2e8V9(G0blJY^B+c84W`fo_1o&jv04a?%C_w|jVY}c2 zX-#Gl+%41X=vxZawmOCH_^B@8s^n7@T*ARofs-#YHuEo;AnA! zg{9RANgAe$yxLsJ*gAElbNifWpgQ3MyFEY=$+UG*jN(T+)xFnYH`NqK%|G;KmNdh` z3C4n;ITF}Q4o~s2O}OnvG`r`%IpW}C`h)D$1NdUYMspyR4VXe@|9#Ua_Ih1JF#w?w zTaei)m|}yR|;EtaCBaOi6}I@c>t)I#hE65qPXnMu45NEl>cD9n4%ET{<^ zGF&NR#Zr?Uw7$#_OmSjsf{>O3!2aP^xIla>_ zF&H4IO#i?Ct^axfLWIMwc+v9N1GfCe%h^ez|60CWyV`1qPTSbx%&LkpBroMX?B{t7 zaIfS_y>*N%&YVpTIy;<(V#>KvZ@RQ~m+@p=Y41PD#6D{CA1ybtOUw)Ri7~Q{;4}ow z6#LvB{kPq7Dgn2Ls0|-*`Zw96UYT|U=1f}Kw`5R697z!D@!Gr$}(K@1O zb9LDN`$^zVclgYG7@+ZA>`h9Dxv$7U{`us}R1p{YogL#!yR^WgrJ4KO5lZ&<3sH39 z1+Npd?CtZJN}rRAm)j`X+p`)zxGD*7;Xf8yI`bU7=h-2j2w1*6!@K-)e6_Z?7!i9t zufoR+!?nvNBW9p4z>u%Q-r=ecI5IpkLMQ5G`;{0wTFOGsvc|1G@eQDl-jzWUQ39;% z%x>1OcfL0@2#`iZN6fGhVLz5yIU!=D_Uro9=fCI)Lnhys!-WhW;X>jO8+Hbyw*>BB zxhj)Z+m!Q}gW&l7kkLJZqPy7tY1IJ29T%F$Z{&AaUdlGF1(pQMSId<1f;A=l8GOrn z681a}&bzyynEk*0wvz>(29||PR_q0HSUcta<9CESOWalb7r9ad*P;-Yaq`ee;cnf} zv#%Ah2OO$~6}1lmmUBC?8yJU-)8MHDeRRjr&!4oB3hs4gh0(>axjKbvECR9a3fbEI zk64bbk1f0^y(#TO6UU9MiljRi-o1bx3P|JvGGu2dDl z?0pUXWZJ{Hyh04-$C~)D^?1W|kE4zD= z0iW|JQ!ikY;8GOIla`e{JpSlAhq@qjWXFtDMl?;35C7q_{9t8h(r#*Ms%S*X%M;=+ zmC?Vj;wQHMJjRW$jhW;s@y=jl_I9-yQJAO*~G-em@eTy zJ7J%1-`GBUdC2X25@#nv!nXTcujI-7pZjj>e$kX~d~#DX@>&1S9)8dgnmZwQUgdo~ zq0T4r%lE|PM@P?I5~3A)N_n+K+6Ox=8Q;(STq_-!`(V&FtZ(asnZ zp_A#!!Iw@xEjn!TAZ2spp>G$h@om_)Ob=sr5Rp6g~gqn^Mmbfv3ag z{duY&!u3(afb&mX{gWAjb-)}sX-C|#9={Ws`oKx8!->H@ryuJX0&k^=-?v#~_SsqP z^B+E4{ePKx=%oAa`P&c2IJ%m*WwR$I$?KW=`3Px(zvIufP93n=~m#@A>DS zP74Lz9&|O#SikjWiOOqFgCghHD<3Q7NY`6F&`c=$vUV--B)^F@-8-#hj&~jhUMTRR zW}kzCfzN*fHm%Y^e&It`t|e`ZSjoR6Y3B1=!t->2ceGdSU+h`x)cfJqK?$DHn^`yN zW;niQeOOST)L*ho;+53HxPTJpyC-&joGuLt=^xVdaS8$!`}UmKoABgC%NmE7KFhXl zy?Ujj7}cewo&ui*5-$zuZzt1-D{UOwmK>9zkmPEojE>gmBE~%J<|3H zC-*3w-F|_csd3vjGoTd#s}{)}OPKL`-R8}g?>wrtlaDQXTz+Wx$qFf5;9#rire};i zSx)O^pYT>$_OBH#3V1eiHwU}bUf|4bX4|fb#gFyP@BC0dTM>7rKwrYrN^$ul#_+g* zUvkWD11R@ zPWhRLTcikZen{d=k(ha1!j~Q5Ju;cOr;26NC3t?-?ECiZ+eH81qfdZ`K>`Z}W)**nq>Wd|hX{-4-8AC^+DBHbyT!?WymLiGJd)XU)|ve?yXuHW*@KYIhtHr(=1nPl(m4!q2B_JL-DbiL;X5ra&V2=ylo%NxFZ zD+A_l`~MwB_9krEVd`I*_O>X&pw^kGD|^OO>)OM`)z#H?`#L1elg=GbzS8n&WtG!R zUMFA~aZ~o{okO>8-TIV%B0nb4?(Lg5Z+7pnxj*mtk7r4S*E?=5v)ONI(EnffpveZF z;>YqIL=N=sSE=BdVbZ*8E2BT-yN$b?{>3GL{n!`%d5XEu!zq?x!s#uUXG>!@PulR_ z!GLR_aPRV0ooUbXXU{IFYwp??FZ&_n?#-LP!(M;Yapy;fgj>x$mv4IdsP#gjPM3ev zYW_U_`O%*d7`^iTjFZzqCfx-t2CCnF=>7N4WtUb|#9Vs;s&gHFCZ6H|)e^X?6 Date: Sat, 23 Jan 2021 17:56:14 -0500 Subject: [PATCH 55/67] doc -> docs --- .codedocs | 2 +- .doxygen.txt | 2282 ------------------ .gitignore | 2 +- README.md | 4 +- {doc => docs}/Interpolation.md | 0 {doc => docs}/On-the-use-with-Ceres.md | 0 {doc => docs}/Writing-generic-code.md | 0 {doc => docs}/images/se2_interp_cnsmooth.png | Bin {doc => docs}/images/se2_interp_cubic.png | Bin {doc => docs}/images/se2_interp_slerp.png | Bin 10 files changed, 4 insertions(+), 2286 deletions(-) delete mode 100644 .doxygen.txt rename {doc => docs}/Interpolation.md (100%) rename {doc => docs}/On-the-use-with-Ceres.md (100%) rename {doc => docs}/Writing-generic-code.md (100%) rename {doc => docs}/images/se2_interp_cnsmooth.png (100%) rename {doc => docs}/images/se2_interp_cubic.png (100%) rename {doc => docs}/images/se2_interp_slerp.png (100%) diff --git a/.codedocs b/.codedocs index 519c28d6..e859abf5 100644 --- a/.codedocs +++ b/.codedocs @@ -1 +1 @@ -DOXYFILE=.doxygen.txt +DOXYFILE=docs/doxygen.txt diff --git a/.doxygen.txt b/.doxygen.txt deleted file mode 100644 index f3ba8752..00000000 --- a/.doxygen.txt +++ /dev/null @@ -1,2282 +0,0 @@ -# -# CI Hello World -# -# Copyright (C) 2017 Assured Information Security, Inc. -# Author: Rian Quinn -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. - -#--------------------------------------------------------------------------- -# Custom -#--------------------------------------------------------------------------- - -# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by -# double-quotes, unless you are using Doxywizard) that should identify the -# project for which the documentation is generated. This name is used in the -# title of most generated pages and in a few other places. -# The default value is: My Project. - -PROJECT_NAME = "manif" - -# Using the PROJECT_BRIEF tag one can provide an optional one line description -# for a project that appears at the top of each page and should give viewer a -# quick idea about the purpose of the project. Keep the description short. - -PROJECT_BRIEF = "A small library for Lie group theory with application to state estimation in robotics." - -# The INPUT tag is used to specify the files and/or directories that contain -# documented source files. You may enter file names like myfile.cpp or -# directories like /usr/src/myproject. Separate the files or directories with -# spaces. -# Note: If this tag is empty the current directory is searched. - -INPUT = include README.md doc - - -#--------------------------------------------------------------------------- -# Shared -#--------------------------------------------------------------------------- - -# This tag specifies the encoding used for all characters in the config file -# that follow. The default is UTF-8 which is also the encoding used for all text -# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv -# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv -# for the list of possible encodings. -# The default value is: UTF-8. - -DOXYFILE_ENCODING = UTF-8 - -# The PROJECT_NUMBER tag can be used to enter a project or revision number. This -# could be handy for archiving the generated documentation or if some version -# control system is used. - -PROJECT_NUMBER = - -# With the PROJECT_LOGO tag one can specify an logo or icon that is included in -# the documentation. The maximum height of the logo should not exceed 55 pixels -# and the maximum width should not exceed 200 pixels. Doxygen will copy the logo -# to the output directory. - -PROJECT_LOGO = - -# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path -# into which the generated documentation will be written. If a relative path is -# entered, it will be relative to the location where doxygen was started. If -# left blank the current directory will be used. - -OUTPUT_DIRECTORY = doc - -# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 4096 sub- -# directories (in 2 levels) under the output directory of each output format and -# will distribute the generated files over these directories. Enabling this -# option can be useful when feeding doxygen a huge amount of source files, where -# putting all generated files in the same directory would otherwise causes -# performance problems for the file system. -# The default value is: NO. - -CREATE_SUBDIRS = NO - -# The OUTPUT_LANGUAGE tag is used to specify the language in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all constant output in the proper language. -# Possible values are: Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese- -# Traditional, Croatian, Czech, Danish, Dutch, English, Esperanto, Farsi, -# Finnish, French, German, Greek, Hungarian, Italian, Japanese, Japanese-en, -# Korean, Korean-en, Latvian, Norwegian, Macedonian, Persian, Polish, -# Portuguese, Romanian, Russian, Serbian, Slovak, Slovene, Spanish, Swedish, -# Turkish, Ukrainian and Vietnamese. -# The default value is: English. - -OUTPUT_LANGUAGE = English - -# If the BRIEF_MEMBER_DESC tag is set to YES doxygen will include brief member -# descriptions after the members that are listed in the file and class -# documentation (similar to Javadoc). Set to NO to disable this. -# The default value is: YES. - -BRIEF_MEMBER_DESC = YES - -# If the REPEAT_BRIEF tag is set to YES doxygen will prepend the brief -# description of a member or function before the detailed description -# -# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the -# brief descriptions will be completely suppressed. -# The default value is: YES. - -REPEAT_BRIEF = YES - -# This tag implements a quasi-intelligent brief description abbreviator that is -# used to form the text in various listings. Each string in this list, if found -# as the leading text of the brief description, will be stripped from the text -# and the result, after processing the whole list, is used as the annotated -# text. Otherwise, the brief description is used as-is. If left blank, the -# following values are used ($name is automatically replaced with the name of -# the entity):The $name class, The $name widget, The $name file, is, provides, -# specifies, contains, represents, a, an and the. - -ABBREVIATE_BRIEF = - -# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then -# doxygen will generate a detailed section even if there is only a brief -# description. -# The default value is: NO. - -ALWAYS_DETAILED_SEC = NO - -# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all -# inherited members of a class in the documentation of that class as if those -# members were ordinary class members. Constructors, destructors and assignment -# operators of the base classes will not be shown. -# The default value is: NO. - -INLINE_INHERITED_MEMB = NO - -# If the FULL_PATH_NAMES tag is set to YES doxygen will prepend the full path -# before files name in the file list and in the header files. If set to NO the -# shortest path that makes the file name unique will be used -# The default value is: YES. - -FULL_PATH_NAMES = YES - -# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. -# Stripping is only done if one of the specified strings matches the left-hand -# part of the path. The tag can be used to show relative paths in the file list. -# If left blank the directory from which doxygen is run is used as the path to -# strip. -# -# Note that you can specify absolute paths here, but also relative paths, which -# will be relative from the directory where doxygen is started. -# This tag requires that the tag FULL_PATH_NAMES is set to YES. - -STRIP_FROM_PATH = - -# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the -# path mentioned in the documentation of a class, which tells the reader which -# header file to include in order to use a class. If left blank only the name of -# the header file containing the class definition is used. Otherwise one should -# specify the list of include paths that are normally passed to the compiler -# using the -I flag. - -STRIP_FROM_INC_PATH = - -# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but -# less readable) file names. This can be useful is your file systems doesn't -# support long names like on DOS, Mac, or CD-ROM. -# The default value is: NO. - -SHORT_NAMES = NO - -# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the -# first line (until the first dot) of a Javadoc-style comment as the brief -# description. If set to NO, the Javadoc-style will behave just like regular Qt- -# style comments (thus requiring an explicit @brief command for a brief -# description.) -# The default value is: NO. - -JAVADOC_AUTOBRIEF = NO - -# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first -# line (until the first dot) of a Qt-style comment as the brief description. If -# set to NO, the Qt-style will behave just like regular Qt-style comments (thus -# requiring an explicit \brief command for a brief description.) -# The default value is: NO. - -QT_AUTOBRIEF = NO - -# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a -# multi-line C++ special comment block (i.e. a block of //! or /// comments) as -# a brief description. This used to be the default behavior. The new default is -# to treat a multi-line C++ comment block as a detailed description. Set this -# tag to YES if you prefer the old behavior instead. -# -# Note that setting this tag to YES also means that rational rose comments are -# not recognized any more. -# The default value is: NO. - -MULTILINE_CPP_IS_BRIEF = NO - -# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the -# documentation from any documented member that it re-implements. -# The default value is: YES. - -INHERIT_DOCS = YES - -# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce a -# new page for each member. If set to NO, the documentation of a member will be -# part of the file/class/namespace that contains it. -# The default value is: NO. - -SEPARATE_MEMBER_PAGES = NO - -# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen -# uses this value to replace tabs by spaces in code fragments. -# Minimum value: 1, maximum value: 16, default value: 4. - -TAB_SIZE = 2 - -# This tag can be used to specify a number of aliases that act as commands in -# the documentation. An alias has the form: -# name=value -# For example adding -# "sideeffect=@par Side Effects:\n" -# will allow you to put the command \sideeffect (or @sideeffect) in the -# documentation, which will result in a user-defined paragraph with heading -# "Side Effects:". You can put \n's in the value part of an alias to insert -# newlines. - -ALIASES = expects="\pre expects:" ensures="\post ensures:" - -# This tag can be used to specify a number of word-keyword mappings (TCL only). -# A mapping has the form "name=value". For example adding "class=itcl::class" -# will allow you to use the command class in the itcl::class meaning. - -TCL_SUBST = - -# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources -# only. Doxygen will then generate output that is more tailored for C. For -# instance, some of the names that are used will be different. The list of all -# members will be omitted, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_FOR_C = YES - -# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or -# Python sources only. Doxygen will then generate output that is more tailored -# for that language. For instance, namespaces will be presented as packages, -# qualified scopes will look different, etc. -# The default value is: NO. - -OPTIMIZE_OUTPUT_JAVA = NO - -# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran -# sources. Doxygen will then generate output that is tailored for Fortran. -# The default value is: NO. - -OPTIMIZE_FOR_FORTRAN = NO - -# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL -# sources. Doxygen will then generate output that is tailored for VHDL. -# The default value is: NO. - -OPTIMIZE_OUTPUT_VHDL = NO - -# Doxygen selects the parser to use depending on the extension of the files it -# parses. With this tag you can assign which parser to use for a given -# extension. Doxygen has a built-in mapping, but you can override or extend it -# using this tag. The format is ext=language, where ext is a file extension, and -# language is one of the parsers supported by doxygen: IDL, Java, Javascript, -# C#, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL. For instance to make -# doxygen treat .inc files as Fortran files (default is PHP), and .f files as C -# (default is Fortran), use: inc=Fortran f=C. -# -# Note For files without extension you can use no_extension as a placeholder. -# -# Note that for custom extensions you also need to set FILE_PATTERNS otherwise -# the files are not read by doxygen. - -EXTENSION_MAPPING = - -# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments -# according to the Markdown format, which allows for more readable -# documentation. See http://daringfireball.net/projects/markdown/ for details. -# The output of markdown processing is further processed by doxygen, so you can -# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in -# case of backward compatibilities issues. -# The default value is: YES. - -MARKDOWN_SUPPORT = YES - -# When enabled doxygen tries to link words that correspond to documented -# classes, or namespaces to their corresponding documentation. Such a link can -# be prevented in individual cases by by putting a % sign in front of the word -# or globally by setting AUTOLINK_SUPPORT to NO. -# The default value is: YES. - -AUTOLINK_SUPPORT = YES - -# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want -# to include (a tag file for) the STL sources as input, then you should set this -# tag to YES in order to let doxygen match functions declarations and -# definitions whose arguments contain STL classes (e.g. func(std::string); -# versus func(std::string) {}). This also make the inheritance and collaboration -# diagrams that involve STL classes more complete and accurate. -# The default value is: NO. - -BUILTIN_STL_SUPPORT = NO - -# If you use Microsoft's C++/CLI language, you should set this option to YES to -# enable parsing support. -# The default value is: NO. - -CPP_CLI_SUPPORT = NO - -# Set the SIP_SUPPORT tag to YES if your project consists of sip (see: -# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen -# will parse them like normal C++ but will assume all classes use public instead -# of private inheritance when no explicit protection keyword is present. -# The default value is: NO. - -SIP_SUPPORT = NO - -# For Microsoft's IDL there are propget and propput attributes to indicate -# getter and setter methods for a property. Setting this option to YES will make -# doxygen to replace the get and set methods by a property in the documentation. -# This will only work if the methods are indeed getting or setting a simple -# type. If this is not the case, or you want to show the methods anyway, you -# should set this option to NO. -# The default value is: YES. - -IDL_PROPERTY_SUPPORT = YES - -# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC -# tag is set to YES, then doxygen will reuse the documentation of the first -# member in the group (if any) for the other members of the group. By default -# all members of a group must be documented explicitly. -# The default value is: NO. - -DISTRIBUTE_GROUP_DOC = NO - -# Set the SUBGROUPING tag to YES to allow class member groups of the same type -# (for instance a group of public functions) to be put as a subgroup of that -# type (e.g. under the Public Functions section). Set it to NO to prevent -# subgrouping. Alternatively, this can be done per class using the -# \nosubgrouping command. -# The default value is: YES. - -SUBGROUPING = YES - -# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions -# are shown inside the group in which they are included (e.g. using \ingroup) -# instead of on a separate page (for HTML and Man pages) or section (for LaTeX -# and RTF). -# -# Note that this feature does not work in combination with -# SEPARATE_MEMBER_PAGES. -# The default value is: NO. - -INLINE_GROUPED_CLASSES = NO - -# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions -# with only public data fields or simple typedef fields will be shown inline in -# the documentation of the scope in which they are defined (i.e. file, -# namespace, or group documentation), provided this scope is documented. If set -# to NO, structs, classes, and unions are shown on a separate page (for HTML and -# Man pages) or section (for LaTeX and RTF). -# The default value is: NO. - -INLINE_SIMPLE_STRUCTS = NO - -# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or -# enum is documented as struct, union, or enum with the name of the typedef. So -# typedef struct TypeS {} TypeT, will appear in the documentation as a struct -# with name TypeT. When disabled the typedef will appear as a member of a file, -# namespace, or class. And the struct will be named TypeS. This can typically be -# useful for C code in case the coding convention dictates that all compound -# types are typedef'ed and only the typedef is referenced, never the tag name. -# The default value is: NO. - -TYPEDEF_HIDES_STRUCT = NO - -# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This -# cache is used to resolve symbols given their name and scope. Since this can be -# an expensive process and often the same symbol appears multiple times in the -# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small -# doxygen will become slower. If the cache is too large, memory is wasted. The -# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range -# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536 -# symbols. At the end of a run doxygen will report the cache usage and suggest -# the optimal cache size from a speed point of view. -# Minimum value: 0, maximum value: 9, default value: 0. - -LOOKUP_CACHE_SIZE = 2 - -#--------------------------------------------------------------------------- -# Build related configuration options -#--------------------------------------------------------------------------- - -# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in -# documentation are documented, even if no documentation was available. Private -# class members and static file members will be hidden unless the -# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. -# Note: This will also disable the warnings about undocumented members that are -# normally produced when WARNINGS is set to YES. -# The default value is: NO. - -EXTRACT_ALL = NO - -# If the EXTRACT_PRIVATE tag is set to YES all private members of a class will -# be included in the documentation. -# The default value is: NO. - -EXTRACT_PRIVATE = NO - -# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal -# scope will be included in the documentation. -# The default value is: NO. - -EXTRACT_PACKAGE = NO - -# If the EXTRACT_STATIC tag is set to YES all static members of a file will be -# included in the documentation. -# The default value is: NO. - -EXTRACT_STATIC = NO - -# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) defined -# locally in source files will be included in the documentation. If set to NO -# only classes defined in header files are included. Does not have any effect -# for Java sources. -# The default value is: YES. - -EXTRACT_LOCAL_CLASSES = NO - -# This flag is only useful for Objective-C code. When set to YES local methods, -# which are defined in the implementation section but not in the interface are -# included in the documentation. If set to NO only methods in the interface are -# included. -# The default value is: NO. - -EXTRACT_LOCAL_METHODS = NO - -# If this flag is set to YES, the members of anonymous namespaces will be -# extracted and appear in the documentation as a namespace called -# 'anonymous_namespace{file}', where file will be replaced with the base name of -# the file that contains the anonymous namespace. By default anonymous namespace -# are hidden. -# The default value is: NO. - -EXTRACT_ANON_NSPACES = NO - -# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all -# undocumented members inside documented classes or files. If set to NO these -# members will be included in the various overviews, but no documentation -# section is generated. This option has no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_MEMBERS = NO - -# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all -# undocumented classes that are normally visible in the class hierarchy. If set -# to NO these classes will be included in the various overviews. This option has -# no effect if EXTRACT_ALL is enabled. -# The default value is: NO. - -HIDE_UNDOC_CLASSES = NO - -# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# (class|struct|union) declarations. If set to NO these declarations will be -# included in the documentation. -# The default value is: NO. - -HIDE_FRIEND_COMPOUNDS = YES - -# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any -# documentation blocks found inside the body of a function. If set to NO these -# blocks will be appended to the function's detailed documentation block. -# The default value is: NO. - -HIDE_IN_BODY_DOCS = YES - -# The INTERNAL_DOCS tag determines if documentation that is typed after a -# \internal command is included. If the tag is set to NO then the documentation -# will be excluded. Set it to YES to include the internal documentation. -# The default value is: NO. - -INTERNAL_DOCS = NO - -# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file -# names in lower-case letters. If set to YES upper-case letters are also -# allowed. This is useful if you have classes or files whose names only differ -# in case and if your file system supports case sensitive file names. Windows -# and Mac users are advised to set this option to NO. -# The default value is: system dependent. - -CASE_SENSE_NAMES = NO - -# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with -# their full class and namespace scopes in the documentation. If set to YES the -# scope will be hidden. -# The default value is: NO. - -HIDE_SCOPE_NAMES = NO - -# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of -# the files that are included by a file in the documentation of that file. -# The default value is: YES. - -SHOW_INCLUDE_FILES = NO - -# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include -# files with double quotes in the documentation rather than with sharp brackets. -# The default value is: NO. - -FORCE_LOCAL_INCLUDES = NO - -# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the -# documentation for inline members. -# The default value is: YES. - -INLINE_INFO = YES - -# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the -# (detailed) documentation of file and class members alphabetically by member -# name. If set to NO the members will appear in declaration order. -# The default value is: YES. - -SORT_MEMBER_DOCS = NO - -# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief -# descriptions of file, namespace and class members alphabetically by member -# name. If set to NO the members will appear in declaration order. -# The default value is: NO. - -SORT_BRIEF_DOCS = NO - -# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the -# (brief and detailed) documentation of class members so that constructors and -# destructors are listed first. If set to NO the constructors will appear in the -# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS. -# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief -# member documentation. -# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting -# detailed member documentation. -# The default value is: NO. - -SORT_MEMBERS_CTORS_1ST = YES - -# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy -# of group names into alphabetical order. If set to NO the group names will -# appear in their defined order. -# The default value is: NO. - -SORT_GROUP_NAMES = NO - -# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by -# fully-qualified names, including namespaces. If set to NO, the class list will -# be sorted only by class name, not including the namespace part. -# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. -# Note: This option applies only to the class list, not to the alphabetical -# list. -# The default value is: NO. - -SORT_BY_SCOPE_NAME = NO - -# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper -# type resolution of all parameters of a function it will reject a match between -# the prototype and the implementation of a member function even if there is -# only one candidate or it is obvious which candidate to choose by doing a -# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still -# accept a match between prototype and implementation in such cases. -# The default value is: NO. - -STRICT_PROTO_MATCHING = NO - -# The GENERATE_TODOLIST tag can be used to enable ( YES) or disable ( NO) the -# todo list. This list is created by putting \todo commands in the -# documentation. -# The default value is: YES. - -GENERATE_TODOLIST = YES - -# The GENERATE_TESTLIST tag can be used to enable ( YES) or disable ( NO) the -# test list. This list is created by putting \test commands in the -# documentation. -# The default value is: YES. - -GENERATE_TESTLIST = NO - -# The GENERATE_BUGLIST tag can be used to enable ( YES) or disable ( NO) the bug -# list. This list is created by putting \bug commands in the documentation. -# The default value is: YES. - -GENERATE_BUGLIST = NO - -# The GENERATE_DEPRECATEDLIST tag can be used to enable ( YES) or disable ( NO) -# the deprecated list. This list is created by putting \deprecated commands in -# the documentation. -# The default value is: YES. - -GENERATE_DEPRECATEDLIST= YES - -# The ENABLED_SECTIONS tag can be used to enable conditional documentation -# sections, marked by \if ... \endif and \cond -# ... \endcond blocks. - -ENABLED_SECTIONS = - -# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the -# initial value of a variable or macro / define can have for it to appear in the -# documentation. If the initializer consists of more lines than specified here -# it will be hidden. Use a value of 0 to hide initializers completely. The -# appearance of the value of individual variables and macros / defines can be -# controlled using \showinitializer or \hideinitializer command in the -# documentation regardless of this setting. -# Minimum value: 0, maximum value: 10000, default value: 30. - -MAX_INITIALIZER_LINES = 30 - -# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at -# the bottom of the documentation of classes and structs. If set to YES the list -# will mention the files that were used to generate the documentation. -# The default value is: YES. - -SHOW_USED_FILES = YES - -# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This -# will remove the Files entry from the Quick Index and from the Folder Tree View -# (if specified). -# The default value is: YES. - -SHOW_FILES = YES - -# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces -# page. This will remove the Namespaces entry from the Quick Index and from the -# Folder Tree View (if specified). -# The default value is: YES. - -SHOW_NAMESPACES = YES - -# The FILE_VERSION_FILTER tag can be used to specify a program or script that -# doxygen should invoke to get the current version for each file (typically from -# the version control system). Doxygen will invoke the program by executing (via -# popen()) the command command input-file, where command is the value of the -# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided -# by doxygen. Whatever the program writes to standard output is used as the file -# version. For an example see the documentation. - -FILE_VERSION_FILTER = - -# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed -# by doxygen. The layout file controls the global structure of the generated -# output files in an output format independent way. To create the layout file -# that represents doxygen's defaults, run doxygen with the -l option. You can -# optionally specify a file name after the option, if omitted DoxygenLayout.xml -# will be used as the name of the layout file. -# -# Note that if you run doxygen from a directory containing a file called -# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE -# tag is left empty. - -LAYOUT_FILE = - -# The CITE_BIB_FILES tag can be used to specify one or more bib files containing -# the reference definitions. This must be a list of .bib files. The .bib -# extension is automatically appended if omitted. This requires the bibtex tool -# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info. -# For LaTeX the style of the bibliography can be controlled using -# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the -# search path. Do not use file names with spaces, bibtex cannot handle them. See -# also \cite for info how to create references. - -CITE_BIB_FILES = - -#--------------------------------------------------------------------------- -# Configuration options related to warning and progress messages -#--------------------------------------------------------------------------- - -# The QUIET tag can be used to turn on/off the messages that are generated to -# standard output by doxygen. If QUIET is set to YES this implies that the -# messages are off. -# The default value is: NO. - -QUIET = NO - -# The WARNINGS tag can be used to turn on/off the warning messages that are -# generated to standard error ( stderr) by doxygen. If WARNINGS is set to YES -# this implies that the warnings are on. -# -# Tip: Turn warnings on while writing the documentation. -# The default value is: YES. - -WARNINGS = YES - -# If the WARN_IF_UNDOCUMENTED tag is set to YES, then doxygen will generate -# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag -# will automatically be disabled. -# The default value is: YES. - -WARN_IF_UNDOCUMENTED = YES - -# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for -# potential errors in the documentation, such as not documenting some parameters -# in a documented function, or documenting parameters that don't exist or using -# markup commands wrongly. -# The default value is: YES. - -WARN_IF_DOC_ERROR = YES - -# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that -# are documented, but have no documentation for their parameters or return -# value. If set to NO doxygen will only warn about wrong or incomplete parameter -# documentation, but not about the absence of documentation. -# The default value is: NO. - -WARN_NO_PARAMDOC = YES - -# The WARN_FORMAT tag determines the format of the warning messages that doxygen -# can produce. The string should contain the $file, $line, and $text tags, which -# will be replaced by the file and line number from which the warning originated -# and the warning text. Optionally the format may contain $version, which will -# be replaced by the version of the file (if it could be obtained via -# FILE_VERSION_FILTER) -# The default value is: $file:$line: $text. - -WARN_FORMAT = "FIX: $file:$line: $text" - -# The WARN_LOGFILE tag can be used to specify a file to which warning and error -# messages should be written. If left blank the output is written to standard -# error (stderr). - -WARN_LOGFILE = doxygen_warnings.txt - -#--------------------------------------------------------------------------- -# Configuration options related to the input files -#--------------------------------------------------------------------------- - -# This tag can be used to specify the character encoding of the source files -# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses -# libiconv (or the iconv built into libc) for the transcoding. See the libiconv -# documentation (see: http://www.gnu.org/software/libiconv) for the list of -# possible encodings. -# The default value is: UTF-8. - -INPUT_ENCODING = UTF-8 - -# If the value of the INPUT tag contains directories, you can use the -# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and -# *.h) to filter out the source-files in the directories. If left blank the -# following patterns are tested:*.c, *.cc, *.cxx, *.cpp, *.c++, *.java, *.ii, -# *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, *.hh, *.hxx, *.hpp, -# *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, *.m, *.markdown, -# *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, -# *.qsf, *.as and *.js. - -FILE_PATTERNS = *.c *.cpp *.h *.hpp *.md - -# The RECURSIVE tag can be used to specify whether or not subdirectories should -# be searched for input files as well. -# The default value is: NO. - -RECURSIVE = YES - -# The EXCLUDE tag can be used to specify files and/or directories that should be -# excluded from the INPUT source files. This way you can easily exclude a -# subdirectory from a directory tree whose root is specified with the INPUT tag. -# -# Note that relative paths are relative to the directory from which doxygen is -# run. - -EXCLUDE = - -# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or -# directories that are symbolic links (a Unix file system feature) are excluded -# from the input. -# The default value is: NO. - -EXCLUDE_SYMLINKS = NO - -# If the value of the INPUT tag contains directories, you can use the -# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude -# certain files from those directories. -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories for example use the pattern */test/* - -EXCLUDE_PATTERNS = - -# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names -# (namespaces, classes, functions, etc.) that should be excluded from the -# output. The symbol name can be a fully qualified name, a word, or if the -# wildcard * is used, a substring. Examples: ANamespace, AClass, -# AClass::ANamespace, ANamespace::*Test -# -# Note that the wildcards are matched against the file with absolute path, so to -# exclude all test directories use the pattern */test/* - -EXCLUDE_SYMBOLS = - -# The EXAMPLE_PATH tag can be used to specify one or more files or directories -# that contain example code fragments that are included (see the \include -# command). - -EXAMPLE_PATH = - -# If the value of the EXAMPLE_PATH tag contains directories, you can use the -# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and -# *.h) to filter out the source-files in the directories. If left blank all -# files are included. - -EXAMPLE_PATTERNS = - -# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be -# searched for input files to be used with the \include or \dontinclude commands -# irrespective of the value of the RECURSIVE tag. -# The default value is: NO. - -EXAMPLE_RECURSIVE = NO - -# The IMAGE_PATH tag can be used to specify one or more files or directories -# that contain images that are to be included in the documentation (see the -# \image command). - -IMAGE_PATH = doc/images - -# The INPUT_FILTER tag can be used to specify a program that doxygen should -# invoke to filter for each input file. Doxygen will invoke the filter program -# by executing (via popen()) the command: -# -# -# -# where is the value of the INPUT_FILTER tag, and is the -# name of an input file. Doxygen will then use the output that the filter -# program writes to standard output. If FILTER_PATTERNS is specified, this tag -# will be ignored. -# -# Note that the filter must not add or remove lines; it is applied before the -# code is scanned, but not when the output code is generated. If lines are added -# or removed, the anchors will not be placed correctly. - -INPUT_FILTER = - -# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern -# basis. Doxygen will compare the file name with each pattern and apply the -# filter if there is a match. The filters are a list of the form: pattern=filter -# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how -# filters are used. If the FILTER_PATTERNS tag is empty or if none of the -# patterns match the file name, INPUT_FILTER is applied. - -FILTER_PATTERNS = - -# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using -# INPUT_FILTER ) will also be used to filter the input files that are used for -# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). -# The default value is: NO. - -FILTER_SOURCE_FILES = NO - -# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file -# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and -# it is also possible to disable source filtering for a specific pattern using -# *.ext= (so without naming a filter). -# This tag requires that the tag FILTER_SOURCE_FILES is set to YES. - -FILTER_SOURCE_PATTERNS = - -# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that -# is part of the input, its contents will be placed on the main page -# (index.html). This can be useful if you have a project on for instance GitHub -# and want to reuse the introduction page also for the doxygen output. - -USE_MDFILE_AS_MAINPAGE = README.md - -#--------------------------------------------------------------------------- -# Configuration options related to source browsing -#--------------------------------------------------------------------------- - -# If the SOURCE_BROWSER tag is set to YES then a list of source files will be -# generated. Documented entities will be cross-referenced with these sources. -# -# Note: To get rid of all source code in the generated output, make sure that -# also VERBATIM_HEADERS is set to NO. -# The default value is: NO. - -SOURCE_BROWSER = YES - -# Setting the INLINE_SOURCES tag to YES will include the body of functions, -# classes and enums directly into the documentation. -# The default value is: NO. - -INLINE_SOURCES = NO - -# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any -# special comment blocks from generated source code fragments. Normal C, C++ and -# Fortran comments will always remain visible. -# The default value is: YES. - -STRIP_CODE_COMMENTS = YES - -# If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# function all documented functions referencing it will be listed. -# The default value is: NO. - -REFERENCED_BY_RELATION = NO - -# If the REFERENCES_RELATION tag is set to YES then for each documented function -# all documented entities called/used by that function will be listed. -# The default value is: NO. - -REFERENCES_RELATION = NO - -# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set -# to YES, then the hyperlinks from functions in REFERENCES_RELATION and -# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will -# link to the documentation. -# The default value is: YES. - -REFERENCES_LINK_SOURCE = YES - -# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the -# source code will show a tooltip with additional information such as prototype, -# brief description and links to the definition and documentation. Since this -# will make the HTML file larger and loading of large files a bit slower, you -# can opt to disable this feature. -# The default value is: YES. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -SOURCE_TOOLTIPS = YES - -# If the USE_HTAGS tag is set to YES then the references to source code will -# point to the HTML generated by the htags(1) tool instead of doxygen built-in -# source browser. The htags tool is part of GNU's global source tagging system -# (see http://www.gnu.org/software/global/global.html). You will need version -# 4.8.6 or higher. -# -# To use it do the following: -# - Install the latest version of global -# - Enable SOURCE_BROWSER and USE_HTAGS in the config file -# - Make sure the INPUT points to the root of the source tree -# - Run doxygen as normal -# -# Doxygen will invoke htags (and that will in turn invoke gtags), so these -# tools must be available from the command line (i.e. in the search path). -# -# The result: instead of the source browser generated by doxygen, the links to -# source code will now point to the output of htags. -# The default value is: NO. -# This tag requires that the tag SOURCE_BROWSER is set to YES. - -USE_HTAGS = NO - -# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a -# verbatim copy of the header file for each class for which an include is -# specified. Set to NO to disable this. -# See also: Section \class. -# The default value is: YES. - -VERBATIM_HEADERS = YES - -#--------------------------------------------------------------------------- -# Configuration options related to the alphabetical class index -#--------------------------------------------------------------------------- - -# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all -# compounds will be generated. Enable this if the project contains a lot of -# classes, structs, unions or interfaces. -# The default value is: YES. - -ALPHABETICAL_INDEX = YES - -# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in -# which the alphabetical index list will be split. -# Minimum value: 1, maximum value: 20, default value: 5. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -COLS_IN_ALPHA_INDEX = 5 - -# In case all classes in a project start with a common prefix, all classes will -# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag -# can be used to specify a prefix (or a list of prefixes) that should be ignored -# while generating the index headers. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -IGNORE_PREFIX = - -#--------------------------------------------------------------------------- -# Configuration options related to the HTML output -#--------------------------------------------------------------------------- - -# If the GENERATE_HTML tag is set to YES doxygen will generate HTML output -# The default value is: YES. - -GENERATE_HTML = YES - -# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a -# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of -# it. -# The default directory is: html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_OUTPUT = html - -# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each -# generated HTML page (for example: .htm, .php, .asp). -# The default value is: .html. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FILE_EXTENSION = .html - -# The HTML_HEADER tag can be used to specify a user-defined HTML header file for -# each generated HTML page. If the tag is left blank doxygen will generate a -# standard header. -# -# To get valid HTML the header file that includes any scripts and style sheets -# that doxygen needs, which is dependent on the configuration options used (e.g. -# the setting GENERATE_TREEVIEW). It is highly recommended to start with a -# default header using -# doxygen -w html new_header.html new_footer.html new_stylesheet.css -# YourConfigFile -# and then modify the file new_header.html. See also section "Doxygen usage" -# for information on how to generate the default header that doxygen normally -# uses. -# Note: The header is subject to change so you typically have to regenerate the -# default header when upgrading to a newer version of doxygen. For a description -# of the possible markers and block names see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_HEADER = - -# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each -# generated HTML page. If the tag is left blank doxygen will generate a standard -# footer. See HTML_HEADER for more information on how to generate a default -# footer and what special commands can be used inside the footer. See also -# section "Doxygen usage" for information on how to generate the default footer -# that doxygen normally uses. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_FOOTER = - -# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style -# sheet that is used by each HTML page. It can be used to fine-tune the look of -# the HTML output. If left blank doxygen will generate a default style sheet. -# See also section "Doxygen usage" for information on how to generate the style -# sheet that doxygen normally uses. -# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as -# it is more robust and this tag (HTML_STYLESHEET) will in the future become -# obsolete. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_STYLESHEET = - -# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional user- -# defined cascading style sheet that is included after the standard style sheets -# created by doxygen. Using this option one can overrule certain style aspects. -# This is preferred over using HTML_STYLESHEET since it does not replace the -# standard style sheet and is therefor more robust against future updates. -# Doxygen will copy the style sheet file to the output directory. For an example -# see the documentation. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_STYLESHEET = - -# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or -# other source files which should be copied to the HTML output directory. Note -# that these files will be copied to the base HTML output directory. Use the -# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these -# files. In the HTML_STYLESHEET file, use the file name only. Also note that the -# files will be copied as-is; there are no commands or markers available. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_EXTRA_FILES = - -# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen -# will adjust the colors in the stylesheet and background images according to -# this color. Hue is specified as an angle on a colorwheel, see -# http://en.wikipedia.org/wiki/Hue for more information. For instance the value -# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 -# purple, and 360 is red again. -# Minimum value: 0, maximum value: 359, default value: 220. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_HUE = 220 - -# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors -# in the HTML output. For a value of 0 the output will use grayscales only. A -# value of 255 will produce the most vivid colors. -# Minimum value: 0, maximum value: 255, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_SAT = 100 - -# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the -# luminance component of the colors in the HTML output. Values below 100 -# gradually make the output lighter, whereas values above 100 make the output -# darker. The value divided by 100 is the actual gamma applied, so 80 represents -# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not -# change the gamma. -# Minimum value: 40, maximum value: 240, default value: 80. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_COLORSTYLE_GAMMA = 80 - -# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML -# page will contain the date and time when the page was generated. Setting this -# to NO can help when comparing the output of multiple runs. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_TIMESTAMP = YES - -# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML -# documentation will contain sections that can be hidden and shown after the -# page has loaded. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_DYNAMIC_SECTIONS = NO - -# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries -# shown in the various tree structured indices initially; the user can expand -# and collapse entries dynamically later on. Doxygen will expand the tree to -# such a level that at most the specified number of entries are visible (unless -# a fully collapsed tree already exceeds this amount). So setting the number of -# entries 1 will produce a full collapsed tree by default. 0 is a special value -# representing an infinite number of entries and will result in a full expanded -# tree by default. -# Minimum value: 0, maximum value: 9999, default value: 100. -# This tag requires that the tag GENERATE_HTML is set to YES. - -HTML_INDEX_NUM_ENTRIES = 100 - -# If the GENERATE_DOCSET tag is set to YES, additional index files will be -# generated that can be used as input for Apple's Xcode 3 integrated development -# environment (see: http://developer.apple.com/tools/xcode/), introduced with -# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a -# Makefile in the HTML output directory. Running make will produce the docset in -# that directory and running make install will install the docset in -# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at -# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html -# for more information. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_DOCSET = NO - -# This tag determines the name of the docset feed. A documentation feed provides -# an umbrella under which multiple documentation sets from a single provider -# (such as a company or product suite) can be grouped. -# The default value is: Doxygen generated docs. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_FEEDNAME = "Doxygen generated docs" - -# This tag specifies a string that should uniquely identify the documentation -# set bundle. This should be a reverse domain-name style string, e.g. -# com.mycompany.MyDocSet. Doxygen will append .docset to the name. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_BUNDLE_ID = org.doxygen.Project - -# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify -# the documentation publisher. This should be a reverse domain-name style -# string, e.g. com.mycompany.MyDocSet.documentation. -# The default value is: org.doxygen.Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_ID = org.doxygen.Publisher - -# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher. -# The default value is: Publisher. -# This tag requires that the tag GENERATE_DOCSET is set to YES. - -DOCSET_PUBLISHER_NAME = Publisher - -# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three -# additional HTML index files: index.hhp, index.hhc, and index.hhk. The -# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop -# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on -# Windows. -# -# The HTML Help Workshop contains a compiler that can convert all HTML output -# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML -# files are now used as the Windows 98 help format, and will replace the old -# Windows help format (.hlp) on all Windows platforms in the future. Compressed -# HTML files also contain an index, a table of contents, and you can search for -# words in the documentation. The HTML workshop also contains a viewer for -# compressed HTML files. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_HTMLHELP = NO - -# The CHM_FILE tag can be used to specify the file name of the resulting .chm -# file. You can add a path in front of the file if the result should not be -# written to the html output directory. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_FILE = - -# The HHC_LOCATION tag can be used to specify the location (absolute path -# including file name) of the HTML help compiler ( hhc.exe). If non-empty -# doxygen will try to run the HTML help compiler on the generated index.hhp. -# The file has to be specified with full path. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -HHC_LOCATION = - -# The GENERATE_CHI flag controls if a separate .chi index file is generated ( -# YES) or that it should be included in the master .chm file ( NO). -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -GENERATE_CHI = NO - -# The CHM_INDEX_ENCODING is used to encode HtmlHelp index ( hhk), content ( hhc) -# and project file content. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -CHM_INDEX_ENCODING = - -# The BINARY_TOC flag controls whether a binary table of contents is generated ( -# YES) or a normal table of contents ( NO) in the .chm file. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -BINARY_TOC = NO - -# The TOC_EXPAND flag can be set to YES to add extra items for group members to -# the table of contents of the HTML help documentation and to the tree view. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTMLHELP is set to YES. - -TOC_EXPAND = NO - -# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and -# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that -# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help -# (.qch) of the generated HTML documentation. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_QHP = NO - -# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify -# the file name of the resulting .qch file. The path specified is relative to -# the HTML output folder. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QCH_FILE = - -# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help -# Project output. For more information please see Qt Help Project / Namespace -# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace). -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_NAMESPACE = org.doxygen.Project - -# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt -# Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual- -# folders). -# The default value is: doc. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_VIRTUAL_FOLDER = doc - -# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom -# filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- -# filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_NAME = - -# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the -# custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- -# filters). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_CUST_FILTER_ATTRS = - -# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this -# project's filter section matches. Qt Help Project / Filter Attributes (see: -# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes). -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHP_SECT_FILTER_ATTRS = - -# The QHG_LOCATION tag can be used to specify the location of Qt's -# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the -# generated .qhp file. -# This tag requires that the tag GENERATE_QHP is set to YES. - -QHG_LOCATION = - -# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be -# generated, together with the HTML files, they form an Eclipse help plugin. To -# install this plugin and make it available under the help contents menu in -# Eclipse, the contents of the directory containing the HTML and XML files needs -# to be copied into the plugins directory of eclipse. The name of the directory -# within the plugins directory should be the same as the ECLIPSE_DOC_ID value. -# After copying Eclipse needs to be restarted before the help appears. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_ECLIPSEHELP = NO - -# A unique identifier for the Eclipse help plugin. When installing the plugin -# the directory name containing the HTML and XML files should also have this -# name. Each documentation set should have its own identifier. -# The default value is: org.doxygen.Project. -# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES. - -ECLIPSE_DOC_ID = org.doxygen.Project - -# If you want full control over the layout of the generated HTML pages it might -# be necessary to disable the index and replace it with your own. The -# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top -# of each HTML page. A value of NO enables the index and the value YES disables -# it. Since the tabs in the index contain the same information as the navigation -# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -DISABLE_INDEX = NO - -# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index -# structure should be generated to display hierarchical information. If the tag -# value is set to YES, a side panel will be generated containing a tree-like -# index structure (just like the one that is generated for HTML Help). For this -# to work a browser that supports JavaScript, DHTML, CSS and frames is required -# (i.e. any modern browser). Windows users are probably better off using the -# HTML help feature. Via custom stylesheets (see HTML_EXTRA_STYLESHEET) one can -# further fine-tune the look of the index. As an example, the default style -# sheet generated by doxygen has an example that shows how to put an image at -# the root of the tree instead of the PROJECT_NAME. Since the tree basically has -# the same information as the tab index, you could consider setting -# DISABLE_INDEX to YES when enabling this option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -GENERATE_TREEVIEW = NO - -# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that -# doxygen will group on one line in the generated HTML documentation. -# -# Note that a value of 0 will completely suppress the enum values from appearing -# in the overview section. -# Minimum value: 0, maximum value: 20, default value: 4. -# This tag requires that the tag GENERATE_HTML is set to YES. - -ENUM_VALUES_PER_LINE = 4 - -# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used -# to set the initial width (in pixels) of the frame in which the tree is shown. -# Minimum value: 0, maximum value: 1500, default value: 250. -# This tag requires that the tag GENERATE_HTML is set to YES. - -TREEVIEW_WIDTH = 250 - -# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open links to -# external symbols imported via tag files in a separate window. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -EXT_LINKS_IN_WINDOW = NO - -# Use this tag to change the font size of LaTeX formulas included as images in -# the HTML documentation. When you change the font size after a successful -# doxygen run you need to manually remove any form_*.png images from the HTML -# output directory to force them to be regenerated. -# Minimum value: 8, maximum value: 50, default value: 10. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_FONTSIZE = 10 - -# Use the FORMULA_TRANPARENT tag to determine whether or not the images -# generated for formulas are transparent PNGs. Transparent PNGs are not -# supported properly for IE 6.0, but are supported on all modern browsers. -# -# Note that when changing this option you need to delete any form_*.png files in -# the HTML output directory before the changes have effect. -# The default value is: YES. -# This tag requires that the tag GENERATE_HTML is set to YES. - -FORMULA_TRANSPARENT = YES - -# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# http://www.mathjax.org) which uses client side Javascript for the rendering -# instead of using prerendered bitmaps. Use this if you do not have LaTeX -# installed or if you want to formulas look prettier in the HTML output. When -# enabled you may also need to install MathJax separately and configure the path -# to it using the MATHJAX_RELPATH option. -# The default value is: NO. -# This tag requires that the tag GENERATE_HTML is set to YES. - -USE_MATHJAX = NO - -# When MathJax is enabled you can set the default output format to be used for -# the MathJax output. See the MathJax site (see: -# http://docs.mathjax.org/en/latest/output.html) for more details. -# Possible values are: HTML-CSS (which is slower, but has the best -# compatibility), NativeMML (i.e. MathML) and SVG. -# The default value is: HTML-CSS. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_FORMAT = HTML-CSS - -# When MathJax is enabled you need to specify the location relative to the HTML -# output directory using the MATHJAX_RELPATH option. The destination directory -# should contain the MathJax.js script. For instance, if the mathjax directory -# is located at the same level as the HTML output directory, then -# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax -# Content Delivery Network so you can quickly see the result without installing -# MathJax. However, it is strongly recommended to install a local copy of -# MathJax from http://www.mathjax.org before deployment. -# The default value is: http://cdn.mathjax.org/mathjax/latest. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest - -# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax -# extension names that should be enabled during MathJax rendering. For example -# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_EXTENSIONS = - -# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces -# of code that will be used on startup of the MathJax code. See the MathJax site -# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an -# example see the documentation. -# This tag requires that the tag USE_MATHJAX is set to YES. - -MATHJAX_CODEFILE = - -# When the SEARCHENGINE tag is enabled doxygen will generate a search box for -# the HTML output. The underlying search engine uses javascript and DHTML and -# should work on any modern browser. Note that when using HTML help -# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) -# there is already a search function so this one should typically be disabled. -# For large projects the javascript based search engine can be slow, then -# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to -# search using the keyboard; to jump to the search box use + S -# (what the is depends on the OS and browser, but it is typically -# , /C++', []), + ('Python', []), + ('GitHub', []) +] +LINKS_NAVBAR2 = [] + +SEARCH_DISABLED = True \ No newline at end of file diff --git a/docs/conf_python.py b/docs/conf_python.py new file mode 100644 index 00000000..f3e61b70 --- /dev/null +++ b/docs/conf_python.py @@ -0,0 +1,16 @@ +PROJECT_TITLE = 'manif' +PROJECT_SUBTITLE = 'Python API' + +MAIN_PROJECT_URL = '../html/index.html' + +INPUT_MODULES = ['manifpy'] +OUTPUT = 'site/python' + +LINKS_NAVBAR1 = [ + ('Modules', 'modules', []), + ('Classes', 'classes', []), + ('Github', 'https://github.com/artivis/manif', []) +] +LINKS_NAVBAR2 = [] + +PYBIND11_COMPATIBILITY = True From 4170520ba0daea67351d7e6645abea4abd09946a Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 25 Jan 2021 17:45:56 -0500 Subject: [PATCH 60/67] ~private Python base classes & add documentation --- include/manif/impl/lie_group_base.h | 8 +- include/manif/impl/tangent_base.h | 2 +- python/bindings_lie_group_base.h | 293 +++++++++++++++++++----- python/bindings_manif.cpp | 2 +- python/bindings_rn.cpp | 76 ++++--- python/bindings_se2.cpp | 12 +- python/bindings_se3.cpp | 12 +- python/bindings_se_2_3.cpp | 12 +- python/bindings_so2.cpp | 16 +- python/bindings_so3.cpp | 12 +- python/bindings_tangent_base.h | 341 +++++++++++++++++++++++----- 11 files changed, 601 insertions(+), 185 deletions(-) diff --git a/include/manif/impl/lie_group_base.h b/include/manif/impl/lie_group_base.h index afec8075..2adf0960 100644 --- a/include/manif/impl/lie_group_base.h +++ b/include/manif/impl/lie_group_base.h @@ -152,11 +152,11 @@ struct LieGroupBase OptJacobianRef J_mc_mb = {}) const; /** - * @brief TODO tofix - * @param v + * @brief Get the action of the Lie group object on a point. + * @param[in] v A point. * @param[out] -optional- J_vout_m Jacobian of the new object wrt this. * @param[out] -optional- J_vout_v Jacobian of the new object wrt input object. - * @return + * @return A point acted upon by the object. */ template Vector act(const Eigen::MatrixBase<_EigenDerived>& v, @@ -256,7 +256,7 @@ struct LieGroupBase /** * @brief Evaluate whether this and m are 'close'. * @param[in] m An element of the same Lie Group. - * @param[in] eps Threshold for equality copmarison. + * @param[in] eps Threshold for equality comparison. * @return true if the Lie group element m is 'close' to this, * false otherwise. * @see TangentBase::isApprox diff --git a/include/manif/impl/tangent_base.h b/include/manif/impl/tangent_base.h index e2689049..b14ae756 100644 --- a/include/manif/impl/tangent_base.h +++ b/include/manif/impl/tangent_base.h @@ -117,7 +117,7 @@ struct TangentBase /** * @brief Get inner product of this and another Tangent - * weightedby W. + * weighted by W. * @return The inner product of this and t. * @note ip = v0' . W . v1 * @see innerWeights() diff --git a/python/bindings_lie_group_base.h b/python/bindings_lie_group_base.h index 219b803b..30cd0c3c 100644 --- a/python/bindings_lie_group_base.h +++ b/python/bindings_lie_group_base.h @@ -1,10 +1,8 @@ #ifndef _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_ #define _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_ -namespace py = pybind11; - template -void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { +void wrap_lie_group_base(pybind11::class_<_LieGroup, _Args...>& py_class) { using Scalar = typename _LieGroup::Scalar; using Tangent = typename _LieGroup::Tangent; @@ -16,57 +14,128 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { py_class.attr("DoF") = _LieGroup::DoF; py_class.attr("RepSize") = _LieGroup::RepSize; - py_class.def(py::init<>()); - py_class.def(py::init()); + py_class.def( + pybind11::init<>(), + "Default constructor, uninitialized data." + ); + + py_class.def( + pybind11::init(), + "Constructor given data vector." + ); py_class.def( "coeffs_copy", - static_cast(&_LieGroup::coeffs) + static_cast(&_LieGroup::coeffs), + "Return a copy of underlying data." ); // Makes a copy! py_class.def( "coeffs", static_cast(&_LieGroup::coeffs), - py::return_value_policy::reference_internal + pybind11::return_value_policy::reference_internal, + "Get a reference to underlying data." ); py_class.def( "inverse", &_LieGroup::inverse, - py::arg_v("J_out_self", OptJacobianRef(), "None") + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + R"( + Return the inverse of the Lie group object. + + See Eq. (3). + + Parameters + ---------- + J_out_self [out] : numpy.ndarray + Jacobian of the inverse wrt self. + )" ); py_class.def( "log", &_LieGroup::log, - py::arg_v("J_out_self", OptJacobianRef(), "None") + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + R"( + Return the corresponding Lie algebra element in vector form. + + Eq. (24). + + Parameters + ---------- + J_out_self [out] : numpy.ndarray + Jacobian of the log wrt self. + )" ); - py_class.def("adj", &_LieGroup::adj); + py_class.def( + "adj", + &_LieGroup::adj, + R"( + Return the Adjoint of the Lie group object self. + + See Eq. (29). + )" + ); py_class.def( "compose", &_LieGroup::template compose<_LieGroup>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + R"( + Return the composition of self and another object of the same Lie group. + + See Eqs. (1,2,3,4). + + Parameters + ---------- + other : Lie group + Another object of the same Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the composition wrt self. + J_out_other [out] : numpy.ndarray + Jacobian of the composition wrt other. + )" ); py_class.def( "between", &_LieGroup::template between<_LieGroup>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + R"( + Return the between of self and another object of the same Lie group. + + Parameters + ---------- + other : Lie group + Another object of the same Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the composition wrt self. + J_out_other [out] : numpy.ndarray + Jacobian of the composition wrt other. + )" ); // That pops some nasty compilation errors. // py_class.def( // "act", // &_LieGroup::template act, - // py::arg("v"), - // py::arg_v("J_vout_m", tl::optional>>(), "None"), - // py::arg_v("J_vout_v", tl::optional>>(), "None") + // pybind11::arg("v"), + // pybind11::arg_v( + // "J_vout_m", + // tl::optional>>(), + // "None" + // ), + // pybind11::arg_v( + // "J_vout_v", + // tl::optional>>(), + // "None" + // ) // ); py_class.def( @@ -78,79 +147,197 @@ void wrap_lie_group_base(py::class_<_LieGroup, _Args...>& py_class) { tl::optional>> Jb) { return self.act(v, Ja, Jb); }, - py::arg("p"), - py::arg_v("J_out_self", tl::optional>>(), "None"), - py::arg_v("J_out_p", tl::optional>>(), "None") + pybind11::arg("p"), + pybind11::arg_v( + "J_out_self", + tl::optional>>(), + "None" + ), + pybind11::arg_v( + "J_out_p", + tl::optional>>(), + "None" + ), + R"( + Get the action of the Lie group object on a point. + + Parameters + ---------- + p : numpy.array + A point. + J_out_self [out] : numpy.ndarray + Jacobian of the new object wrt self. + J_out_p [out] : numpy.ndarray + Jacobian of the new object wrt input point. + )" ); py_class.def( "isApprox", &_LieGroup::template isApprox<_LieGroup>, - py::arg("other"), - py::arg_v("eps", Scalar(manif::Constants::eps), "eps") + pybind11::arg("other"), + pybind11::arg_v("eps", Scalar(manif::Constants::eps), "1e-10"), + R"( + Evaluate whether self and other are 'close'. + + Parameters + ---------- + other : Lie group + Another object of the same Lie group. + eps : double + Threshold for equality comparison. Default: 1e-10. + )" ); py_class.def( "rplus", &_LieGroup::template rplus, - py::arg("tau"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_tau", OptJacobianRef(), "None") + pybind11::arg("tau"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_tau", OptJacobianRef(), "None" ), + R"( + Right oplus operation of the Lie group. + + See Eq. (25). + + Parameters + ---------- + tau : Lie group tangent + An element of the tangent of the Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the oplus operation wrt self. + J_out_tau [out] : numpy.ndarray + Jacobian of the oplus operation wrt tau. + )" ); py_class.def( "lplus", &_LieGroup::template lplus, - py::arg("tau"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_mout_tau", OptJacobianRef(), "None") + pybind11::arg("tau"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_mout_tau", OptJacobianRef(), "None"), + R"( + Left oplus operation of the Lie group. + + See Eq. (27). + + Parameters + ---------- + tau : Lie group tangent + An element of the tangent of the Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the oplus operation wrt self. + J_out_tau [out] : numpy.ndarray + Jacobian of the oplus operation wrt tau. + )" ); py_class.def( "plus", &_LieGroup::template plus, - py::arg("tau"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_mout_tau", OptJacobianRef(), "None") + pybind11::arg("tau"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_mout_tau", OptJacobianRef(), "None"), + "An alias for the 'rplus' function." ); py_class.def( "rminus", &_LieGroup::template rminus<_LieGroup>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + R"( + Right ominus operation of the Lie group. + + See Eq. (26). + + Parameters + ---------- + other : Lie group + Another element of the same Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the ominus operation wrt self. + J_out_other [out] : numpy.ndarray + Jacobian of the ominus operation wrt other. + )" ); py_class.def( "lminus", &_LieGroup::template lminus<_LieGroup>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + R"( + Left ominus operation of the Lie group. + + See Eq. (28). + + Parameters + ---------- + other : Lie group + Another element of the same Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the ominus operation wrt self. + J_out_other [out] : numpy.ndarray + Jacobian of the ominus operation wrt other. + )" ); py_class.def( "minus", &_LieGroup::template minus<_LieGroup>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + "An alias for the 'rminus' function." ); - py_class.def("setIdentity", &_LieGroup::setIdentity); - py_class.def("setRandom", &_LieGroup::setRandom); + py_class.def( + "setIdentity", + &_LieGroup::setIdentity, + "Set self to the Lie group Identity." + ); - py_class.def_static("Identity", &_LieGroup::Identity); - py_class.def_static("Random", &_LieGroup::Random); + py_class.def( + "setRandom", + &_LieGroup::setRandom, + "Set self to a random value." + ); - py_class.def(py::self + Tangent()) - // .def(py::self += Tangent()) - .def(py::self - py::self) - .def(py::self * py::self) - // .def(py::self *= py::self) - .def(py::self == py::self) - ; + py_class.def_static( + "Identity", + &_LieGroup::Identity, + "Static helper to create an object set at the Lie group Identity." + ); + + py_class.def_static( + "Random", + &_LieGroup::Random, + "Static helper to create a random object of the Lie group." + ); + + py_class.def( + pybind11::self + Tangent(), + "Operator overload for the 'plus' function." + ) + // .def(pybind11::self += Tangent()) + .def( + pybind11::self - pybind11::self, + "Operator overload for the 'minus' function." + ) + .def( + pybind11::self * pybind11::self, + "Operator overload for the 'compose' function." + ) + // .def(pybind11::self *= pybind11::self) + .def( + pybind11::self == pybind11::self, + "Operator overload for the 'isApprox' function." + ) + ; py_class.def( "__str__", diff --git a/python/bindings_manif.cpp b/python/bindings_manif.cpp index 898e5614..96757b38 100644 --- a/python/bindings_manif.cpp +++ b/python/bindings_manif.cpp @@ -11,7 +11,7 @@ void wrap_SE3(pybind11::module &m); void wrap_SE_2_3(pybind11::module &m); PYBIND11_MODULE(manifpy, m) { - m.doc() = "Python bindings for the manif library," + m.doc() = "Python bindings for the manif library, " "a small library for Lie theory."; wrap_Rn(m); diff --git a/python/bindings_rn.cpp b/python/bindings_rn.cpp index 5dd93703..b2289a2f 100644 --- a/python/bindings_rn.cpp +++ b/python/bindings_rn.cpp @@ -9,94 +9,96 @@ #include "bindings_lie_group_base.h" #include "bindings_tangent_base.h" -void wrap_Rn(pybind11::module &m) +namespace py = pybind11; + +void wrap_Rn(py::module &m) { // R1 - pybind11::class_, std::unique_ptr, py::nodelete>> R1_base(m, "R1Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R1_tan_base(m, "R1TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R1_base(m, "_R1Base"); + py::class_, std::unique_ptr, py::nodelete>> R1_tan_base(m, "_R1TangentBase"); - pybind11::class_> R1(m, "R1"); - pybind11::class_> R1_tan(m, "R1Tangent"); + py::class_> R1(m, "R1", "The R^1 group."); + py::class_> R1_tan(m, "R1Tangent"); wrap_lie_group_base>(R1); wrap_tangent_base>(R1_tan); // R2 - pybind11::class_, std::unique_ptr, py::nodelete>> R2_base(m, "R2Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R2_tan_base(m, "R2TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R2_base(m, "_R2Base"); + py::class_, std::unique_ptr, py::nodelete>> R2_tan_base(m, "_R2TangentBase"); - pybind11::class_> R2(m, "R2"); - pybind11::class_> R2_tan(m, "R2Tangent"); + py::class_> R2(m, "R2"); + py::class_> R2_tan(m, "R2Tangent"); wrap_lie_group_base>(R2); wrap_tangent_base>(R2_tan); // R3 - pybind11::class_, std::unique_ptr, py::nodelete>> R3_base(m, "R3Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R3_tan_base(m, "R3TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R3_base(m, "_R3Base"); + py::class_, std::unique_ptr, py::nodelete>> R3_tan_base(m, "_R3TangentBase"); - pybind11::class_> R3(m, "R3"); - pybind11::class_> R3_tan(m, "R3Tangent"); + py::class_> R3(m, "R3"); + py::class_> R3_tan(m, "R3Tangent"); wrap_lie_group_base>(R3); wrap_tangent_base>(R3_tan); // R4 - pybind11::class_, std::unique_ptr, py::nodelete>> R4_base(m, "R4Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R4_tan_base(m, "R4TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R4_base(m, "_R4Base"); + py::class_, std::unique_ptr, py::nodelete>> R4_tan_base(m, "_R4TangentBase"); - pybind11::class_> R4(m, "R4"); - pybind11::class_> R4_tan(m, "R4Tangent"); + py::class_> R4(m, "R4"); + py::class_> R4_tan(m, "R4Tangent"); wrap_lie_group_base>(R4); wrap_tangent_base>(R4_tan); // R5 - pybind11::class_, std::unique_ptr, py::nodelete>> R5_base(m, "R5Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R5_tan_base(m, "R5TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R5_base(m, "_R5Base"); + py::class_, std::unique_ptr, py::nodelete>> R5_tan_base(m, "_R5TangentBase"); - pybind11::class_> R5(m, "R5"); - pybind11::class_> R5_tan(m, "R5Tangent"); + py::class_> R5(m, "R5"); + py::class_> R5_tan(m, "R5Tangent"); wrap_lie_group_base>(R5); wrap_tangent_base>(R5_tan); // R6 - pybind11::class_, std::unique_ptr, py::nodelete>> R6_base(m, "R6Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R6_tan_base(m, "R6TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R6_base(m, "_R6Base"); + py::class_, std::unique_ptr, py::nodelete>> R6_tan_base(m, "_R6TangentBase"); - pybind11::class_> R6(m, "R6"); - pybind11::class_> R6_tan(m, "R6Tangent"); + py::class_> R6(m, "R6"); + py::class_> R6_tan(m, "R6Tangent"); wrap_lie_group_base>(R6); wrap_tangent_base>(R6_tan); // R7 - pybind11::class_, std::unique_ptr, py::nodelete>> R7_base(m, "R7Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R7_tan_base(m, "R7TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R7_base(m, "_R7Base"); + py::class_, std::unique_ptr, py::nodelete>> R7_tan_base(m, "_R7TangentBase"); - pybind11::class_> R7(m, "R7"); - pybind11::class_> R7_tan(m, "R7Tangent"); + py::class_> R7(m, "R7"); + py::class_> R7_tan(m, "R7Tangent"); wrap_lie_group_base>(R7); wrap_tangent_base>(R7_tan); // R8 - pybind11::class_, std::unique_ptr, py::nodelete>> R8_base(m, "R8Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R8_tan_base(m, "R8TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R8_base(m, "_R8Base"); + py::class_, std::unique_ptr, py::nodelete>> R8_tan_base(m, "_R8TangentBase"); - pybind11::class_> R8(m, "R8"); - pybind11::class_> R8_tan(m, "R8Tangent"); + py::class_> R8(m, "R8"); + py::class_> R8_tan(m, "R8Tangent"); wrap_lie_group_base>(R8); wrap_tangent_base>(R8_tan); // R9 - pybind11::class_, std::unique_ptr, py::nodelete>> R9_base(m, "R9Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> R9_tan_base(m, "R9TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> R9_base(m, "_R9Base"); + py::class_, std::unique_ptr, py::nodelete>> R9_tan_base(m, "_R9TangentBase"); - pybind11::class_> R9(m, "R9"); - pybind11::class_> R9_tan(m, "R9Tangent"); + py::class_> R9(m, "R9"); + py::class_> R9_tan(m, "R9Tangent"); wrap_lie_group_base>(R9); wrap_tangent_base>(R9_tan); diff --git a/python/bindings_se2.cpp b/python/bindings_se2.cpp index 0e6b5503..17f52e96 100644 --- a/python/bindings_se2.cpp +++ b/python/bindings_se2.cpp @@ -10,18 +10,20 @@ #include "bindings_lie_group_base.h" #include "bindings_tangent_base.h" -void wrap_SE2(pybind11::module &m) +namespace py = pybind11; + +void wrap_SE2(py::module &m) { using Scalar = manif::SE2d::Scalar; using Translation = manif::SE2d::Translation; // group declaration and constructors - pybind11::class_, std::unique_ptr, py::nodelete>> SE2_base(m, "SE2Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> SE2_tan_base(m, "SE2TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> SE2_base(m, "_SE2Base"); + py::class_, std::unique_ptr, py::nodelete>> SE2_tan_base(m, "_SE2TangentBase"); - pybind11::class_> SE2(m, "SE2"); - pybind11::class_> SE2_tan(m, "SE2Tangent"); + py::class_> SE2(m, "SE2"); + py::class_> SE2_tan(m, "SE2Tangent"); // group diff --git a/python/bindings_se3.cpp b/python/bindings_se3.cpp index 0b33b256..fbd154c6 100644 --- a/python/bindings_se3.cpp +++ b/python/bindings_se3.cpp @@ -9,17 +9,19 @@ #include "bindings_lie_group_base.h" #include "bindings_tangent_base.h" -void wrap_SE3(pybind11::module &m) +namespace py = pybind11; + +void wrap_SE3(py::module &m) { using SE3d = manif::SE3d; using Scalar = SE3d::Scalar; using Quaternion = Eigen::Quaternion; - pybind11::class_, std::unique_ptr, py::nodelete>> SE3_base(m, "SE3Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> SE3_tan_base(m, "SE3TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> SE3_base(m, "_SE3Base"); + py::class_, std::unique_ptr, py::nodelete>> SE3_tan_base(m, "_SE3TangentBase"); - pybind11::class_> SE3(m, "SE3"); - pybind11::class_> SE3_tan(m, "SE3Tangent"); + py::class_> SE3(m, "SE3"); + py::class_> SE3_tan(m, "SE3Tangent"); // group diff --git a/python/bindings_se_2_3.cpp b/python/bindings_se_2_3.cpp index a740d54c..e6423dc2 100644 --- a/python/bindings_se_2_3.cpp +++ b/python/bindings_se_2_3.cpp @@ -9,18 +9,20 @@ #include "bindings_lie_group_base.h" #include "bindings_tangent_base.h" -void wrap_SE_2_3(pybind11::module &m) +namespace py = pybind11; + +void wrap_SE_2_3(py::module &m) { using Scalar = manif::SE_2_3d::Scalar; using Translation = manif::SE_2_3d::Translation; using Quaternion = Eigen::Quaternion; using LinearVelocity = manif::SE_2_3d::LinearVelocity; - pybind11::class_, std::unique_ptr, py::nodelete>> SE_2_3_base(m, "SE_2_3Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> SE_2_3_tan_base(m, "SE_2_3TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> SE_2_3_base(m, "_SE_2_3Base"); + py::class_, std::unique_ptr, py::nodelete>> SE_2_3_tan_base(m, "_SE_2_3TangentBase"); - pybind11::class_> SE_2_3(m, "SE_2_3"); - pybind11::class_> SE_2_3_tan(m, "SE_2_3Tangent"); + py::class_> SE_2_3(m, "SE_2_3"); + py::class_> SE_2_3_tan(m, "SE_2_3Tangent"); //group diff --git a/python/bindings_so2.cpp b/python/bindings_so2.cpp index 661b41de..318c6b6b 100644 --- a/python/bindings_so2.cpp +++ b/python/bindings_so2.cpp @@ -9,15 +9,17 @@ #include "bindings_lie_group_base.h" #include "bindings_tangent_base.h" -void wrap_SO2(pybind11::module &m) +namespace py = pybind11; + +void wrap_SO2(py::module &m) { using Scalar = manif::SO2d::Scalar; - pybind11::class_, std::unique_ptr, py::nodelete>> SO2_base(m, "SO2Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> SO2_tan_base(m, "SO2TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> SO2_base(m, "_SO2Base"); + py::class_, std::unique_ptr, py::nodelete>> SO2_tan_base(m, "_SO2TangentBase"); - pybind11::class_> SO2(m, "SO2"); - pybind11::class_> SO2_tan(m, "SO2Tangent"); + py::class_> SO2(m, "SO2", "The SO2 class"); + py::class_> SO2_tan(m, "SO2Tangent"); //group @@ -26,8 +28,8 @@ void wrap_SO2(pybind11::module &m) SO2.def(py::init()); SO2.def(py::init()); - SO2.def("transform", &manif::SO2d::transform); - SO2.def("rotation", &manif::SO2d::rotation); + SO2.def("transform", &manif::SO2d::transform, "Get the transformation matrix"); + SO2.def("rotation", &manif::SO2d::rotation, "Get the rotation matrix"); SO2.def("real", &manif::SO2d::real); SO2.def("imag", &manif::SO2d::imag); SO2.def("angle", &manif::SO2d::angle); diff --git a/python/bindings_so3.cpp b/python/bindings_so3.cpp index 62b05c2f..6a6047bc 100644 --- a/python/bindings_so3.cpp +++ b/python/bindings_so3.cpp @@ -9,16 +9,18 @@ #include "bindings_lie_group_base.h" #include "bindings_tangent_base.h" -void wrap_SO3(pybind11::module &m) +namespace py = pybind11; + +void wrap_SO3(py::module &m) { using Scalar = manif::SO3d::Scalar; using Quaternion = Eigen::Quaternion; - pybind11::class_, std::unique_ptr, py::nodelete>> SO3_base(m, "SO3Base"); - pybind11::class_, std::unique_ptr, py::nodelete>> SO3_tan_base(m, "SO3TangentBase"); + py::class_, std::unique_ptr, py::nodelete>> SO3_base(m, "_SO3Base"); + py::class_, std::unique_ptr, py::nodelete>> SO3_tan_base(m, "_SO3TangentBase"); - pybind11::class_> SO3(m, "SO3"); - pybind11::class_> SO3_tan(m, "SO3Tangent"); + py::class_> SO3(m, "SO3"); + py::class_> SO3_tan(m, "SO3Tangent"); // group diff --git a/python/bindings_tangent_base.h b/python/bindings_tangent_base.h index 0932b3df..978664ae 100644 --- a/python/bindings_tangent_base.h +++ b/python/bindings_tangent_base.h @@ -1,10 +1,8 @@ #ifndef _MANIF_PYTHON_BINDINGS_TANGENT_BASE_H_ #define _MANIF_PYTHON_BINDINGS_TANGENT_BASE_H_ -namespace py = pybind11; - template -void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { +void wrap_tangent_base(pybind11::class_<_Tangent, _Args...>& py_class) { using Scalar = typename _Tangent::Scalar; using LieGroup = typename _Tangent::LieGroup; @@ -16,76 +14,215 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { py_class.attr("DoF") = _Tangent::DoF; py_class.attr("RepSize") = _Tangent::RepSize; - py_class.def(py::init<>()); - py_class.def(py::init()); + py_class.def( + pybind11::init<>(), + "Default constructor, uninitialized data." + ); + + py_class.def( + pybind11::init(), + "Constructor given data vector." + ); py_class.def( "coeffs_copy", - static_cast(&_Tangent::coeffs) + static_cast(&_Tangent::coeffs), + "Return a copy of underlying data." ); // Makes a copy! + py_class.def( "coeffs", static_cast(&_Tangent::coeffs), - py::return_value_policy::reference_internal + pybind11::return_value_policy::reference_internal, + "Get a reference to underlying data." + ); + + py_class.def( + "generator", + &_Tangent::generator, + pybind11::arg("i"), + "Get the ith basis element of the Lie Algebra." + ); + + py_class.def( + "innerWeights", + &_Tangent::innerWeights, + "Get the weight matrix of the Weighted Euclidean inner product, " + "relative to the space basis." ); - py_class.def("generator", &_Tangent::generator); + py_class.def( + "inner", + &_Tangent::template inner<_Tangent>, + pybind11::arg("other"), + R"( + Get inner product of this and another Tangent weighted by W. + + ret = self^T x W x other + )" + ); - py_class.def("innerWeights", &_Tangent::innerWeights); - py_class.def("inner", &_Tangent::template inner<_Tangent>); + py_class.def( + "weightedNorm", + &_Tangent::weightedNorm, + "Get the Euclidean weighted norm." + ); - py_class.def("weightedNorm", &_Tangent::weightedNorm); - py_class.def("squaredWeightedNorm", &_Tangent::squaredWeightedNorm); - py_class.def("hat", &_Tangent::hat); + py_class.def( + "squaredWeightedNorm", + &_Tangent::squaredWeightedNorm, + "Get the squared Euclidean weighted norm." + ); + + py_class.def( + "hat", + &_Tangent::hat, + R"( + Get the isomorphic element in the Lie algebra. + + See Eq. (10). + )" + ); py_class.def( "exp", &_Tangent::exp, - py::arg_v("J_out_self", OptJacobianRef(), "None") + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + R"( + Get the corresponding Lie group element. + + Eq. (23). + + Parameters + ---------- + J_out_self [out] : numpy.ndarray + Jacobian of the log wrt self. + )" ); py_class.def( "rplus", &_Tangent::rplus, - py::arg("state"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_state", OptJacobianRef(), "None") + pybind11::arg("state"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_state", OptJacobianRef(), "None"), + R"( + Right oplus operation of the Lie group. + + See Eqs. (25). + + Parameters + ---------- + other : Lie group + Another object of the same Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the oplus operation wrt self. + J_out_state [out] : numpy.ndarray + Jacobian of the oplus operation wrt state. + )" ); py_class.def( "lplus", &_Tangent::lplus, - py::arg("state"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_state", OptJacobianRef(), "None") + pybind11::arg("state"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_state", OptJacobianRef(), "None"), + R"( + Left oplus operation of the Lie group. + + See Eqs. (27). + + Parameters + ---------- + other : Lie group + Another object of the same Lie group. + J_out_self [out] : numpy.ndarray + Jacobian of the oplus operation wrt self. + J_out_state [out] : numpy.ndarray + Jacobian of the oplus operation wrt state. + )" ); py_class.def( "plus", static_cast(&_Tangent::plus), - py::arg("state"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_state", OptJacobianRef(), "None") + pybind11::arg("state"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_state", OptJacobianRef(), "None"), + "An alias for the 'rplus' function." ); py_class.def( "plus", &_Tangent::template plus<_Tangent>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + R"( + Plus operation in the vector space. + + Parameters + ---------- + other : Lie group tangent + Another object of the same Lie group tangent. + J_out_self [out] : numpy.ndarray + Jacobian of the oplus operation wrt self. + J_out_other [out] : numpy.ndarray + Jacobian of the oplus operation wrt other. + )" ); py_class.def( "minus", &_Tangent::template minus<_Tangent>, - py::arg("other"), - py::arg_v("J_out_self", OptJacobianRef(), "None"), - py::arg_v("J_out_other", OptJacobianRef(), "None") + pybind11::arg("other"), + pybind11::arg_v("J_out_self", OptJacobianRef(), "None"), + pybind11::arg_v("J_out_other", OptJacobianRef(), "None"), + R"( + Minus operation in the vector space. + + Parameters + ---------- + other : Lie group tangent + Another object of the same Lie group tangent. + J_out_self [out] : numpy.ndarray + Jacobian of the oplus operation wrt self. + J_out_other [out] : numpy.ndarray + Jacobian of the oplus operation wrt other. + )" + ); + + py_class.def( + "rjac", + &_Tangent::rjac, + R"( + Get the right Jacobian. + + This is the right Jacobian of 'exp', + what is commonly known as "the right Jacobian". + + See Eq. (41) for the right Jacobian of general functions. + See Eqs. (126,143,163,179,191) for implementations of the + right Jacobian of exp. + )" + ); + + py_class.def( + "ljac", + &_Tangent::ljac, + R"( + Get the left Jacobian. + + This is the left Jacobian of 'exp', + what is commonly known as "the left Jacobian". + + See Eq. (44) for the left Jacobian of general functions. + See Eqs. (126,145,164,179,191) for implementations of the + left Jacobian of exp. + )" ); - py_class.def("rjac", &_Tangent::rjac); - py_class.def("ljac", &_Tangent::ljac); // py_class.def("rjacinv", &_Tangent::rjacinv); // py_class.def("ljacinv", &_Tangent::ljacinv); @@ -96,8 +233,18 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { [](const _Tangent& self, const _Tangent& t, Scalar eps) { return self.isApprox(t, eps); }, - py::arg("other"), - py::arg_v("eps", Scalar(manif::Constants::eps), "eps") + pybind11::arg("other"), + pybind11::arg_v("eps", Scalar(manif::Constants::eps), "1e-10"), + R"( + Evaluate whether self and other are 'close'. + + Parameters + ---------- + other : Lie group tangent + Another object of the same Lie group tangent. + eps : double + Threshold for equality comparison. Default: 1e-10. + )" ); py_class.def( @@ -105,35 +252,99 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { [](const _Tangent& self, const DataType& t, Scalar eps) { return self.isApprox(t, eps); }, - py::arg("other"), - py::arg_v("eps", Scalar(manif::Constants::eps), "eps") + pybind11::arg("other"), + pybind11::arg_v("eps", Scalar(manif::Constants::eps), "1e-10"), + R"( + Evaluate whether self and other are 'close'. + + Parameters + ---------- + other : numpy.array + Another object of the same Lie group tangent. + eps : double + Threshold for equality comparison. Default: 1e-10. + )" ); - py_class.def("setZero", &_Tangent::setZero); - py_class.def("setRandom", &_Tangent::setRandom); + py_class.def( + "setZero", + &_Tangent::setZero, + "Set self to zero." + ); + + py_class.def( + "setRandom", + &_Tangent::setRandom, + "Set self to a random value." + ); - py_class.def_static("Zero", &_Tangent::Zero); - py_class.def_static("Random", &_Tangent::Random); - py_class.def_static("Generator", &_Tangent::Generator); - py_class.def_static("InnerWeights", &_Tangent::InnerWeights); + py_class.def_static( + "Zero", + &_Tangent::Zero, + "Static helper to create an object of the Lie group tangent set to zero." + ); + + py_class.def_static( + "Random", + &_Tangent::Random, + "Static helper to create a random object of the Lie group." + ); + + py_class.def_static( + "Generator", + &_Tangent::Generator, + pybind11::arg("i"), + "Static helper to get the ith basis element of the Lie Algebra." + ); + + py_class.def_static( + "InnerWeights", + &_Tangent::InnerWeights, + "Static helper to get the weight matrix of the " + "Weighted Euclidean inner product, " + "relative to the space basis." + ); // operator overloads - py_class.def(-py::self) - .def(py::self + LieGroup()) - .def(py::self + py::self) - // .def(py::self += py::self) - .def(py::self - py::self) - // .def(py::self -= py::self) - .def(py::self * Scalar()) - .def(Scalar() * py::self) - .def(py::self / Scalar()) - .def(py::self == py::self) - ; - - // Jacobian() @ py::self - py_class.def("__rmatmul__", [](const _Tangent& t, py::array_t lhs) { - - py::buffer_info lhs_buf = lhs.request(); + py_class.def(-pybind11::self) + .def( + pybind11::self + LieGroup(), + "Operator overload for the 'plus' function." + ) + .def( + pybind11::self + pybind11::self, + "Operator overload for the 'plus' function." + ) + // .def(pybind11::self += pybind11::self) + .def( + pybind11::self - pybind11::self, + "Operator overload for the 'minus' function." + ) + // .def(pybind11::self -= pybind11::self) + .def( + pybind11::self * Scalar(), + "Multiply the vector by a scalar." + ) + .def( + Scalar() * pybind11::self, + "Multiply the vector by a scalar." + ) + .def( + pybind11::self / Scalar(), + "Divide the vector by a scalar." + ) + .def( + pybind11::self == pybind11::self, + "Operator overload for the 'isApprox' function." + ) + ; + + // Jacobian() @ pybind11::self + py_class.def( + "__rmatmul__", + [](const _Tangent& t, pybind11::array_t lhs) { + + pybind11::buffer_info lhs_buf = lhs.request(); if (lhs_buf.ndim != 2) throw std::runtime_error("Number of dimensions must be 2"); @@ -145,12 +356,16 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { return result; - }, py::is_operator()); + }, + pybind11::is_operator() + ); - // Jacobian() * py::self - py_class.def("__rmul__", [](const _Tangent& t, py::array_t lhs) { + // Jacobian() * pybind11::self + py_class.def( + "__rmul__", + [](const _Tangent& t, pybind11::array_t lhs) { - py::buffer_info lhs_buf = lhs.request(); + pybind11::buffer_info lhs_buf = lhs.request(); // if (lhs_buf.ndim != 2) // throw std::runtime_error("Number of dimensions must be 2"); @@ -162,7 +377,9 @@ void wrap_tangent_base(py::class_<_Tangent, _Args...>& py_class) { return result; - }, py::is_operator()); + }, + pybind11::is_operator() + ); // This is necessary to 'override' numpy's ndarray operators // with the __*mul*__ operator above From 53aa9ec5a4ad797ecb4d9d5e0d3f35eb3782aa71 Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 25 Jan 2021 17:46:21 -0500 Subject: [PATCH 61/67] wip doc website --- docs/Doxyfile-mcss | 2 +- docs/Doxyfile-mcss-site | 2 +- docs/conf.py | 4 ++-- docs/conf_python.py | 8 +++++--- 4 files changed, 9 insertions(+), 7 deletions(-) diff --git a/docs/Doxyfile-mcss b/docs/Doxyfile-mcss index 79dbcef0..092e313e 100644 --- a/docs/Doxyfile-mcss +++ b/docs/Doxyfile-mcss @@ -9,5 +9,5 @@ XML_PROGRAMLISTING = NO XML_OUTPUT = "site/cpp/xml" HTML_OUTPUT = "site/cpp" -##! M_MAIN_PROJECT_URL = ../html/index.html +##! M_MAIN_PROJECT_URL = ../index.html ##! M_SHOW_UNDOCUMENTED = YES \ No newline at end of file diff --git a/docs/Doxyfile-mcss-site b/docs/Doxyfile-mcss-site index c244a785..6d3f08de 100644 --- a/docs/Doxyfile-mcss-site +++ b/docs/Doxyfile-mcss-site @@ -7,4 +7,4 @@ GENERATE_XML = YES XML_PROGRAMLISTING = NO XML_OUTPUT = "site/xml" -HTML_OUTPUT = "site/html" +HTML_OUTPUT = "site" diff --git a/docs/conf.py b/docs/conf.py index bc28a7ce..f97dc36d 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,8 +1,8 @@ DOXYFILE = 'Doxyfile-mcss-site' LINKS_NAVBAR1 = [ - ('C++', []), - ('Python', []), + ('C++', []), + ('Python', []), ('GitHub', []) ] LINKS_NAVBAR2 = [] diff --git a/docs/conf_python.py b/docs/conf_python.py index f3e61b70..a2022fd7 100644 --- a/docs/conf_python.py +++ b/docs/conf_python.py @@ -1,16 +1,18 @@ PROJECT_TITLE = 'manif' PROJECT_SUBTITLE = 'Python API' -MAIN_PROJECT_URL = '../html/index.html' +MAIN_PROJECT_URL = '../index.html' INPUT_MODULES = ['manifpy'] OUTPUT = 'site/python' LINKS_NAVBAR1 = [ ('Modules', 'modules', []), - ('Classes', 'classes', []), + ('Classes', 'classes', []) +] +LINKS_NAVBAR2 = [ + ('C++', '../cpp/index.html', []), ('Github', 'https://github.com/artivis/manif', []) ] -LINKS_NAVBAR2 = [] PYBIND11_COMPATIBILITY = True From a236573581ac458ed69f0fa2e5054b8af4387887 Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 25 Jan 2021 17:46:48 -0500 Subject: [PATCH 62/67] wip CI docs --- .github/workflows/docs.yml | 82 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 82 insertions(+) create mode 100644 .github/workflows/docs.yml diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml new file mode 100644 index 00000000..168c3605 --- /dev/null +++ b/.github/workflows/docs.yml @@ -0,0 +1,82 @@ +name: documentation +on: + push: + branches: devel + workflow_dispatch: + +jobs: + + # There is no way as of now to move artifacts around jobs and + # across workflows. So we build the Python bindings here too. + build: + runs-on: ubuntu-20.04 + steps: + + # Build manifpy + + - name: Checkout + uses: actions/checkout@v2 + - name: Set up Python + uses: actions/setup-python@v2 + with: + python-version: 3.6 + - name: Setup apt + run: | + sudo apt update + sudo apt install -y libeigen3-dev + - name: Setup + run: | + python -m pip install --upgrade pip + pip install pytest "pybind11[global]" + pip install -r requirements.txt + - name: Build + run: pip install . + + # build: + # runs-on: ubuntu-20.04 + # needs: [pybind11] + # steps: + # - name: Checkout + # uses: actions/checkout@v2 + # - name: Set up Python + # uses: actions/setup-python@v2 + + # Build documentation website + + - name: Fetch apt deps + run: | + sudo apt update + sudo apt install -y libeigen3-dev flex bison doxygen graphicsmagick-imagemagick-compat + - name: Fetch Python deps + run: python -m pip install jinja2 Pygments + - name: Fetch m.css + working-directory: ${{runner.workspace}} + run: git clone git://github.com/mosra/m.css + + - name: Build Python docs + run: python3 ${{runner.workspace}}/m.css/documentation/python.py conf_python.py + - name: Build C++ docs + run: python3 ${{runner.workspace}}/m.css/documentation/doxygen.py Doxyfile-mcss + - name: Build site + run: python3 ${{runner.workspace}}/m.css/documentation/doxygen.py conf.py + + - name: Archive artifacts + uses: actions/upload-artifact@v2 + with: + name: site + path: docs/site + + deploy: + runs-on: ubuntu-20.04 + needs: [build] + steps: + - name: Download artifacts + uses: actions/download-artifact@v2 + with: + name: site + - name: Deploy + uses: JamesIves/github-pages-deploy-action@3.7.1 + with: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + BRANCH: gh-pages + FOLDER: docs/site \ No newline at end of file From 06575cc93dfce4f382516d94fbe3c93839b3edc0 Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 25 Jan 2021 17:47:10 -0500 Subject: [PATCH 63/67] wip doc website --- docs/conf_cpp.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 docs/conf_cpp.py diff --git a/docs/conf_cpp.py b/docs/conf_cpp.py new file mode 100644 index 00000000..75756889 --- /dev/null +++ b/docs/conf_cpp.py @@ -0,0 +1,12 @@ +DOXYFILE = 'Doxyfile-mcss' + +LINKS_NAVBAR1 = [ + ('Pages', 'pages', []), + ('Namespaces', 'namespaces', []), + ('Classes', 'annotated', []), + ('Files', 'files', []) +] +LINKS_NAVBAR2 = [ + ('Python', []), + ('GitHub', []) +] From 466c6c4c728ce2552f71a9a07a557acb5831d2e0 Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 25 Jan 2021 17:48:07 -0500 Subject: [PATCH 64/67] wip CI docs --- .github/workflows/docs.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml index 168c3605..dd452637 100644 --- a/.github/workflows/docs.yml +++ b/.github/workflows/docs.yml @@ -56,7 +56,7 @@ jobs: - name: Build Python docs run: python3 ${{runner.workspace}}/m.css/documentation/python.py conf_python.py - name: Build C++ docs - run: python3 ${{runner.workspace}}/m.css/documentation/doxygen.py Doxyfile-mcss + run: python3 ${{runner.workspace}}/m.css/documentation/doxygen.py conf_cpp.py - name: Build site run: python3 ${{runner.workspace}}/m.css/documentation/doxygen.py conf.py From fe5d025bf6a8053f0ad34af7fa96ca9e076d0b1e Mon Sep 17 00:00:00 2001 From: artivis Date: Mon, 25 Jan 2021 20:41:05 -0500 Subject: [PATCH 65/67] wip doc website --- README.md | 189 ++---------------- docs/Doxyfile | 8 +- docs/Doxyfile-mcss | 3 - docs/Doxyfile-site | 2 +- docs/conf.py | 1 + docs/conf_cpp.py | 3 + docs/{ => pages/cpp}/Interpolation.md | 0 docs/{ => pages/cpp}/On-the-use-with-Ceres.md | 0 docs/pages/cpp/Quick-start.md | 82 ++++++++ docs/{ => pages/cpp}/Writing-generic-code.md | 0 docs/pages/documentation.md | 63 ++++++ projects.md => docs/pages/projects.md | 4 +- docs/pages/publication.md | 48 +++++ docs/pages/python/Quick-start.md | 90 +++++++++ 14 files changed, 305 insertions(+), 188 deletions(-) rename docs/{ => pages/cpp}/Interpolation.md (100%) rename docs/{ => pages/cpp}/On-the-use-with-Ceres.md (100%) create mode 100644 docs/pages/cpp/Quick-start.md rename docs/{ => pages/cpp}/Writing-generic-code.md (100%) create mode 100644 docs/pages/documentation.md rename projects.md => docs/pages/projects.md (91%) create mode 100644 docs/pages/publication.md create mode 100644 docs/pages/python/Quick-start.md diff --git a/README.md b/README.md index 60e5e03c..13bdf24c 100644 --- a/README.md +++ b/README.md @@ -59,7 +59,7 @@ Please find more information in the related [documentation page](doc/Writing-gen - Authors: - Jeremie Deray [deray.jeremie@gmail.com](mailto:deray.jeremie@gmail.com) - Joan Sola [jsola@iri.upc.edu](mailto:jsola@iri.upc.edu) -- License: MIT +- License: [MIT](LICENSE) - Bug / feature tracker: [github.com/artivis/manif/issues][manif-issue] - Source: [github.com/artivis/manif.git][manif-repo] (branch: devel) @@ -79,118 +79,8 @@ ___ ## Quick Start -### Dependencies - -- Eigen 3 : - - Linux ( Ubuntu and similar ) - - ``` - apt-get install libeigen3-dev - ``` - - - OS X - - ``` - brew install eigen - ``` - -- [lt::optional][optional-repo] : included in the `external` folder - -In addition for the Python 3 wrappers: - -```terminal -pip install -r requirements -``` - -### Installation - -#### From source - -```terminal -git clone https://github.com/artivis/manif.git -cd manif && mkdir build && cd build -cmake -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON .. -make install -``` - -##### Using catkin_tools - -```terminal -git clone https://github.com/artivis/manif.git -catkin build manif --cmake-args -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON -``` - -#### Use manif in your C++ project - -In your project `CMakeLists.txt` : - -```cmake -project(foo) -# Find the Eigen library -find_package(Eigen3 REQUIRED) -target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIRS}) -# Find the manif library -find_package(manif REQUIRED) -add_executable(${PROJECT_NAME} src/foo.cpp) -# Add manif include directories to the target -target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${manif_INCLUDE_DIRS}) -``` - -In your code: - -```cpp -#include - -... - -auto state = manif::SE3d::Identity(); - -... - -``` - -#### Use manif in your Python 3 project - -The Python wrappers are generated using [`pybind11`][pybind11]. So first we need to install it, -but we want it available directly in our environment root so that `CMake` can find it. -To do so we can use, - -```terminal -python3 -m pip install "pybind11[global]" -``` - -Note that this is not recommended when using one's system Python, -as it will add files to `/usr/local/include/pybind11` and `/usr/local/share/cmake/pybind11`. - -Another way is to use `CMake` to install it, - -```terminal -git clone https://github.com/pybind/pybind11.git -cd pybind11 && mkdir build && cd build -cmake .. -make install -``` - -We can now generate `manif` Python bindings, - -```terminal -git clone https://github.com/artivis/manif.git -cd manif -python3 -m pip install -r requirements -python3 -m pip install . -``` - -##### Use manifpy in your project - -```python -from manifpy import SE3 - -... - -state = SE3.Identity() - -... -``` +Get quickly started with **manif** following our 'quick start' guides for both +[C++](docs/pages/cpp/Quick-start.md) and [Python](docs/pages/python/Quick-start.md). ## Features @@ -293,82 +183,27 @@ For more information, please refer to the [Ceres documentation page](doc/On-the- ## Documentation -The API documentation can be found online at [codedocs.xyz/artivis/manif][manif-doc]. - -Some more general information and tips on the use of the library is available on the documentation `Related Pages`. - -To generate the documentation on your machine, type in the terminal - -```terminal -cd manif -doxygen docs/Doxyfile -``` +The documentation is available online at the accompanying [website](manif). +Both the [C++](cpp) and the [Python](python) APIs are documented. -and find it at `manif/docs/html/index.html`. +Do you want to build it locally? Find out how on the [dedicated page](docs/pages/documentation.md). -Throughout the code documentation we refer to 'the paper' which you can -find in the section [Publications](#publications). +Note: throughout the code documentation we refer to 'the paper' which you can +find on [the dedicated page](docs/pages/publication.md). ## Tutorials and application demos -We provide some self-contained and self-explained executables implementing some real problems both in C++ and Python. -Their source code is located in `manif/examples/`. -These demos are: +We provide some self-contained and self-explained [C++ examples](docs/pages/cpp/Quick-start.md#tutorials-and-application-demos) to help you get started. -- `se2_localization` [`.cpp`](examples/se2_localization.cpp)/[`.py`](examples/se2_localization.py): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. -- `se3_localization` [`.cpp`](examples/se3_localization.cpp)/[`.py`](examples/se3_localization.py): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. -- `se2_sam.` [`cpp`](examples/se2_sam.cpp)/[`.py`](examples/se2_sam.py): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. -- `se3_sam` [`.cpp`](examples/se3_sam.cpp)/[`.py`](examples/se3_sam.py): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. -- `se3_sam_selfcalib` [`.cpp`](examples/se3_sam_selfcalib.cpp)/[`.py`](examples/se3_sam_selfcalib.py): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. -- `se_2_3_localization` [`.cpp`](examples/se_2_3_localization.cpp)/[`.py`](examples/se_2_3_localization.py): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). +You prefer Python? The same examples are also available in [Python](docs/pages/python/Quick-start.md#tutorials-and-application-demos). ## Publications -If you use this software, please consider citing [this paper][deray20] as follows: - -```latex -@article{Deray-20-JOSS, - doi = {10.21105/joss.01371}, - url = {https://doi.org/10.21105/joss.01371}, - year = {2020}, - publisher = {The Open Journal}, - volume = {5}, - number = {46}, - pages = {1371}, - author = {Jérémie Deray and Joan Solà}, - title = {Manif: A micro {L}ie theory library for state estimation in robotics applications}, - journal = {Journal of Open Source Software} -} -``` - -You can also consider citing [this paper][jsola18] as follows: - -```latex -@techreport{SOLA-18-Lie, - Address = {Barcelona}, - Author = {Joan Sol\`a and Jeremie Deray and Dinesh Atchuthan}, - Institution = {{Institut de Rob\`otica i Inform\`atica Industrial}}, - Number = {IRI-TR-18-01}, - Title = {A micro {L}ie theory for state estimation in robotics}, - Howpublished="\url{http://arxiv.org/abs/1812.01537}", - Year = {2018} -} -``` - -Notice that this reference is the one referred to throughout the code documentation. -Since this is a versioned work, please refer to [version 4, available here][jsola18v], -of the paper when cross-referencing with the **manif** documentation. -This will give the appropriate equation numbers. - -### Lie group cheat sheets - -In a rush? Here is your Lie group theory take away: -[Lie group cheat sheet](paper/Lie_theory_cheat_sheet.pdf). +Check our related [publications](docs/pages/publication.md). ## They use manif -You may find [here](projects.md) a list of work and projects using **manif**. -Your project is not listed? Let us know about it! +Find out [who's already using **manif**](docs/pages/projects.md). ## Contributing diff --git a/docs/Doxyfile b/docs/Doxyfile index 9efb7d55..5111a47a 100644 --- a/docs/Doxyfile +++ b/docs/Doxyfile @@ -46,9 +46,7 @@ PROJECT_BRIEF = "C++ API" # spaces. # Note: If this tag is empty the current directory is searched. -INPUT = "../include" "../docs" - -# "../README.md" +INPUT = "../include" "./pages/cpp" #--------------------------------------------------------------------------- # Shared @@ -816,7 +814,7 @@ EXCLUDE_SYMBOLS = # that contain example code fragments that are included (see the \include # command). -EXAMPLE_PATH = "../example" +EXAMPLE_PATH = # If the value of the EXAMPLE_PATH tag contains directories, you can use the # EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and @@ -884,7 +882,7 @@ FILTER_SOURCE_PATTERNS = # (index.html). This can be useful if you have a project on for instance GitHub # and want to reuse the introduction page also for the doxygen output. -USE_MDFILE_AS_MAINPAGE = # README.md +USE_MDFILE_AS_MAINPAGE = #--------------------------------------------------------------------------- # Configuration options related to source browsing diff --git a/docs/Doxyfile-mcss b/docs/Doxyfile-mcss index 092e313e..ae92e257 100644 --- a/docs/Doxyfile-mcss +++ b/docs/Doxyfile-mcss @@ -8,6 +8,3 @@ XML_PROGRAMLISTING = NO XML_OUTPUT = "site/cpp/xml" HTML_OUTPUT = "site/cpp" - -##! M_MAIN_PROJECT_URL = ../index.html -##! M_SHOW_UNDOCUMENTED = YES \ No newline at end of file diff --git a/docs/Doxyfile-site b/docs/Doxyfile-site index 6d6cb0d3..8e6588ce 100644 --- a/docs/Doxyfile-site +++ b/docs/Doxyfile-site @@ -46,7 +46,7 @@ PROJECT_BRIEF = "" # spaces. # Note: If this tag is empty the current directory is searched. -INPUT = "../README.md" +INPUT = "../README.md" "./pages/projects.md" "./pages/documentation.md" "./pages/publication.md" #--------------------------------------------------------------------------- # Shared diff --git a/docs/conf.py b/docs/conf.py index f97dc36d..cee6bda9 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,6 +1,7 @@ DOXYFILE = 'Doxyfile-mcss-site' LINKS_NAVBAR1 = [ + ('Pages', 'pages', []), ('C++', []), ('Python', []), ('GitHub', []) diff --git a/docs/conf_cpp.py b/docs/conf_cpp.py index 75756889..ded1ffa8 100644 --- a/docs/conf_cpp.py +++ b/docs/conf_cpp.py @@ -1,5 +1,8 @@ DOXYFILE = 'Doxyfile-mcss' +MAIN_PROJECT_URL = '../index.html' +SHOW_UNDOCUMENTED = True + LINKS_NAVBAR1 = [ ('Pages', 'pages', []), ('Namespaces', 'namespaces', []), diff --git a/docs/Interpolation.md b/docs/pages/cpp/Interpolation.md similarity index 100% rename from docs/Interpolation.md rename to docs/pages/cpp/Interpolation.md diff --git a/docs/On-the-use-with-Ceres.md b/docs/pages/cpp/On-the-use-with-Ceres.md similarity index 100% rename from docs/On-the-use-with-Ceres.md rename to docs/pages/cpp/On-the-use-with-Ceres.md diff --git a/docs/pages/cpp/Quick-start.md b/docs/pages/cpp/Quick-start.md new file mode 100644 index 00000000..3e14ef5f --- /dev/null +++ b/docs/pages/cpp/Quick-start.md @@ -0,0 +1,82 @@ +# Quick start + +## Installation + +### Dependencies + +- Eigen 3 : + - Linux ( Ubuntu and similar ) + + ```bash + apt-get install libeigen3-dev + ``` + + - OS X + + ```bash + brew install eigen + ``` + +- [lt::optional][optional-repo] : included in the `external` folder + +### From source + +```terminal +git clone https://github.com/artivis/manif.git +cd manif && mkdir build && cd build +cmake +make install +``` + +## Use manif in your project + +In your project `CMakeLists.txt` : + +```cmake +project(foo) +# Find the Eigen library +find_package(Eigen3 REQUIRED) +target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIRS}) +# Find the manif library +find_package(manif REQUIRED) +add_executable(${PROJECT_NAME} src/foo.cpp) +# Add manif include directories to the target +target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${manif_INCLUDE_DIRS}) +``` + +In your code: + +```cpp +#include + +... + +auto state = manif::SE3d::Identity(); + +... + +``` + +## Tutorials and application demos + +We provide some self-contained and self-explained executables implementing some real problems. +Their source code is located in `manif/examples/`. +These demos are: + +- [`se2_localization.cpp`](examples/se2_localization.cpp): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. +- [`se3_localization.cpp`](examples/se3_localization.cpp): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. +- [`se2_sam.cpp`](examples/se2_sam.cpp): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. +- [`se3_sam.cpp`](examples/se3_sam.cpp): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. +- [`se3_sam_selfcalib.cpp`](examples/se3_sam_selfcalib.cpp): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. +- [`se_2_3_localization.cpp`](examples/se_2_3_localization.cpp): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). + +To build the demos, simply pass the related flag to CMake, + +```terminal +cmake -DBUILD_EXAMPLES=ON .. +make +cd examples +./se2_localization +``` + +[optional-repo]: https://github.com/TartanLlama/optional \ No newline at end of file diff --git a/docs/Writing-generic-code.md b/docs/pages/cpp/Writing-generic-code.md similarity index 100% rename from docs/Writing-generic-code.md rename to docs/pages/cpp/Writing-generic-code.md diff --git a/docs/pages/documentation.md b/docs/pages/documentation.md new file mode 100644 index 00000000..b8c376ea --- /dev/null +++ b/docs/pages/documentation.md @@ -0,0 +1,63 @@ +# Documentation + +We detail here how to build the documentation locally. +The overall documentation relies on two tools, +namely [Doxygen][doxygen] and [m.css][mcss]. +The former is mainly used to build the C++ API documentation +while the former is used to generate the Python API documentation +and the overall documentation website. + +See how to build each below. + +## mcss + +```terminal +python3 -m pip install jinja2 Pygments +sudo apt install -y doxygen graphicsmagick-imagemagick-compat +git clone git://github.com/mosra/m.css +``` + +## C++ API + +The C++ API documentation relies only on Doxygen. +If you are fine with the antiquated look of a Doxygen-based +website, here is how to build it. + +First let's make sure doxygen is installed, + +```terminal +apt install -y doxygen +``` + +Let us now build to doc, + +```terminal +cd manif/docs +doxygen Doxyfile +``` + +You can now explore the website by opening the file +`manif/docs/html/index.html` in your web browser. + +## Python API + +```terminal +cd manif/docs +python3 ~/path/to/m.css/documentation/doxygen.py conf_cpp.py +``` + +## Building the website + +```terminal +cd manif/docs +mkdir -p site/cpp +``` + +```terminal +python3 ~/path/to/m.css/documentation/python.py conf_python.py +python3 ~/path/to/m.css/documentation/doxygen.py conf_cpp.py +python3 ~/path/to/m.css/documentation/doxygen.py conf.py +``` + +[doxygen]: https://www.doxygen.nl/index.html +[mcss]: https://mcss.mosra.cz/ \ No newline at end of file diff --git a/projects.md b/docs/pages/projects.md similarity index 91% rename from projects.md rename to docs/pages/projects.md index 14ada198..2b329776 100644 --- a/projects.md +++ b/docs/pages/projects.md @@ -1,4 +1,4 @@ -# A curated list of work and projects using **manif** +# A curated list of work and projects using manif ## They cite us @@ -7,7 +7,7 @@ You may find on Google Scholar publications citing either: - the [Lie theory paper][jsola18] accompanying **manif** - see [here][jsola18-scholar] - the [**manif** library paper][deray20] - see [here][deray20-scholar] -## They use **manif** +## They use manif - [`lie-group-controllers`][lie-group-controllers-repo], header-only C++ libraries containing controllers designed for Lie Groups. diff --git a/docs/pages/publication.md b/docs/pages/publication.md new file mode 100644 index 00000000..c812ddb5 --- /dev/null +++ b/docs/pages/publication.md @@ -0,0 +1,48 @@ +# Publications + +## Citing manif + +If you use this software, please consider citing [this paper][deray20] as follows: + +```latex +@article{Deray-20-JOSS, + doi = {10.21105/joss.01371}, + url = {https://doi.org/10.21105/joss.01371}, + year = {2020}, + publisher = {The Open Journal}, + volume = {5}, + number = {46}, + pages = {1371}, + author = {Jérémie Deray and Joan Solà}, + title = {Manif: A micro {L}ie theory library for state estimation in robotics applications}, + journal = {Journal of Open Source Software} +} +``` + +You can also consider citing [this paper][jsola18] as follows: + +```latex +@techreport{SOLA-18-Lie, + Address = {Barcelona}, + Author = {Joan Sol\`a and Jeremie Deray and Dinesh Atchuthan}, + Institution = {{Institut de Rob\`otica i Inform\`atica Industrial}}, + Number = {IRI-TR-18-01}, + Title = {A micro {L}ie theory for state estimation in robotics}, + Howpublished="\url{http://arxiv.org/abs/1812.01537}", + Year = {2018} +} +``` + +Note that this reference is the one referred to throughout the code documentation. +Since this is a versioned work, please refer to [version 4, available here][jsola18v], +of the paper when cross-referencing with the **manif** documentation. +This will give the appropriate equation numbers. + +## Lie group cheat sheets + +In a rush? Here is your Lie group theory take away: +[Lie group cheat sheet](paper/Lie_theory_cheat_sheet.pdf). + +[jsola18]: http://arxiv.org/abs/1812.01537 +[jsola18v]: http://arxiv.org/abs/1812.01537v4 +[deray20]: https://joss.theoj.org/papers/10.21105/joss.01371 \ No newline at end of file diff --git a/docs/pages/python/Quick-start.md b/docs/pages/python/Quick-start.md new file mode 100644 index 00000000..244884f7 --- /dev/null +++ b/docs/pages/python/Quick-start.md @@ -0,0 +1,90 @@ +# Quick start + +## Pybind11 + +The Python wrappers are generated using [`pybind11`][pybind11]. So first we need to install it, +but we want it available directly in our environment root so that `CMake` can find it. +To do so we can use, + +```terminal +python3 -m pip install "pybind11[global]" +``` + +Note that this is not recommended when using one's system Python, +as it will add files to `/usr/local/include/pybind11` and `/usr/local/share/cmake/pybind11`. + +Another way is to use `CMake` to install it, + +```terminal +git clone https://github.com/pybind/pybind11.git +cd pybind11 && mkdir build && cd build +cmake .. +make install +``` + +## Installation + +### Dependencies + +- Eigen 3 : + - Linux ( Ubuntu and similar ) + + ```bash + apt-get install libeigen3-dev + ``` + + - OS X + + ```bash + brew install eigen + ``` + +- [lt::optional][optional-repo] : included in the `external` folder + +Python bindings also depends on `numpy`. + +```terminal +python3 -m pip install -r requirements +``` + +### From source + +To generate `manif` Python bindings run, + +```terminal +git clone https://github.com/artivis/manif.git +cd manif +python3 -m pip install . +``` + +## Use manifpy in your project + +```python +from manifpy import SE3 + +... + +state = SE3.Identity() + +... +``` + +## Tutorials and application demos + +We provide some self-contained and self-explained executables implementing some real problems. +Their source code is located in `manif/examples/`. +These demos are: + +- [`se2_localization.py`](examples/se2_localization.py): 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. +- [`se3_localization.py`](examples/se3_localization.py): 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. +- [`se2_sam.py`](examples/se2_sam.py): 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. +- [`se3_sam.py`](examples/se3_sam.py): 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. +- [`se3_sam_selfcalib.py`](examples/se3_sam_selfcalib.py): 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. +- [`se_2_3_localization.py`](examples/se_2_3_localization.py): A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). + +To run a demo, simply go to the `manif/examples/` folder and run, + +```terminal +cd manif/examples +python3 se2_localization.py +``` From de0c9ca182a74aa9518f25e31d2069793c9aa398 Mon Sep 17 00:00:00 2001 From: artivis Date: Tue, 26 Jan 2021 17:44:51 -0500 Subject: [PATCH 66/67] python test fixes --- test/python/test_manif.py | 84 +++++++++++++++++++++------------------ 1 file changed, 46 insertions(+), 38 deletions(-) diff --git a/test/python/test_manif.py b/test/python/test_manif.py index ed397a9d..00844051 100644 --- a/test/python/test_manif.py +++ b/test/python/test_manif.py @@ -135,16 +135,13 @@ def test_LogExp(self, LieGroup, Tangent): assert state == state.log().exp() - # def test_ExpLog(self, LieGroup, Tangent): - # delta = Tangent.Random() + def test_ExpLog(self, LieGroup, Tangent): + delta = Tangent.Random() - # state = delta.exp() - # delta_other = state.log() - # print(delta) - # print(delta.exp().log()) - # print(delta_other) + state = delta.exp() + delta_other = state.log() - # assert delta == delta_other + assert delta == delta_other def test_Between(self, LieGroup, Tangent): state = LieGroup.Random() @@ -203,11 +200,6 @@ def test_Act(self, LieGroup, Tangent): def test_smallAdj(self, LieGroup, Tangent): - if LieGroup in (SO2, R1): - pytest.skip( - "hat is a scalar (Dim 1), numpy doesn't support matmul" - ) - delta = Tangent.Random() delta_other = Tangent.Random() @@ -467,26 +459,24 @@ def test_Adj(self, LieGroup, Tangent): Adjb = state_other.adj() Adjc = state.compose(state_other).adj() - # assert ((Adja @ Adjb) == Adjc).all() - assert np.allclose(Adja @ Adjb, Adjc) assert state + delta == state.adj() * delta + state - if LieGroup in (SO2, R1): - pytest.skip( - "Adj is a scalar (Dim 1), numpy doesn't support inversion" + if LieGroup.DoF == 1: + # Adj is a scalar (Dim 1), numpy doesn't support inversion + assert np.allclose( + np.ones((LieGroup.DoF, LieGroup.DoF))/state.adj(), + state.inverse().adj() + ) + else: + assert np.allclose( + np.linalg.inv(state.adj()), + state.inverse().adj() ) - - assert np.allclose(np.linalg.inv(state.adj()), state.inverse().adj()) def test_Adj2(self, LieGroup, Tangent): - if LieGroup in (SO2, R1): - pytest.skip( - "Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support matmul" - ) - state = LieGroup.Random() Adj = state.adj() @@ -496,7 +486,16 @@ def test_Adj2(self, LieGroup, Tangent): Jl = tan.ljac() assert np.allclose(Jl, Adj @ Jr) - assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) + + if LieGroup.DoF == 1: + # Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support inv + assert np.allclose( + Adj, + Jl * np.ones((LieGroup.DoF, LieGroup.DoF))/Jr + ) + else: + assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) + assert np.allclose(Jl, (-tan).rjac()) state.setIdentity() @@ -508,24 +507,33 @@ def test_Adj2(self, LieGroup, Tangent): Jl = tan.ljac() assert np.allclose(Jl, Adj @ Jr) - assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) + + if LieGroup.DoF == 1: + # Jr/Jl/Adj are scalar (Dim 1), numpy doesn't support inv + assert np.allclose( + Adj, + Jl * np.ones((LieGroup.DoF, LieGroup.DoF))/Jr + ) + else: + assert np.allclose(Adj, Jl @ np.linalg.inv(Jr)) + assert np.allclose(Jl, (-tan).rjac()) - @pytest.mark.skip(reason='invrjac/invljac not implemented yet') - def test_JrJrinvJlJlinv(self, LieGroup, Tangent): - state = LieGroup.Random() + # @pytest.mark.skip(reason='invrjac/invljac not implemented yet') + # def test_JrJrinvJlJlinv(self, LieGroup, Tangent): + # state = LieGroup.Random() - tan = state.log() - Jr = tan.rjac() - Jl = tan.ljac() + # tan = state.log() + # Jr = tan.rjac() + # Jl = tan.ljac() - Jrinv = tan.rjacinv() - Jlinv = tan.ljacinv() + # Jrinv = tan.rjacinv() + # Jlinv = tan.ljacinv() - Id = np.identity(LieGroup.DoF) + # Id = np.identity(LieGroup.DoF) - assert Id == Jr @ Jrinv - assert Id == Jl @ Jlinv + # assert Id == Jr @ Jrinv + # assert Id == Jl @ Jlinv def test_ActJac(self, LieGroup, Tangent): state = LieGroup.Identity() From a76ae35b63f2527a08987dd38848e442ae019edc Mon Sep 17 00:00:00 2001 From: artivis Date: Sat, 30 Jan 2021 12:23:20 -0500 Subject: [PATCH 67/67] wip doc website --- .gitignore | 4 +- CMakeLists.txt | 2 +- CONTRIBUTING.md | 73 ++++++++++++++ README.md | 120 ++++++------------------ docs/Doxyfile | 8 +- docs/Doxyfile-mcss | 2 + docs/Doxyfile-site | 4 +- docs/conf.py | 6 +- docs/conf_cpp.py | 2 +- docs/conf_python.py | 2 + docs/pages/cpp/Interpolation.md | 6 +- docs/pages/cpp/On-the-use-with-Ceres.md | 42 +++++++-- docs/pages/cpp/Quick-start.md | 35 ++++++- docs/pages/cpp/Writing-generic-code.md | 5 + docs/pages/documentation.md | 2 +- docs/pages/projects.md | 2 + docs/pages/publication.md | 9 +- docs/pages/python/Quick-start.md | 27 ++++-- docs/pages/python/index.rst | 112 ++++++++++++++++++++++ 19 files changed, 335 insertions(+), 128 deletions(-) create mode 100644 CONTRIBUTING.md create mode 100644 docs/pages/python/index.rst diff --git a/.gitignore b/.gitignore index 5595af15..982efe74 100644 --- a/.gitignore +++ b/.gitignore @@ -6,7 +6,9 @@ build docs/xml docs/html -doxygen_warnings.txt +docs/site +docs/m.css +*doxygen_warnings.txt *.cache .vscode *.egg-info diff --git a/CMakeLists.txt b/CMakeLists.txt index 832580a2..bec9cf75 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,7 +26,7 @@ endif() find_package(Eigen3 QUIET) if(NOT EIGEN3_FOUND) - LIST(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules) + list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules) find_package(Eigen3 REQUIRED) endif() diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 00000000..18eeb4ba --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,73 @@ +# Contributing + +## General guidelines + +**manif** is developed according to Vincent Driessen's [Gitflow Workflow][git-workflow]. +This means, + +- the `master` branch is for releases only. +- development is done on feature branches. +- finished features are integrated via PullRequests into the branch `devel`. + +For a PullRequest to get merged into `devel`, it must pass + +- Review by one of the maintainers. + - Are the changes introduced in scope of **manif**? + - Is the documentation updated? + - Are enough reasonable tests added? + - Will these changes break the API? + - Do the new changes follow the current style of naming? +- Compile / Test / Run on all target environments. + +Note: The test suite detailed below is run in CI for many targets environments including, + +- Ubuntu 16.04/18.04/20.04 +- MacOS 10.15 +- Visual Studio 15 + +## Development environment + +We will detail here how to set up a development environment. +It is recommended to use containers if you do not want to install the dependencies on your host. +You may refer to [this blog post](lxd-post) to set up a LXD container. + +First let us clone the **manif** repo, + +```terminal +git clone https://github.com/artivis/manif.git +cd manif +``` + +Let's install all dependencies for development and testing, + +```terminal +apt install libeigen3-dev +python3 -m pip install "pybind11[global]" pytest +python3 -m pip install -r requirements +``` + +We can now build **manif**, its Python wrappers and all tests, + +```terminal +mkdir build && cd build +cmake -DBUILD_TESTING=ON -DBUILD_EXAMPLES=ON -DBUILD_PYTHON_BINDINGS=ON -DBUILD_EXAMPLES=ON .. +make +``` + +To run the C++ tests execute the following, + +```terminal +ctest --output-on-failure +``` + +To run the Python tests, + +```terminal +cd manif +pytest +``` + +[//]: # (URLs) + +[git-workflow]: http://nvie.com/posts/a-successful-git-branching-model +[lxd-post]: https://artivis.github.io/post/2020/lxc \ No newline at end of file diff --git a/README.md b/README.md index 13bdf24c..dc6aed26 100644 --- a/README.md +++ b/README.md @@ -36,21 +36,18 @@ in a simplified way so as to make the entrance to Lie theory easy for the averag who is interested in designing rigorous and elegant state estimation algorithms. In a rush? Check out our [Lie group cheat sheet][cheat_sheet]. -**manif** has been designed for an easy integration to larger projects: + -It provides analytic computation of Jacobians for all the operations. -It also supports template scalar types. In particular, it can work with the -[`ceres::Jet`][ceres-jet] type, allowing for automatic Jacobian computation -- -[see related paragraph on Jacobians below](#jacobians). +It provides analytic computation of Jacobians for all the operations listed [below](#features). -All Lie group classes defined in **manif** have in common that they inherit from a templated base class ([CRTP][crtp]). + ### Details @@ -63,20 +60,6 @@ Please find more information in the related [documentation page](doc/Writing-gen - Bug / feature tracker: [github.com/artivis/manif/issues][manif-issue] - Source: [github.com/artivis/manif.git][manif-repo] (branch: devel) -___ - -

- Installation • - Features • - Documentation • - Tutorials • - Publications • - They use manif • - Contributing -

- -___ - ## Quick Start Get quickly started with **manif** following our 'quick start' guides for both @@ -115,78 +98,44 @@ and ![\mathbf{v}][latex20] or `v` represents any element of ![\mathbb{R}^n][late ### Jacobians All operations come with their respective analytical Jacobian matrices. -Throughout **manif**, **Jacobians are differentiated with respect to a local perturbation on the tangent space**. +Throughout **manif**, **Jacobians are differentiated with respect to a local perturbation on the tangent space**. These Jacobians map tangent spaces, as described in [this paper][jsola18]. -Currently, **manif** implements the **right Jacobian** (see [here][jsola18] for reference), whose definition reads: +Currently, **manif** implements the **right Jacobian**, whose definition reads: ![\frac{\delta f(\mathbf\mathcal{X})}{\delta\mathbf\mathcal{X}}][latex22] -The Jacobians of any of the aforementionned operations can then be evaluated, e.g., - -```cpp - SO2d X = SO2d::Random(), - Y = SO2d::Random(); - - SO2d::Jacobian J_c_x, J_c_y; - auto compose = X.compose(Y, J_c_x, J_c_y); +The Jacobians of any of the aforementionned operations can then be evaluated: - SO2d::Jacobian J_m_x, J_m_y; - auto minus = X.minus(Y, J_m_x, J_m_y); - - SO2d::Jacobian J_i_x; - auto inverse = X.inverse(J_i_x); - - // etc... -``` - -Shall you be interested only in a specific Jacobian, it can be retrieved without evaluating the other: +in C++, ```cpp - auto composition = X.compose(Y, J_c_x); -``` + SE3d X = SE3d::Random(); + SE3Tangentd w = SE3Tangentd::Random(); -or conversely, + SE3d::Jacobian J_o_x, J_o_w; -```cpp - auto composition = X.compose(Y, SO2d::_, J_c_y); + auto X_plus_w = X.plus(w, J_o_x, J_o_w); ``` -#### A note on Jacobians - -The **manif** package differentiates Jacobians with respect to a -local perturbation on the tangent space. -These Jacobians map tangent spaces, as described in [this paper][jsola18]. - -However, many non-linear solvers -(e.g. [Ceres][ceres]) expect functions to be differentiated with respect to the underlying -representation vector of the group element -(e.g. with respect to quaternion vector for `SO3`). - -For this reason **manif** is compliant with [Ceres][ceres] -auto-differentiation and the [`ceres::Jet`][ceres-jet] type. - -For reference of the size of the Jacobians returned when using `ceres::Jet`, **manif** implements rotations in the following way: +in Python, -- SO(2) and SE(2): as a complex number with `real = cos(theta)` and `imag = sin(theta)` values. -- SO(3), SE(3) and SE_2(3): as a unit quaternion, using the underlying `Eigen::Quaternion` type. +```python + X = SE3.Random() + w = SE3Tangentd.Random() -Therefore, the respective Jacobian sizes using `ceres::Jet` are as follows: + J_o_x = np.zeros((SE3.DoF, SE3.DoF)) + J_o_w = np.zeros((SE3.DoF, SE3.DoF)) -- ℝ(n) : size n -- SO(2) : size 2 -- SO(3) : size 4 -- SE(2) : size 4 -- SE(3) : size 7 -- SE_2(3): size 10 - -For more information, please refer to the [Ceres documentation page](doc/On-the-use-with-Ceres). + X_plus_w = X.plus(w, J_o_x, J_o_w) +``` ## Documentation The documentation is available online at the accompanying [website](manif). Both the [C++](cpp) and the [Python](python) APIs are documented. -Do you want to build it locally? Find out how on the [dedicated page](docs/pages/documentation.md). +Do you want to build it locally? +Find out how on the [dedicated page](docs/pages/documentation.md). Note: throughout the code documentation we refer to 'the paper' which you can find on [the dedicated page](docs/pages/publication.md). @@ -195,34 +144,19 @@ find on [the dedicated page](docs/pages/publication.md). We provide some self-contained and self-explained [C++ examples](docs/pages/cpp/Quick-start.md#tutorials-and-application-demos) to help you get started. -You prefer Python? The same examples are also available in [Python](docs/pages/python/Quick-start.md#tutorials-and-application-demos). +You prefer Python? The same examples are also [available in Python](docs/pages/python/Quick-start.md#tutorials-and-application-demos). ## Publications -Check our related [publications](docs/pages/publication.md). +Check out our related [publications](docs/pages/publication.md) and how to cite them. ## They use manif -Find out [who's already using **manif**](docs/pages/projects.md). +Find out [who's already using manif](docs/pages/projects.md). ## Contributing -**manif** is developed according to Vincent Driessen's [Gitflow Workflow][git-workflow]. -This means, - -- the `master` branch is for releases only. -- development is done on feature branches. -- finished features are integrated via PullRequests into the branch `devel`. - -For a PullRequest to get merged into `devel`, it must pass - -- Review by one of the maintainers. - - Are the changes introduced in scope of **manif**? - - Is the documentation updated? - - Are enough reasonable tests added? - - Will these changes break the API? - - Do the new changes follow the current style of naming? -- Compile / Test / Run on all target environments. +Want to contribute? Great! Check out our [contribution guidelines](CONTRIBUTING.md). [//]: # (URLs) diff --git a/docs/Doxyfile b/docs/Doxyfile index 5111a47a..263bce78 100644 --- a/docs/Doxyfile +++ b/docs/Doxyfile @@ -151,7 +151,7 @@ INLINE_INHERITED_MEMB = NO # shortest path that makes the file name unique will be used # The default value is: YES. -FULL_PATH_NAMES = YES +FULL_PATH_NAMES = NO # The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path. # Stripping is only done if one of the specified strings matches the left-hand @@ -163,7 +163,7 @@ FULL_PATH_NAMES = YES # will be relative from the directory where doxygen is started. # This tag requires that the tag FULL_PATH_NAMES is set to YES. -STRIP_FROM_PATH = include +STRIP_FROM_PATH = # The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the # path mentioned in the documentation of a class, which tells the reader which @@ -301,6 +301,8 @@ EXTENSION_MAPPING = MARKDOWN_SUPPORT = YES +TOC_INCLUDE_HEADINGS = 4 + # When enabled doxygen tries to link words that correspond to documented # classes, or namespaces to their corresponding documentation. Such a link can # be prevented in individual cases by by putting a % sign in front of the word @@ -834,7 +836,7 @@ EXAMPLE_RECURSIVE = NO # that contain images that are to be included in the documentation (see the # \image command). -IMAGE_PATH = "../docs/images" +IMAGE_PATH = "./images" # The INPUT_FILTER tag can be used to specify a program that doxygen should # invoke to filter for each input file. Doxygen will invoke the filter program diff --git a/docs/Doxyfile-mcss b/docs/Doxyfile-mcss index ae92e257..13a0140d 100644 --- a/docs/Doxyfile-mcss +++ b/docs/Doxyfile-mcss @@ -2,6 +2,8 @@ PROJECT_BRIEF = "C++ API" +USE_MDFILE_AS_MAINPAGE = "pages/cpp/Quick-start.md" + GENERATE_HTML = NO GENERATE_XML = YES XML_PROGRAMLISTING = NO diff --git a/docs/Doxyfile-site b/docs/Doxyfile-site index 8e6588ce..ef3e8f1c 100644 --- a/docs/Doxyfile-site +++ b/docs/Doxyfile-site @@ -79,7 +79,7 @@ PROJECT_LOGO = # entered, it will be relative to the location where doxygen was started. If # left blank the current directory will be used. -OUTPUT_DIRECTORY = "../docs" +OUTPUT_DIRECTORY = "./" # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 4096 sub- # directories (in 2 levels) under the output directory of each output format and @@ -163,7 +163,7 @@ FULL_PATH_NAMES = YES # will be relative from the directory where doxygen is started. # This tag requires that the tag FULL_PATH_NAMES is set to YES. -STRIP_FROM_PATH = include +STRIP_FROM_PATH = # The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the # path mentioned in the documentation of a class, which tells the reader which diff --git a/docs/conf.py b/docs/conf.py index cee6bda9..adaf3ae9 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -4,8 +4,10 @@ ('Pages', 'pages', []), ('C++', []), ('Python', []), +] +LINKS_NAVBAR2 = [ + ('Publications', []), ('GitHub', []) ] -LINKS_NAVBAR2 = [] -SEARCH_DISABLED = True \ No newline at end of file +SEARCH_DISABLED = True diff --git a/docs/conf_cpp.py b/docs/conf_cpp.py index ded1ffa8..6ac0cfd6 100644 --- a/docs/conf_cpp.py +++ b/docs/conf_cpp.py @@ -5,7 +5,7 @@ LINKS_NAVBAR1 = [ ('Pages', 'pages', []), - ('Namespaces', 'namespaces', []), + # ('Namespaces', 'namespaces', []), ('Classes', 'annotated', []), ('Files', 'files', []) ] diff --git a/docs/conf_python.py b/docs/conf_python.py index a2022fd7..a5c0b725 100644 --- a/docs/conf_python.py +++ b/docs/conf_python.py @@ -4,9 +4,11 @@ MAIN_PROJECT_URL = '../index.html' INPUT_MODULES = ['manifpy'] +INPUT_PAGES = ['pages/python/index.rst'] OUTPUT = 'site/python' LINKS_NAVBAR1 = [ + # ('Pages', 'pages', []), ('Modules', 'modules', []), ('Classes', 'classes', []) ] diff --git a/docs/pages/cpp/Interpolation.md b/docs/pages/cpp/Interpolation.md index 8dbe06fa..1fd6ee49 100644 --- a/docs/pages/cpp/Interpolation.md +++ b/docs/pages/cpp/Interpolation.md @@ -12,9 +12,9 @@ In this example, `k` points in `SE2` are generated on a 8-shaped curve (large bl Between consecutive points, `p` new points are interpolated (in `]0,1[`, smaller red arrows). The results for each interpolation algorithm is shown in the following figures: -![SE2 Slerp interpolation](images/se2_interp_slerp.png) -![SE2 Cubic interpolation](images/se2_interp_cubic.png) -![SE2 Cn Smooth interpolation](images/se2_interp_cnsmooth.png) +![SE2 Slerp interpolation](../../images/se2_interp_slerp.png) +![SE2 Cubic interpolation](../../images/se2_interp_cubic.png) +![SE2 Cn Smooth interpolation](../../images/se2_interp_cnsmooth.png) To reproduce the figures: diff --git a/docs/pages/cpp/On-the-use-with-Ceres.md b/docs/pages/cpp/On-the-use-with-Ceres.md index 03b0b42c..354d0824 100644 --- a/docs/pages/cpp/On-the-use-with-Ceres.md +++ b/docs/pages/cpp/On-the-use-with-Ceres.md @@ -1,12 +1,38 @@ # Ceres -While the `manif` package differentiates Jacobians with respect to a -local perturbation on the tangent space, -many non-linear solvers -(including [Ceres][ceres]) expect them to be differentiated -with respect to the underlying representation vector of the group element -(e.g. wrt the quaternion parameters vector -for ![SO3][latex1]. +- [Ceres](#ceres) + - [Jacobians](#jacobians) + - [Example : A group-abstract `LocalParameterization`](#example--a-group-abstract-localparameterization) + - [Example : A small Ceres problem](#example--a-small-ceres-problem) + +The **manif** package differentiates Jacobians with respect to a +local perturbation on the tangent space. +These Jacobians map tangent spaces, as described in [this paper][jsola18]. + +However, many non-linear solvers +(e.g. [Ceres][ceres]) expect functions to be differentiated with respect to the underlying +representation vector of the group element +(e.g. with respect to quaternion vector for `SO3`). + +For this reason **manif** is compliant with [Ceres][ceres] +auto-differentiation and the [`ceres::Jet`][ceres-jet] type. + +For reference of the size of the Jacobians returned when using `ceres::Jet`, +**manif** implements rotations in the following way: + +- SO(2) and SE(2): as a complex number with `real = cos(theta)` and `imag = sin(theta)` values. +- SO(3), SE(3) and SE_2(3): as a unit quaternion, using the underlying `Eigen::Quaternion` type. + +Therefore, the respective Jacobian sizes using `ceres::Jet` are as follows: + +- ℝ(n) : size n +- SO(2) : size 2 +- SO(3) : size 4 +- SE(2) : size 4 +- SE(3) : size 7 +- SE_2(3): size 10 + +## Jacobians Considering, @@ -215,6 +241,8 @@ std::cout << "Average state:\nx:" << average_state.x() [//]: # (URLs) +[jsola18]: http://arxiv.org/abs/1812.01537 + [ceres]: http://ceres-solver.org/ [ceres-costfunction]: http://ceres-solver.org/nnls_modeling.html#costfunction [ceres-localparam]: http://ceres-solver.org/nnls_modeling.html#localparameterization diff --git a/docs/pages/cpp/Quick-start.md b/docs/pages/cpp/Quick-start.md index 3e14ef5f..3cdd888e 100644 --- a/docs/pages/cpp/Quick-start.md +++ b/docs/pages/cpp/Quick-start.md @@ -1,5 +1,27 @@ # Quick start +- [Quick start](#quick-start) + - [Installation](#installation) + - [Dependencies](#dependencies) + - [From source](#from-source) + - [Use manif in your project](#use-manif-in-your-project) + - [Tutorials and application demos](#tutorials-and-application-demos) + +**manif** has been designed for an easy integration to larger projects: + +- A single dependency on [Eigen][eigen], +- header-only for easy integration, +- templated on the underlying scalar type so that one can use its own, +- and C++11, since not everyone gets to enjoy the latest C++ features, especially in industry. + +All Lie group classes defined in **manif** have in common that they inherit from a templated base class ([CRTP][crtp]). +It allows one to write generic code abstracting the Lie group details. +Please find more information in the related [documentation page](Writing-generic-code). + +The library supports template scalar types. In particular, it can work with the +[`ceres::Jet`][ceres-jet] type, allowing for automatic Jacobian computation -- +[see related paragraph on Jacobians below](#jacobians). + ## Installation ### Dependencies @@ -7,13 +29,13 @@ - Eigen 3 : - Linux ( Ubuntu and similar ) - ```bash + ``` apt-get install libeigen3-dev ``` - OS X - ```bash + ``` brew install eigen ``` @@ -24,7 +46,7 @@ ```terminal git clone https://github.com/artivis/manif.git cd manif && mkdir build && cd build -cmake +cmake .. make install ``` @@ -79,4 +101,9 @@ cd examples ./se2_localization ``` -[optional-repo]: https://github.com/TartanLlama/optional \ No newline at end of file +[//]: # (URLs) + +[eigen]: http://eigen.tuxfamily.org +[crtp]: https://en.wikipedia.org/wiki/Curiously_recurring_template_pattern +[optional-repo]: https://github.com/TartanLlama/optional +[ceres-jet]: http://ceres-solver.org/automatic_derivatives.html#dual-numbers-jets diff --git a/docs/pages/cpp/Writing-generic-code.md b/docs/pages/cpp/Writing-generic-code.md index 874f8547..383f90de 100644 --- a/docs/pages/cpp/Writing-generic-code.md +++ b/docs/pages/cpp/Writing-generic-code.md @@ -1,5 +1,10 @@ # Writing generic code +- [Writing generic code](#writing-generic-code) + - [Examples](#examples) + - [Small example](#small-example) + - [Multiple templated arguments](#multiple-templated-arguments) + All Lie group classes defined in `manif` have in common that they inherit from a templated base class. Therefore, template-based generic code can be written - similarly to Eigen. diff --git a/docs/pages/documentation.md b/docs/pages/documentation.md index b8c376ea..ba9f6b5e 100644 --- a/docs/pages/documentation.md +++ b/docs/pages/documentation.md @@ -1,4 +1,4 @@ -# Documentation +# Building the documentation We detail here how to build the documentation locally. The overall documentation relies on two tools, diff --git a/docs/pages/projects.md b/docs/pages/projects.md index 2b329776..121d1971 100644 --- a/docs/pages/projects.md +++ b/docs/pages/projects.md @@ -10,6 +10,7 @@ You may find on Google Scholar publications citing either: ## They use manif - [`lie-group-controllers`][lie-group-controllers-repo], header-only C++ libraries containing controllers designed for Lie Groups. +- [`bipedal-locomotion-framework`][bipedal-locomotion-framework], The BipedalLocomotionFramework project is a suite of libraries for achieving bipedal locomotion on humanoid robots. Your project is not listed here? Let us know about it! @@ -21,3 +22,4 @@ Your project is not listed here? Let us know about it! [deray20-scholar]: https://scholar.google.fr/scholar?oi=bibs&hl=fr&cites=1235228860941456363 [lie-group-controllers-repo]: https://github.com/dic-iit/lie-group-controllers +[bipedal-locomotion-framework]: https://github.com/dic-iit/bipedal-locomotion-framework \ No newline at end of file diff --git a/docs/pages/publication.md b/docs/pages/publication.md index c812ddb5..711e1c86 100644 --- a/docs/pages/publication.md +++ b/docs/pages/publication.md @@ -40,9 +40,12 @@ This will give the appropriate equation numbers. ## Lie group cheat sheets -In a rush? Here is your Lie group theory take away: -[Lie group cheat sheet](paper/Lie_theory_cheat_sheet.pdf). +In a rush? Check out our Lie group theory take away, the +[Lie group cheat sheet][cheat-sheet] +(or hit [dowload][cheat-sheet-download]). [jsola18]: http://arxiv.org/abs/1812.01537 [jsola18v]: http://arxiv.org/abs/1812.01537v4 -[deray20]: https://joss.theoj.org/papers/10.21105/joss.01371 \ No newline at end of file +[deray20]: https://joss.theoj.org/papers/10.21105/joss.01371 +[cheat-sheet]: https://github.com/artivis/manif/blob/devel/paper/Lie_theory_cheat_sheet.pdf +[cheat-sheet-download]: https://github.com/artivis/manif/raw/devel/paper/Lie_theory_cheat_sheet.pdf \ No newline at end of file diff --git a/docs/pages/python/Quick-start.md b/docs/pages/python/Quick-start.md index 244884f7..d51d11e0 100644 --- a/docs/pages/python/Quick-start.md +++ b/docs/pages/python/Quick-start.md @@ -1,12 +1,20 @@ # Quick start -## Pybind11 +- [Quick start](#quick-start) + - [Getting Pybind11](#getting-pybind11) + - [Installation](#installation) + - [Dependencies](#dependencies) + - [From source](#from-source) + - [Use manifpy in your project](#use-manifpy-in-your-project) + - [Tutorials and application demos](#tutorials-and-application-demos) -The Python wrappers are generated using [`pybind11`][pybind11]. So first we need to install it, +## Getting Pybind11 + +The Python wrappers are generated using [pybind11][pybind11-rtd]. So first we need to install it, but we want it available directly in our environment root so that `CMake` can find it. To do so we can use, -```terminal +```bash python3 -m pip install "pybind11[global]" ``` @@ -15,7 +23,7 @@ as it will add files to `/usr/local/include/pybind11` and `/usr/local/share/cmak Another way is to use `CMake` to install it, -```terminal +```bash git clone https://github.com/pybind/pybind11.git cd pybind11 && mkdir build && cd build cmake .. @@ -43,7 +51,7 @@ make install Python bindings also depends on `numpy`. -```terminal +```bash python3 -m pip install -r requirements ``` @@ -51,7 +59,7 @@ python3 -m pip install -r requirements To generate `manif` Python bindings run, -```terminal +```bash git clone https://github.com/artivis/manif.git cd manif python3 -m pip install . @@ -84,7 +92,12 @@ These demos are: To run a demo, simply go to the `manif/examples/` folder and run, -```terminal +```bash cd manif/examples python3 se2_localization.py ``` + +[//]: # (URLs) + +[pybind11-rtd]: https://pybind11.readthedocs.io/en/stable/index.html +[optional-repo]: https://github.com/TartanLlama/optional diff --git a/docs/pages/python/index.rst b/docs/pages/python/index.rst new file mode 100644 index 00000000..f1341957 --- /dev/null +++ b/docs/pages/python/index.rst @@ -0,0 +1,112 @@ +.. Automatically generated from Quick-start.md with m2r +.. Manually patched + + +Quick start +=========== + +.. contents:: Table of Contents + :depth: 3 + + +Getting Pybind11 +---------------- + +The Python wrappers are generated using `pybind11 `_. So first we need to install it, +but we want it available directly in our environment root so that ``CMake`` can find it. +To do so we can use, + +.. code-block:: bash + + python3 -m pip install "pybind11[global]" + +Note that this is not recommended when using one's system Python, +as it will add files to ``/usr/local/include/pybind11`` and ``/usr/local/share/cmake/pybind11``. + +Another way is to use ``CMake`` to install it, + +.. code-block:: bash + + git clone https://github.com/pybind/pybind11.git + cd pybind11 && mkdir build && cd build + cmake .. + make install + +Installation +------------ + +Dependencies +^^^^^^^^^^^^ + + +* + Eigen 3 : + + + * + Linux ( Ubuntu and similar ) + + .. code-block:: bash + + apt-get install libeigen3-dev + + * + OS X + + .. code-block:: bash + + brew install eigen + +* + `lt::optional `_ : included in the ``external`` folder + +Python bindings also depends on ``numpy``. + +.. code-block:: bash + + python3 -m pip install -r requirements + +From source +^^^^^^^^^^^ + +To generate ``manif`` Python bindings run, + +.. code-block:: bash + + git clone https://github.com/artivis/manif.git + cd manif + python3 -m pip install . + +Use manifpy in your project +--------------------------- + +.. code-block:: python + + from manifpy import SE3 + + ... + + state = SE3.Identity() + + ... + +Tutorials and application demos +------------------------------- + +We provide some self-contained and self-explained executables implementing some real problems. +Their source code is located in ``manif/examples/``. +These demos are: + +* `se2_localization.py `_ : 2D robot localization based on fixed landmarks using SE2 as robot poses. This implements the example V.A in the paper. +* `se3_localization.py `_ : 3D robot localization based on fixed landmarks using SE3 as robot poses. This re-implements the example above but in 3D. +* `se2_sam.py `_ : 2D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE2 robot poses. This implements a the example V.B in the paper. +* `se3_sam.py `_ : 3D smoothing and mapping (SAM) with simultaneous estimation of robot poses and landmark locations, based on SE3 robot poses. This implements a 3D version of the example V.B in the paper. +* `se3_sam_selfcalib.py `_ : 3D smoothing and mapping (SAM) with self-calibration, with simultaneous estimation of robot poses, landmark locations and sensor parameters, based on SE3 robot poses. This implements a 3D version of the example V.C in the paper. +* `se_2_3_localization.py `_ : A strap down IMU model based 3D robot localization, with measurements of fixed landmarks, using SE_2_3 as extended robot poses (translation, rotation and linear velocity). + +To run a demo, simply go to the ``manif/examples/`` folder and run, + +.. code-block:: bash + + cd manif/examples + python3 se2_localization.py