From e33b53030dceb5017a6346759d9f08a5ba00e5f3 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 10 Nov 2014 17:32:31 -0500 Subject: [PATCH 1/3] Parse joint dynamics properties of urdf only if they exist --- dart/utils/urdf/DartLoader.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index a9f0ce4921936..4798e1b64864e 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -241,17 +241,20 @@ dynamics::Joint* DartLoader::createDartJoint(const urdf::Joint* _jt) joint = new dynamics::RevoluteJoint(toEigen(_jt->axis)); joint->setPositionLowerLimit(0, _jt->limits->lower); joint->setPositionUpperLimit(0, _jt->limits->upper); - joint->setDampingCoefficient(0, _jt->dynamics->damping); + if (_jt->dynamics) + joint->setDampingCoefficient(0, _jt->dynamics->damping); break; case urdf::Joint::CONTINUOUS: joint = new dynamics::RevoluteJoint(toEigen(_jt->axis)); - joint->setDampingCoefficient(0, _jt->dynamics->damping); + if (_jt->dynamics) + joint->setDampingCoefficient(0, _jt->dynamics->damping); break; case urdf::Joint::PRISMATIC: joint = new dynamics::PrismaticJoint(toEigen(_jt->axis)); joint->setPositionLowerLimit(0, _jt->limits->lower); joint->setPositionUpperLimit(0, _jt->limits->upper); - joint->setDampingCoefficient(0, _jt->dynamics->damping); + if (_jt->dynamics) + joint->setDampingCoefficient(0, _jt->dynamics->damping); break; case urdf::Joint::FIXED: joint = new dynamics::WeldJoint(); From 3caff944738993d93633f147b7193057e67b0301 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 10 Nov 2014 17:33:05 -0500 Subject: [PATCH 2/3] Add operationalSpaceControl example --- apps/CMakeLists.txt | 9 +- apps/operationalSpaceControl/CMakeLists.txt | 7 + apps/operationalSpaceControl/Controller.cpp | 136 +++++++ apps/operationalSpaceControl/Controller.h | 85 +++++ apps/operationalSpaceControl/Main.cpp | 85 +++++ apps/operationalSpaceControl/MyWindow.cpp | 153 ++++++++ apps/operationalSpaceControl/MyWindow.h | 73 ++++ data/urdf/KR5/KR5 sixx R650.urdf | 397 ++++++++++++++++++++ data/urdf/KR5/ground.urdf | 28 ++ data/urdf/KR5/meshes/base_link.STL | Bin 0 -> 49884 bytes data/urdf/KR5/meshes/bicep.STL | Bin 0 -> 74784 bytes data/urdf/KR5/meshes/elbow.STL | Bin 0 -> 48284 bytes data/urdf/KR5/meshes/forearm.STL | Bin 0 -> 74384 bytes data/urdf/KR5/meshes/palm.STL | Bin 0 -> 113384 bytes data/urdf/KR5/meshes/shoulder.STL | Bin 0 -> 54284 bytes data/urdf/KR5/meshes/wrist.STL | Bin 0 -> 22084 bytes 16 files changed, 969 insertions(+), 4 deletions(-) create mode 100644 apps/operationalSpaceControl/CMakeLists.txt create mode 100644 apps/operationalSpaceControl/Controller.cpp create mode 100644 apps/operationalSpaceControl/Controller.h create mode 100644 apps/operationalSpaceControl/Main.cpp create mode 100644 apps/operationalSpaceControl/MyWindow.cpp create mode 100644 apps/operationalSpaceControl/MyWindow.h create mode 100644 data/urdf/KR5/KR5 sixx R650.urdf create mode 100644 data/urdf/KR5/ground.urdf create mode 100644 data/urdf/KR5/meshes/base_link.STL create mode 100644 data/urdf/KR5/meshes/bicep.STL create mode 100644 data/urdf/KR5/meshes/elbow.STL create mode 100644 data/urdf/KR5/meshes/forearm.STL create mode 100644 data/urdf/KR5/meshes/palm.STL create mode 100644 data/urdf/KR5/meshes/shoulder.STL create mode 100644 data/urdf/KR5/meshes/wrist.STL diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index cc76ee4073fdd..debf4ba91775a 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -6,12 +6,13 @@ foreach(APPDIR addDeleteSkels atlasSimbicon bipedStand - rigidLoop - rigidCubes - rigidChain - hardcodedDesign + hardcodedDesign jointConstraints mixedChain + operationalSpaceControl + rigidChain + rigidCubes + rigidLoop softBodies vehicle ) diff --git a/apps/operationalSpaceControl/CMakeLists.txt b/apps/operationalSpaceControl/CMakeLists.txt new file mode 100644 index 0000000000000..5bb78453a0016 --- /dev/null +++ b/apps/operationalSpaceControl/CMakeLists.txt @@ -0,0 +1,7 @@ +############################################### +# apps/operationalSpaceControl +file(GLOB operationalSpaceControl_srcs "*.cpp") +file(GLOB operationalSpaceControl_hdrs "*.h") +add_executable(operationalSpaceControl ${operationalSpaceControl_srcs} ${operationalSpaceControl_hdrs}) +target_link_libraries(operationalSpaceControl dart) +set_target_properties(operationalSpaceControl PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/apps/operationalSpaceControl/Controller.cpp b/apps/operationalSpaceControl/Controller.cpp new file mode 100644 index 0000000000000..ca6d460c016a0 --- /dev/null +++ b/apps/operationalSpaceControl/Controller.cpp @@ -0,0 +1,136 @@ +/* + * Copyright (c) 2014, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Jeongseok Lee + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "apps/operationalSpaceControl/Controller.h" + +#include "dart/dynamics/Skeleton.h" +#include "dart/dynamics/BodyNode.h" +#include "dart/dynamics/Joint.h" +#include "dart/simulation/World.h" + +//============================================================================== +Controller::Controller(dart::dynamics::Skeleton* _robot, + dart::dynamics::BodyNode* _endEffector) + : mRobot(_robot), + mEndEffector(_endEffector) +{ + assert(_robot != NULL); + assert(_endEffector != NULL); + + int dof = mRobot->getNumDofs(); + + mForces.setZero(dof); + + mKp.setZero(dof, dof); + mKv.setZero(dof, dof); + + for (int i = 0; i < dof; ++i) + { + mKp(i, i) = 750.0; + mKv(i, i) = 250.0; + } + + // Remove position limits + for (int i = 0; i < dof; ++i) + _robot->getJoint(i)->setPositionLimited(false); + + // Set joint damping + for (int i = 0; i < dof; ++i) + _robot->getJoint(i)->setDampingCoefficient(0, 0.5); +} + +//============================================================================== +Controller::~Controller() +{ +} + +//============================================================================== +void Controller::update(const Eigen::Vector3d& _targetPosition) +{ + // Get equation of motions + Eigen::Vector3d x = mEndEffector->getTransform().translation(); + Eigen::Vector3d dx = mEndEffector->getWorldLinearVelocity(); + Eigen::MatrixXd invM = mRobot->getInvMassMatrix(); // n x n + Eigen::VectorXd Cg = mRobot->getCoriolisAndGravityForces(); // n x 1 + Eigen::MatrixXd Jv = mEndEffector->getWorldLinearJacobian(); // 3 x n + Eigen::MatrixXd dJv = mEndEffector->getWorldLinearJacobianDeriv(); // 3 x n + Eigen::VectorXd dq = mRobot->getVelocities(); // n x 1 + + // Compute operational space values + Eigen::MatrixXd A = Jv*invM; // 3 x n + Eigen::Vector3d b = /*-(A*Cg) + */dJv*dq; // 3 x 1 + Eigen::MatrixXd M2 = Jv*invM*Jv.transpose(); // 3 x 3 + + // Compute virtual operational space spring force at the end effector + Eigen::Vector3d f = -mKp*(x - _targetPosition) - mKv*dx; + + // Compute desired operational space acceleration given f + Eigen::Vector3d desired_ddx = b + M2*f; + + // Gravity compensation + mForces = Cg; + + // Compute joint space forces to acheive the desired acceleration by solving: + // A tau + b = desired_ddx + mForces += A.colPivHouseholderQr().solve(desired_ddx - b); + + // Apply the joint space forces to the robot + mRobot->setForces(mForces); +} + +//============================================================================== +dart::dynamics::Skeleton* Controller::getRobot() const +{ + return mRobot; +} + +//============================================================================== +dart::dynamics::BodyNode* Controller::getEndEffector() const +{ + return mEndEffector; +} + +//============================================================================== +void Controller::keyboard(unsigned char _key, int _x, int _y) +{ + switch (_key) + { + case 'i': // print debug information + // mController->printDebugInfo(); + break; + } +} + diff --git a/apps/operationalSpaceControl/Controller.h b/apps/operationalSpaceControl/Controller.h new file mode 100644 index 0000000000000..26623d71c2409 --- /dev/null +++ b/apps/operationalSpaceControl/Controller.h @@ -0,0 +1,85 @@ +/* + * Copyright (c) 2014, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Jeongseok Lee + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef APPS_OPERATIONALSPACECONTROL_CONTROLLER_H_ +#define APPS_OPERATIONALSPACECONTROL_CONTROLLER_H_ + +#include + +#include "dart/gui/SimWindow.h" +#include "dart/dynamics/Skeleton.h" + +/// \brief Operational space controller for 6-dof manipulator +class Controller +{ +public: + /// \brief Constructor + Controller(dart::dynamics::Skeleton* _robot, + dart::dynamics::BodyNode* _endEffector); + + /// \brief Destructor + virtual ~Controller(); + + /// \brief + void update(const Eigen::Vector3d& _targetPosition); + + /// \brief Get robot + dart::dynamics::Skeleton* getRobot() const; + + /// \brief Get end effector of the robot + dart::dynamics::BodyNode* getEndEffector() const; + + /// \brief Keyboard control + virtual void keyboard(unsigned char _key, int _x, int _y); + +private: + /// \brief Robot + dart::dynamics::Skeleton* mRobot; + + /// \brief End-effector of the robot + dart::dynamics::BodyNode* mEndEffector; + + /// \brief Control forces + Eigen::VectorXd mForces; + + /// \brief Proportional gain for the virtual spring forces at the end effector + Eigen::MatrixXd mKp; + + /// \brief Derivative gain for the virtual spring forces at the end effector + Eigen::MatrixXd mKv; +}; + +#endif // APPS_OPERATIONALSPACECONTROL_CONTROLLER_H_ diff --git a/apps/operationalSpaceControl/Main.cpp b/apps/operationalSpaceControl/Main.cpp new file mode 100644 index 0000000000000..8ae86532c637b --- /dev/null +++ b/apps/operationalSpaceControl/Main.cpp @@ -0,0 +1,85 @@ +/* + * Copyright (c) 2014, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Jeongseok Lee + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "dart/utils/Paths.h" +#include "dart/math/Helpers.h" +#include "dart/dynamics/Skeleton.h" +#include "dart/simulation/World.h" +#include "dart/utils/SkelParser.h" +#include "dart/utils/urdf/DartLoader.h" + +#include "apps/operationalSpaceControl/MyWindow.h" + +int main(int argc, char* argv[]) +{ + // create and initialize the world + dart::simulation::World* world = new dart::simulation::World; + + // + dart::utils::DartLoader dl; + dart::dynamics::Skeleton* ground + = dl.parseSkeleton(DART_DATA_PATH"urdf/KR5/ground.urdf"); + dart::dynamics::Skeleton* robot + = dl.parseSkeleton(DART_DATA_PATH"urdf/KR5/KR5 sixx R650.urdf"); + world->addSkeleton(ground); + world->addSkeleton(robot); + + assert(world != NULL); + + // create and initialize the world + Eigen::Vector3d gravity(0.0, -9.81, 0.0); + world->setGravity(gravity); + world->setTimeStep(1.0/1000); + +// int dof = world->getSkeleton(0)->getNumDofs(); +// Eigen::VectorXd initPose(dof); +// for (int i = 0; i < dof; i++) +// initPose[i] = dart::math::random(-0.5, 0.5); +// world->getSkeleton(0)->setPositions(initPose); +// world->getSkeleton(0)->computeForwardKinematics(true, true, false); + + // create a window and link it to the world + MyWindow window(new Controller(robot, robot->getBodyNode("palm"))); + window.setWorld(world); + + glutInit(&argc, argv); + window.initWindow(640, 480, "Forward Simulation"); + glutMainLoop(); + + delete world; + + return 0; +} diff --git a/apps/operationalSpaceControl/MyWindow.cpp b/apps/operationalSpaceControl/MyWindow.cpp new file mode 100644 index 0000000000000..d4e00977ebff7 --- /dev/null +++ b/apps/operationalSpaceControl/MyWindow.cpp @@ -0,0 +1,153 @@ +/* + * Copyright (c) 2014, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Jeongseok Lee + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "apps/operationalSpaceControl/MyWindow.h" + +#include + +#include "dart/dynamics/Skeleton.h" +#include "dart/dynamics/BodyNode.h" +#include "dart/simulation/World.h" +#include "dart/gui/GLFuncs.h" + +//============================================================================== +MyWindow::MyWindow(Controller* _controller) + : SimWindow(), + mController(_controller), + mCircleTask(false) +{ + assert(_controller != NULL); + + // Set the initial target positon to the initial position of the end effector + mTargetPosition = mController->getEndEffector()->getTransform().translation(); +} + +//============================================================================== +MyWindow::~MyWindow() +{ +} + +//============================================================================== +void MyWindow::timeStepping() +{ + if (mCircleTask) + { + static double time = 0.0; + const double dt = 0.0005; + const double radius = 0.6; + Eigen::Vector3d center = Eigen::Vector3d(0.0, 0.1, 0.0); + + mTargetPosition = center; + mTargetPosition[0] = radius * std::sin(time); + mTargetPosition[1] = 0.25 * radius * std::sin(time); + mTargetPosition[2] = radius * std::cos(time); + + time += dt; + } + + // Update the controller and apply control force to the robot + mController->update(mTargetPosition); + + // Step forward the simulation + mWorld->step(); +} + +//============================================================================== +void MyWindow::drawSkels() +{ + // Draw the target position + if (mRI) + { + mRI->setPenColor(Eigen::Vector3d(0.8, 0.2, 0.2)); + mRI->pushMatrix(); + mRI->translate(mTargetPosition); + mRI->drawEllipsoid(Eigen::Vector3d(0.05, 0.05, 0.05)); + mRI->popMatrix(); + } + + // Draw skeletons + SimWindow::drawSkels(); +} + +//============================================================================== +void MyWindow::keyboard(unsigned char _key, int _x, int _y) +{ + double incremental = 0.01; + + switch (_key) + { + case 'c': // print debug information + if (mCircleTask) + { + std::cout << "Circle task [off]." << std::endl; + mCircleTask = false; + } + else + { + std::cout << "Circle task [on]." << std::endl; + mCircleTask = true; + } + break; + case 'q': + mTargetPosition[0] -= incremental; + break; + case 'w': + mTargetPosition[0] += incremental; + break; + case 'a': + mTargetPosition[1] -= incremental; + break; + case 's': + mTargetPosition[1] += incremental; + break; + case 'z': + mTargetPosition[2] -= incremental; + break; + case 'x': + mTargetPosition[2] += incremental; + break; + default: + // Default keyboard control + SimWindow::keyboard(_key, _x, _y); + break; + } + + // Keyboard control for Controller + mController->keyboard(_key, _x, _y); + + glutPostRedisplay(); +} + diff --git a/apps/operationalSpaceControl/MyWindow.h b/apps/operationalSpaceControl/MyWindow.h new file mode 100644 index 0000000000000..199dacba8eed4 --- /dev/null +++ b/apps/operationalSpaceControl/MyWindow.h @@ -0,0 +1,73 @@ +/* + * Copyright (c) 2014, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Jeongseok Lee + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * Redistribution and use in source and binary forms, with or + * without modification, are permitted provided that the following + * conditions are met: + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF + * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef APPS_OPERATIONALSPACECONTROL_MYWINDOW_H_ +#define APPS_OPERATIONALSPACECONTROL_MYWINDOW_H_ + +#include "dart/gui/SimWindow.h" +#include "Controller.h" + +/// \brief class MyWindow +class MyWindow : public dart::gui::SimWindow +{ +public: + /// \brief Default constructor + MyWindow(Controller* _controller); + + /// \brief Destructor + virtual ~MyWindow(); + + // Documentation inherited + virtual void timeStepping(); + + // Documentation inherited + virtual void drawSkels(); + + // Documentation inherited + virtual void keyboard(unsigned char _key, int _x, int _y); + +private: + /// \brief Operational space controller + Controller* mController; + + /// \brief Target end effector position of the robot + Eigen::Vector3d mTargetPosition; + + /// \brief True to make the end effect to track a circle path + bool mCircleTask; +}; + +#endif // APPS_OPERATIONALSPACECONTROL_MYWINDOW_H_ diff --git a/data/urdf/KR5/KR5 sixx R650.urdf b/data/urdf/KR5/KR5 sixx R650.urdf new file mode 100644 index 0000000000000..ac8fbc99299d6 --- /dev/null +++ b/data/urdf/KR5/KR5 sixx R650.urdf @@ -0,0 +1,397 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/urdf/KR5/ground.urdf b/data/urdf/KR5/ground.urdf new file mode 100644 index 0000000000000..06d2973f4a364 --- /dev/null +++ b/data/urdf/KR5/ground.urdf @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/urdf/KR5/meshes/base_link.STL b/data/urdf/KR5/meshes/base_link.STL new file mode 100644 index 0000000000000000000000000000000000000000..878f783bd20dfd9e93ca655fc2f96d7fb6d6a704 GIT binary patch literal 49884 zcmb`QeavlFao#s}AmGv#%tuj#C}1uTY6;@QEyVY|CshfNS|I~UB?>_bsoI80NkIic z3&b1YiWCw^)r8PeDq>>-f;g^$0`Wcf1sbcgg#@7*Oi&1<5D1V!Xut$h==^5Qv-Y#j z-Us`S9{Ij!&YpSZnVI#m*Z%Z0{r~-Z_Tp*!;LqK7@`k%zb&BU3-|&_FrN8pwn||tE zPd_L5ia)sW+{=IJPxe>8;D6-y5#gFG1n6n{#>=lh_s36qVRAS^GFHF&_%H1r{;2mC zha+6Gg=id+$G-BIKXdD!^>`&?r3lF{^XLfIY#|!QtDk-Ax%XfE)0u}yB^j$r9{tDr z2VQbx<>3g|Y#|y)WPYJ)HNWekKkqe>jFlp6c{su~TZqQ-!CNlf-Q%54%{)9R$yhz> znV;WZ{*pJS%?;t2Ekxt^+t0rB!pB;z=4W2=jb0PUSSiAmha+6Gg=idiz3b(>&wStI znTJOu8LO|{{JH&8&Rku2IKnksh{o}qTP{8Q>^rhn^Y?%Hwq6s-SSiAmha+6Gg=icf zd&g6E_x{+WnTJOu8LNA}^s_NGpImu3!Zlln#u1sHR;}h2yx=c-O(bKb2wNVGaLpE? zaeVgTpWfa6leb=AF7c=&WA(mQ{_p)ied9eV4@bCW3(+_t^V6!;{NoqC)oUUdD@EAy zaD;2N5RK#WPkQ0*9#>zTd3aQkv3kZg{&0Wu|9tgtH4aC(W((0c-V*<87oEDI2_@cEkxt^k9WIj_t>j$+|wQ&m1L}*{o8*S`Zr$FIE46HPr3eD*Q^mg za!up7_{Uy&`nZ_0$m5b9{dTX3WULfn<8Xv)wh%)eC;#YcZ@!GE-uclFXS~P{c*QSe zBo*Ng4|$we=Be32bdFPM^{IQ_>rEHG@Z0-)e&pX=hA-sb{X1{E3@b(0ITCT0`4*ya zR4+Mq7?onjs(Q>7jl&VH*+L9?WabrbW-b{kBAlkzW`5HYZB8C1fAiP=^21!SM%<89 zn5G)FnTJOu8IBskm4_o-vxR7RR4+-6>Luw*GFFPP)yfgB*+MjqnnicChestDtC~?O z4@bCW3(+`g)Mg$vYSWiwtQ29(!x668LNt!rt7RS@m1L}H4_A3O!Zlln#!<6qa?~uE zz9eI%2wNVGaLpE?an!mbIXo)KSk;Q7@^FM}wh)b@_G-ydd$sf>87oED@^FM}wh)b@ zR(;9gQAx(CR)CdDZ-YABV4nEXdJZ)PY#btGFG)BuRI*# znk_`*s8wHb)T%FiNybVMwmcl+nk_`*V0^dFy!-HnK6L*4^Y8QXZ+h;@xzAm`KmWwj z2cAd%uOIoP^ZY}WHQ)0tEY61ISu}6E?sE?f4=EosEXVqKM|5Yc>$)*Bp*0IjyQz3rCO2HIDGM zseq#SXu+_eis`qq6$dSwaz}*F+kA!ax^+ZyP(k@}t4F^7TlAQbBN47~MCCUki0bqc zzjNFE=}&mv`7b~9@#oIm?JgJI{QBR%$>b}LdsK-y^Tt~`!qM+~-N$1E@WnG75fSm3 zPhI1P;@jYGgj*H&*)@l298r9Qs528eGx%I0nXz5R?KS&2!ZllnJ~Pajc(l2%8QMDN z=W~UmHAsFdq)(F@5Oyun}*2*=Gs55$3tT`Ov zR=y@0Ib7oit(-c?+;H=*G+B2)w^&u*Xb*2GZ^7dT*Epi0-QaM9TY0pZLC?cuuj-~> z_tbJ$=B{x>wd@^4omJ&3(+{f7*`qow9ZC3LNZoym4UNu`^Mo2*K8pMj$COK z;sjrku_|=dFxFWuszkVE3(+_(-1o)1|910_o%_+({@ZJ76@H$UVkLRy7d~?h>uAZX z1q*S37Ickd5asD?TZIb|9GA%oUv4G2aXj{uKfb&534i4j4%bM=Z>`9S;~2uNBsY%m zzYA1yxJEJ@egrU0#}IBMxp7e0$UZq-BN>jLc*G@CrScGh_K+36-0Hng`{g_~>>L;1 z_|kJ8`6kymB0TjY%V`RZM9?0Na4X5ZR;N{~*)@`@J?sdQ)>Cz5g|Db?x02jAu&y?r zT_YKeXn#9`G{ht;e7Tk6#zCFPKDyQH8p&|b7CNS$CLwBkBs;#`O7g&wW6(8{Esr|# zDh|eA_5|21kF=@?b8JpiWu7y&Yb0BH6vr_{)h(?gw>+u^lfyNV;i#4^j$;V7lH53| zCnkq$B*XEbci%T>4dmW;cQropNElykb@pf9nn%K&gE6@K@^c>fFxNOD_|8Y|Dvuh2 za9rjHx02jz#ayC1(ia+8RePL|+AX!(L|`E+$&Ca5QDL=5TA`5@9OM9JtJN`tTS;yl z)QRkE-pw8-EBr=3?t6x5y3egIIlbREZ#a3!Tkd+{1E2UL=K#*)>-GQQ_x8`a&wohS zkHV+vzJd7N+io~{OCVh12;X-##3usr>jwz8YUc+2sLnIMaZ7Qy#u2`jAYVRnR@cuC zNG2zbw%H5e8b^3Vrs=D31^Kq`yF5AkY=mSugl^|D9O0TRL~Fr_=#)hG=T?&OTk=f< zA`^1W7Gj7Bo~feBGewfKR(95?XPyXg;A;z^sPLY-bPhB^fUfG+oQS=$ca0;eoif_q zclY$&>V4_U(IbL>6+LlJ-);TsOWEUEU)tv?bB&0exVOHW?2f2jS!>Z6AIagq+{&Yk zE3S`t!Rb4n{qhS$*8Qt~<<;pc z?hfHDg0x~Ax|W9{T;m9k{BEo8r~dN2Pk-YJS0;xe+=?8CxN$rs5Z4ESJY3@lav+z+ zL7k}AA;PU_3+mW7s1x;~1zqC^jwGmE=Qsxk?GcC*`3kEOSw*xbOCG^-4vvbdYa9`L zCrchts~xpEM7UMd@MLL^sMU^Iy)B}0jU%FNCrf)o4!fw=x$0LZR*}OA5jT#=VMi|H;TlIo4kzT&IHD)+_*Z?m z`*N$QNO3sAHIArS6-Tv4ayY`Rs?Cd|+9NY}jU%dUii5VGO{~q+ms?eTD~{?{yXw32 z#1*3Y*uug1*j3+U93&#F=;3J<(J}@X4#tO~>KaExgp9$ZR*dr%!mXl)%q7K9<2>8k zHI9h7F_#oa%|2?6?#rzh8?;sHSB`LvBf>wkU2!nRX_M-^%&+MyGG*pWE5^RY%``E_ zX%pJRHI870(CF&>j}^kLe0A0kvHwVfYaCJgk~%X{cTMKn$Im)Sran4r)Xok%!Zlln zR^6IQw8vr2*rTaYyJw`**P>RrJ!{2Wl6y|qID#HYKO5$fQyb^$t43{F)vQz;HJ6;) z?6X2R-!#?CkQ_D66G5+_cMwUjI(RedaMHIC9KnFMQX+QI9d*l8t279 zdkf(jN6@F}1Fcqn6!&uedAp-=qOZ~e(MW#u-QRxJBb+8jxMm9hdYYaacglXS?v!9qH=_5wh)bjwUuSw_uGN!d*rC$dDU>5SX&9<8b?Ik&a2Xy$A!vcj;Q)-LNbv! zdPKNp3(@k3>Yi46%u(IGDw15a>fG5L9U;F|aSKr#aYy65uD<%*UwZdNmp$#p*Y7`n z`&;*~`M?X#-u&Pj_LqG8TF$UelGz>{4Z%5?K_e@+IA~>#<6~5d`a^v_v zanu$6^7z9wlHnlI4?O1I7soM#TS;ylH^;r_U#)x3T_YI|D)5wF{MF(R;*zM9tnlSl zk~_zR;+S0{84l{Sd!m5Y$Rm_;M@B14o|AaE)ZV;)%*5caC$^N><84Rzft6$~^aKu91va z>O?<7?zLJW+)8reh|zR`F#_5(lG#q37zxO6hhZTYgR;VxTS@L5=fvR}$#|s#OCF4I z5R5@t;mfTgH;$+kV=(h@jbu3R&u`?c)h5ENBsY$lOR~*fBN?xnF_8T;pT73*zH0x~ zXT5gMOvX3Ak@=Q9O&k$%6lp86+(WW=V~%8gthHV3IXNO?by-If{kYZoP$D8Cd+iTQm$}9flH1;ZJzDH< zbDY=OFzX|kYfxT=cvdD5&kMvSo_LRUxW*CZ?*Fd+r7!=HeY=A7-vjY8#o-9I()P#y z-d(b9WV_EX`RvN?3BC%E@(VBg^$Wp~a$47)5#d%^@3yEG%)IkRJdZ+G9*%I0BZ}kv zn!^!pYOZla zwP2!qFUhv_7L*K!w`N1I@_Xms|KyFXam2_`{p#GOZ+y+Qj&Li9sMSvj$UhSuT{p*RvF2z zy#WzQW}feBpB*b1&%>>1O;mZ*+9wgNaYU`0DymwMWmJxEE6Hu`Q%Bp`uj<%2eM!bj zh?a*VT(gB}9IUNk#grUgMaftR-8dZKnk_`*s53=s!4tJ@AUM~PIn^1YrOi20q+Y_g zrPMg0&Kgy9*)uDTh>9~ss#VHF;^=``qY8VBzs}RgSvci{JNp2jz zKX;8}{1R!*6yxl3ibhuWax2M=L;G|0b%>w>?6tAUqg0L{Pgw!DFSnB1IeZ0>zR<`D zuhePDBck#ZKu5Th3l}GLzoVnwyTCyt-SqafNG>d|Ejbye{5qc1EuT_pH zS>emABsUK2&q2FJGTW&WBLO)o*UotD7=yCHms?5h9KHfbUxx@Pu;g*D0_X_0lH53I z3})u8kxbZKg)g^~+&DD*fOd^!wrj>f=9724%t-9zZLgm)e%bzmAA5K0 zISTlZ+p_|ML+Y9 z(~n;DLuViU(qB0F)0dnM2>c3>flObE5%r&A-sKmFdp-TVS;arN@)u98`e)}8EqOrX zyz3gta5(oQjupbKBsUJ5OEN0*P=v~9%%f_xyY21MWoVxHfL3>J1IgdJy7KGQZBa#? zE>JIi$;xFA7yXS_oczRVK2Yr;#J~K9^EHleE6JVXoH$$~8IFJVfUB*|X+03Z@laXe z%dI3gjv7&!hifFm@u^#1mc0kLkEj*Gtt2;&h-gRl{Bn(C{GPen%d(F(4k4(OtU$Y! zWVUC&f`h&rcWgCZY?rJ&=+gtoIcg;<5b()LGTVFRyAWsBNX9R9Q-2!}-7lWpN;2E0 zsah~OTq79{TK1YB{Vz+uqRn^IN>+GsE6Hq64*D(}-O6P+eB3Mu^()vxxRqqKPm{(V zvTG#6F^<7+UVQm!{M&u%;kR5NE6{G`v(hx(bp4Y~pYhKhl6kmh3(>}TWW71V35}J{ zU3rau$J(7MysW@kqjOBgaT=>{*0^=eyVmWj*>zRlHI87#&q}qq|)kOYQFSSI<1oHI85}L?uAyx$qsRC@5DgbKQRE7i;aimcCnOw!21XA{jY6 z5BKF(+TPk@3xUQFk{f~}364SN864kmtU)A_$w^gcwQ_`Owh*mW97Ay|1&6nkWUPd4 z9FB0!7NT*`OSmFl_m}j$DGIU2Z}qpjGqd_tB3$E$>SJ{eB=NV;ywlUG^j)5oeESc5 z`qz+kZ*@D*Aam9ydJ+kZ-+^0qg61fYf4=9PTe)A|TfOF}@v%qaImMmQJR?w<;~WM! zT;m8m7cg)n!r65P_F+!xy#9=NI70VqcaFJ1Mub~Mg#G^Qk;65PD88k-ox>4s6*aW` zmKK(I=d({B`coHGw}qoX^UgJnI9^>xxYg4>`uiu3d(mAU)@#){T;quHw6u9gcu&+l zOn1Ho9pQI9EtNX#yKYs_`CYNjLw8`K(et&)dQx|d(396_bYD2Kp08dbT;m8mg}p}j z*wz!$SowGyGk1+6^!)Ie!x3(!r-3_SZcOp4e!XQ6jo%lpr#9CJ*EmAYtF93~4t#w0 zwXiXB*EphPjAeZEJRIRxeuXYMI>P&po<+7QEF2ZuIF~p=&p!9eHxX`CHC*~`kIFTA z=KRh_<%nwYg<~@+xANXo#`%?R@#xR|I6}|VuQPXFZsmKsk;6x)-b{dBAI&4eHIC4G z8`e=d!mWG+Z*pW69l<*wo_xRdHnZahx7wT;W@b2_ee?zi%Y35+JzhuXN%o$3_~$e4 z9N|{S*9@+4gr0rx9E~D49N|{Jmnh@>>ifZ5Wz=3R_cAe>``xW0!ZnVFG0$_C8~Z3n zxRu{W+QMl}^UmiCpG*9%=`kwTIHE?uGMCKaaD-cp_k}Mk^KQHbkJc61`*&xmlV$ejJk$dL%wI3jZD z*I4DB@4k;pUv3qd_va}_gs;MDmdMy^UfGDsHIAr0J!U==l_T8B$L1K7YaCI1dgRE= z9pP3!f=7;8dEZ3a*6f^e&EV&UHct-MI6`j?84xp>JHoAeA3R3o8b|0|CId%CTSeR0vwaI@T!rhM zB}C}!>%|@p*Em9NKUvqx5pLz}G;+Ac5p@)nJ?1#Vt-QaD2tP9MBZwOR8$HoAj_~|O z4o4hX-Eo^cB94SPYp@X&jPm7Hb?npo*s?e9-cWN?x00tZ59e@1&2}9v)Yuc2XF7ne$?G-Z$lVQ^>&;tT-z_AV3SzqB%Uj8`p>SXzHA9q9qRqzaF(h z)Y;)gZ(hMlgj-2&9C4Pj-`(aK$?H6H_FPx6;;LTOgj&Uwzd>&2MUPci_3`SqsJJ3S zz4#?7mqFBZgK7^UxYFPVx02jB@_H1%Tq7Bdx@NI(B*LyVWOdz2a^t9T$eD+0B*Rfx zXo}+)!mT7X4z8AvJ-=Kd8IHP!R2)K3D_MbdE6Hr%yn>aP%Sw6Br;!%~wUQN{;FFbP zwlC-OL(D5!8XvO4FLhIY8xY+up4>_@+t*jH@Wpmn!9n}SmC>=y`xPu9+)6T@mg`Z- zu8|A}J#@*V`Ys&0GMZ7jm1MlGuV5)ES;3+4*v8=D6)Yj#iZQRMudiT9vxR6J$7VSB z#Y!_=L+E}6-AxsDbL31`_b_A?BoBz}?XHnbb?R=2MCX04+_81R?xso(x02jAdk`=z(N^yQ!i^$ssE^>OP>QRzh@ke7Tk6#&LKzRb-zWvVx=TXDSXM zbT^d{ZY6o($m?pZk*qu-uaU#=rs`42iU^U1TIJEBYb3)#-QxFHs};hnBsY$_A1)ED zkqied8+jFn5Y$Rm_;M@BorC-OlEXEU;h={uc?3ryxbsX__;M@BjiW|Xa=1n^9E`_^ zc&XKJHx=yoax2M=L$iN6c*0DZaSBy+`F}MrkU^LSt8Io?o7RIZUswsn{H2EsL4 z2-OPjeCC~7J^$XXx#F;H17ZfD`k+Bp-F)Sg&g;*-bB(Xz+|!6~jU#-Oc^u(Zp5KUY zjU#-ud>r9cs`^l?fX+MDI6~|B?~QP)y6e7=K}9z2T;mA%IHv9#bHj`Xw_42%MKbT) zidw}zaOw9r!ZnVdHRJxWji?;qR`dmpe`U>g>xt4hg8rrmk0aa)4$WiJ#5-$i49?Ml z{rwe^sc7^bdozV2T(gB}?Gbay-e!h=-N4b)^rdBvVJ=BTn|&6|h`4*7SH{d^Y~Q4@ zEd-H7=6h`)5w3BB=QJW*6TLFuk#Xla91(pX-@MUkwXkHH_juikXw?_6Z*RpzQXaJj z=xDa{ug&d;2x){?9>+NxAuG1=ZHGlDa+bR_~-qn|@FxFhLLaP-SiI4-)z2`yy zx?9BxaL=&_8b|Y6pE)_?*AcAvILeTvzDI;xt)eQ(eCirj#PFc>{N$hS#-Yp|fv06H zx?o0xTj2$s#kNT;D*56Y6uRRG*EoWFmX-d(G@m-ct*H2RRBlBZE2`rN*EoXKQ+`WK zRM!!1#ddm-TO-e>ZbhF`3m!+f#u0eh?z@g~EAP`D+1T41fq#Cxb<4wjxfS_ntmK-y zA3J*sN@g|~`>q|I550N|p}C}w+MQxYqgo+rX6T4YDF2^GIWwTq_&_Eq%`u*RLrCKY z`WKa0b2$59RPYRlIeN*?ebMvC>&{2z2(?G&2>*P>Jlx8oZMN-i+Z!lzN2vWfN5Mvf zTX{Q;99|!+$OXUfu4)y~Wgmr=BjBTs+fm7vTX`QFqjD=Ur`_>;9N`*Akk2ZrnLHff zRz!-f=MmO?#=h$a{Ht!ww*4IuZsq-0h_+9Mo!YZcl}se;bG3ay%&u_+*8J;v1gvp5 z!mT7P`}3L|hWD5Fdq(1HLcZ~)z5U|7_j~GN{w&V-eLarTUE>JkTVC{>i0bPnEf3ys z{EZESte*d*x9lY=bH3-DG^!O=$d}ifbe23CZr-_uS_z@L-7$h1VdXW9c{kp1_xX6Y z8ay7A^J#m_d<%ib5t7?koUaGR=Yr#!U%mRV?#r#b>UpN4kG$Ww0R-&9XrK$ zLKWQ8G;JXAjX91ex%w4|Z$u8?j(^U99FZi4qgx&zzO`iDBXI;WRUm_Dj^4hbw>yWw zDaQGx=?kxa;A3^((lw5#b~@?rDVk$^>=+-8aI5MI8SOMxFWC{ETS=y!M?{=Yq?hb& zf7B1EU!^ZcRF64ny`=hXa=0(I()Ko@wh(9>A$dIpYowl_albWcb36I!)AzM2#EN5X zm=WPtHO>c)e%Ao=Yt*W*Uec;&(cHd7gyb5J{V2!m2)EMqp;j~VJ8RMKo&B@cr772b zzUExT1)^4#sUfOBrOX~J_U{`AtYQzDn%a}C&&%) z>-mjQxyBK!KDIM=gj;!~M-JCGf|b*D=8kZy<1OeK5K)QD98c;C>!_r01QABHm-d(& zZtPcXRja54QAG2pTh)pzt&SsH;|N-IhzgFGe&qRX2w%eyU0=QS*(W@ttOz?|ZrQ~BaMk0`X#PM}?^z>U;|S!4 za+u+=J$8o(S*ee8juuqp;Zf0J;&=LWzB10QevFe=j?f5RbGR?JqSB!o^9Yu9JV`WCtK;qA^&tc^Ere)Z$1^yLVR!FA^D%dHN_M;;N)L6iI1K=pk%GJdIH?0fqPpr3n9 zgfw1hZ7(1_Zoqf zs#|Bz?|{SoI-<_j_cqUNm{B>xt;VS8I%iflH2vLFl8HSka#n9l%d0Y68C839%@(3% zUe{~Y=3JM}HXr>yznd3yHaTYcm1`VP*YP&;aD-b$`}cQ~jd{4n5p|_;2j! zZ!o+INwI7Ds<)r2KExQS`{Y1YPRRb5PhH~(_OtN0HS&mXD^+2Qz;7HGrLR~4_P3U? zc3=gtM!<}3GsOI+g!uUnpH(0#A7 z&xw-RFL{0=!Zlk6?bYbFeB$l+6)zfElgN;jUq>`RAY9`J^`4HHA%MdXZl!s?BRYp` z9HIX9y%BDuO0N;B6&kOV`q&!5dYZjG8qktKz_~`aFZFz(;anp;Do1Ev^1Tsmy%Vwdx2WVU-HPdp_G~#m-ToE$iJw1kuty9Wijoms@$yFZcPC zXS_PQBQ!sDjvkf!aw{JN;>dON?0wX0rR~0^?$>d$@1k*pY4bIG2OQ?o?MjPv-Haw5W-PaEgl(+;9$gOqEQSP%^m2-i5G#^!>U8)QVdRqeGm z5Uz0qEf~Ky5T2oDUVULf^gL?DNey#(%pob`iMylMvyW>WQR|00K)97hTLI-)Ymd;T zFGtj#=m>`pZsmQUId4pT|B=3GpONzMTDis%wWr>Q$`NkG_MrtU{Wh0K69N`ec ztw5_a%Y7>V_w{uRdBpFYxjc;skJk~k_ql_p+{*j($l)4Ccn|G}+19(s?pC!X8ly^t zYaHQyy07$4VN>QVGbW-=?6vo79}%t*+7YV}#oY-UBd4!A=a91cZsUl*bCc%NIwnu6 zI#y4)j-yjf+m3LJBb>W=7snw&5!O-o!U158|AwgQoZKqH=Dq#xXARQI5p{lU4C_#&4(K)98Uc}2u`-oMKm#`mnY z>*ytAqGC5LuZ`_4o4tIJOA8` zC;#bgS7qi;{*8U!e z*tpxh&K{K`+{&ZPJod^X5cync>kZ$zE{^20Uuk>GBRE!wrdbfv<^f>Tt~O0u>yW3;{y{&NOB z)NCQJ=|^6mX8d5ucFE$?tTZC9mSzi~sPNd&i*^p$7!Ozpjio*R@$!i zAm&}`1XhLa)onS5LvaQ5XiKFxYZsVk>gyxu!?b)evcwnQ8@y+ z*GcnLawtP_V1=w`N0c;*T~;-__Pz@$bJ5gap%z5ndOI_vI3&|EgvL^zhH#A|n2YhGeg&$H4@bC_ zwy&ddjUyy$e5^U}lnKQ$5{h7S87Y;{DZirf0CZg7ZIZ`Fp znwk}0ZqGF}E6ZK2sk_DzXa3id?5<*u%Gn1ii?$ydD09Yi)#SdOQ*Q5>b2O281czxB zMEt)nEvh=2*wvca5Q|mhl-CFwM;%RMRHJ5%7}nGo74wC9oMd`Lv}WJVZ$7Q>y2cUF z-xASm+uzoA9pP5m-tsU+XGh}*$?M+kzT9f8x^uW@3n7j+y9JWDBr`-K8IQ=zd=-YL zjc3$sA(~yCHAobGutXzSeEeP`#C{B+JkYnuXm4>y#!7sRqy23N*K8rg(b^j%R#cc4 zl#CTJZKXDEeM$&v4iQ8s-ZTM96X#&CQz?|qBN5K8S$6Wld zHZyosj&LiFw&$@Yk3!r;>{w0Hr#+`Um${7~4@We4u6qqC^F4E-I2J^+s+`U*wc=a@ zQMtzbYP;sdvCX3e_iA%wKQsn4^WiCM)4CyC16l}=FcI~qU+v4--74f^ z{~=V5D&zHRi!Vo7TF(vB5M+N?ALo;QzDI;xwXrhg2p$oxafDZ4M0jsFY=1oT>J}`c z>iud1ku@ASg1sY3PAl4bo5M95hz*YL!wMkdrM)Gy9dGMAT;m9xBV8jZD#cE(OuruO zn7M00?g-~Tj&Liu@V1W1HI6u*ha=pI-l@8cQGp0eW?oh)m#3812r?#KN5s95eMNp8 Z;Z~K?HiwPQ#c#Fd9U$Ba4&^sZ{|{d+LKFZ1 literal 0 HcmV?d00001 diff --git a/data/urdf/KR5/meshes/bicep.STL b/data/urdf/KR5/meshes/bicep.STL new file mode 100644 index 0000000000000000000000000000000000000000..2191bd5a5e24368434146a45bd0f11429004955e GIT binary patch literal 74784 zcmb`QdAv>a_y6BCeHvU5B`O)Jk2IOX-TP#27D7VCLXygu!Z9TcC>0_yXNX+%5%=5^ zl@etrL#Zf*lx9uB@3r3Vv(A0J_i=lC|M=a$%r^T>HJ>d#$~V`TzU3{S-Z4 zJc*<&wyumsk?fc?K4e11oBV!w!jnE>N1{rY;1c?!;&ZWFaKTlF~kfE1ykw2&oC@O8zQ zf(X`t8&^5+?X6VYTCq@d?(F<9r***k(JUE=E0A!i3CV>2p_eAu6J+ zq6BNnaeiCbREMbCI2F3`1{-_uwSWAw@hU@bO2KKQw9>KU`2@@D&wjORI z7DTX?9E%M{9Gf)6+L(*^!4f8TEn$ohGC!gOYss~i?2nBp$Wt@HKG>Ms_B-FcE9KkU)n2|@)(N5| zR{&W*$g%t`$Hp|??|i!uEMY=?u+Va*G-09yYss`D3dFOMJ3V+j-DgT;nhGo%O;C0I+2#fBsPN%{6m&T+n7B}`x(TN`f8 zAjF0B&#n+9SWAxOOpfT2^6mGge7j1R5Fae{aBBu3E`=|N609Z1awbQ-5%KLRVM2Vc z*l=rxf(X`y!}&biL{_97|Yt`a812a63^`x+wz>QOODu$COlnH=G~wEW+BYLze{ zJ~-cosEU4+U@bY;GZ|C#I_KN7Qoda!Oo$K8Z>xd`){ z%#T@7g07@Bv*KnH&kwDK%n7+t3&Hnlj^Gil zW2pqZTfw89B~0k3>gP6V@ZnwN-!h6~=JEHD?JE>c`ThO1CZ( zti_%vqaL>1r5;SEACq>oMA`m#V-{Tti|KauQ^MY z_!?eLdJruh>2oGni)TT^23^Ut|HT^=e2roW6KW&FU&WbVEuO)CsaV2<)=4~S!31k* zyQMutT<1B@3H53++6$Z?h9yj(6$0rG@hg6*m|!hg`wEfieOOC9wfL?K0*0I~VF?p@ zEy)}uOt2RFF~1%xVFImdYn~qM=~6MlT9_-g=9rg}`LSW&-F5|8?w_3WUHq9ZEwj%M zWM#>BMfrYLB{GBMSO}SE`nz8bskunx&P4h~j^z&G{HF&8ay)U{Y`fPbl(QjzS0r)| z&~?NVt97KyB#-uO@Ohc&*nFI&gG19IHke?oj8et5RC?YGR}KtijUpwKI|!wll<66< z!4f9qIxn=lH*hs^HDAB)?p%=!Jz78AAF`_=b5nkID}5%;dwOs}BolA!5Xzj_^LA=J z&ibGwzC^W*$5T|)G;_)4+i?oz?T zwRKs-gj~CXaQB>CDjt2>ZZeJw9*HbrVs7`Ztc@EkTI%YNE)^53#iey+I#E5CxM#>E zwna`azSwUo!{=fxZbNG$T`C@8YBZ$A12&%3om+%sg3r5_BQi1Y^&ti@i* zx4{x7)ZV=No{89Cg0-}M;_ZAJI$qf`ELmO8^AbLx^MiM2h0xZOGZjp*mfZVD4`zBF zmN22cdG#BOBR0}=8~#d1_>}WndcMmq75gYAbgnGhaOuY5?OiRni_iWhb&T?My;jC4# zr%v|=ytDdwxmp(NcUi)O+DMPxbUm10Ep8FN9xP!(>y(~RX&X$i7Pp&kgU6`)D;Y~X zrhS4XOsGedaa=ILS_Q8FSi(fw=VRXZHke>7UVZpP<7dX?RxdfCZlN*d!+nRJ%GP83 zeMVa4RQB)(@q_l zq;+k2_d|9<h;)e<$=@OvthP?(Vz>ciL%fymM0bBx^S{ zwRDF?cex8DRKkQD%kOR{^;?W5vGE(m7i;OBjO=D-64%z5QBes!7ZY+Uzq`HgmoP8H z#%9bD*5bXMe<$=@OvthP?)Jjf#y-qm)>3=21C>c+*O@U}2|X7RS}M1H^p?=>|NPfUmnkuag7-R-c@9E`D+&PUzrl{4iNn1gdL2Q8rzCUl+)ZOoyRFZpp< zvlwfsUqRi1Orjxti4tN%&c%fKE1`|KDdiKloYXzWTIwHVSLNRcu_5PTLjA7WlR15) z^X>Z^4~VfA`FTsrnevGS7*|TDgbBJDpdO`$x@#2XNsP7hdL?_||4xVvjBf9VlF;(I zd%ASdP9`os;mMk%2Z zCgfOtck@GLlGwmpjIkExV|p(%lfc?%juLtkj^+3Cbx>@WEX;S-QhRbm{&zyp#e|m1 zUC*&*ur_1`z*^dFva-k|ux6O8gxHXCF`@n8)+Jc`SR1nTVJ+={St0#9AvWY(Oz60B z>#Nk*H5iFW*3xk-E4@qtV|R`cVk5QEvppz;&JVXvOwB;NHddq0!dHstdXX%jb@^Hk!}v60mJYe2-FX1Hlp|*dC%kZ?B$QI4mde-0jt4 zu|uO1(pD)O32AAu@xKeY+TZJ;493g^F%6}976eORBTd{sw~IYqfsz_?p1Yo#Z?LxJ z9hT_s;4@R+uH$yqgs8b`+-xOO!h{^l?{3d>UTW;-V(juh4BM06g>burQ9>n5$g$cs zW+`$P$qFyWW#lvC{W+LNBsDw(G@Jof=8+(m<1GDNx`}lHR`CZQB zo*P67m2e6DQl*GEYy_$$yO~jYawfOSNj5B@5+?jorLO1k-?8@5+RCmh+tZr6-C7~4 zqpg$>8&N{*;YyY2!8rOn-OsXb%=WYg-P2dIvCj3%iCRrOYvvd~8voyA+GfI9pGFxL+HWj@@39%6+{8Ihx zd`WyC=AwE7dE&Qj?m4HV?m6XYhQt@JJ-O$U zGs*ARRRd9TQ_+e_sDuf>RPU$morTcnHBu@$uiBH}wY0`W36(J6m#SoH4?t>;8m6Bw zvpxA;&gA+-h+3((VhIy|scNS7GPa}7^{JJN61FG5iw!rfqJ&DAVB5z0j_Zc3;l9P# z)u(SV+S#7`E@yJ{Lx^mQDRJy+_o|>O? zu|4@+&g49`5b*7@l~4&2eyMQ9vGtH^6hA*>d-A)SDSaLE2$eA5mx^p8R7q!^Q%nB|a*0Cx{Pm z2YeL7tNU+DvewaaOIaIFPH!Ii#5xdbvC3Zsf+b9pd7_lHv8-2f*!U55@}od3E7vW_ zS~ZJrws(y^Pq`)ZiM1dGJ)D#H00c{zSiEF&w$!}!CW&GB4LcH@L7da7f0DJnYtq8n zs4(${&?okQcxXUQq6`R@F!9m;7S_gqyKaDu@|%|i^*}Vr8j@r!?X@nwuMd4<#MY%j zk&!ux(jZvEgd9sfKB{p&Y@D=tX`(oYav)giP?HvRy(9JTi5IpmO*BTS!W5zBVq)9= z7P<1ftH+VTBl8{vQ3^F@t?I=$TN~0JKJf*J=g_((L9m1gw4t@(`s4SpJMuPycoRLy zTIhd!?UQlk6RSX6gHf^u1WTAG{Y0sR)WeOd&5esEn}S$@k;qz~jcQFXn`jSBtl4}C&r>nyCqv453h2@{=4kF+-0-f=(1RW5ebI>W{?wDR`{#|Gj{rVJbu zzV`YEdn`6ewH_Bp>wec&a*3TLjxVA#5JuQ{mkh9BQ z+!9g`kubrwou&owKZ!P4(6CUp#x0eo^L<^3Jkls6`8|`+=qAyM5*+Dd$)rR&u?;=e z2q?9oWr|yZZ77jZs&s$IxwIr~Pi<(a^814&Cn7RR7310pq4u;?Y9n0_OGrIL!UWqk zW(8(a^VWzhIdEHSaKAh4esr%}pY-;oht6%282&+4cA?QvqCd8SSdV$W5Oa|wyl3t2 zQ-1Xqqg_p#W0b`z*>j#J& zcp)ZO>+MOuKg{g5&+HjrDjAVobL!OB1qMx*}_cN3fP$&sXg| zHM`L*OF?YG3g8CR`~naxi4yYEVQ>i{x@=h*Tn_@P437|6wQjnte|CO7_F^To2Bo?R z1WTBxi|02&yLzCl!lfY2M9rCCt+kVW$~=>I@$xN)@ytJkm4R^u@enP9E?SzUuW#~021 z{A+nCgH=YXG@g>Z34$d|w8YaNvEiQMOv5VtZ4h(uFB7cw_kxl3IaU1`_rk_(Xl}%e z8i#*b!UR8?!uo{R@P`cmw*@IeE37E!pX>QZlxcyn-Q}-0}p2RWX+j#Snt71=% z8X2ztAQy~kM!qVr=T!zCbiZQv2*dITlznq0TR1i33ZXnz7Ru^>i z?j~MOY|8$v@}j!E%SZ2V?gViMN_DVIN3T>&usvg{ns``v7~<_dz2Cc=IOoge*|Ses zQg`C&=siwl5DihP?jZOchY7Z4OwFE)f<>tLyDj_M`wzXFu%6+_lDY$4h~DE2@3AO2 z1RK3^ZxFr5X_z9|o-s3eE=v3aqDSOzqU4v&bG05~Pi-4>ZjVKYB`DPgky1qowP#Gs z#Piz0MrT*^^qtA_#HL*B55AKzrUHnQ(7H`Qu!IS=haLLDTk=|=2meM7^4&z^L+2%Q zT=AU@<~fL`QK|-Rl%z|=1lz;aAKr5^o;!btE6<>JpSNrEDzip}yoTR-?F)7lUS*o( zG!zDLDLlhhAXvf#ujh^V>Wd+<3BP0olRD%C_th95^!pqUdeb_GRaZU}#Hu|M40yA1 z*!e;C`@$xjU}GnUQ+~|~&gzmAu!M=_KRgp0&+8jFqSeI%Vwb~4x85T$>c?3d3lDY) zbN7u8mOaofXkEE$$hM7X0-_s;Z6H{}1lu#_lQnn8D#2g%YrH*VkHb&+zi2)s_$pR9 zyZJkn;NfK<4v33KWQ9#51Z#Ew@9bddixaa)9{T|i5WBwU8w){f zsXfArnYgpqf}nl7&Dmr2_0DG6m@hzF2I3tMEMda8Q5DzmW?0GW!F8SEGB_6Fxd)co zD~^ke5~68}UB8!TbMkBwp*Ot6;5ehk5y)VIMBCj8haw!s8z>6N+_VnBQwEMdZrjba;2u$HbL zmLcZEx4{x7{MabA!31mRI_SK%lOr}*!h|0i#Wt8=EnUw|xo2*~21}Umqp8>i6Rbt+ zQfC8@8|^G%!jGn68%(ekt*;|CSaKr5W!JC`CiGae=sqE0gC$JBp1os{cztIHSW+KhkZ*5+=}Y_U_Kbs&PG-U@eRVOQgqD+6GIQ(AaYqrN=gyU@g7>OwW(B4VEyW zG4w9lkZmx*T9})*9_e|Ww!so6Fdr@9q9)k}6Rag|B%V6$uhKSH!UQ6(E#aa+*#;A= zC4DV6(tbB>gC$HzUkl-)SlI>>tOcKMiS+d&ZG$CDXpV`C#$_8!uokXe)<*iOmbSqX zCUCtvF%f5iwbZtYfjm*EM8bsHbJ5X6#Q9vTrEMrtnoeJ5ElZftc5_kQY=a5b(y<^> zn!XK|FroeLqSe_36Rf3US|TWY8!TZ$$FYmLXB$kgmd;Ige@=v92@^UWUG@MGaVA(x zeT>^@Ai}VO3H2+en_u%d6Rf4a((RY94VEyW{?TP~5D{mBwaDlDr7|pGg8aNs#F=0% zz52NQD=rmFPDG^N-4@r;&V(L|7F~lQrD6#auxEFpFlQW*w!s8z=~^PAKjJK50__%v zPfYhm+6EJ>g|T3XjBzESBrRb=*FouVmA1hIYw6l9V}8V0!i28p((@y2g9+Bc+_a_5 znCEepFoF4KiS#^A+hBsVbgiA?ui`9WLf6-6f0eeu1Z(L%Lx$gtvxEt~Pe}XSv<)U$ z3qIf0{Djw!w1f%0-$`FT(l+>9ti|_mCiRzjcgF^tWBmB{67bEW6+BqXXXt zG?T+{?_9WkHO~eU6DAE!)I0cc_7lr{VxIp2VmgT5V1v)aS_=w~O4M7pBK!SX9YD

hZfqV%>R$-=`&hQ~p$gb9u) zFs2xY=t!c)|OP5(AEP3U)QQC2ahv z`&~v1cJ4r|2C=+zPJ$&&d|9(`qRZy4fg@U8JRtcGh9Lp@f3 z_!Vt+ItZ39;m2i2&+P$GDnhW<<|Pj%9=_^_qogpIX`kGUMriss^ZC&znWf7eEf zNK^;YHufVau^+F2UV@M4Ia0-+A1q(zgFQ6VGVM6V>cxtx6=VC2w!wKQUhz*u7q3!14!r2BBtfgb2 z*>x{PY_Nn0?SB{F&Ni4}EgjR97tf5?U7jS#H-=c^GLEMY<;eqH_t+hBsVG}5u@k|hxv zEMY<;eqBBe+hBsV#lC_nr|b{k`oaw9|tz#x*}sjk3~x(Pc!NfX9*L21`pd{ zg0(b)Hlsh{EMWreX5(zr{gJK*6Rd@?V4r4Yj4ODbdah(bSPQ<=_QwhRZd$^GpK-`G z_*|@|Pp~tuA1q=Q3Yl z1AlIP#RO|<8_IglsVl(}CbZpLK8|HlHke>79Saiu>)T)n6WaeSABSx)!CE?|B~seA z!4f9YQ`Jo4%=XYwbWNi z1isVPK4%FN>K|P`4%=XYwbbWJCV_8*B}}NFcX=#qg9+BstB+(v_%>K_BEse4uni{k zShVySoLLW+FrnAo%z7}vTDq3V><^YOfp)Vw6q)_O1Z!a|BxKEy9#^Qm^9(FuLf1hj z99QXcv6imw((@y2gC$Jpdd|&{s}U`70MR1V5Y5Uyk$qR`Cnnh_Bw6QZo3v@q`n?MEVyxDsq9_n^bW5JMhDyed^x+t7mtLTBY?dO5I^GH zxflqRFyTi!tr&Y_tSW32!reC8VEXgEj|R)%ADe%RyWR!hm226C8zT%y1Cz zB3A8t?Ef&qTD86S#4>-pwEW3$hbD(SxILHSUO7Hh;=(m@-I)E8rdJnY7zmCx=SXRe zfi`Au{a#gt_~!vfXuNsXpUNaYzIb=tEzQriQRVqI?s@rSTdE5qHkj!BL#@Q+e-z4| z^Wl5g7ag^_ge9h@Z0NaIi%W-MgFPw4fH*B}2$bg^x<0i|Lad|vro zGdqmwK6kpUM;xW%UgPLrzXx+ow`Ed~UtohJO!R+lO7O(g)3OhJ`YKwt?7M?3Aw9?h zYsv50v&K|;cCRJMqEswlLh?WI>mhDITbBve;@ksc?zwQ)OeI*tgx^*xx1VZDb$)7G zX?a7 zj$6dL1{(FTHLneVJpgAbu*Wdw@9rBdQ4Iu3n2@VzeujcvouyRbub5yh9-+oGKWn4y z!Kxrw!USg(7<1;S4_QL$!31luuQVoa)K|7YUIW2#x*Sg{BStfy@b%WRS5=pK6a~Q& zkDypyyhG^h|JWY9p`TCi{yuvmy#3;w$8D)f!v;r;cRuh;@LRR_>dsqSIrOgv$169n z#MvNN!o=UDMh6uynp^kRw(^D130qd$dUV13V1l*S^BI%<^c%L%KLEj_{goRh1z+F$ zUES8N6tY=#`JQ3zflHT4Ta`ztcy2SnB{b%TVSnWaAzqXT){@`z`(wxHm2IEzP7x|$ zg4@uTVdLJmzP%!RJD-cS{22P|QI&1$7DGK)!cp*iCSwY1*kfCFL8|6jDkl8+cJ-pa zMhMp8@n+0vB}>}=xbPu=TrnYYB|pBs-wg+C>;4EEd@k1FS%56;PwtQXg4NRc<3sa! zh4j;$F~Li-zsNrC3Ot2q%^9HkL7axQ&zXpfX9*Mj8csYzYV{gldg#%h(2Y+8WzOyp zUU}8S_V~#04q^3EhuP!Pc0}(7nP4qFZo2ZW$lU}>^jOY2{`nEsMy;VK8(J!(T5>Md zYTj>@C0dW`?AwTQ+5h@*fYp+ic0E(N9vL=7!i1hF!$!JPLa>&$NM=2_ygyWYETdHa z-d0TLnWS%|_vFvre`pQmT&$(-COwPnnx~q@#{ZNR+_AoRvi>zs2fg2z7*xKpUHJXB zr)-pe(H8B(KW}|HX!`WTAX%>+h|ec9i&e*yxUzZ0lPqCke8;ht-hE$t5Zyq$d^jsu z7a>^dwsXb>qdtE+Xi!^-hP%7P9>Md$a`krRX}-a{*>{DvjT;}_eeS4WZy)r(XQRlT zZn09Zkr(XDV+j+!4asSE1vZe=kf#|6zy8!A{NnLvf)?LC8l3h~hjgxk*v1#3L5v0Q zEC?p{+)@&q;8m1!q^VZI{il1vXlB$Vsq-3AX3jY5;6pTyJN(P5P9- zJKQ;HTyS;0Awk&zcc<$iIUC4=KRzds==kiDL8ty>gLysW3GZ~A zyEN+Y5o~ciSc^+&%yp~ojQxi1<4%A7?679pSwW9y4rLE*-6}LYr`qEdO?!lVr8Xu6 z@i&O2AUp{X{`LH{tJ}p+#`o0+#x@0$_AIjJ?eoUj$&7BHwcz6q0xITBK}n5_PvLg zJ9!@q6Rf2fV~@Tm`B9Ro-V!!G2Eh_0Gz!s0_OC-O^%@ZK5G}$4YiWMm3lB(s6e3dW zJAM~|Us0>Kg{G%D0(T1fWw zP7pKj1{Wq+YX#mCEN}9axIg=j-f>@8ZA0}992;SN(HYy|}KWYYupO8oYJ_wdD zq0zaNo*I$lAU0zrorth^MJX-3$vQW`9y>wY zo3gHh#fOst@8HyPI!lcWdb{Z~w| z)^nJ9V#AHADIgkQl)MLmB}}0I6Vg_0Tz!F=)E)%h`{5C+rO~Z!eqij{H-*dw!4f7k zJHpM6shCOA5vwL|&t`(PH0IXLbG*+WSsgW>kAGRhgvJQFc`oID62v}~jtSP%_+;m= z7J-mC_$dgMFrhKY&R^l3j$m|Nx2$)34$d|z|Y%0ch?VGaguVyc@LwW3D&~3%i2ii2`5u| z!g5thOPJs+D6INmgEEWL1Z$~n_f~l!D0|rv@HR}SJr@y=w~!>?L!TqZU2>|^1Z!!l z%Ny;DIYU|(HBY_k-V!2VLfg$n_RHK0VdEuuQ$81K=~$4scVpg4jgkc*Si*$%zspeQ zKfh^mJXRUy@P-YJF~9rE=MssB_GLf&ZRJRO`{N+8L7W9bN4va-o(Z;%H-(ICp6rL! z($`y`2+IbO6SC$ke|jm8*nRI4_V;^#dl2>L148aUJ_f-Ow!x(}W&j9T^{tB#ti|#4 z#?+bA$`Z5RyesVWNq1|#*s2c#w&xR*K)iJ9cwWUdcZK{+h@Ta41imrXf;fUwO@|GZ zFu}HssSQGE{!)ZsEkClq1_)Wbz5;?JO!)Qqrgz&Uwpfz;_WctS>wTN8`Ac<+d9A=t zIq;klgxr7p1cD`OgX?5Wjb-hVgPHjtnH8H1h)F!YM0rc(yTBTBHA9II_( zt~}Mfi}j6@@TPH+Fu^hV1rw|#$6~|f0(_8qH|{#@jk1IZ&LqHlwm}?0J)#6_$+6gQ z@$H40*!S;(lMQ`xs9ck znzMun&QLK1ZFNF|wd7d(Jl%tqkRD_S6P!1LXA_u7Qu8RmT5_B}t}qfUAtR9`OsKu| zXpdp+mX8vwrKNQQ=AgA9bC4xWXuG*wnSuz`(pGl_^||MLn9%-r-X|QBlh{yhX015h z*jw(5@`*xY<^^p}ZWCU-?1Dsvr{)EH_T6Fq)uniSPyFiHX36&o*G{zk?y;cS!0W@N^K04jmfd}Q zxZsCsi9R!*3C`Kn1U3#NaLcY=8OR|KCQuV7@deiw5e^vgvop}pkBfh&^^5@QO zH1vGDNmz2xRf#6QP71DW)g<(ZQ?Unr@Qd8CMgFo%79=p8ywTa;4 zNkOfhx2OAj$Ku<=+;i&K*6q?=p73_~wtDgp?6(&`P(8*H?Q>azB{9N=o8_DX357;s*^yl zgo%+|u1mBX_E@m@8;P3ifzdG^BXQJqJ44OdI^LsMcuJ23i3)`u3A)T}7BY?D0peMy zd2FXAVZyiZIP$#8;km)VUL(^PU`sB%E!=;1qr^=udj(7C-R9Z0Z<;G<4Aq+4BV8#5Svel|+A08iq$R7|ivLkW21+b?9#;Ahc|1tELLWk7fm@(iAjF+bof zZ+r3l{Fg#oJc2XoJlp155c@zBMtmYmnDF!Nz6bFgh~Hs@3D!!sxFfN<{ef3BU_eQxZaev+xI};PJ zYrtBZC6-C_0WlQ>OPD}ZsI}qZMe%;rq!1gi=f_%VPcjBFiFP2ifM5v|YJ16NlCO3W z+DdBv33d%wOWRE{A2JDP-JKv$O?C~sg6NJt0M_CxF`vNOPLsdLo6Oo}+A8e7Ed|jZ zyXdT?@xqc(;}f!L{tMnJzZe8dn9%&;Kl(_%+Gp5*`=WnNVjcGOSxe)dB{Rq;4uiM_ zJ6=;ju!ITCmOj0qM^Lh@V^bkFl0Ul}o0UPizL!c|=a)2nd!iq3@uaw?XpNPR2}n21ErsGh!{-r`C)! zpSS=->PrGKmM|g5@|Mj%I!M0S>6l4Mu$D&oOFev|0thKpd6bGJOz1m7T|LlNVJ8rO zqUNln*$UDhKCux*GqmpSAXvf#+Av${;rgR9X3`RTLjhkBh_M#>-)08MxblhDL5##G z5rQR5=yxdGxWXIjWAX;&Wf+O9rP(7gKYZd;%+@b4+VQsk7)zMYcg?!_u>mvb2h6C) z@h@v>7K~(^`2>A2B*qdZG!EU(^Jh_-5cB*`)Q7b+n@2Lvd?E?rX?UN{L9m1gjgEKz z>Ql7pPw;S~(aNj^|7iO|{H{-|1knkl5}(KtCg3Y=zJc?**gcP30^(ha7S_^y1G#?q z#Bq!#d9$i~%akQdz~@^V?)rfzSF!!D(HZaCW-ZQ$@CkXs`z>~zKgK*^2@{+hfe2I7 z178LXi`}~@@qFJdHfpN&s4?NF!|qtFmVfpd6UZ*^E%!c#S&L_OHVfi0yd#$-O!ziV z1F;=8cEJV{ti>^Yu2hAvWAG?!u!IS%pIb9r^jXW;tysQyT-U>kbYXjZCS(2!;woA2 zgW%YFj&$Li4P%;ukQkQkAXvf#N7)#23y1?C5)p#6I5raByayrc#8*Lh5{kv~>#-Gg zLyZv+w;1tD8&^MWqmXv|)-4?L`{TjW>n8^DF6$n0bdoWV;-r+>%Gs z9An4AxZ>T>=k;OZUEHe`LsS)?t2=3N43jZ!hs$oQnRPLCj3la1-tjB(dmQ5@$MU<2 z9mEbx9`1)_S1ra8Cj3Z1A+RGXyJ{Z6T5_zm5xJcDdfn~#f+S0r;K)NqNIjwiYss1p{kWzD&Fu`%Qc3j0$h`ozy77T5_B}u8O4gcMoFrvV;k>=SI6FFm|H^YiVg6fl;Du6=Mk# z+HNl5SBTWO@(9+_R(FJWAMqto@56-lzws(`Q4b6e=kkUzP4BGtp7MdB}`0hG%VPZH!nC+Scv-{%?S=+pWzwo&AhzKoww*~ zZNi!>Mg+;7vx0F8+k}^XGTinDo;ZS-dmrktJ1a)d z_m4Iqp9yi64~z`6VB|u$;H6;o;5$RM zZOpHAc80C@WCd?xx7L#o!S?Wt5nMk?;`;F__Wbnvv8hAb@Se&~27mN_F({hdHuP+p z>p)aOJxXH#hb2sK35_{|2-%W9W(5PWo1>Ak5(~~T;%wWPqu8t5hMl55*!N)x6P`V@ z;>-cDv-jT~c6hvk7un76%^cB+@dRSnzT3mEXqSXNI z&q4eEqCITz%7O|1&GoZDd=KKb2*Fx@JarC;cR-XvsaWDgM0=&02Vw_^qae6cO!$$@ zc_7{f@y}?VU@eY&#xpMv{{yiOHaL!*`@oN(m)2baVuBD9!Oz6NmE-K%r|h4y7d{8X z<>>QG5rVZitH7AN*9O{pJXGRfz~|*SWTqYQK1$UU1WTBB0pBT-=O0T>x&o!j`T60P z5Sy>)<3(U|9C9YHQQ8UwOPI(WGR@jpy}l4^bZ<2%Cd4=AtPwcJ^8&|yY zaI7MFaOVdvCOUrhqLqw1G(4NN=8l*i96c)@^f;*#qIar**ajO@L9m1gwudMr5U+#y zIzq74$|8u4-f%1x9eoW5nIF4Bu!ISYls2Y1h-o0+i4d&C(ci|b$Cn)jB6{cMIwQh$ zv8lG^H*{~8&8@)o!%81<$bCVyMjSFrxP*Kr7rER6#1s%LVdCRg+_-WvUJ~mp#IQB5 zC6s90y6)xM}54QZH}$>iAzDW zhmF1*myTK6*f*ozJ&A#M!graEqlE( z?<5-ACoTpdH5Y;&wc+N+pO{HKLEwGJUd*;en@XIvPhbuvyMT~6 z$Py+nH?0jf&t>k3zY<@Mitxl6kj zp0@_U5+O&FxDwyaS{joq*Cn68*PxPeHCPXVB}~BQTN`o>w%4enTnAIv zC>yyf=jCYZOhQ`seRn-ipNolYn0rzWw*rvaD#TeXKg!w=iIz&@w0%NmtIWZ#vC3cx z6Iv=+;n?e-t$FG@Sk4B{tL-My*ghd`C9S&wev2hcXd9M*Z#3qA=)uk)2E&_jtn>6| zpG{n5&JQ}rDh1lJTj8;d5r5kl#LXadlt?r;$2zk;`vtJ%?I0R}U%!4;hIv2Qd;umN4PhV>o7%jP~NVR#l(ysO{TT-9xXo+zQ5&+|ny4caS?bObvgn z)7uhj_udmQ&C%G#oC8AcarS~>2@}4Jvq9_!@oj`)Ev}O>i#k4JOEqxfBc2V8b>`AK z;$7Gn1cD_@JkzPZt>3G=)}zlq-8mq+9>lP%SzgpN$2$AOCm`hh<7p5qVd8jD$=cZT z^x3#qtK4l+QtpcWx@6*N*5atJOyUC&J1(8Lnk7tpQ1WtXqf97oHoD@Wk$DFYM|QaE zfaIDgm28w&hpU@}58YBJvFYzAL7D$F2|3;mJKKFm=FP<}P67l=nBW*cV_v{Jyv?6k z!4~Y1Y2;#;VohwMWRFVIgAIQ)4%xOb&)k!fD2qtIjUZSev=VF&?~Otf)qu@e0dn1w z#UFLi+)|GYeet&Xt}}xH6`ehapcLE2JkmcW*o*kY>5)=J3AKkiFGPbqvL!2c8T)W- zwTrUi*3}`}?l%8lqH#I_}Jq zJpLL0eNN8# zJy+<{j@=x--R*CC{73zpP!IR#-WpM)$LaRGmG?LHYRhNx36^mC`1N2LOt6;UA53U@ zkKfol)O!3l?zWK6RB)-7sQS=hTXPqu&o=m6tfjQHn{Pu)C9Qa4U1Qs=!K@qpkELQ_ zQR|Z}J)&~zjf?RU^&o3;KiN{H35~6js8WsPy{vD`P$RH2zq-H@Ce+6~c?#ZlkovQu z#C`=s#*&b6&(;E;v6-pQJV7Q z0*+$$>S0*I1jp8UL|ofPVzafSC5lno(8afN%~`?($3uEH3=^!yrS%DxFu^gN1rw~r zZRitPb{SV%Lg|0C=OULKOlWB{zZk*JevxwYY>{snX+0YRH7Pu0%~2Ot4mgHBZkE$&b+aA=h1P>3<)IOz3=+tOCDOd@k1F zSzw8{`YX;vQV;jPgDpbNg7R&!gbDSo;`4nQOt6;Pc6lsdGD;;9CfMiurQ&n3mS#a^ zwk}JU;Pr}cg9+ABU+FSm9OHXYk(`Kd>#KqYJ+EkS|NEuVD{`{;9rjy7>gWAj8MeU^ zt&?~LwU>D{V1l*u*k#wS4VLJ!oVUQML3)13xmb%=P6gLoS2BBFZSA#!PjGFS(5v%? zxv6VZT;~T9tfk{E(dy?$ySJ6sZiw;19ZNYxIvpxIAg10x)&}byyDCxgwCO?Ri&~|}mAjsoyJuwH z=51NQ>~eTcn7YRi2@`D3m~zN=`Y)a$BikvaUPe|g$DXa0nE1(*;OdDjy%h(ZJ2%>y zx1liNufFK!m5K?r=W?*txE!n)U)4C9hi&5xn8@0?6s79*Tr;m!Ot3waYEA#-8F)(e z^&OYzapn|fRQdOVe}VWFcaR<1T<&F5@mG!f{Ew5@_D@a+@eypW7TW zp3JdfCA`+g zE#lsQY4cU&3t5PDwZ{_c%CvpUW>VsJ*WoRjEMelOAswxa)i;iUjSaA|6|spY!v+(q z<(CTayUCwnV+f*g`Mik6wWX36VW#mM2ZX#SeSyU9l658!FKkQY@^O^N>9NSmu2Fju z5q)9;HUgF~p|&r(W*ln%9cunPN`;!ITU5@=Suj5FEeNSc2@ot{qFl{ZwjLe+nE)G- zgC#wP94zm=oCV_(lIQg;h#v}V30cBKsh*9jjrEUCf{k2!!|ebFeD%%CuHh^gpI8gx z8xVL8eT*ec^nLj%YopWHsjzVXU*D7Lv!6e?%FC|dEEu2I4nlIt3V(W4j3rDA9$nnp z7+UOQ*tiVuxR;vG!yD{bi?d*S;uzj>|0jqwAXvi0$isW>Q?ic^N?y?^$b}PPAKu;1 zTAT&r6E#5m1mZIgEMem7AEsCvHBO!b8^LG2#5+?Tj zFvZ$%{ULKt>Tv))$Xc8Q;}g|E`~_kc2$nGM*x|j_h8tIxV`WQEEMWp;I*_(<^8<4*Ci7h8AZu|Jj8A+FP5HXxshEQ-VWQv5S6Lfwp68)7GS5## z=~#=iV0;3;B=$83sSit-IKO8jYs2{~nR`<6;%H^o;w%`S_z8q~(Y^4AEMWq^(%Nu- zSLU9KMDgvcg{wh2qsAu=fH(-^Vh}80;^!e9tqphmkUSPCm0Y7(i?dRELUUyX%FLp3 zF~NB=h`D>}!Puu*Wpq1br1u_K&a~h>9o*x9=>Prg;om3w1Z(+GlVW2#Z1jW;mN3D2 zGsfHtLZb9KMhH*Ki~f|T;!_b-`~>cbG=5jIQZ!z;?ql7(3>Cc50Xh0LK#T;znJ7#= zbl+pa^X*>@hUUmBdIi}*Obkhm2v)~l z3cfSQBr^T+tmsw{TXE0HS{frBJK8<;iJyDt1jCOa9|r_Wn2_TyTfH2ND<(Ed-JO$| z00K|2(y`}q-shLPycwy7PlP>k64UXN?5z}`=VGGQtB(fd#>@&Td?Rhutk=lAUyo!3 zlTdS(Fj45KK{och4<6*&yYsm20n9kyBv=2pwHKkTb#f8$mZ5ifOJ0FUIHsMWlH7#rYI|Jw}afW7~bo z**|^QHzfLQb=J~)NUnsoTju-QnRt3yH(Qcj-P(j#KHb?K zS6h_&_L;U-oJUEgfBIOh{nPyZ_iN5Jm>4#=m!;q8C~vuOf3D_Cuojol>c_PQKX~9S zd#)}$?@5=v?A~r(eoM+ks?WKnw6;R1jRBX*taX33RB zjQL?$!i3HOo70ps;`*Ek*3vPZIivI&3i4F~{nkN;X`Rz~p6RPWT)mIhLnKUa)}~)` zEs3m_v>x(R0WEFjRgEP~XiK|q55P*gR7|iIm)0*8OPJ8HAYV!-m|!h#L!UUj)8!)0 zs@gN;tEgTXdj2F|$a8@&_1kSPmN>gJ200gIDwq z%C5`}dOUeQB9}kDFNnPcqUmWjg{+0RXS?GeG1NY>6NJ>`jZ<$5S;EAaN`rz%7bk+# zAG`)O`nPjExEpV!U@gw`@`-^U#Kvj4j|VJa;%M{xSUF5-7nHJ^OyO=@EQ4?9Cwi z^ZBr`eRY-C|3JLIW{#I1g{W)WAChC>6YD@ELHr1UB}~kCp=EIQh&91|Gk%AShO;lW z-sk*3_DH@#`n;USNT-al6P;=ac31ez4JR`OWM7Zz_FF%U& zn0%sUiim+=2@^lAx*)jh%C~~K@6~~gtNz#%ij8`+FZS}IIFHFEE&!1L(Fg=fnE2xT zU$Pgz|5mWLL37x6XU&{YJoV<)RlNKt&SUb44?&2HO(0mp#Nu&tvUdk>2j@P}1vVyN zCJC|azQD_m;yfmwXaQnvieL#7T{c{nU2Npr!Lfb4U?YZ^B*cB~8f4^0$xgH6MEOK} z5OOu>1%f5I^Dl%P&zbUe@Zr4=!bX_;ctQ!*;yfmwXa_<|#S$jkZ@4TszaCFxCJC_x zZN*xg$K(^YgOJw!1O!W%STt@;q{m3L_T`~>?OPIK(ZU036^#j+zq!1@z z)Uy`nF=Y~RH7EswB}^PE{%9iqIw&?$gqI(s_T+l*6AyuqmCQq!?<`?rbfrOw{Oh^Q zBx&8j@ItJm?It-Kg{KCIIL?{HidtoqUfcqrStWMIdmL~QKS&K7aAhp=PiLH>Yv`o z%S7UgA)ojagse+K5G-NhnHSDUl=*d8aQM=9U}Jdc`nDcpm+uZ(i!+9NVkijdkI6#N zxtRELOrgY%YDH?!5VAsTg?(CjtoB|F}=fr z;G~}xKr?cIE_P<3>P^rddvJkj@h}GaOC*aOXdf1%(i`kB~e04XiUG8x?3CDI`2$Jk4w&vM3SHX_bWj( z|Hmh|R8c}pi1z`wchH$)5=%yzT5>#p!z(Aq+G0Xu+NC5>LQ9CdZRC(ipZ`2KC*TYx zIeu%(EB4zZY}+ST5+$^R9+6N&GPUG*ch6S>IcD2F!ICJUCG^@VPirn&0&?6dcqNEt ziTMPVDoSVxk#Cpk^Rk_G=4lT~9)le3D)ves$86gtSP~_)gvKmi=EiRQ?ZuNi5+#~j zjvqdVZ(87(ZTkdEqJ);vn^8%fQ4*Cd#}B_ZFOXxl?Gr4C5?VsfGbGhBNZh;}?_V@8 zkYl#(6D)}mT0;2UE-pK>6Z(ZS6y*5%N%I29R$$vc!ICJUCB%0DhPs^50r(OPXDGPw_mn)&MBo@$@$>q%5`5(tgj}89!PS5zOuT*XHHjk| z=L8eS+h?gDJ_oTVLa-KpL&caKxZ)HaTQPPW2#%HKn0B^jOc&Vb3>%l=io+5nI6B^# zy|8f{#6s9$g0(na+?dj^A#3WdL2z4fHV2;x(YUbjU({nkH{S*me!f9l*ysiuLnHNI zEp8EGru|gUt`kq5dLY5pIm(w?8t*&>}*0>Kg{>Ri|`QSXvj!8;EP!}{tQtn^<2 zF&}qDtff)25_{|u--3{x?TsKxMNue;%eL#u@*=F`ox1E zWDPeKdwncnV))}N5)a-oBXDuZ4}g%n)QY$(VlA~NkzhU{rCJ2yb?kDogo(EfHA_@z z`Eqdh^RcMM9@Jb~cQ)>dSc{{7ed0q9vcvK|2$nFhZtD$+S36D*O5P`N$ZzAW=zS2f zkHuOX{p%C2fsi@483aq1IM||Y;?RI;LEE+R?SZPeD>?{b)9-si*5c@2pJ)tX2Z#?r zu!M=l>n=?!o%vEQVf7T)D25%0y&$S#myoqM`qw9lfY_fRSi;2iRc9qS9he%ls6HJw z*8RRG?_^R6i=%&i;$09&KuiU} z5+=}w+4=pk8#77z;|25}YjO0iPwWNJ3q*MAqWy zU!TB!V)!SB(?PI=iEXRS3i9X2e=zrc0C6?`Wi5{W^@%f~DYLc?{$&XhOV(W)l3>{$d$7=p2V@lBMvnS@~G>=QEgmVsEf^6>;qm}ohnc~Ec2 zjNql)$6%gU!^dV@VeON({?@R_r2awAS#yF47xoNUi(^9Y#aj^4Rs%t>gbB81%!n(3 z*s7;0##+38YseCgr{-v5yw@2vONhI>WzB4ONe`e zle$|QXLR0~$MJ%4{Oiqg1BozX+djdPD4`|9mw{66p+6O0CgmtbIqvev+(05F*|txx zBuZ!r@%1{q>0SDK^YEMm$5YGk4S3&@d})Dg`vgm(gq9F-GR{W4!LXb_35m^?Dy=a6^m&0Cvu&SXNtDnMrh71sK2P_pMBqwqR;e*B zkYjCi7h9VeC6-`Gl+Y5UM`9dfH>M*|B7Ws~Lc4iEH2T*kbX-YEqJ)+(JqP15vvfvD zOuHOU7&0%&jBiiPK}&F{qJ)+(?HS^-PpzIo;@IW*vKQwCa?G}Uf+bNxOPKa>arnfT zdN_%+m*a;Q&kN+3ZTkdEqJ)+ZcV5`n#q@|{*EYtH{c`;6s(FFrg0O9$U`dqF5*o9! zZw{U@nfM!#uP(?nO24PTwta#nQ9?^7GaL~kbBD%m>(DCT^%bv!_yVYk*}|<03vx`tAJxqIUbTnCEkX3`nA_y0b)s~Rsl#RO|{+#>c9S2oI#dfWhldx|4R{I)vd$eYWBcrQ|OCO9Sp(YQxe+EMac zWR$QLM|ik7C^pW*Q4}x!|f}Mw8V-WjyW;J1HOcoP_HiAkKgBKCs*5%ctd0)GQlxA#*EMV&CZV(VS~@bS{!j>Or7KB*Afpm3-#cb zRE{0xGZ{1V@;mL=9T>5}1V@D$^LM`^)uqq-MF`g7Szt`7(yvz&pZFgTTwadk@k=#l zUpssKsEvBCgb9w(F=qC$@k_^6}AWON1wBV3BRpotsMQj^v5l*!31mZb=TJ1 zdLOAddupDk+?zhZ5+->6+7UWRm|!h`ln7G|^|<#=e_XK^@5wqFO0a|p-i^*L)n#Za zCRoegbv{t&BzrZu68*tfVUF_Wt2UmDei^q!6%Z_8g5&oQ?{oN5>q{<;5Uj=PYeb90 z&$Kh@IuI;jg6F?6kM;S+t}<#w2-cG8RsOnt(63M0mF3kSSi%IagN>QrsHrVgUW8yR zzTYwCz6-Wm8`8QgVS;1W5a0gzXDh^0x5L4y|j%buER*= zbFr3`DnHU`07Hy>rQ|T zCRmI2{fxPL?8q822YX-+vV;kaLc nwtDu_UMpnnQx$6;CRj^s=kJRaZ&uc}?k%V}OPJukG3NgPArF~l literal 0 HcmV?d00001 diff --git a/data/urdf/KR5/meshes/elbow.STL b/data/urdf/KR5/meshes/elbow.STL new file mode 100644 index 0000000000000000000000000000000000000000..5e3da87997068a4c4de01a9fe1caebcac6679789 GIT binary patch literal 48284 zcmb`Qd6-ny^|g=UfFK%B6h(~+j)2Of(eCO};~X3#!7)GL1d1AmAmRWeG>V`SP)rDD z5JVACW+&=aVH|>>Mg!s;6~!oE6eDV!_|`h7cJ(^9s!aa)`gs!1!`|;*XTIm|eQ&pO z|9^j;Zl>4EWyfzgCjYCg9!mD<+Pq=ZySeG@5V-3BQda;HLE&9YQ_q9@s5^RTQmo-qxWwnLuUF&J3V?r%TaAd6)Y7^?Eqv_nL zqXuQSX>4pDOAF`dgiG5r=!~&4|J}JyK&%+vSRkPmE88y7w9bv_Fe|sadGT7*GcPL# zjc+&UnO(a{&!W|eUTK1TXsgS)T7-I8IcS`ZR=;u7Ag`eoE3+LOS=+~)GXm|HVqUzK zdRaMW9NpMh_(#ylsm03F&^7Oz5YD`KE%mZ;(0B#?)Ou6jS2?vw^Xw=$$%!}8x9V2Lz_L2s!L3;6Sz-!UV_CYHLjgQe!>t(;9SDN6JY!7zM2x{oH z)XU02Bfb0ZTC|uK>&_l&x~tV9)XU0218rzP&C2@~uSJV_QG+9E_g&|V;J#~KB-G2w zL4*4`dYBr1zv8vh1m|&6JB*-)UQ4~K95iJ2@%xpv!@SrIuC%7{5W??QMyQvSg9g?{ z5i_3mD8FCXc$gP8xMSFian1;=kKN6S*HSMl2aVDWhk5UuTC8mCu=7fJPplxQXI@s0 z`l`HN*=#p2YOvp$P8p@Xsvy+M%0Z)a$MJ+(tV|7#Y}47N7NK5N4jQF9r`J%6m8roQ z+SCpsY+g~F*HSMl2aVE-@)~NfGBvm!t*6Uph6+NxtQ<6K_u-hU#mdyM9fM{1*-tLJ zcE5Y_?;P6Mw`2Cir}KCIe6%kc5j0BvIi3^MLJgb8dL_F){~K#4!CtU+#Db0ElTK)QM$bUPcEy3dR}$IS(M;xUwFZy|3au2wVO_TO>NI* zIWy9G32UNyP5$g%wb))lf*Q6T*Cy0US946T7x^s1>uL>I=JQ9?S2@;7ElOx@V+|$L zi)}LPm{5xnIyLK(o=EZTc+QuzcixS+GjP^uXLkacb>Z(3>)uIIVn5eJH8cL`a*SxK?xE*Ry zf_qG~2C0Gn<+4hs7qxBudkqr!X^JOuq?FJ-Civ1lO{kZyn=(NttClpuQ${pPyoM4i zn-@pZb`0nCYW8lz6Y^KxE^GMxOONE6&)li7pu@G9)sr_(SRQ|6zfAMq!}5!k>{fWD zMfZ$zn}ApgqE+|H8q}i1c_Ry+7{AdTARay7X0P$;hM^7PryT4xx=$FMQN3sSY~qRD zQ|nTMT9i<2=gwXFSbhy^^}@!D4HsN+-(1#x&Eydo)#Jaj9p{g1fX22jJeFt6lM-PT zB~;tFUoL&Dp2U+N2244)o*Hb2>P_skNj$If9{9H}tD(;CM{Me_P>t z?5jP{9&OVrs6UArXpeL6!IK&!)uM#9&$*W|pEyhAE_p298S{x67h|2Q#QbHs#j8`h zorrZojhR>{&b?G3CW26l61_3YNsw+Lpi!@0rgsPCb4*yRCV^0k5~jTzvmVc!n1O7^ zEtrw&^$_MS+c66BIVRSZh;bm)qQq0!b$mN|4}->c*r%v57IRp=MsS~k#wyI`nBYFe z@fZj~ElP~WK1Gd-FzdPR=KM1hOQ#+@KePSBN0VPZc6Wy5)?H>Mbvump<=3B`lyvGj z5_30Ati_X1hY@QcFVf%NaAoq~r5{xx%t9}_F3Y^q!d*sGAy|`%qu%ivtl{uAFZ=Qj zvy$ZBJ)f*Xq-({Rs9w~LoLa1GglR{F?<=jld6Bk0j0mq`7J4aByB$iH7ipH?zhqXG zmf!GtraXdkXLa>nBv`K9SL}CsacnrwR{rlJsKl)cPW3Y;YPs(#9dq-d2Fo1TO2RDW zWi!#*_v3_lk!G1Qrjjs=dD+Zw>Z_feY?GZjqIt5_ohN5?S3CXIE}6Z$HZQDNenPa* zJNNFQHrcO-HBah5=zgxmstucYdc?8|QLD=if30CLh*wwkiwO17yANVkAWmp(o;(dg zElNBx`>}e~@cc)wheqpjuFLkgv6GK#=$XpO1N*o3=eefmS|#);wHiU%xflChm;G#N zrvm#~&xTf}m(k%2r-WLn5kce6M;@R3?yGi1YUml)%GQpi^R5zhU8+|jg2wKLPHMRS zxhuVfp4F{PFQY>{lu%1GB51Jw*h#&HK66-^UPkMA*AqFlR3n1Mj)zVvOb_kI>9doS z>1A}#P(m%$h@dh3$m5Ia!g%EL8PLk~GCF7|p_Xby&^W2_y5i4H+ne($r_ZuhrkBw{ zLkYE1BbqdNoVK@LA0%uYSeaf%H)$B5mTE-Mn25gG`0IB5e#@3yoXX194%2o{3A--U zs}VutG>rM(&t2&?ID!^$vogJm4((7vE!Bvi;iqot+`yS=8dj#4(LqBAwNxX5MqjMK zyGrfgin6}4GQErr8cL|88WA*Z$6nH^G#=a;tlzCnFQbEo5^AYN1daC1LneIbMm@7D zPF(*iW2emR;`O;`*km#zw+${)ljc71D{D2Z~J-D ze&5fau@b}t5E&3^QG(@(b!(Dkdp-|hy9?%KZp1z6S1X5P_4(}mNpEll0xCTJXVd1J$|(0HQ5py)oR_deBj?*7Xf8}7cL zdGa?9YEk08{^R_ev(v>lK;uzpjD*GmDMG!phR!{A!j}TuQL;W-ZJU`-M^ABOCA8RFNnQBs6~lZEicYraL^`&XF9gT zELjBN01&&T2=yAc+2H&o|NOS3vERBeg+ssVTHN}yeWH1#qp360xhFpyQ|SL~*Wx~B z?i0;jB___gFIoAouac?TeTBYy7sMbC+oTBf(jIZ{_>aaEeh%WhGxmx4N(t=+e_AT+ zhw)f}vya9|X72HLzD3Vwh4p=gL=he5u08yX#5qBVt zr4}XZ=`}o`@Azb!;?`(+Yn*qrceO_~=HT2R79}jIwzNg}q&A^m79;z`)VdU*wNkxzQA<8;--$>| ztf3Yq;&_R+TnY7xBSk{w5Yh7LeAa&ft+d#JUdj9C>@2F+(kNF20W6$e)uKckhm%@4 zCDbd94l1GjZeC}OZ1^9?TnW>w96=oe^|CgVXGyuQjNsT>ROMHQ2HV(hhK5#HU#Ue2 zU1_xm^@`UZm~ySuqOmO1uC1YjT`5Go0u#nuuccmA!xlb%rG)mP&9VP|)heOdQ9E)r z9*j+@m-Vzoyhw%TD77e2yB#){7+1Gh$@sU<>8MuGY*)hel@QquOy!DFFWb99oLULB z*iOWl?*CS+YD9?ds)k<6%JkAbrgqEEz>dk?hxZI4xK?69ElSwl74A_|tDIRl?eMI^f6@7h(=Joj1Kp~iT&z)ygflIT<>bzFYJ{tTFXef_Ox?PfMC4+ z91vMww%89E zJo7w*GebX|fvUyyd6N0l`kOM79{G0?vH&Fh17b%IYSEL-@()IM;^KGeF%wCA6Evcj zzUmoq$2;})O|^nXMlDLHHqO*I9}a`Yrg*Bb6B%;_Rx9Qvb{jF&*J`zU0vbGnZjSNj z0YWWGsJ3%Y;heh{h((AJ>MT*c*4Gd48q?Nqj^6znh;gXZZ6MU5glgjrs!^k-9`$n9 zhCVx8S8TWc+dhtO5p#>Z^WUxP*HiAWm%A2DD-mX4>{ZJaDfSv2Y7yo|4J!wYI_HWD z=AG?pWfp2^*<#CKmDeK7iyBrA8Ux!OQGEK=j$Xqo)X=iUmYutKRLgs75#~h=D+i5v zV=gP!?>wuZ7K>9`{-Y^QJ!(|Tj;=a^;5@Dv$lVg+Gd)Ua~U81}cWg#kNV=Lxguby?gtQ<6M z`dilq(=dx(mu1UrIR}lYwFvW~hLy{GmBkwL?J$d8mu2R^!g!EDUsWZ{iyBrA8W_PW z)}Yrgi(Z#y%bu0jU{%7rsA1)x@yM9VvIp!u%gWaXeynkAkvi(Z#y&Ns_imgiLkVP4d*a?q%CS2HhaaNRKH9f&sg zGG#fww&1mxaoecV=6=Rl?9C#D{CDTBY_o26Bh*6Lh&XaL@wrQT{s%GMPoSZMdTHD* z)XMgDC9KTIrbaw#6Y8byiwQmTnHSH7dVY)vwJ2fb&{u&8Pes)TdTGux)=-OHSKH)? zTuG<=HZG&GmXBnabl2uH^C4PmDqM$ZNfS1jP5va9W8oWryq3m#nHS;PhLsv>Q9{Q* z)>z;9(!AA|L|wa;zV4RasnpQATb7hwY+vT|lbt-F=uy`h_m*%Eo4V{V1 zE;47%>*^ef3AHF;`OnH)DWP6ED=Rf@zA9n)&*~aRsF#kcb9XK2TcA?ECkOj%hGpM0 z=P}`wmy-)m+CDjZ4l{9I{k3o5s5Y0)zZHa9l!&t#e;_gNcRg-T5$g4`RilzCrn=;T zyS9MF2O#4Ak?CS_MvloF78{Hx%G&tqf>->#l5?r)lG#t*L2SIc;tYn9je#u zh$YFK_RI6v{_rX8Y6*xLAPxbc7A1}!KQ8&@p|kVLMtlciTJIf;Ke=I-?Ail+h1>*5u z*+SirYnfy5ePw;3HPpZP?hrNhff=WcH%>t~z|;$I-ff#?B3 zElRL#edyf4-+z&`>@=h}rrGX2G&`v^j5Am-foK6@`YGKWdE?}4vZme@M*O}Zqh3G! zWOB0LiLaCKIldJ(wxrSdscpNfMG4h&ZViYnpz(E|TX$1Jy{sJi>KG7Pf;e~ISv~Z+ znu*i)Id@8l_-xR)sO3t;dCrlgb_}`6&DU$GSA2RsvqUWVN5}cBJF6@=4p5}C%%Y$Gn{A>_vQ9`wy`%mdT{jocoUa)sL zM_<`5Q9aE~IrlmUM(CG-P>T|(?OZRst4-pk-7hQHyPOYpxHeHe&7L{;m(n*4uXekv zpcW-m8@njpIp@~{?`{}cu(w{iOc%07~yylWfAk?CSYUA4_tR&8>`!EwNAI0^ddX{wxnd-lkzA?e-EvQ8a z)pl-JDT8${*C4LVG3Pp0JRF~S?4r#}#N{B=qJ(NY$Js#*ti_}o z<}5Y1@2Xy$Q8eNn5Nc6EwUNicx}e4^d@J+OHWCG*419kQkeev?k~WPcE9Q9{p; z*hN7c0*#YXgnB*Pm%fyCxhUsZM{jm2DK=m zJ>uM?+;4qUd*QPAg}o1WJhR7(&*#@~vss2^=4e@NF=LMZ_ZGj+BhRUXTGE8i@Ot9F z%`Wj86R&u(paje2HKo}Mud(f_bD*JwTG9mRK(uPz&uhGL!CM6-ST?U6cbV)pPPyeu z1gMozOPU}Zh!wm3#%o+t{C7bKmd)#5f4;+O^!exO3!PI!Eop*uAm01o9Iw&-v9$#y zST?W458dcBRt&rcXE-I)k|sz80{f`@9&zfA`3CbAXZyI}s%hjsK~I(Jv!dW>h`AYe0?n;oS@|_cUQ%8jZ$y;4Q;zZfu_Hj4ydKxBbezvwh21 zE3K__dxPNnqTk?49@VgOB3Eim90-E%A%6%$ElSu)mU|4o83l0+PT_l_R!XRs)|Tz& zPsqONX?urJgMB-$x_?=o;}nmF#R2Tx&i58{w%e7$y9T1+)S`s0$KY=oN~l-Ob~v>t z(WXVdJT|e066&R+85343KAC9$SdWBf9BsK;l+c+UYbc>!@w*?Yp%x`{1;-jnsF!Jn zH&RqXElTK46l*A0d+di*j6BBCTm@C0D*CT7y^j#`< z0LxUf%*=-EE2kgaBX2uHOsJRAwy#ubXztGT66$HbHrAjzqXYD^cP3b_T`RMs3DWk? zM5P8>XoS6Gp>IIMgtnGhOTLjnx^~OWLN6tlW3?Q8S;Oa@l`t>T)^F8&*V>_k<<)hC%gfTs@?X{_%L&Kru&i#HVEZi7;E5dTM=#ajI~u&M(v|Jdnkd1yNGiX5 z)oZbAUM$;utJE+{n$UNO$}RWpP{O=O+dQt+uo-6>oEcWD>T6JEyS+0*!rpDE)KJ2_ zNZ6c?2tVdF8|Y>4Hn41~IU;<^&5|bceTI0T6|;n5Uc)T(Qo`O^sH~L|=0)0O zsK2zsn*&+?7ED@nUfF1BrZFbeLfVMG{B>@J6)E4{rW-q zWB-p|BAxetmlg(Gx_@@@^aHYAT`?{>Xy4iSHKV`FXnsiZMj*bsq|kHF{@L?WgnGpq z(?MJTVs{W~Q6kQHEd((L#7-$fy|jJK{q)J*3!fCO^QYt^T0ff%?e}uN+31|lt5_z6 zSpdt>G!Z+EY%@nKn!(a5H4&|Uwb2~4D53r4+^(fswYvAUu1cs^+lAwj`%jylAOF^` zap&w<+`X_-@w)8cSAR2GElTJ(IoB7&2DH3!W#gZfP%kTwm`9C$kA9%g@9}-Iw|w5I zsI^jhS&J8w`@h&OX?x6>AhIB?0WlDST9i2Q4=uG&5M|u6ilC;j0~!J@#iFrw@qsAU*-17A3T{c)JY*vzAY$2=&t1hUXiutJQc0 z;dL!1q&3tWQg~X~wEI>)`NX0YCA79!gWvQhQe(fZV?w=H&b529)bgXQnpOB)$8N=A z$L>}<=gq0f_7A+D4BR`Lsg?x_nV-)=%mr~siqQN}tnn#`*&s3?)S`su+nlTKi?>%h zbSv&NAtuyIdjt{sizgJiywSZlDzit_j@KG~oh);!lYwrhs7=n@0^(Q@SAo#hDiKFN zW`o!R#P}4UUK%^W_qE7>yn?5@F8IdpgJ0i}Sv+h}a^UIt{Op#)GyFY}S3OtA_t>k^ zm%lvpVLUs(i1(?-f*6M{5B2#>pG7o#65iQ<90cCkE~v$x2O06yD>=6q8vg__Bc-9l zC8IC*wOaVQmPsI1gP55j)Jxmv+!AQ;t@|k;)S`s;f^#kKT)P28M||U_URtYZ(|h|` ztvQc#?k;1Zo!%>NV$gExpEo(U(Jm@r9#7Yz;y!N@#}0x!>b$`@=!t?fZyO zuZx~5)N_tK)N(j9_?tp50)cN|i)v9qGc?Yfj;{v#gLtIFpombfWltRDHG2Q*W@zjV z;yw@w2(>7o85(4M@b$xV5cqx~BGijH7Pe!-??yv|--cfe0^f!g)siL{BVUC$w%14o zmo$`M*}T4g;xPYvSwlOZkvve+P>T|pp>ggEG0n>8SKH`oD$T9mNN26IUMOQhn% zAWp&8PD-fP6IgrHD1RSSqLhnd(aoOf0%E#!F`_{BR%_;b)V z`;^W;-FWu-^S#GpXC1iR!S8*)OHt1ZdP0hcx{r^^cH8#6`Fq^IOHt1_N^2a}x!xeQ z+4`&=n}AS@60ycEAb6%eE=8ypufzys$Y%5bam%SU&fmC1m_-Tg1^hM=5bGvQ>(MDi zsMmzagS^IpLtjH*g`W^>*yEjxyk+2@HqW$Pah5ML%E@@C#zn(#RVAr}dOh>{5Krve z_&8>J_zAHe_0rgDZ9*+dFe1!ah1?x9au%^wLcN-g9^r}Qefi~N_zAUAixP}LQzK;J zK;%qA3H7@8Pd9~H={LN7+|{B4`92>wGhB{x?@t zixL*svMhj6F`-_yYo!(?SZ1^>(#Tn@n9Z>4f_Z6%F4X8>h>tOAsn<=ngHg2*7d`0j z!xywiRBdUAFpCnGPdXv<{vSr>+y1%>?l}DUD>QzJr~x&MP_MzC_ALK2iWhgy{QX6d6o zX4&)l>rxs@sF(fwk^AtsAs)Has^sPKhGZAlZ9H$gaoMEPnG^Es*Vbn=%JtspF3Ip- z;g~3mN;`|-z@`G=@JpcZbMi57ph}$OYGgmE2 zXoMASq?Cv&M?61A3H9PL)wDrpi&92eXA>u&OgsZQ+Dv4&cd*x|JBlzM8yr#n{3 zYNdpF>2snd2>EuXMTy*1`jjdfIVIG~w8OKr5Kb*hnBK(+pSHt~uT@S7^|C$;F#y$2 zixSpvd|HY%lu$35Jt3B%8fsC(#{b%@7~c&)p&d%7mquQ^f6m53ElTu%Fhp_cj!XTP zw44&^rSYIxLoG@ihHEo2aVE4vD@wJ>DWP5(*NQdNqQo%t5jC#GT8uT6P%n+o#Tsf+ zVlBp+8fRlI#u`efm&O@m4YepS5ObCqZLt<(4JFiz_h1qs_6jCvy{ndL#PwK!4JwJ5>3IOz~?Z#%b5aeol+=T43Y_0pXPc{LFE2fAgR2cZ@v7~iJ` zzdga5vRz&)%mvY9X}^e2FWrfpyT0>lh4HA>2_V#>1oITsco5%J;H$=S8w+=WnAu`b zM5veUM9wV$@f#4+L8wIu=3A)2Z-Jbf{>!<^c_0Qa9ug7ir8^P+njnayKwJ$%Eop)p zAs+>e%+VzcC0I5u-HE(LhP9%GT9jb^tEnBgpWE1Q4hZ&@66&Qp5x%_ZoyfVL zf#`}_EdikxC74&GMpz$MQCVA2N~o9aM1Bos4}b>Opjwn*ewZ2|AN6MLWKZmhm8FDw z=}v^-3Jl^dXlw*RElM!YO^uL`s$1GGyD^9tv9kCc04>ZSX%sIe4hL}~h&dqCqC_0) zBQXlZtQ4VMT3hEbAZCDg283Fa&?vWa$AXxJF(02I)Ju0%e3gPs!y+Ng$2|p%x`HQXDi$ zKqI4GrpG*2CBa%jBcm22Oglu+u_O4Fqpup&%leIZu9#q7v3Jo|4Qf%s`Y_}TWG4FG zRLK6}b#0C@&lM9#W6ZxtJMQfKT7z1Y(42*Hf5-ah3!)3wyT*{!OJk(?@&&|h4|dD! z2|_JOs2-yqCue^Gjqm5ggnDUI)wy*bI38HFS+yu(D>!7yxce-g-YxSn{%iXOzw^?# zXiU5T&jt5&%kaNyQ9@&~_}vNcJOj0Iug8RXX>FZ5815C_fdmN^iFT9nYpE#lyqvzw!@ z9>5&7I~o5LoyPr?cJ7CB8XGn|)Gbp0p%x|L=-}n&H#Q7Ltp=nB^@?ltJyz?-s1^4V zyNC0y@Ud*MP_3feH!IfZR9p_ z-`Em!_dF14Q9|{?d3ORdaNhObT2g~+P-E|QE~U0}J#klNtw^Xv3Dv{5$T%yE1hE!t zQN8R;O}*_TpMbdw;(ib~Wn|T&gq`}sUh+DKjv!u55$dJUX#5TtoRTJk=!n&8ksC%D zH3F&8Vf^(v5PO373VWhnOEqF*Er|DU|7Z>kwJ5>22-xf44TzUPEQ%MRoVauP@t6)m zElTiR6KaHaSg>0C^WYWOA(T)rjYj%2Ly=DtJTs_83BEH!jqvskHAozU^{#|^nRbYB zk~lGFBx+H@^ujwu*b$27g2-csP(r<|5Ap1PC@1@h&r#^Bf?AZYehcqLam%Gkm9Uu~o()Qo z3IDFa%(Ld;?=DTuFMqyQ{T=rX_vIxkC)HoF{g%GG`ie#MPlk8^Uvqi zYrytf*7M)LykZf0H~fU`t6G$>D=m5c`B=kQO;)U&l(!nLeZE)zxY^J7TD^McZTPZS zHSAhiE7nByVnQueCZXE33H7oXvJYcIElSjGhZ5>#L-evA6bXMXg&JNS(AGThZhOv?JdGs`mXqGb(F=;>97>p^)MSE)^?m!45$LM=*c zy=7ak(P3NuHK_0tGFVEem!3FdLM=*+`e><-$$Y!jEh!Bp)JxBgv4&cdSla4DuQ6cp zxRizx>J^_XwdHE5Mr^a?_@I$1Wg2|mfFormWR~fr=f}7mYB4<$>spz;GV+|$L z%jQBj^{Iwhl(6w{iM1GOD4||9r^~0loQ;QCl(2bxE!JYJp@e$b+6<9xZHHQvu=RK? z)?%!ognHQ?6C(7gp%x`!Ylp7A5RFSFt{v z66$4V)bctnYp6vDJC|0hbEkxQSvyRP4JEpSeuNc`i|l64r0!b4gi43H7qMPKR78#Z{2f8uY~s6`2Tjt)=TBo1D<<-KV_y;%0`@XzP`%R_7j z|8|X9l(6UM@U%_h5NMB!=(gfpI z7Ge2u!Xhlx2t=t?Ikcl-8s=r!wKj!Fk+dTs)XRD#5T)_R@h{P+MF|_55R)m5N5?dw zUN*9UD9x)JW=T;kO4u9=(ZSNZ>X;_f%VuaGO6w!XzsRN*C2XyP=%B2qh)^$EX@TIX z<#_XNxT!@6i~EIImDc&xG@)L${sZy%4I8}1D)g0Fl(4v8=v@*&!}>@Q>cukWRe1!n zYzIeBElOzA5Wn#qf2*jp1|vefSf)mpSNJPtUW0$bO)W}bPW#wvnC-O)^cDbP)nMy8uItI_xBp3FfJO6V3}S#d8>9zs3lEU4e|TiF`w9u4VWz& zRbiQ4Jb9~jOsFMISPk))VmBM=HEtdOt zwMrAz2+syGce6GVdD^zw&a!Gpb2qD&G(nBVY$m;7hm$ywVO7$vvehh^2qZ)g%iEos7Q_*nQaN_*nV&H86;hhwzgc2Sm9+c_oF zk|wATV)`dHhQ0mmqXuPdr)JiIWqPr!+RiDVmNY>+Qg++^x|%y z+A*P)G+{OLJDk_ReXv2J5iHYd2F6~sV?r%y!fJ@WiG=yY@mP($U85>2(~G;aYR80H z(uCE}-*LRg6}U%fbckho@jj^9F`%)D}w}WRN8$q6_Y?iRB+T}5KB-D~7s1ah8 zxDR>_p5bgJGAe7con_T7&s~4&Q%jnlMu@%Q_uP98{;qplQ9R??s%2TV%WKe)P)nMi z25act8(}YT-{DMZI|I+^w)?QG+A*P)G~qQ+L+73ed!k!_GpX%xeCA-8UM#D2OsFMI zkPb2ZzhLcg?tX@ImhIGhGO@b>%c_kr7eXy*!fNQ;n4$h2ZNUp z2|cS@%%Sw&l0Th=n2faC*|j*%Rzr(fvq!=cJ&2sOLpAi=u6l8;)S?7W&eRAeWT{n7 z3H8!mk2Tbygr3N26Y8a76B9Of**`Wj*l#x9%6$bao{6+5VRNiveK@_Adg(a%TIEc` z;=7DGA%5j|IL5E^eigUFyf_>5?ri@aVq|QDX{bdBz3*1n;I-7NX03A2@N<-eK0DjL zSI%9vD4|cq6}2j_1NG859TPSa*}LY&JF;n)`wCbXbG0a8dg06vR4NJe(l*7lvf0ik zpv`vPU$wR|p%x`CCG^Z#n@}(9H&5hj4O%;R@3UT*fzuz>rr#f{?j>c561I1Rh!<4K8hS1D z()}^6m9?B_25UL*eOg;jP{z+hwJ2d@6XI8asU*}(+Z1cq{Nb6(<`p9oHbX-OOEuJ@ ngpEgt6tNN34kgq}dnB%vT9mNy$693k#{YztE1_Q6Z_fQctyv37 literal 0 HcmV?d00001 diff --git a/data/urdf/KR5/meshes/forearm.STL b/data/urdf/KR5/meshes/forearm.STL new file mode 100644 index 0000000000000000000000000000000000000000..e97269275035c36bc4b51fd524583a1adb99489c GIT binary patch literal 74384 zcmb`Qd6-ni_5O>^4V_U0MA5haQG*c`apU&1QBe>QHELYY1h?RlxQ2*gq{UryCgL6x zP{3`1aRKwi>6vlY2)KhNE>S@QH13Kb`a5sceS6-z-A(exk0(#8=brPaxAuGI-m25i z{r~;(}%x*)4=ghg!Fym<~F1M%mI`!fa$;TJuefr+VM-z2DiN?pjYKk?q=2|Ch!;y+^@n;LP#ok-g?5WIv{VN? zH>^~4?VFfTixS#~)d}@FXt&V+<)cI`O2n=E&IgCpLFwI*=jTzwQ?C8Em>n5t1zZoK z#E2FWYSFgRG3Hz~LcNftwsW=Tb#H~nlRXd0t3?Uz&FX}DAq@@8H0Qp4=vc3DSeP%osR5&GOli6=0w)S`s0e9l!P)C*~7gt6PowMPF0U3P^e*8X2#l*NpocAYEhzVRShN73w2@%OB%jZYEhzk%~6l`eJ}U*&~`%!*@h(zON6$fMTzPf znwNU*YAwyai8a)sgw_c}p_N?CYg3D>=U+B(PP^xdNPj>7vL>b<`h1__oGoVhH8Caz z{MfPBZRTSMh_zl{yxsh{bA8&bC%9g&K?{g2XWW={o^_SioB8=ZNmUJ>7l?PRACt_w z?RKwm$2pD3y=#Z(D_^Pt)ZoRukk&d;d(EX%qO9g64dw+6dLeDseT!7oD7BRmTg|w! zh*nrLK`&^0aCK90!4 z&r9aX_N?BvV`eX8Hq~J z3-pCoJe^c-D_Y>CgpNdKB?^D5EvXGpkh6NNN?!j*cw+5)ONX33qoTg}7YMZ|p-;}i zpTt+o!kq;gdIxBCV0b!*UQDP(iRv0ks29^KrgX|^sD)|#J)m`}T&e-LbZ92AWJ;%I zeI|+twJ4!aYB90r2_wQ2%N?_uPI&jXK7HehyA}0WA|}+Lgg)VTqQL$*x5rjK-&0@Q zEg4h4jZc3y<KG>J)hI5uib0yZ$IibYP zUmxb_ZcTGTsS4CkLcO#_Vhyz@aZuNzg2r==nVKu1UfOPvM&X_gKl6EYZkk&hzod^( z_kFIhsDCX*gj0(W`Zrumun#bcSdtY}E-jYL55q!#s6`3Z2_=j*lu$4IOU4rgYUnIt zJ-S(oR-I8!ElRKrOMT9I6qHaeUBTmes6~mFp54*+4Mt^kLcR395)-=m=(=+IjX&`k zrCG~*IJGFD?*?KGCDdzH*Pv0h`V`or=v(#;MoIN?r4}VvKa97yR7$9qmM|vNq6F*L zXm^R~gnCu2xr@eYx_)3jmW^E#3iCrPTp2)cB^rOu(oD^jP%phd#`RE(5?m`Ad#%c7 zD4||_GQeFs*3dgL@A~knes@-j5*+R2rBXt@bRCOJr4}VPyUJTv3H9O(M&CHMUdJAF z-#>InYrFXyv~F_9es$-~8`ga3r~{ivt{mpmefs^PdFrnF)Ezzh^yZVU-OSqRkPbcS zRv7V9Bh;eAP3H`*yZhd=nwMN!YeX;8m~6xq8A81VZnTdlZaB8P5w&}cuKUP{wYqj{ z)qGcXKirq9+j_e+EA8APdyKAIY{V8us6~m_#{9}_Tso+uX`FP{-E~WiSlIAsi+auY z<1t=izy(`0$Haw3d~C#nMyN%J8$LPIYm9fxt#!NH{emYByZeO}^&0ua@m}NbJ{_B5 z;ul7sKR&$cg%-6aaoV&ay~doQo-~bO!>4uM7_sMBcekk5yC0178l7*LSB!}VjQGrm zlZ{Y|60=7g<26<^-E0~iyLQTdVZ@VrjBZh{UiY8oHBOsybulK|8-X6&W6#koYEj~q zLBI1F3%)qmG`h{-AdlAFvSW`H^=fK&y4P4Rr=}PawMKkv#0edGw5Uaimwp)GHTwSi zRa+BZ-M@<`j(K8OvwBVbSJ1#6ASM9|vBrMJ^^jxa$R9 zs=N_uQG#=Glv{2Zbyk`mOyhPdoqBOy>ABu6xtREq5ty|%7@-y=xW(SxElg+M!&WEsZ7tJ5W2a67^8f5Oz`yTP3)9fhw~@|~_~uzRm0rk8y_gOf zuUf7Dv;VnXLoG~0L*JL$T9OhgpDo-$FXW|OOqVoTQjLOIn1+VFFZCLpFpX{Kg}l^@ z>7ZdXZ%x~(pcbZ~p>J4yTY19Tsu#VGmwGWBG;EZ#+9*Mv7u3QuG~&0lLO6OMFZE(N z(g-6leM_DtkW<^c@KmFWP%ox~M%q^RqTx%0ykMah`=jlhJ_(E~dVxT@(TnMzaiz7> z%Kgvv8fsx08t7SmPjHR|#udGgmwGW>(x{_`T9}3gMkq_@H9Wy_1$E@5UQ7p#bVm7l zsD)|Y=h3$b5*SzXLSC4U>@}u?Mzz(4UeM5W#kq@CkIjGkV@(k~c;7|O$+5HIfQ$j73h(XWc>DB%f?0Ua7Va zC;a1!mYw<>$5NHPW{`j$zdATK`;_&jRU_yH4W>gq&Nwn@9eVuFy#_6sFVg(Vv1Wo^ z&|o?cKRxr**2VYEt5b{Si!{G-IM;0Ts7BBWIWZkHw%=-O>#1AblT(Z4i!{HBteKz} za$?#Og-Jgf-FoGSF)eD*e35SZ#xnbqt9n%<=!Kk^4jPvn{F~MV9oKJFi{^_ozfFaD zR3qqxoR|(8JLI-#?bzu+uR)9Ei!{HO1&wM1y`aH#(CC@Jvt`4r&-NO$Xue4Eo2UIH zY;9GIpcgcl4y6kJU+@~VXue4E>*AUTdO?HfKx~%3vySzkMe{|P-#^z(&Z+;L2zo(->7ZfrJkNPfi{^_ozZM&NZWeszrL@Tpcgcl4uste>UjU4Me{|PcRPRo=v|GV7c`g-8rANc z^nwQOiGc|JA9lTT+;mdHr?6XYxy7gPv{d}lbv_*vc(VM{i&q3MdyanRplbqc&)Q`~ z!JZrZt{2-a;=Po{vmJAaHPoU6p7bkgD4||>0%QqG8opF&QKEXy@l^chmdU;z&||xy zgiMz-ED?6S(4s_j4b4lv@HYedCe~1k5?Uwc#=+>M*of z-{Qs^&;I_hT;nFq#ilR*l3P%7S#I9kxjwzwM-Su{7gzXnOsGW(rt~lnQw*mFj_b_{|v=G}NNR{+~TqrBq6&*Iq*&Dz$V+Dx9%@md{ioOGuJ~X>Pgf_@Ytk?7&+W4IcNJ=`7A0Q(VMgxt(H+_} zO7+loKePLlrF^xt)k~#B-BIIXjT9^7H81tjHZ0d*-@@zf7hUda3wr5Y6XKd%T?+Y@ zmYZ{nKkedcc*l2lmHImFC8fsAjZCJTfN~jmwimecrN>>1^3|t>|#qdNSaD}{D zl+ZSeHIz^<%r5p*tf3YqD$Wl>3wiBxj91Pg?ajDUYEeR4IxdwG>V;Vl^@-h zhm-vmMS9^)I@0)}xMl(x$V&;nhX-x@+vj)j@5ffz9a_EcMF1N3qPS)P8pulteop}H z+-n^Nc#RG1J+FG<%LX*?MRCmpG?14P{4N68xlS_=@fy$1@6xJX_(B5>d{JC80S)A( z1i$ZqcJ7%DCwq-^k6Y-!C^BDsX+j!b6xU2Z19>UI?^K|jv(e!-Y_#|Z%#g+x z#d5;NRWB0IKwe7ldmCuyZe44v*VuFHgZ_&m^Tn4xr14E~%>*=%mlFEjFw*c}6g6L@ z@kMdX1T*9-IIZT~}^5ha0zqXb_R z*GxboOK_Bcw)0&Ng|XXiL6^Md%W;e^iWP_z>rW#A4dkT+M>}ZeZ0`9!$6Qn|&PRMv zTr&X;E$C=1$*ULF6?{=#GXV|cr36RajCdoZD{Ki zYm5D2s>hm#ePkfMw6-DvjV!@>gi^hl_IaJHyX-aWXj47*AgmpT9k-O^-Ovn+|urYy4y_ka2+{?olYQTSv^S5qC{LO zE5D!TR=QT*ZKis-j-0~&t1Ll_5^<@lRsC~`wQ{TOPg6ZyM^0fM83^l-J|t*SA}&>9 z`h4}0Jzwd*H`T*+(4s_KD$G4-VC?FSKh?u^;aHV6BVphbzeR45JVfzs)ITGhjK`2Ih(G>{UHnM^52Bm=c(a zo}fjExKu*q=!N@sRu4Ia`+1h2MTxjn_5^@>I6MKcws`(fJ=Q!tmw>QmhG`_AktJA< zP%3+p@fvuNVXxtdMfKQ&;YkLBJ^S<_0gWsXm#Qg@UAKoli*oc~H^1s}B;vYrSppha zA}$qX650xPH_jsL`By#8sBjhl#5z_F5?&)i#HEszAO7kR_mzCE`-0 zYodSJ;Hrj`VXDU!4%fpfn%)QVYEdFC)wyBMlKak{nz%aSl$q*rr4FahvIOdpB~;tF z{^R^T%3W_yn7qs2l$q-BjuTFwf#~r1-n~gcBTK}kGQ!_$LGW&gQmG#AoS_~dOk)}e z)Fw6th;}cn!A6Wt#St2f#%_y&d8O5hb%v#mslVzCaAZ!j!C*d_R zL|iIc8N3G85k%NmrJz{8H_bTZ=sd&H7QX^W= z7+m~`5o%H5z<&4p{a1YtZ?Jt!uN$%M9|jk<%M#)>;l*jWZDx#WKK-fg@!qHc^Tp1r zJCAz8=Zg~q@#z8U?gDOu=y%;ut^1ytQ`i*-PZBKez^R+(m`2%$?!2$x<-KUTZhrQ) z5o%GQszxCqWPe(`8y7`lskH36x4No^Q;QP1YZ`UHztC1nsF&`64(=q>qPv(iCr?z= zP(t@7S0~h~tgXs4FiLb}{BNaFf*Ro*ODI=)Td5aI7|xg|p%&I0r$qj@QYpb!59dEr zL-SHE_GUQEp@dpEN^l-Sa|-_KbG0bJ5gJZfsD={irE@cSL+|&uW4*$AD!i3P8vEPh z_gC^xzidZ53BJ<@?c7s#`k|fei2vc$4f1MvY~4Zr`}xFw49T%K!;bjcPCfhyo{n~Y zLM=+@Y-U@9)5R0kxhC0btH1lbwOtzjn*8gqY0(bjuneE66*EbwCk$WLoG^ZE3~z(job^cETuM-jR>LFpzb^E)v!$Ce)(D z(l?$SSh?m(s26s1RPGP$gD*$-kNT!^e}JGxiR%|_lem5dR_G5U)C>Dr5YeT)&voqT zsC;D8E0U-CK2(8FixSukgT3eF8cL|w8y&|bx9>f>0)cw`bIz0Af^qzE=a9yA?qZL7 zP%TP4IsEs@w=X@`rcnr7TYMjsSG}}^v4&cdnD+UoQz?rQmHU@ zxt2V$_U8lH2N-WWxe%91ElOPf^G;P-R|)mPD5>0oI>JXTdSW0)c=ge)7A25Vw8E9z zN(uGS(pImz5}3hUgR2wjrL7(lI*VrRw{h~_IfwXuu0EsGq6Av{fkTE@7$r)m7i#|B z*DEE^|0BnYte~NJsh6&mam};$53WQQ`IT26wdhKOc~g1yQ9`{iSJ={Vsq`L&wTtV# z-hE<1ElOZjDr>6(?jK61mzFTrP>T|n=au_h3H2(gxs?e23VEHW7*||zs?S=rD1k8@ zt%*UxG?Y*;U0qXW|DSjjRRZ@buG-ZJ^@0Z1e0$S%djI^*H|>`H&m*Vr_Q!WNs{6pr zFV3&MZ(yfxoA~F%`JcTp5ZC9}^}a{nYJYQfKBIsBa3i3m7A2T&ob|78x~9PA-4)*) zQFrpSA1BLu9iNQseYj5#IOf{q^^bb{^l$Fp%)XL^f8lR~ueKfHEscd&i$9k&~{`qBVznN@f-nQ`>a zKK<2ePbBP3q&-n!f2c)?lMea0r{@ox5!bw+7S0v4kLDDW%Be*Oj!?}1h$twbUL0fP zrBaI$+E0;2)E`Q)Kg#Ez=A~ZjO^lvcgKdSGgSWuw!4cz2JUJrU<>}vm$z$}P0)S?7yj-09! z>cw_z)3~Cxwpg$;u)iF>W3Fb)OPf!hwcl(#srl{d!%Ekk`_;0glS!yW34M#}+)Yn5 z?fSrXHAR1FR`OD>_-*YU+6`#^`{q;*AT1U_g`Pq z{M5G4xYpim&mTLu_}e3fw(7g-1Jn1rcpJ&L>NuC|+#DmeKXq`izY%OvoFLx+!)dum ze;(01Yo|fY?Kho~8~)hY&GV1j!-(&U_~x9!#o7#^Ua>~Iu|4yh?G639MyN%J&8D^F zuDSLP&7-Dchv^fhasT;)i+f}U_0szJv0M1?OFv4Yda&2Bb&3hCtrB0Y{&}et!YH}$ z=YCwZszr&oKQOM=-7yeqi3mAsjZ%fx4JkdHg*4AyA^qOcMFX1__so?OUtRWj((R%- z3A}g`4QZYjD<_y2ye9wk$Yji;UH!RRp7|;#Xvq@C51W+q-DKSgrBZ@kYc3Vb3oj*l zTisB{@=_^5FVJj}a>7dGPhrE$TA>LoiZolgoS>x=F?`rhD%4yFq~Vp)ReI3s;Umw& z>x5yGifB=!S=#ba(UK*sH;d@aH52qoOXXW3A_}mu6_Ng_mFRHmYos~GBEpYdTC&8s zR-$`toUNIl7igZ^EGKAzmlBUyPtLbFvSxx_pn3YVoZ#tqczu1@=S9vg_ER}QOP1(! z(VSw{v0LhMdVyyDmutXlg_QOf}Nz^HGm>ZLUZF@C5V95-3%l zP1bFOU%Xx^K`+oOZ8^bn|M0RNY{tkynyp?U3P`CXOQ1v;l_dg+GJ;;9*_$PzK!Rt( z;e}ay(y*WSwqhHW2%mr#Em;EV%B;mbE3}mo^a9PkDc9g>^3*F~53;lo;cHGymcW`{ zR;mKLl%N-`vlYrU81VpJHlvywt;R@ev;{v(3SiZeC62dN4!gp#-3XCuqqM7?r2ltSS)&q%<$2>4h{~ zy+k1430krQ>T#pZ`w~&8M9>Q~d$UCN1T2g>fHdy4T!}bBBf^)8mMnpLJL@TIa=^!Flo+1Sltgd<)3 zjzdcsVL4%TRnSNyyZd}oFQnNb5#ei2OO~+y&qbpIXc<8-&}`{aTs6O=3h(rBULIeU z@b!eJ?U@c=;?j6a*o*Ac!gMy8KuM#FfF94aGaWS2C{TVcj#`+82Hq|6e0_QBHsp)E z)Qjn$VG*+s&B|-2g=uKu9Wqb-m*QWwGIkr(k(YWgUD7}tFKGDKZOAK2;LUwoJ<>Q{ z(D1R_NT?UnLBrZAirvOi(F^s!7YMd=dF(b4>cw=>kVtGkb{kulUcS$x_zXh$C}||{ z#hv4d=}04t#MBEGda)jD5gk&EG6JQd7t>K&`FHwiVHz4}x3Y3t@0yN&Zhy_gOf zjKqfdp%$j0fl*@LzkD=_^4M)qM_%g1bV(zM-G;of1jcb&J<`#h=eQ!FUQ7p#bPoEq zQVY|*&(jqH>CzlTTlv^+tOsT-`-ADAk*+172W9o47xLA0#ktLnI4Zx(ply={`L$c? z&R&)q@|)><4SH-?^X|XjsP6W8KknK1(bT5D{drk#<&Yg_&7V8W?ol9q7!nAzD52kX zoZHxlZ}-_YdCxSIP_OzEm**a^Z$(Sq9%>rbE$xw?`{{uEHNR|W(QiVNZvQ%mJw<&U z7}~6KOsGYPSYyS759S`&q1~+8Y`^}_bN2RMt&p#teb$H`cItOb*ztR(5o%E)J|T@U zi}<4N*|~{#hp%6X4x+S1Z-&1s+-1aJ3%a!G9yop16BC!LJEi|yMyzdwT9nYYM$S!Y zJgPsU>0*Dl66&R;b?)gGcdk2j^9x!#9{$T&YEfdn-Yat#9e8B(4a*L+9(>z~V~qHG z+TOdWMG1ZT(vRfD8cl^7HIsRor0K^?%SpX_0Wg~yk4DvMG2-G zTcNR;?a=#2x^J5nXlV2UUawBTq6E_`WWXlSekUawBTq6E_e$3bIL zJF~=dytF_=<38|ubpjS8O6e1!@!*9IHczti3|NLr7Sqs35vA)9QJizpHfm9V>Aw3y zWA$Gi%uPu(XhA(RY6!1aCty*6>G3~F+p3OjMGG`E0tv6j#O!~zo2nKim|peGuS1{L zvCnCNMx}@+)d^UXV0z+<(6F(a=h&qM8XCoe*JEP#KQ5Z87A2UTcn>se4(2%rX@N$i zXe8AMSd?IT;3d#F!eUt*nXV4$ixN!F*#{am7Mc5FO+1z;B&d_5H(gKZ2F>X?L1P1Js}INdbG*JD^g_Ea z&e?w_ke3onH?BU!G}1oze+koqdZ0HMyNlOjV)EMKdZ|STrYC+6jbGc?9bxwnv=uGT zz&K{KFJ7-sz@h}x!`q{+Ua>jYH9bQ}3p6kv8UKves}ry&!StLOXuNOp55I_jde8z5 ztP+f?#_KWhhe6|}sznK=$8Qadk@ie7Cq2_i3pB7kGWr^?S0`Xmg6YnCLE}4nwpy0H zXP^ZdShX3OjMrmg*=g;ksznK=#~%TWI{VvTayZB9Xn_XqON=hY>(vQZlwi8&dC>UW z?zQ;a!@8qD3p8*SWj%O3CZ4#m{WfY*qLjWZZL5~FtqLWJY2Z15{ZYCe5u0A$eyUoO zV0!42(6BylN&CD&3+jRA9gZtrFC&~t%#fixNyX zcEK})&B4}m4i;#E2A(oG&w0I!aB5M4=~cT!qnkZb|1+#51zMni=V-21yk15)wJ5=K zGhNQG)64*B#a=tAc+P9e7NLM>g@41O540yaV9rTz|%>>{lw4&~v+c%?fW2#*aJ5 z>Jk104Yeo{pDeCMs8@X6SqZi1$!pb43zgPfElR{^!&O5G_2PRJ?97cd)S^Uu#@(0# z`$Gx!;`P%0T|mAE)uKdvRzH-hoKUYgf`Agt7ZE5}4@A7scR<0PrBaI$Z0Qh_Lo^Ed zrU*OTF!~TlMc)BM8U?i|!Bg1fzkQ~JdhrZih@~f`a%xe6r?AU@`>ddZdNEE_h^40* zYEgoxu*-h?te}K?F_Kn@rKcKdQG%zi%lktK^8cqrIqIQU-r-WLRpk9bZQjJhAwqb~+r-WLRV7rAFDb)z|;#df= z^psGG672sFbD$cbUL4aQmYx!7QG(+*#7?M2s2AsEh^425T9n{?3^5?85$eS?CdATH zLM=*gT?w%)suAkNwKAMuRzfXGaD5ChIjRxrrOzwDpYua4N^qSIu|-rv3H9RLCqz6^ zLhq>>1xWAOajDdz1ak_}lZ+{_9!jW}-h*QewJ5=-fe-~MFyWa&3H8z^gIGiF^n5zQ zolJ9z3AHG}C&03Mty4n1^jRX-P>T|LE-im%P(r=f=ONnLf@3z#ul31*{CTez>-0I1 zeS>Gi`rj?jE%@=(;`pB&Y){Cq8nLbsql{3C68PTsL3;knc6o2tGk@I6{qvXCwnl_{ zAq|cBYu{(jqA#c4iay!xfSKG8-?Y_ErMMr60rJ~HALjOY|Jdg7{qWqrFeTRi^MaXb zVcZW8{7%(0?UzQpk`icV)nFQX_LXiUl9ztJvs#phciqny4JFiz*FzkZ`#bbbKDT!= zJH6N?PYcSfu?*sRd~U?2M)WsAElOxq1m}9DaR(P$3?W^wbd|t$L@Es{+?)1><;LsI znuTbzYEdHAINRO0NAC(AL^gJ)qL%V|5(!PJ74(LHz@YTE0 z$@`etWO0Y-Bw$g3>AoGIai4tupoRMY7@vXHs}rzbe*p=m7kzd_(8%!{3oX#dp63N! zoq$CNrdPZLjk~P}zf9YT7HH^sUS5xhZdWYotrjJiUi2(9tOx7Z=d}2?lC#0QUY&qN z&(tzK{2^#;ZE=?7q~Gpnfkvehxz!0+lwi8&Bxu}Y?_TTDZ;-S=qtZFy>I5uGFx_+| zGAZ7w0v08hUi4>Q51W7Arr(5Vfkveh+0_YHlwi8^@1gO9jj6w< z-?nLihDHtH^_V#RPxnkyixN!FIRYB@+P8_b&VSHS&d~x5jWfdQ)d^UXD5Zz_wla;& z&JW)|N|v-9jDAqMUY#%tNNyQo-xh30Rb1x+xEhbnN0iwW9?Z7{`o$!Rs-x^sQdg)uIH`EB5jI z5$2%RpamM3kBmUV>oM_ekDvBYixNyX4uQrdwwAn{e*d5a8dz6&R-f0a6R;@3^om2F zk*mX0`^Lk9|yXB63)S?8_Lyv<-y0&`_TA+bdnI;PsgJX1{^c)Pg%4qXsbDcyX%HoND;JobBgI&kv=n^9tB!Z4?GR9KX|>2aB5M4>Bhf9BYl$b8ni&8QbdO`!avENB(NyK zbl=CJahH8F*vh^gpdPgNdPoczUXO|QwqDvtEgGeQ>C;|=hV21peJ+h9ObawB#jGhK z90^#IV0z99Xgp-|Z(rM|hI-Hf4UO-@>oKwN%yE6xq6E{8KR{!xj`rIkBSLIvTA)!W zo=h3xNWh{*DP4=_#Q(GJA17ZLVpNwbrcp7tW+eUp#gjtkedd?QmxX0#SdXFm5 z;_D&teR#c$aB9)`K1_Gs9vXJ9ZRNd|7HEKGTrFO&PQaoB(<^q8wyLu}_oXW3E0Mn{ z6J!3lWgoSm-54v3>45{F(b4++Y>Ocb4O%#^7=eb@s}r!G|4A@C$7`fxHxCV3pn*}z zI5oT;6Mdh(ZMs^NV7hS^)FYjPUV|2BV0JN14X;-xU{QkUMSY?1fUPB)roSyi3pB7w zFs2W$$HZ&3*Y#105=@7`?(SZ7RQ|lr`y@SfTPv?`4fOB+NoOs~eQUdlo4R6`#hpgH z^l6`@rx9vVVq4pj{PcAl_L~3BEPHEkj}f;P%L(<`?T^cHpY^(HuYv1AW38{p=2w1F zpG>&9&n_2zwqf0gKfIbWPQJAX>EkSY`270@>MrI$jQO-a+4rg~XQ@RA)w5siF^#>x ztxpE5y>&#W7wXg&7YD=%MqIW2VYAedCEDJX@Qs=c#DWsqR!FzKld-)F7*mB>+t;8G zXplbk^VJE?<1pe$h)kh`TCxP_K=5zcDfTxs2}CwQ8eZ9`I<}i8l*)n7Qe_F2u?N=A9hXXN0kcL+_zEezSsj>u1=-ff+-?Z+4 zb6XkT15rnih8NPR9TRHF5-g!}n0sg|>?^`sS;luk+Ly#)y{L9fs3l9Vgw7plGl?3E zc!IJcO)u4s3AJPimeAMS|GkN}VjLFq0n+e7TD4UP!BUOsFMGu!PR7Z_iiIIM~)iMl-@%i!{8DR_&NjOO{{>{YvdM zu(mTw67CsD!wYHEjtRA736{{`al8iZI2wryX?Wp2sM;~1mMp;%hWU-Q!h9!zJ0wem zv}(tMTCxO7=zq`4*8{(_!I~om6`5`}xvzALl3bT+JRt^ev7Oq*dFV z?uAfGmVicxn1#8Aw!(dcBN6ezINFg`?P%=g)siKk5n_d5?m+|hL(V9~1mmnlTD8L+ zlZ0Bb1T;dlH_SZ{xUX|%K>ReWK1i!}w3bAr$`a5B5zJ&w%yWf9)GDr`**I>|ni!QT zOF$z;d$ao>*Y-SDYQ(wX-2iFTj@I_5R9ONVA;y;6qx^4kFj5`wYUNSul+aRT3220< zTFbDZ$iJ8NvSEN-tCe)H8pb_Q=$`1|Hhfl~@0r(V-v}%XhNIk8hECG$MUZv-j3Rv6u7YkNo{#AsuYL|Z9(GzOP63__i z?v$H$%eS1~->+GRe%sC8`{plLG*JJp<@HAQT$7C}Bc3+mlz+c4Q!Pp$&A+LwmHfXD z8|V2h9R?yY9=_@`jo58*v^OR6D?8JmH8x!;k;dOqixSiW9g2j3h?ElQ#Zn<+UPKhs zQi%vr>t=1f)qrR0Ez5fL##Yb1>UmdMT`xWW1~Xbm7c7rm?nZXe2fzVvUP_J7CsABYv>Ebe3RAGzy%rhhsg|qWNl_?C+0_ zd(8a7G#1nu8ncEGnn3Wn zbC13~q7MnRfL4O(pfT6pp7*q;4R~oR9OjFhc-{8Nm<9>8XbDw2XkfR5^Bj3ZKZul)rEFO7x6*gMFH*F&jDs6|Vt+JV3+=~wJ&173`= zqk15C-MM*h|GPH{wPcC7R5)GJ&Q7_(%c9QsxJs&roOs>2L*5=Sjf7gVL|ds)6MKi% z`Zs&hrx)TXsUAxk;w?RE8YI+`CE7{_4b*(Ty`g{?YRLFtC<*dKPP`8PHbO00Le&n$ zZ0mEJD2EsNnX&DdF9=?b3AJbmRXY&rNX)|vBaTtzm@f!kch1J{bP{UO5~_C4=x+1x zMSIHdUTLg3)$>Gp-6A@e1_`xfiMCQfWdmDFUboc;URVJboe=XJ@sN-cuRHgoX^>Eh zmQb}rJr1$?_o6*Jz)PbOGG7q99usQO5~_9}X4(Av+;()p3(?mY`;qyA;PseLiJ_d!k?(IcgwY8|%S*Q^H>_X?Q{{T0+$h8rD{I zY%4_HVuVoYf#CI^K|(EQJ$y-2J7^qc^Y4YU&o$mB^98}{L4$-^prHiQLBmF3o?}-d zgfd^`#Or?S_93AbXehyS(6AYm=N!a*;5=u($cfke9PC3vEznSc>7apA@t@m{DtKuu zPUef8cs;Zg3AKP$g6W`9w7!_0u8Fn|`iPyXhn#plXpm4#mWWDKu(dtUwcXb9Qj|32 zi=22pXpm3~G?ZXE)C1pHc#pC>OI!4{R1Z1vx^s4q>PJ}YVZZ3xe1EGxc;5YRM9$gGRc-`L@DJ#(1C1 z7di2IOsEAKN-!OWbfxwhSkDm^6a@1{PP`ryYRM9$1My?w!Q4&utOzg05k;E$A}3zA zI4m|lNT?-CkS=L7Q^PDi=BnzYrA=e8n#MHK@Pt~jL|dt#Vr_+I2KGlOf-d!tlhxc` z52YfZmb4zeB&r>V^x4O2@GmS7%ohZ&$Ant41nEH7{}=3kdF)TL{T@Er8+J1QVhC>=d`66!7$_= z{=bk%NuE7yTB+=e518&FZ7WrZ74m99ZAnxwl@jWOowA5QSY8jcD50$o*8}@x_T1|4 zJ}>OpVVxMMvRp$gN?_-Z?aZxEDkap5k@3nku-lM*fL(#wHCA zD&6Dd^GbJV`81<1mbb22l)x^l%B`z}dNGP*xrUB#?B(N3tv=e-q6Bh^R=84IDWP6k z+PFW|qC~n&uR?z)p`xohuf^wEeMYH83AFT-y=PY_l@jWO(sD(OOQjYi z(Em^MeW-$l66&REWvr3Ce{dzj$gjNms6|&I%$v%qj}q#Ixx$u?OQrWHtX*8^_3jfB zYEc5KQdwISc&}xM!t~z(I5!V>;LHEa6)S_RM-e~wRcZ2QH3=v|tKkTS{vG?R;QvWz^t$OK>P3QU= z@nE0H$wVX6qJ-*&n!mFu{GyJY;nlOY8p+juujr=9+xA)=2t12oe=DNqYSdd?=hqYG zw%dK^%s-_XYEdGNTZ?i%`$L-s^HMMU>g3$>=Z~0m&yRsnixOHt=ia$w{H*&c5bDL# zr-M462l0<>r4}XPwnF^fUp>}mH@tI4i*hu)viuiym#)1-Zq%?4ix<}~9fg>(?~M*S z=D$&8FZsfDg9ZMxSXs`Fc(9@(iI~aeTP0t|9ru;M(FiBh;c1-c;MU89&q~3-_umUYyZT zLL;}cCjeC7tV#Y;1Udc~30PI;$3*>qeWuu|j1nVt;8*)IJ;=iEPQ8j{8{LR+Z? zD>Y7^fxwE2Q)1!NR^IkfFWn_*aDL#41yQF?o-nzn(PBfq*8v+eB#%z7DPCsvs1&;m zG1gSuxzSeheLo9?S~OmpMo+U{-tX5ZQ`*=1KF6~NPAK5)Li&_Z#JK=1t#jWe4aqGp z)f6wZQmI9W^tq%M&H{9AsZZ|NrnY!ZhET8c39uM;_V4&see&}?Yl?q0LVHSEAs!`f z+t|I#egO<^r4}W$MV#AXRekbW1wy?vPJr$4veEv^=Rrd)N^t&%llPO1`1Kd%gnH@8 za_7!nS)cS@83?r~5uZOlwR=Ny+fQqXS6a=}zfy}hQ>o)vBh6XNfz|cNiLV6>wJ4!= za_;f}t4~gCzoDN|N~o7c%rnA9`y*XzeSfG$iFhQ|uGNsVn-FFcqP;D>YeEt80MX_C ze$nMcL?PDkW^eASbtkM-KBJUC{JXb4x}X>$506}0pPX@XSW7f7^+Nr++;T=S#1a1H zyZYq)C84b<#co5qw)nK{GAq@&YlTv&MI*e$akiHjaaRRGz0k9mo8i>&fUoM4lYbgC z)S?9R8aHV!Hu*T)Lv3YP^g*bH66%Hi#~Gt=difR`C7aF&{h<~m(!aus;Y{_so(;+N zi)#GZuJajB`Z&RZ6E)iE&aJa~L-OStfl!MQcml-PoN&5k)PvT8zbao#)GK|SD~3o2 zH;-;eo_(aI_-C6Ry27bme9mkBXZ6VmUx&MzT9iPVdo*k}uGRcxS6jTuG_nM}ppDbg z;k?=|n>HlhbPKb#Qv5_jK-AIW-2Ly>CwHb}S1pwyBZk<9vpY5<&(((>RH9Ox!w{+P z%rEMbL*EZI$Nd#^P$Lf`cCemMveRJi)+f1t)D*9_nyUr(cHGrK;A!CDH)j+>RN$F5 z67T&uj6@~WOIL8)t7LO@;3>9>zR)Sm4<*z~pNX8yy-}ZRdvADJ z()%|4#=$9UoPE}{%eftFy_)j3&{k?u0)G|Ze04bQyp5IW_4IC_gnGr}>gm1>$<4iL zi+{1!Rf`h%TNI~g!+Gap->gsm^tSzKXogTP{Dq8D#^Lnx_+bsnhF669xz3#QZ=50` zdg#cvJ$E*){%H3>JXxwmiS)0cG>XR~lj@W1x0TOY^-AA<6+=vpZ|2k|U)e~+GXvHV zJV)VFES?$ge1$Wr+9LM%$IT7N?|au4PtVj`2|T0tXafFR>NPf_zO$z#+&MKb^@?Zh z-T$sn4rmCYMDMkFPt=*_TnBqDdBg5ecrH za5wnqd%H*3NJP!`8CORP?xZPT1?xhJv z6uT79wo<7@3CtCH&rnPww>)2;ygGJ6|GcY&dTFcM`43wedYu`@l|D`2IcUlm)>iiG z0a_>L-n2Dwc-n(%Q36j(o$f!e7=9PvFe83UpGB2WFI`0OEh6wx**>lO1j$v)rywpqYUCv$5sUf-6{-Vcvg?{GRht&s>7Z8&HZOA*d zbHB0Yk|7(0QmI7=taivL#7L(wm8-Zwctqx z_YA}`(46ee$CvdR1s}QB&;N|tndY^FHeOW*YJR^4pS)jZljc@mb`T?&z7{ZNL7luin&J zr(UYJ;F9o;tmlmf**D0er}oTG+qZw~o;SDFsYMCCZNpyf@J`0wKKi}R`i6yPGjKAH zXF+gkuR5V#`hG4Z)S?8>wBR&obwa&ZkFfVVFrglLmPpV1Xp6)eYEeQ@^TdRfgkCre zSiMwgQG$9n=ND@zpy=uR(6dsJhL32?ywnSEU~xT)5bHJ6qJ*B6iZzr_FT}HjMilARYp6vDJu4M!D4|}6 z%L|PtVsB_Gu|z}~O(2|I3MzgM`iR!dOHWiGzA&ywk%zs8T9nYUQgJ<$P%p$uhDH=Y z*=wjp2|X(nYbc>!i1!SQQY7dC?}KVlLeEOY8cL`aqEJJFzt#*YtZ-^kLStumjY1_t zy{H{U=Jsu+7A2^M^)c2^LcQ3AQH1fRKVVUU?N+*fl!+>V$gn{>V~=Iv88PUlaJki!WG6XU-e=^9|652|W$QU5udl z9XBGJT98&kcQlqX$_RRa=J)7w4O-x(1ow4Dgs-`I`Q5l6{;}Eaxmo>(HY2TjQcI=s z1T9&D+L4B@hZ6Jxt$R|vMggo^kXE8%Jv_1f=u>h$ImtcLpmoo7sUDs{zU*`4i}NNR z+WvNyKKBGI@KORTjguthHCKXOpwa(0Zxj&)SZp7Av+RQRzjKf4I0qTdrDjV-3%snh zB?9}n@w@SnhOdVb^aB0Aja?=5#9`dJ%nSL_3u(@q@={^PIQF%}Yu_Dr&NW^Y-WuQ< z&YqMLv}6g41)dX*OQi(8Kx4$aA3&1hT| zz-nGd(+g>i>2eKPvIOQPM*f-!dV%KpSWaMMpcUc8bGu0Exx2VOXvq?sH{}{i&z)Oj;IamPe^OAaCMxmdzgykAqTO}}?!4A~Y~@mM zO{5nzxW<$d7)v;t0WY4eK$>@ka)OpDq31v1K39TXpt*vVYtRBOB`}+D>SoOZy+HHM zP)=Yz<0KNitbP2+r~kcFO6X~)xaL|9dQqeDdZjCl640wWu9Tn`G}_iHiwca0y?L|& z-U4$+JkxlGjCZ}<9q;1^mk6~~A}0EXy=mlOuYvc}%!_G!uOl7yIxC@;N<@e}tkLoD z1%o?cnZ{Q{(m_KBwNxU)7e$SZk1r$K5z92bhLR2%N~on05x#S#5v_e&={{7Z8LOJw zr5MXitTuoNlXM~KBv4xTGvdT1I0oqLjFg84$D5)tB_e`co*o6<;v>6cNzo11CwNTRlL zN-$q&R3cEqI66MQjB+=BDcu&6KHW*4ji=8uF_nlAhdw2mG0#yF?)hh$vGu84DwQWn z`KI*%9T8T-Qq6s|Db$?ju9(LD8|sB|m9~{9)KZBEJB04Bvz+#e2%bO>@|+jb@>>UK zTPeYOIj%q}5q1b^bbO3Np1WaMz6qxqO0Xo*s6>RX$hX^B&OvDuGt4ONBxhQ_RHqtB zFkfg?BEq-r^p`eT{n~CT19zxn^+B57(y3kgZ4OT`UuaY!P(tUfva{5Wr!nHN!f_uv z)BG(EYR3fgg+?VJ{QieV$Hz*|ee6tQX9a2GR31;CrK&`Pui^G9G57_S&{neZ9d{q> zf|uWBN&7+_bh&wb>2_AS2GA}zo9lWHize4$Z^KnY6`t$kbJ zt1ibV)7W!II`nxO1KSg7sYHZ5cin9My_`nJPxtlt@-jU!jk!&2`>kIgm@m{T5h2dD zM#oS01$zyqv6Gl|sD~12sYIZJrAX;m6AS5XWv{`s#6VB`BaN-@3FZs+N<`S}{IH!5 zJ~xeykG(^@e=se3t5Xdnm@hOc5h!6Pa(%O}hn#BTd9_vBg_!izjtS=L>ygq*gvj+8 z9UlbmoJ==aoPO$s{!l_Kl?doLm)5)v>n>`}X9K3kwEadv+*Y1ozU&XsN}z} z`i+sYQdJ_t?|$G*c<$_r6VSukjWJ^U zvaziT&syN$mPHz=-tdRF$SIv6q$H%3Xc~q0S11kYVWrD6FIbddsXCvrpAoAT@7lU} z!X~-1j8KabC*IY|*F5}vzK>}PGL3CBgnG?9?)>CHH#pb%uLqb0{q2y+q+HBfhIZ(Cb%!8JBA-)uXe9?E1737TYkd7R~p& zq04gjKAPl)pNV}-Lw;PnYdfpQyQZOpdUbhre6DZPvAIP@?h$HUc;V~?$yLk7M)goy zTRqf+gj$q%@uNZx<0|wZnAdGwVSMRGB#qIB=z?uycdMVeJ4mQS32KC~JETkZ0l8E| z3H9o+{kUAqmdEApn=sc#JN~7u+q%!e-{$m<7t_p%@A}#ZwV*#pu>ac#yZQUIgal?M z)9}(338f;T7A2}{D4|}QD_AjN4Yer2G~alE^7SZGBH+dAnDdcFiGW4()tP2-^q!b} z*QdQ}lfr6?^7rRuxs~a8P7wUMRCo5W+>qZ)-)qog!@tA=Hv3K!+VE z&)AzH)Z<+HYgGxP>7{#H>={=GwPXp7{#g+J3tRgj%u$=&(bG zZ|C>4H}y&&O)uS@VR4wPXpx;l;5K_QNTmmMj5{KwwosJ^b^J?5*P{ffvVg z*w?3oTCxN*0%3E{YhY$6!O;#c&dsntQ3;123+XVZW#nYRMAN2t@i@*aiL;Humqq!c`P$-K*-{M>Yc6A3kxw z3LBAXQR0C|!`)}a>LK=&k^a)S?~~=%PRrpwv1mb;oId07`k3=KF(Uol@cc&Ohxb>D z68g04+@kPH(R!kPqe4fs~gzu!yW$(5gd-TJQjX`QS;me(h>BWe?zl~Icl{2~;-{A^&S0k69)Xegmxaa+As5 z_e}T_qpfZys+QF!GyYneTx_LMixQ=8Fa8_Lt=5D4yP%ZNtE^R;%C?3!;vsnnu`p3|{2Kc=zOg3#wmsF${ab442^ zPyMIHk1PFFz&GjTr%Vr9VyCdTsP$u)e?j1FjS_fQgKrk$UHBQBH6&}l9_FAD>ZNnj zxq)_`bC-6tzIAm4z`I4XG~R`3PR?Dqc6~DVl-gvfwXRx};M>pemh-T68F?NsBSaX~{ZO6d1`ixqBtKI8gwLcMfVvftRU6K+q;3Zq@;2fr2K zo1l(-=kBxlanp=Is6`2W1q@&NuC^1o{pN?UtAu*-n_l>Kch)`i$qu%P;%uM35#){w zo*!gCIro;GI6PpTuwH5FDuHid*x?cOOq{={K6&}InuO=JnU{KLOWS@1>%n;|!mQQu z@>?Ok32ObEJFi1S^6Oh`6P!3yixT`k7{2!5lvjSiz;x?(tY+q3n_^ml4Jp`)5_(s?$VZD_N0UVZZTyMfUD zP(t6mJNK&HaoT-aKBLr&Z@j~s?PWF+SAP}8m0I*&xN2KO2b<@&b`Slb7A5#LI=ppG zy4bi{x7I&pD4||DLY-T8WY7E;dw0)u++%2~zHig_aD0lo_x|1NZB%jb{qhBUX6oBhmJn};^i7y^Z>Pj|-#@miT9n|k9U`VV_o5NUZhnFP`$ILD z#=BmnoqIRcxa)yG?5Y+ebl%wS0*HnZ>c#6}Mq!*Rv%em{wzoL6ptky6EUt$VYEeSp zu;E_YqYhs(I?Ug|zg5HEeR!v*@A@|Q;sF2VZcw}RtgW^(;#(s+8le^?^o^c#o%bAF z_a6{lJNdV2(7^jP{yhl2Pg;NJHHQA~hoVLJ+hcSc{%&5+2(>7o+7`>=th?(zGGcDS zr!D+@8SmTpcP;cf{qSqAaay}~O=DjpJ~84IBh;dVYCE_3t{3W78j-*Ig%+st?c7~=BQQ$Z8KD*> zRNLN*?%yTvYyQNr=1T9ypm%Z45ndy_hg)g{G`6wt4r<{WFA%D2zf+wO=R7eiM=!id zQ#}&%JI=KT0t=16{J8qjVL7!Zq1w)Mv6`dL7j)?1->RXl@Fq?5So5E)7@RoQ)d-BM z6KyW4MG4im_q*2T(0ImX7JChE(%8DtV-L=HbAoBCZN%3`G#H^4B~;sXi`Ym+>t1X# zi=z*3(o~Nl@$h*?(|Ev$&x|7o+V+jbW)!~FcDMg>7U4~r>TyPmYWJ>bj4)4( z_D=R+wJ4$57R4i78J@J#aW%l3G}YtEaQN?jFpUF@!0Pk55o%FFwVnIaS{0+@YnxeI z)$k@w^|-Vnzn`H*sHGASo<(uz@r3H6HmBQW7PQOnK|KGg0@np1TRB{+7&ol`Y5FZJR`4EJ*-w7m4fEYh5+mr4oh zg?X+TnwNU9PGR*?LM?1Jtb>|U^-?Lp(Gyl`)zG}uD_*IUP>bF(G^gsNQi3@(`g^Tv zXkO~Y5{4%LB{*L3EXp*VSoJA0E|pr8pmy0`cLgQXD}J)nQmI7=rc1Ndps)j?5&)m_*>a40=b@~4I@;ph_bJqK= zVNbR9uBu%{@&EVF{cFo!uZz`bYk$9U$TvUKxnlW(Yb77`jZbxEKCO*qM3n zRv0}WFEVWM zt1t?o&@?f!Jc19;AX~9d-RR)XePfsZsNy3qh*zjJPdqE2yuS(~MCD7@Gh``?Dr10> z50#thrt0GZyI$Sd_k%yZcG0R^b|l}v?bpVRK7WHCFP(SI*hU{-t6wsDlIjdl>G$1a zDQEn6n?1(neSOouP{j!kziFd;CkJ`0hgM8qw$q;*qC!(=EZt_0>9SP%kPxEs3{YZQ zgwrc|1gbPXstUWFdFjJv>lt@!`?cvRw_v*LQOSEKMaiHfTd7ye%KHfM3U%bhMQ5A$ z{Ax@x{&F8^>Ws_hY}}bS>(jMf>upH}CHcBX*6l1?zM!E#(9{_>9zMBq$nW2AZ61|p zfD-#NV_S3<-t(%ek6yCdSG*~bz9Nxq?0&NkGu)R-!6E$(Bb+9=AvrS;Q4a z@Zn?sSF^v!qQO#g9zJ%@kfqE=85OaEl8;b^jd>8SP)}MuKB}y&N*`qI8M36hsbrop zK*?VyU1L=kp{x||ygwh@7fN}|d-`2LR*5V>aov7}5qx+CD6u7f;8P#2GJ+2@pk$Y* zmj8YIDx=IpwmeF*a$5f48>)=p!^f@~oOkTBm&n7%?isR_`6#0zc2J5+CDNP+@d~9H z^igGHRr(-v&yXe6OU~HGA<}pzj!T=>7lC$wD)CU?+jE{<{d2II# zP+}{mY}^e#eC(=0Mo}Vcu5%*s3|Y#2l=T4vl%fhH(m1vguTZK%A5~UXr4Pn-&yc0& zvE7#yDESNJmd5s?c=FWIk&o_uY*+JhR$EKo`B1sqVr{_6t0?X}b#(m5#9&S48IoBc z6~z{FR$b7>0L9usD?QamQCztC)WJS$Obt5X(x@2Z)Lf7jkhbAb>hSfP_l#^8T+0zIx;!=K;!L7RtseXSrlyy zQ1XFXmQ~l{91wyj{tDeIDw(kpW6Rkb{q&wcRdl z7mc@zKkcK$sM;8cklhyK=)+oxG7o(ajkhaVWf*&HYFCX6P}E1+&wFj74-ENGTNsW$ zE5CL8VEF?_jA)g@s&Vg+{9fy`um;rc$T9Q5K3^Fe`tozG^BT{P?AL=u(Z&EJOUTj3 zkN$bqV3${njeCu^E19+E#0*ffgd7>qzHy(yU*~Tz@EUJd@*Cc|T4&j19{@1)(P zz1J8wpO-U0$r9`K=;N8K_8IJQ{uTpoOERdO@#NI?278Vk5TXL*8Isv^D2fgK^tCB% z3{dic9HY8)<-GBOzVo@@1C6&U+3#f(MH>T@d>}_3@!wwXfyUdFtX(7amSE)!P{~Kw z*8*MiY_~I%E~wa|ktf zNgD%{d>}_3Pj9tPce=GJukm&zTdVBHw!6)rr%(ImH}2EDCAD2_d6X=%uMvG%|LCfJ zc$8#NIm3EwmtG6XGbH<6oT6xBfRYd77?q7BT}B@?-mYYJkS1n;k`Ls-=-HUqWlTil z?Mn8$I7QLM03{#D(Z|B84(t9)QFOh=+m*b0?bZ8>FB`WxT<5|Ym)vBG%^Mh?WQjc| zYgb1V3qEx9VcqTi{*MuFOERb`!{X|#|N8B^>nxleq5|a^lG!^eijDvDiYaXjQ1XEs zGrwrcijm#E`|;odjkhbAUEIJZ+8ChZ13CIQ_&Xbq{AKc&gAX*`u4MMCi{e#(`r3jv z1}OPJj!_w793N=BUCHcO2OpE$7@$H~xxMhB_|B9SIWnvz4%8C8#@m&A@7k+(Vr$=Q>0rq( zt~zY+y42dS>pv5+%qIs8EtbPP-0mBFZaUBb<{xXK3fBZy-A^L z4H$M$^*eHm>T+AH{KZyAUgH^(cmL3Cot1}ws8bYAZSsq$9a|erv3Yx)0ZPAX&xu`w zqIkoaQwKj^ZECk<*lJXE6(Rc!$T6y4TSPy!wVD`cJVUario+i1#0*ffgd7=nn~(EG zN5{R!+m-y~PaoRZ`rnykvFD`Yl#obp|M+W!Jze+ZdleF*1C8z#yj~gSDEs zE65RB zL54a<Nq13}} zl$Gw}HU_A&2Gjmk7)!!R*lWC9$!a~7w%f=6B}>S$2CaW|=^tpkUCArHvR<_hcIktj z0ZKmT1<{A~^Dg}yjkhbA-(%Zt>rtSHkbStKNaIyGGH9n+DAlv}jTIGgjH=$xh4Ku^ zYBB5~=VLnzQ1XEsebmQx+46QJtG&%T;}v!n;QO<`v2=y)^&R1^1~5R$hgu?c0m`V# z{-NDv^5DLKGH0K)ZqYKcQeYV8>Vlo-`k za>Y5LYNc!p$^bnH>j+7+jb0ZNvTW9Dg(Ecig< z?MhZ#$XZFp03{#DWlPlcJd7o1yj{r}iH5B`jaL~1lzbq^mT3K>OaDOQ?Ml{&TIqut zcS9fa3{d1z_Vci3Nk3N}^bZ*1G-RaG4Xwm8ysT0mwyQK34Gi7?ptTz++~-O)804}B z2ioQI8btylMOEHctB!C@sFb;5_z})x4;pV*vXw%=Qo5R1hSK#6Q1W4=9_|&Ed4#=J zX{_gzKCDNTnIp$KU+1f%Bd@hCm^<&&hgv^B>zij!^W#+$N|q?~=;H@p z935F>pXdXPd|+2HzsEe zIcDyA6dL*PvR$vLbzb(UCKP!L`-k@Q=~2GUu}e-vhVN0H;bm$zmM&LL*`oDHru8W* zPBfk&S#7#fA6ngo@yatm$p>;-=jyeg&e3?glGRG$*e*`G;$#d^@_`(E__+@n zZ&$KfWxV3(`q9P!B_GJq$Lgnyjx0#mC^X)#Wc8KhHaZl=&1){6>aS6r0ZKkpgTu^I zKhOFH4Ed-s{8bH&M@goy#60S~R;xInRBk*IfE*cqRfNVfB&%kJbLut*C|b#oky>Io zib~_{N>+Q*-S-$(8v~SlAV-GZH9+I-N>;yV-Zk(HP~=u@x3pPj@+15+i1L9$!cROZQf86U%g|;rS<(MA1wAqw6)EA-TdR+FBwgF=%fw^LlI7lP5x{6jTS4?yx@mDixGxNY)r! zsq=D`>KUNqgPM&|`Bf?!Z&xzE$NFe%C7_5f_K&Y0)Z3EXC~0VYlGUTg9Jws3%D5|( zXGjjE>vs(r8K9Ioa`cgEFpO7dyj{tv&Ef7x8v_)rXUM3JyX=?1kPo%pqix+;X}ck+ zCX{@HUQlM9`bRnL(yp*8A5}(MO9Ukbt*0nH{@We9Yo9kV@`K;(IN(0H-Z2m=JU=mi z&*|KwkIzip{J@UgeJ>apdDH!o!4nXkA^AU#JF2sA&#mn)^1m5l=37_o-uc#5gAdOD zB_BNJVE0(=-?96Lx2@WJ&D$aajkha##usOH_MiVVdpBcSV=Oj5-@kBV+}rXf{myd^ zMe#mkoM?-=bw9E$HC81oqGl-`4~RqwTCf2V~k%U z1{!Zy^4HHfC$+=_jd8Lu=A^dk8KB4`J{7jTF)lL3r0>N3!P8&fF8*SVN-c3_|C49fNL|kyO`SnIo|pkj z>=UoJs55ij_iKc!)gT(7JcIr?F$0v?=iWX)-LI|t@F+%{i5b`u$}?0q@t$zqhi8Bi zdy}2c?kxU~ryDXyBa~;{I{(zp@<(>=S27Q6_lV=>gdI8<8{Iq7muxe@a(A%WO0We( zu_KF}`%om<^--x!v!bv1@C;BBM@76s*$lbNiTo;2g+7R;&X7NLKdMoA1}L$QKIrhy z@<%^a%{=%(Ba~;T2eSiN_2C(y#MZv}q@SML;G>Sxu6!#a)H$|5!C>b;FDuUgCHAfV z{ie<~N1R@bD)>MnlxNuNyd`tb044Sx_PBHUG4Gh)-~)|Np7E2V>rUV1p^K}GP#x5AC>qk37nmR-4sOFZ4cQHUowrIzieW0l`p4j8gv8;4M zS)r*jw7zO?yPg3`Y^&LRYbyyFp*%y^NA5>e`v6m7fD-%21C-dC?sRs)`KpFSD9=z%mFtJ1 z3O+mol-TocpP!yKbfp^@9;K4zjzGpJGe;x4o}m_#UC)CL&j2O%NmpFdugqjhA83T~ z49VH7FZif4gcAGIa~AZQXJoRa{WhWAKJ&a_7k`cHH)DVj z`~NK}l`i{!M406Q%&j2O%_BWi_Z=NBe5y~?*-fB+TxvOXHQEI#F z!)A=K&e6z+XRz;=XYLuG#J*+x`2M0T-`~j@XoT_%Ma!OLD629m&j2O%mH)hV|EyUj zHTXaylxKvxNjqLuAD#h9Y_-s-%jXPzlu_xL!5*2egX}Hp`naL(uH~7dk=;5Y?!DG) zupWu__Zp*;v$C}-UQjUD11zKJH8DVmegC|d^=JR+TMc=j5y~?tk=%!8fD-!^51&3Z zd)4m@eUwq55y~?t!_tR@ka=xh66RE5>-Wmqx#tvGcXqp)DNv9N5nTKac=2;WgJ9!>xhy;eUw-D{b3{YZQ z?`l~`DH5&#wlh)6wqsE}FQd!@jqKXH2jRpEB5b}IcpskOpDM1_pl5)>M{|9s&h-|J zQ2tFD{odSb(bO5d3sjbFnYl`lyM3w~%FV{$@H}kJKqDWXAz3>wB_jwz)fw#1*chCi zPpr2qH28q=nyuzk8Kn=;0428aYaZLt2;~{S96!F3T|au>mSj+p)ha7*VfQSoz(7-H z*qGmGzJ7QHD6!Rg;*;d{kpYcRb;go4PHCtQ&yXyX*cv6c^Ha9nkOvwffnlR-r+K9I z3{YZgRH~GfYA}pGXoT_%8;_?~M(RceD6uu7R_eTDpb^S5)Nh)voSp$nY>mOqeGrXM zo%rdH;B=21^D9J=yG9&~BnmU7bNhfB2!UylZR_mPi`Gn$~LCLEB z<{1E*I)ir?^Qb%n6h12LO4N|KZ+)J@JDANrXyKsbgF8YMMyPYOUG^3#rC|Mr=a9>? z3JmoqX=K+k$gkof zEcieplxOf3W$vTGaBoqnH&<3(q6Qymf{z+Q=Nwji^n~&Z$wH+(^1VLt2pZThcwaU5 zp^=ljub{-%nAln$K_irBShMI2AVp9m1W83NfOF4KX~Cpc0u7I z%RJPeuXE2BJ{8vFgKR;`$1w9rx14{;)OB|lEWLl%@E*P2=tcqg4=T{qC zc*r4vfkt+{tSf5VvwYK}k57H`3#$!Y+rR)NAMDQ+#pLeMQ;&Y+fWdPMUm1M(U1#=s z#UR=k)z^&iv&2B7s9;Fu_sD3=9F)(=7`JS;;E@ZzGMIJ!Vc}dHf2VW>*?MFRtr zd{FAq$Kl5KOJbmr4;Yg9Ju(iq`dEKaUW1^-pl%}LZ*TeN;O4vjJDdpQ?~-vhOHm<5 z#XzyKv5)NJ(eCSyF57--}JhGc$^jJ8$+ zN(}11C_ej4vGg~azGHCk*j591_jg9QAF1Cdk?7<2&E7FM@7l;fBfBsp^Lu2pl`beT zD7VPib<0D?uV3v8Au50Wocr903OO>)dSUtaqaXNWV4#s*FLMWbVg{&?xx0T}6#w(b z*9}hp)qcSTsE}{`p^)W(ypz#dJJg+e^1C)FqM@IZN zp3sEG+m)=jFHc#(${C=NkMg;Uj1e^6Zt~|CZ7tCvEZMX%JD+itFD$v?kFV=4O*QDB zDbiI`&k-pqNL-xyy^3^bl0ncpMhe#>J)L*}5wAg7|(^p?%0JpY!DcE{4V>z|+_!cbQ3 z2|8=P7S*;5dBBhl&CcTUaHsD3?rBGE{*LZxKPktnGILNqr$a5T%FO#u9tZ>(ipdFHo1)fN$Ms{IH=J&|3nM{|N z3>uG;OiqDO?6mF<-D}be+2*+6evME>sHl*mj|(iS?>FQDN^I^l6~%dLAGmbOM-S+( zye!U^nowepQ&D_q{G2Hrn^V8S=G4+KkCx0lT2Ud#JpSj43&!7f&cAiN#xo>y&wFA9 zC|N>|jPK6+-F0_-<%Hk^jkhaVR|f8}6h#{Ylzbq^(ly2me4z1mlfUv_QSi~oum}Sx zTD^T99WbRFsW!1<4l}f$5OIGyezpz^Oo)5-#6ew?3vPSB7?{3$<&z)xL zs4nX$&j2MKw9r^qGoM?n`_@CtwOZMBVaP|7(bn2Qi9rjMkFZI+l_&2T?4G#$ z&HY7>y(h@0?*BlLD~u2o8nHct2rG=9P@Vxwzbjhhlrzu>#+E@FtcfYyx(agZR z{E2ba{tpBOmU16>7h~~b?7zBowylIpMoxNGLO>tb8fpyJYm57@*`& zvMiMh3Bd;%P?U6*M3_eWLp$^Pn2On1d9o1&Z=t)YEbjVz6>O%~* zn35qOFwmq(O2$*x_th3AW`KgNXmiGQt)CG|vErmM!qpx>y~PI_+4T&f&3$+VD6!?c z5>-!JAFpIF=pV3iA86_fMcCXwJOfl?RB{%g`gf}(#`XuSmohTgxYEhS#K1r!yPol7 zYaz0f=P}3Xl`*krHO2^cinYS#F%gY?cn1D*AD#h9Y(?8VCZeh5L5Wm+^n_9#T%+WV zYm_3CTw#Q=LL;_kP=*yo@ZlMth%l>PZ6iq|F;72e!>qN`}qjN`{2M2)0a9XK2)(YxAOs8K6qGMVm7; zzRpdNXoMp|jmOPC(8#W55N+5K1pJ}?g7;rZ!Le&v6IJZ*?TXdd0^1;$aGXqccbIGxrQoWw|wG{*;yf(N+&a{ml@|tb`>$V?sWT{%N>rhAJp+{3l2tbqM#vluDDr5p!3Q2% z)LC}Nyif-#R$kqi+B+x6bKcSKEW6LW?IdR*s=)ZmctG7}h}njezqcB5nOUer6&SJ$ z%Cm!yMg|($^$eoTePoQ3(?b^NGRrY%pecPMMwWTcxS@2FE#*TbW#+!D#0Z&(GBHiv z2RR8>?w14~86%an>ZmynG^LNkXs!?K{Bo~RGWTvJKYZvWom)qLF&q zN#Adsd&8Yk*us^0z?iOkzjel4>s~PZ$&cJU^dV}-05x$`J`Z9SgZrwoT#X8iw=4P6 zpZsWN@jXk2QT4?2wmeEQcS(h-`an}>Z1Uiloy99JXz<|~pn`9AFSY7}dvrp1#yayC zceeTVi48tH15{u)o{=IAPoYTe-*bC^@sUr4FE{&VKdMoosWYBE;rjkYS9ga|sn9~{ zdIl)5E!ygP^d$q0P@XYq{^EWm^F{_Jv3cS`z-k_7gz}6{A3U>Psln2RXMhTMxF=Go zKCC5%6CH%|3~Pz~N=qz#cm^o3htD(A^FSk%XFPQ1CjCl3FMW6hD6x5dLcnSsXoT_% z>%n8K{k$AYK#9$`lKZebSmEtn@>p`u(r|~@?ld*LQ!NylIzuIW*2)Vyxew0(B{t9a zXYCI3{YY-D&={g5y~?p&m7x)?4=n(5urxA z3Zo|t_ckT#nn6qC9&3dW$_h=Lq3hMM(O*<+F!=BcP-1g;Iro7^D9_MU^x2Qx-QdGB zK#9#=^4td+q3VpO>)hMm!!slcmGT(N-p&k}TU0?qBrr5eWO;+3ToT;I{PPYj;2DH%OUUL)Bv#_qYjleNT*0ZMG1 z9Ljy55y~?@vBmOEbN}!RP+||C#Yz3V%ma;3o*_Bw=b=98457s4*`GWQH28p_oU-vM z`0xx+V)Il_?gNcbo}s$Q#@*nf5(&8SerdwCmN^9`jEt`dW)f-fP~f*S$1DsKnS!?3`h? zg2vmGEZ=8syn2HV&j5vw=BRw^o4tC|v12~|*h}O=hO%2_>@+rM(NoQNgffYdL=^0~ ze|oW*u^Z*H>8m%LE);pZbXipyJ56tm%9UAt5mCv^I6$*yTSG<9KTo`&%23jPH`s zgYivk2{5|WrmooK>TAW2EOyC|5PYBk1%qfyMz4thO6)9i5z5RdE6>O>?=>+%HD)eC z@Ije?qNG)B%1OB4yd4x#fzt1kdd^TUn!oYtGlWvhpFVHZQl9-!D>^UD5Gt{E6FX<9 z*VgTdA>Yfke4xRHXMn;-b5uTd_1d%k^deDR+s+{NDr2XyXBR%z996ItBZ(-d3Lm2O1IhuA8GvOao}r1`i-L0fvkGNspk!_dvWRvOxs z7>o?ER2doMBKY{V)hoUBIBOyFL3|5WZM)yHRtRHvYe$R>lC##{QyyrLVGwQZ!!tmM z-I#gsfd&+%(4M(xfD*eg^WXywD14~gnnyU#03|l1ZgpTMj6Y)McwfKMs@qN?-eaei zFS4`G2j`EBcv~K&-w(d=+Vm`^oyy(a#ZI-Jdtqdt@eIksrwz|F#tz2#l%3`6ZFv;F zS8jQTR(P#q49Pl>z-%K<7LLU%Ci3Mjxlr3 z03{!5|LW0D>P0cI(*1^&tbOAkM1{uNm8^T7u|Br28nkon2T!CL^bAn)@q=GKUTs$c zYgeI_pz(Gk51+=>_Y>?J2ZN8=*B!hqk0OuQKMu0Y&#-b@mKcgk8qdIA>>rz3k9uy0 zRR@n*OYycmO24ZN)i;acH0!k|PF;0yvGrW9@eIi->G(X{!}r>$@|TT_A7Z}h3{d)A z^*{B{ubYnt9^A2e*f&SU?^qrgXuMs?`d!cB*>^LHv6h|J|G@?ZDEVNFDT-q)svG8y zj4W6YeW3AnB{QxR#fDb8KeEwhUMj0Qw>+f3;jbPIrK_hQ^z5j7JbTHz`Wv3{TZ?Le zwW|xQoK{IA92(h$Az4pA#HU#QVEyA+`}_7Z`gjH?`S|YqJ<}7vORbf>+Zdat5e|*F zE19Qei{cz(==%e6Q`_|nP~`FK8aG)UPZ|0_`@2bEC@N{ZUHrx8MQ^su_qMFxoO+aJ zC=a3JLuL5vO?n!4S1a8ItYkZByh7vcN>;fovnR%i;{C?>sf|}l(#YT$pyWeO3mtgl zwZ^EAS7^Ll$@)D$BdqaiBR5`o1}ORX*2beLk69MgE3A)yHbsTT+m);*Zekvjjj_)7isKa;Z&xzUp~rFeCL2rEy(o@8o&ice-hAlS zQ@gsvTFGw4cxM`~(0IF&dBVIX>f@DXfFh6BKYpt=WnYfCFST7oC5^X>zt}%gyBb)# z3S)_9@C-fmp}tuZ`&jATW+l6`^<1yse*O5cU5%@K zd5yO#S&aB3x!Tp{HcIRNIs=q`XN)O|qb!dNY*aWdMTN%OmCU$erxe6?)wOmNe0t#*eWZ5PwRRO4Xk-_LWS&Vcij@}s)AsknX}t0bP|CyFLV8;Lch;`9 zF~+^tbG^pfmCQ5gMRA=mCK+QijXv1&C|Q#4I9~m?p&z!tFQm4M#xwBOJYIQ*@?gAD z8OHG{wX3eRtAV_u@pdJv++sghyZU+hwo{z}O21qEcj9>Uh~==@=2!NA@PWqLm8{=~ z|SF*LMlt;P_4(vLZF+j!L*E6tWX z0~C2Qk5`I{@d^h1n#U{8P#!{2A91`&*TI2Z2fJS5?MhZj$MGs%2gmI?m@z=flIp*8 zyb2m`SF#wx@yh1ye!MCfpyY!wrYJsbt$hm{75*(ng~r>J%(#-T2W`&TVLhm4&sh(y zW#f9B@9t$Y%IQ{4pHAyRG_ngrvdzfTdlPTAsBW`}exI&5o&idETw&vSeE%a|2fKD1 z4C56VZ&&j0O^f<^&@({EhkVENV12woPRK#w*VN zB_Fm5PxWz$wU7lizj`svUeS2FlJ(|7tdAFLyt>}TlD*S-R8hw6VDTj%8KK{Vd3Wc{vp1oHhW&j2MKYSS@~rtykAV91ABe$1n3yn+Er zKGZj3eKd_%lr9YUP=Ac|(KKGc03{z9V`95%8n0+2Fyv$S)>hMa1p^d$#QxDVUeVfN zkVotvJK1>k-!@*|HQW&nea)k&5B1HWc-BVIt!-T2FO6`jDSEB);0*p?V%3Wj9;u6H(KyRv%)pN@7TJ_0yxzA8p4-yp&`OwND=FzksgaJxE zwDyVh(X<|=Kh{{l9eOTWt_eCq~L3%9=`B1sVH}%f4s2*G}GXA{n z)O%YVrQcPX``LZ3qWFgGp0AugGJZnNMy4m%i}B?dH!v<67IvWY{Pqr@?mAzkM*&hjaT~^V^JEf(4;&9L$Z}yU+>)( z#n$HIm)6%;8P;I1XI5zLM)2={~N9-R>`|Y%L z7^T0)@k*J)2-&9bO1p-!pQn9>%6>b&7KVJNq+>sC+HZ#eN_kjq_TzZfwBOF?14BN< z7>-x<{dO3jB5i?-WhJ*Z-)U& zKJ03j+EvqjJFNtUeDF4K^L{%FP~_1(UMWMyD;Q-SjpLPPgs9SZ73w35S55ov^ja9y zM;x#8h4H&=y!vYzudwA&%0so;I$i~hXGjk9UyfI=boU3bkVM$%pcY>yM`A8CXqVmptP7qv?4D7>bJZpvo|=qne&)U{wS|K2&ba>p^UJ zl=9I1;pX)q8qbid-<#Kio&iceY<8aVsILdnc)OByXFTTdGV34p=NZTxlzixJf2@zD z=NTwn81i8&@AUq8)AI~4K*@)mTBx+Ea{mgAw<~%0#(Mq!pl5(0kJvw&o@b!7!@yr$ z55C7{0LyGWcuQIjs!U)g522`!=JlZJgI)_mK2&ba>p{-|B_FE)=Jg;NZ&$K@Z(a|2 z1}OPpjLFx7XuMs?j4Szgb?Ai~bdGs4zB|wR=kl@3W>Y%HY^|rG>-PuI$Sw@Yyi;G! z+q-rjC#(lO1C)H6`o^up8~H_%=Ivd(j}sVZyj{t>!(YzZyLKOE+}rXf@|b(&GnPl1 zw|8yc9vF&B8qX;Gg*VpIyuEAtq62Tsqx5?y!$0eJ>PzivcI4DmyWdWG$Y?x6GH>J; z#UJg7l+nvZMh^I0yc6dcpyWfRB5d>QKg@@olR5mGBO~^lOo$4Nw=0=*6pBLgcDoLa z+jBA*1C)GB+VZyP$AmmSXHng3YlBNyL9wkdlHuz3DpMmw@Ug`cI z8qbi-i3LUReVgfTZu{-W+Z|YM%cF=k_7APL?=!}#iJ_>Z@r=@+y-Qydx7*rd4=bmw z((??S!8sH15z5f|W>M^JnJ>3ixJz0Uq49Plb5?`B=VOfPZU5>j^W|-MlzvzJ-}=~H z=0p1o=iA+O{qHrNAvv@dJC7jFcVFlBudwA&vcwn@$E)?NkF$S;#xo={uEdqFp1nFL zW&U9+*{!YT3Z?T0bmoA3{HvAI(KeP9#kSV2b~DC*r1c;g&ydVH3UPk5(8}qj>HeT+ zfRc|}teoOG6WSNu*~;n6G+v?cb|rIeLpg8n+H-wj^zjT(7k)G@8+H-xOM|lRPJIII1@IY&&ap&$2R!(nE&oiL$b|tH%;~5ZXUv$Lw zMS~B|03{zf17ex=!*XA=d|nidw<~#gYJ_@}Uk`c)DEauRjovYj`g#zJw=0>mI*KCg ziw))jw^bDF*Lb^GH0@s_i@VocFzDMAA4D892oMbk5_2CUCEpQQ_kDV=S4jOlzhxI z`>{Ui`&VeZUCEpQlkZ=71}ORXp_NlS9j3m2g~r>J%&9Tub#TD*?VbUOJYxT-@3$)| zX}sOiUpU{VzTfT{oKsWQhqco3K2G_(XeeFNc)OB0fynxYwM4&v z9gVjuIkXr%RVU8d{eHV=fRYc!n0&lKAl*%9QfPgJ~y`VWwSbx z_c{8nyUn}nvwg{z{PK@uM;|)VqB3BGfu_!QVfvf;i{ALQDx;{Q%*VC(XlI~F?2_@z zKVLmIuXkj>5>@cw8KA`8{d4Q}m*2H_1H)&ocl#FIIJ;5`xes4Ho?(`zs|+V*fKpUe zhSRgs4S5i+P`yKE^gr;uO+$TYtU!sq%_l$8pSja6 z4UBC+`I(M1LK&kYyOK{l)V_vc5#~{0OQ@svp54FnvCr=&nP_tcnmXg3$BybB_{g_y zX6agDmIo-YPwu_9fAkMltJX(P8p=II(ouVrOwHy#(9{{`qm%gvQF#U^v8`23Z*IG2 zgz}8{j2+d z{A7Rsy%y~zdC3}&_b)wn&mij^Zhh~tjH)N8&H$y~CGS7~XYnm;T6^$;29)edzW?^W z^{?1-(a?un1RtION{l_<^J4#y^Y^SWf)5}2+duOA@MgL9C(Gq1TKXUo&yc0eN5%jp zA1cG-VFK#8q#Q_WTwp{#y$``QTef1iTce45jK78y;|MI`#Eo1Mml6fdy zAG>GBQsyILfRYcDNOK;)Ok_-=IQ=* zUwR^bgGX0OowxJ(_2=k(pK#ue&iz1ESrx^Jo1H$s^KPFHU+qET8IrAUj?JERn~m*1 zdE*OHU$*(_qxzmP4oy*kl3h?ati>&K zg*$w~=2x%ZZuP6hczpu{lzedhSIo3xS+k+1@-mYYg z?Z?cz%`$ga&Wr&{K6DL^r);kI%-qT8>Krl$CA*-i4AsZTbN%a%dg6rO1C(b-*33ZX z{T9V1Pnt5hjR8tNkVEFh>3{3bn3a5>@pdI2Zll{VQ|>VzZn(?@JxLgoSG8In0uxG0V}>5@y@7@*_>Ic7dK?a`4d z-~6%Q1C6&Uc_X{pY%});%lzK&{A22;cYbtaw1ELiKCFe7XB8KP^{B3Tlx+EvfRXk4 zx&6~Ru}2-d?-_uTN3*BRr51_qJH2Xf5(QOn~KmWS7PyZW7+ zBIDyb&*=VkRvb%+M5zB`vzS|#ogdFnEKg9r_w7GiI)D2a-A|_Rs)-@?sLc_#S^E?# z-G6-JT#ayDMmWy^r3g8@F-A4p7~f1I94OfZl{0Ll?lQK6@(jtG@ECoxF+j-&a%9*Q zr>iTD*Lb^<_ulpPPUWiB<*J4)kCG+MgtR^V4T_8H%GuSG)1xGVsxlOpU7fo&F9}hB z@(jtG30V|&J)hjh03{#DF>@QTx{|!c+ePNANnryc%uBH4QCJ!>Y_`;|q(0d78gEy!`sUQN zPw5oJGrPR{YFn{%S+QWtqhv|_Kc0a3&uh+~_G@EopVl~NJVWw5H=Wnfn#$f${KFMf zKWU7M8W^C&(Ac$X+4;uMpX1*$qkH}Fajk|%DEw8U62n%)U9E(@#xo?pde+IExDtM1 zaP-m(ZKR%O>)JX4lz!Jp9nYP%6gbTT4mjUophz44Pq$2WNAv4MfcGl(jl#d`DQ z>t52vP*g(6H*(Cw7$f*VKu)?8~t%svFf~yVQnd#XdLr^VP1OYn~&|RC3=mwEBUV3+mFT8e*fs` zl3R^&Uux~x^(gWv`(V#{)PNqPJQ%OAD>lD}%zJGk9Hmq|ycD8In1X*q-IQ{EW$M3{dio9P_x@d_0}X3XQjmzj*5D1y+M? z3`NMvs>spD9o7;zPGce(Z&xzs78k|uttGZGKv9OA5L@()`O4_{$?5t5%G;IvxQ&N1 zt)&#jfmgoq$JbaNe02i@lziA8M>t2iDE9q&@8UO|IXeE%y^alQPEfK7s>)FAKedrz z{p16bXGrG!CFIDkI`7g-(0IF&hvzz5E1BHJ z03{#D(TBC&F0CDnw~N2nKdiMcXk#cs&fi6jK0avU;Tfq9qVaYmbJF$13{aFhCl43J z!>5jp9AUY5jkhaVZ9(T2+Z{41t2PEGSwfCcrIr|cpz(GktA#GKSwK;oeBkX%?>%*N z{KyoQXMmCqMy2TES0|5-FG>tF-mYYRkBqhv4wM*-W0CPYS5~^#>KtmJbWP+WaO9FP zPU)iY49U9MaiVomn2$yVC}oZueH>w9)tuBy(0IF&HO_OQby2i2K*JLiQXhdg>|&Jac)G~RCXcXc}V z+-4b5+88Qn&L>BXKGJL{_(0?BN>*El=eIYl4P@7&R8~WVyrel?@PWoNlD}|*dh^;q z-aRU{tHh8GKT=yBLE{;cHQyc9M;il_d?3q1QPgMpvgPeYf5Y?J+ZmeOyLMHc_-@aP z+Nj`X`mS9C6#ioWXqxH6Q0zjHM`S3EkJ(6lQtE@Cyxo{b95IA%XQ-sziT^>4jJDAS zhI}x_M23x`BaEV)*)EixhTt4}(!ru4-t! zUCErxJ~0E7d>}`LpIM^ub|nu_e6P<%Jp+_{AO{~kKeI&R?c%R_F6tTb$6ORS`mi1~ zuoYzJ=V-iL$tuHgW~pA=$N)usl#HIu`o@{{f%0}Gt1akT2eEY97@*_>IWlbaI>PJ~ zjkhbA)BlU&7Mo?XF+j-&a`fSMCeV1hlKF~(oe+EZ8JDy%K*EESje7$_<|F|N0lbzYxPoENX(kz*b&+IsLPTXTAiXGrEmd;3nq zRcB6aV}Oz+iL$M1*v?ZfwEpecIIIr<`C96c@nVH92 zb>@^d1}IrVj(J@CrP1+6ZFT20-mc`+Hu_C}UG2y8^Ev~Re%D*y@sv$@ z`I61TmsojuTarQL4Enj(c!p%XGafUSk2VGO@*?Mhy6uQU2*ZS)&!C9^(%>@$&s>-mqDpwp(o*`Mj#9whd0~DE;j2`nu zukm&ztJLGE^77Hf03}Pv!WX?%=L4_tb|tIz#8c%(X=8wrC1l};D`Btkb|tHS#5}CE zPiF00XMoc0$k9jYgCP$z-mYZz&9ZbW*ALGCB_GJq2PF+j-@ za`a&>v8$HoHQuh|`)=7Mwe~}gpEHfMbDaT-XyZBb@^YqKqs~Y@%8yqt$Z5z(r5pOW zXLwm33_1>5B;UF%es0fT}Vqjh?mkf$j-=jb}(!gs~4=|5(t*07bNA zudR%UpuAnlD)r_u(KA5F2Xd&v^2q_O@pdJv#l$f&U7giR7=40wkCLS!Ltawb4Gc7% zAz3Xy=3%XUavKAbd?1HBDkB^kZ&$MVW?8ze3{dic9DT6b_8M{|9S1f2eLo(lpn3w@dK9D2BuRqXuyZCEfv3Q0eWW|CU zefSj%8gEy!N~C$k;u)Zn2XgfB#xq7ot{BergDr1Y@~JjQjH`*o8$3GAuUN3FZF9{UdO9KO?|NGvrQg*HhM9lmOQR!y816;|jb})%GSZlsjc}mEP;VaAV4b1U zDM9HJNkt__Je^Xx*T+O@JVUZZrFholL<~^!fgDS>J|@bRw~N1c*5pTPyExeLDDsF5 zc}bafy~Z;ntK8yQlM^vO$r5tRBh_H=fyUdFtX8tzRur}p9=4K<0ZKm9-s0($@=_lY zWlMHJ<&4xnf)7xhAz3{tW}fCg>K_>clzbq^%u}xo3^d-ZWcB|_edw-C#sDQB$k9iA zgp)0ASMu;H7)@g$3{dic9DHPBA}tXV{)YXdJ|@CY?DQz)=p&WYfDGwTpyWek7*Ep` zr;P!M`Y0LY9W1Z$b|tGV#M5+}#zaO2P_l#^@}MP#JkWT%lGTnU*=|v#wPy@a@}YiH z=26tgM52NrA5})`=fMXWkCHqb;jEREPa(;>=DRwXTPV#eb>_ByM~<2M`4t+^kgU0= zPNANd0ZKlQBg5t;;VC4q@pdI^B@@rt7N?B?N|unL51y>?8gEy!)@m`2gKU=3#sDQt z$kB(N`=If5C2O4+&pj8XjR8tNkfRUVlc}t>Wy{-@taY?%Hr(^llgo_^Q1XEseDoeQ z#%6A{O)CK+bN)BK2_|*FPoEiirAB;-T z$8T*#bWm!EXuMs?{2m$g^*JpO6cNTgX!EPd)<41%Lh^1cJbd{;C~ITkI|TY2Ir{Kp zA{x(-Z0#z17i3}vDEUB+44(J#8gEy!wX5{)0UNItv@t-*5_0rmtJLtErPp}7lC`HF z$3(jmx1fyyN|unz%*z!d8gEy!?o%|6iJk#UK9Hl2`dt~uL{Rc!^`E|Jp*nA4fRYd7 z;G;4oqVaYm>n>1i?KgaDm1*_6GPFcci2PAfRYd7ScCPuGK_GbfCi# z=W@KluGm#Z+Xx4W2xA|#=S%c#l%7cG%KK}reclg31|w7YCGQNVZj2%3MC$ z7@*_>S@?2iBCJ@@c)OBqZJ53oG7$rmd>{uGm0cV(-mYXlKhwO6;~Ajj13CJz)?RrQ zhm|lW{HaaHS$G>m{^(K2(MKA6LLWrq?MhY|Ht*ti1}N%d$VfF9e1P(HC95qA_hi}_ zpyUHN=8;-r@PWqLm8^CgcZytV&lsTOgHb8^NIfbr(0IF&`8_h)MmSJnFpk+bC+&)p z);QrlCtpMmif=Y3D&*j!_jkLVA2ui6wM63?k{{S-aeDW4-ZpDZwUJtDwQ&9L3{djH zS0!{8dA%uPw)d*HGo|5c1+vSx4)i;6%-r9pM&lWh`F=xwr`j_>$p>=u@r+$Ro?b0p zKhSu)l7BG!`ss1Dw9c&4mRM^q_sBd06q(0wTFA?{jB!A^M)~@HAs_r6qiU-`P-0N( zq0V&|Sy$&!=X~=;D83k@sF0%%i>gahXgovmSD$@tS{0?tyX+2n1}OQUW}^=)-7ckz z#@m(5?~&2gNLY$D#W=mRmoe}f&yXByHhjTFUfLL- zWC=M$)k}La!3P>|SF-YmU!qB?BE8d)F+j-&a_~{yAK#k@3^d-Z zIr>N|$lwEww<}p~p)6gMmEH!-7@*_>Ir^{~?5YO6#@m(r%-kuR_%3o9eY6tJ7@%Z{ zUJ!lQ2-jtVL*wmA=J&{G>rtSHaM;gNE9uHRUtJK2uRQ2?hz#>m=~1A(UCDeGBxde= zlxKjV4C7Zx^fBxpZ)x8Q*8zi-bMDdJW9XoYZc4F*HzMf z`v~_~_(FvkeBS~_{BDLaIlz3pAzjr#c?SMgTKla;6Sn=QVj-%YET+)S2DlH(p4*IYKfr4puI&#nvn$` zd}%`{zU-l>kOQN4#fhWiJEyz)Xgou*&Zb&6a+bBLH!pwpQa_e>1}OQ^mn7nsPvph- z!N9PuV8|}t&=3PT=8;C~5wGzK$$aIb?6n%(GX^MGLXMfg%Ci2ojagpf?MlAgvW{m{ zoq6S!mEA#Xc@)vcZ>5-*-jy~=pO>!ZzCN%kHowQH+G-G#7?gUxO67|>Lh%J3MTHzo z*N+TnJVP>H`IwjiN5uPoFkAK9YQ(@eIlQ9vN+|9h4Z=)}HbRVeN6NWQ1XEs^RU%+IBCjjyj{tBUCGWDjXRKy3{bL!9DP{-=+ZyX zc)OCHu-dEi!Sbyw&j2MK^n&Qa`gxarj>g-S%Ir_Ng;!g~Y_{VQXyvEy=%=cd=W`L3<)TN|unL zkIx_X*}=@6FBtb4Z&xzk{E2zAF+j-@a`drmtAhrsZTqr;*Lb^<`F2tC(Z&EJOUTj3 zq>=3huf1Tm-~)}fE17R46~&Ul+LyF3K*|rK*hD9|(9_Axxyj{tbU;4t4<*}fR0Vvj1LDQM55Y$p>=uaqm_Kb&J$L(0IF&`HI%W3{dic z92v8Z`)v2ash^|qb|v!-rZAQ)Xk&nq59H{>MxQR@6&i0>GGCtxJ}z!!fRYd7=)=a{ zF5@m5Z&xy3yPB8*N`m?Mk-meEDU$qG)4)k`LtQ!)6&H%uCRCyONnjg?Y(>HU=p9 zK#o4zW@Mn`gSl2@9CgCz$Yr)B)K`Z1vXt!VG&8(ukm&z z^Zl?`R&5MWvV>e=jChT=i$A_mRTRlb#_-=ILykVSu^pVgty;)Kw!B@*Dnq_%Wl#OK zFhI!?a`cgEF!(^@?MhZ#h+i4AI^VL50ZKlQqmR@QgAX*`u4KL$H!%a0d?1%))upV^ zc)ODMw%f!EQ1XEs8CHW`YgeHL(RjO(`DWb23{dicTw#Q^i^ki@?MhK)3`Hmu zc?=oWqq_7#P~NU&m0|oYnf1X1Z46M<$M8#LZKDqi`A}Pk-&afRYJ|~;uc8U16M7i0 zkV9GZ%*Qw*92(D%%y;l&>9#RIDG%i6!;d~_yj{tB)h-{eJOh+`AV(j5^g-k8O6J>l zF^@I|DEUCHFhbi!kj(0p;yVR*5u^SDpci`WP}&4TiAM7DXEalzbq^va%6QEiw2&mCV-*CuV?>59A6Xj6P_*UHlD4pEQbQ3`NLzg&ckO(FcvUD_LdOJYIPQ zDC%Q4UZpx8c#XF!S#2SXSGE-%zIvkgw0q`vv;AJUzA6#-`s$2u$KCFlh|N#Tg_1@-JcF||^E}Xq!P%d%Gan&y@53`>i8D;AW#t*5qQ7_=Y95u=0PbYfa6+sY zYB9}Gp-Fa22B*{JK0E^yKIXo4l^M+pX@v3&&f+Z@JxShHj4GbeEBSlRUp1zhEg3fqXov&`=dw=B03|kUI%m{-6n*6nN9@?yaP1eWV@b#y4Y9+}DAC*!Jp+{3LB9OC z1|MijRO-Qco2%J}XMhsho|G?7peg%cPa1zlhQ@R9(ECQ5uu*L#XvFpm$xG({u9`>i zQD+Dxw%(iKgpJZiV4%SVjCJliu`_$t6ICCfK0E`I*!F%yI(4W%CZZ9_GbqEnm3Rgy zvF%-lY96A7sL%-I8SVAq?^JW&QEW;&j|z=Yp1~c=3L}&*cUi@dJo|y$Lwz(dLLO-9 zjNk2H_iLxzQLT^Q!!tlN=FwApUL)BvPMLdlOKbO;gThkQ5`zz)dHs&EN}*C#C4=(u z4DOOo%mAgR9)IBG&a=P&L4yx8LV3pUuBB_cAu7)RCH5|B-QF@I^C*9pw4H%Qc0Gf8 zw|VBC0ZMFUI5`82P@bV^c`l&t@eHlJIHkF~ z4rUBc^4DIvXoT_%PKC~+@(fU7Q#UySjZmJ!N!JrIK#AR6=V*iyL+7_kruF1L(9{`< zkkiqG_ zRGtA!?Atg0bw2t8A83T~3`V8ghi8Bi`xm=h(^)+2`f47bU7-=mGbC%@FZZD}xpp(f z(0UMA>p|X%uht-%Iz#OEUXiPh5LKPQo~72JIwv5H3JpGBu=_bN1C-cWA#+MWH4ijG zdB$Gvx2WbnJ&dX+Z{C(-E$15-GH_!UK5A4dvXE!>lKk2OB z4*OtF-n_;~BAK&O@~E)oQIbD+^f~>?y`s_wnmU6sU~(Ux0ZMFTzW4`sG~_{<;Da-A z=J!u)DJx&1p{(qr0Uq~hFvAf z^OmY(qGx~-`=LWO>EAl~iv}NPgz^l#c9rK8Reg8{D6u(VrL4goc_?Y9-QZaE!hPnnbT-;2AVoU>`MO-HPm^X!Mvos zbkX1ghI|||t7-02X9y)WHCyIUM&mR+vtXS2S* zKvQSjvH7oC`nk^J(77>U=uS2BUCCO7=b1ly!u9=)uI>iLJ9oXk&u$c_dz6fxB-uqH z*;aSuc|uq!84>~mO`T!u&v0JK#0*ekPny5DUs-MU@Ii(`9r23geXR#1QzE$!G<8N+ zx}^`#0426cffIqMV+k6eJcALujH>kE8KA^gDP$|J&`Oj!E7MR4X+P0cljV6bWmJKI zMs__zZ%a4tMtKG(v4^Ls)UO7zOY0Mx^pmu4iysQ(0CLLc8(|P-4#=`%_>0 zOgRG$v2(r?=Sh`}o=KssJOh;2DusC)zpv^eFg%L#X=KPp$OBtMrFB1ytUiJd&+zr} z&^P|x&-NJt1C6&U`On*~a$V*lM5V7MYd2FU|Mm1At+V=d+ErKd)pmuZ&fsa7lF^eS z6q-7NFT$4$2^j+vmh_ZOGlS=EJi~txI^@ywK45^758J=KF1ynZN|#a;%GU=aQbtw! zKvQRk9lsUtN;hO)X9y)W^;G%@f;2vM|1In+k1{GW*wr^6i7?ANMCBQZox2W_<2e&9 zk5E>esvx^|52~*_N|No4&~?rCim)Y=Ki2}^mCUoKJcDyICT4(YjH)av;uXp>I6)-$ z;TfP{$1@;YS%o}&S^1MGD7Vr_85J7JN@rw9RvEV5yDRGelo)f@`CDIi7jqwIyj|o) z>mD#<1gbO|sr5w-WbS!toabvE)v*Lkox!tsWmFPES$PI1u{8$sRm9RqU`V5H3<#yn z6}x0v;`;_w2AVp9a%+xCwqVfORU+}L3-vlj)5K`5LC=tk56xHjqGvS^pSiAAD{VIo ze_0KNvhwBQ8SSO(8KC6j#ZL!vDO+4e*A`>t!< z-fwmWbW;HhCLb4Z+^YjR>}jk9d@7Y%u!5y~^P>f_r^RUe)KN^Gq~`EpiZlr>1a zLis#0hKf0qE}A++EBz(+EFI=i`tS@;ViT<_SM$*7j;GB|oqKjEYuy&V!dGXYkzLQA z_2fQ01C-d>d1)?PG(vd>ttaQA6pX!3PZLsp2E_D6P*aE449X)qnF- zdT8XsGbCqEu?8P?22ZrAW-CwWm3g4S2Ml}Cv7bFP8GLvKsL1AfsjkigLuH~bsS4#8 z_QYPl`AI;}0426cJgC8je1mLF=h7LLNdfUV&1Cj6^v@&(qHSrxhV8?bh=&w(dZvRptydvg;W{ zI57hh?5XSA+u%cXr4hQMnEp z3QLtY6e>P=7XZ6rv|l;3_cHa{CkDHL@$=J$vX83t;q7|HvYXDUX0C)n=AHpcQH9@M z^6Kmvn?87E|E!f449lt-Rl3%Kk`Jy|ilut}@R@5LhB>45wN_r$9r_4V*+L`PGqk%? znOT-mF;^4A&*3tLe1x(>Q)gVW$&D>Dea`^pqm||A_1w2Uu{Bp0gL*0%60#cf43$Fj zEF4?13raGjp8G&kXXwOc&15HLfP&3e#;Te7I*_dM^TeRsavx}f@(fPpo0tJg?EXEs z_m>^{WW!zt8lgPHpY~R5yPg3`?EPQ7JFM07s65J_DA&$FLsb3*yXIX3&rn&hYw*b} zmiHHqZQhVM8u_R*W{z!M-Hi$@QJF73^2xAAA_hC#>~iOsqrnFZu`ACMi5h&=8SKNV z-&CG-Dj90w?C<###?_`PJKH4#jiT}lS;}^VLsXstN^JGCV}5>GU#6?A1dUL2Ms_!& z?B}wDUG8RRL|weH_AE|dps6#sZRF>cLCqHuckRfXDfu_!A_u(0! z#D4hDO*+kYMr{^WJ{4rMu<(^BF?d=?u~b_L8lmcpZRXxk&7EPhXzGl{ zJc19;0427bXSwyUyBeZGBa~-QZk4El51*~AUcy(ue1s*VC&_Chdxot`(s#+4N|*8h zCAO_`JC*zAr4KYhdB(Z@)2h#^l?+?4gfFj&5uRbPF+{SSTdMT)lHpN$yNYKGGKS?H zGe;x4o?$EG(8h$Twkyv7MO2kuD{3fRG3Z5}!PlpR%YDEAg^%VZw&X(^p*%x5HQ#af z3{Yb8v{)XMuQgvc?KOx-c0GeK%zbzUD6uzr@XStSr0$99HIh9;@~z9xulA_2J}9ey z+vu#0p1*-zsln2RY*8Pc!CTFWrM(70;iI|j`q({#Cn%eJa3uqUk4om1JfsoIGbA@Z zd;Y!`?+$Oci1CRnmUlGYk*p_Ln`cXC>I|`)=RS3YQ21!R+b0I|9qfuRcF*k{&7$(M z@(fU7@GN(Q(UZn!?jsbtGT$vr7Y(s9PZT@b3lBc(4EDl*yvdC@BeY%H(=XqNl3ne} z#Mbls&8t*2LV1SG0LyPLSNou6 zfD&8pA!u(Pk4h-5`|!aEQvIW{`ypzm4>Wa#N`Y^zhp2i@3{YaL)SG>v5vtCJUw%)c zPwB%mB(tN_es%&HB7vdymfiCTnR^B(u_rBkxKp`fqQnCOjZmJUr}3Lt+nxbRY~Cf5 zbw)gmy`H&eNES-$ z_NdTMJ}|<&*5T~vx)09)CAO}?%a)x#EL|lO^6)5s?n^rZjqKJL+1c07IxGyVE_^8xi2#?r#S3(i8deK=g$9(*;ewl}akh$K+kVb638>Q2FCM|lZfq|yZ z5WD$Ji#me{@3N=Eni**D0fVD&hzp*%zP4HeKS*=-ah=^92E>u z_|RKo%?#cj^9)6+H-;u=fRYd1Y04RBgz^lPo8HHom;p*`)s5cf${GHdL_ICE(8@@R zAX_=+3^XMwF|57yo6j}y3{YZo4>Udl-S2xE7Z9SC8HrZ^$h>T!aNTcpyY$MTJxxQH&iJ9 z#Y#rkoPnm!7=8n^Ub>zEN^Je!T!UzY@(e}GHxBce3|BQ!Vsqap&%@twRm<0x#l(=D z?GE<51{nt5E6aUgOAJtw87p%JnmU88s7=fOg^%pH@YtiSe5UW8R@RsPVEo^{&OgSA ztBT_{g<5OfE={9de^hZL5X42u0s;+hASg6dtdd4Tg(zqsG&ZKD*3<%hYeQ?=gjUm* zn)<6HiY}$5Wf%WodC#N}LTs9_6sVXOqZBle)W({)(TeAL?|f#@%)DLxASZLq=bm%! zoxL-2=gqmbb+||6Ih9+9!T8>8d-UQYD9H{@0~^P^`T@c+Sds*Rf2EuN<`DQB^fKp z9mhOoj;2cRZC2ffC$JLD`Bo53Nz(Wcq}qm#Gnxe3Gl_#(gZ6i2d$y0q*5NKrOiH?6! z(FeOhiSQNX*@? zBC4h&wS`8qCnomc39LlhXdb>}!@6=`MIUHI52Dd4j#& z3Zf~=w+9{-yB*gqZ| z{-P1zT-uY#3XNo~;_3T1JSxHYKcBf zd7L=4roCfv@`1*;E1Bbyj|WyF=;=fpee!GV{(%b(X~?jelh#X9J%F{}-8^){h#PYP zjVC1Y#2UiObDPgzG-6*f`S1i*@{OFL`t0$$+jA~G5u-xm+Z92LixBpF@2f)_jX3=G zM4<76WS-SSSUGLi-c3gA?Lc59AIK@HxtDgdXI*zij0%l!SHyTVl96Y+hUOVDHZ2io zJRzA?iV$|qe4@YKh-W$wSjmU#<)kV%uiWaAyvl?ZYQVd>_pW{e#iYyE7;mt$0RPgPVsB|=4ooP6APa(esq zx%E7-k`HQvhH%Z3&kg_5GXF(~%(3!0g|PDjS1)|vvBB2vuiO=*;t4`l)PYn~M4O`8 zuzRreMoysdgk+8yx)`Z%f0olVtm?Nv!LusEF2x$KH8p zu&b}N@e7H-N`&r~RM)pmD6Ze%(AT>3`R%pLAw-Y+5OK)*YFCH8!b$}FCi@V6+}+n& zZBcpel6_9diAeu9OPPB@GEbJ16IdxK*_#YrIz$N^i;V%zv5(Ead;CaD=OueeJB%~sWWD3-!6n`j;GAeTORl1vnU#GRgUT= zdmglVhKzd#-lfXQzllXoKJ4n8adk%H3Ca3;B-LWg?*KCH06c+}GN(t954&<^TshJB zb|rH>5q5RXxH_ZpR+8zrMA-dR#+@baab)G+6(T3X?%^`-;m~+OGP`5gbM2n7p=m~Z zI=@@;1XjwNUQa%z8ZqNYx=%#o+m+1mL`*b-Sc#z5Lzw;Q%`e!Uel|0|-?cma_@+u$ zb`KwSnNn2rNc7PZF(W6?ctSGAQ&bc6E>WkMjW#z zuPT9+j??SOhdrxhdRFrq->&2`q4ChOT9v>`1f!Y8<52JXY>lmDNRz&mNxKxx>B>dtYy^LsuK{$jk`KnFSZBysXF%iIm8@AJ z)%VHQGBT}Y__n;2WX_%t9{A1v#ocq~XJ0>F&fI4!!oN`r;iUCdf8JMUJRzCmsdrnq zcV}I;?&I6?Ryxj}iXk)}eR*h)5wmgvjVC1A%2d8T=f0;NU$kz0cNX5Ce0TyY`Op=W zy&CQMF=e2!GGB+|-IlCu6|eYh19BSkd4C>lyq2#HqVa@e-TOQdcUV2Y{P>Wqsx??o z^aNJrJj_e8=lp16+xQA(%+R+hnVeEo|F*t*Jzpb3n3QW#m8!%jHKo~IgC0Q4f z!6*=Hf|3c+K4TDwoJ`ISOcpt3zxu1Idj8%sgZU~1^|NBp8 zFVC;mjnoA{UaVYt{NIa*A9$ei>OPBTdfD|~=sara1vGumx^HzVQ41jwEIH?nPiKQZ z=)8A3x7hbJP4_go#hSeOzhOPwUZS z0|aY1J?_xidChC?A4u45?vbWa)mYMsNHwojy^Fk@hL-zn{U7`_uSbm~OtkmaQA>{> z=57A+F*jU z{P*TkdA=ySwOVQORqJ}dyGfE0+WuwMOVn3PST9j6r_;;;H#vbeS1($RDQQIg8(-yw z_OaHbQXAHHHI1@6o%LNW73Od)mCX{`1~xM^m&#{qm9!$7+5_HI8z_~{kJ=tK+qI~N zTSs0t*Q&4lcjT1!E0!=}v-bDcKwhlnbn+E?x%!H2c+G9BBp>Fb@|vR_t%&A&FyU$T zTXVm1k6K?!p3c2HZ~BhiDBH(REM329?1Ej(_jAsS=m?u_k@Dn+fkF(DFXL<#_jYK_?D?X=xH;#MLToU>k}3fkk$6VR4;$agSY!fe*XncWKh?%l8*eE# zm|#hj03C_rq#a=69vO>FAnjW9p%18yKVG-3=rX~QDginY=ufbL-ogaZt~GJ{>1t#5 z`F0RpCRkD>Ku2Oj85gi|g^Uv>kan$$FS@HYy{X~0%_M; z_5N{G4<=YrCA@?od@1u3Y`|AcAnjUjeY8Eb2NNu*5};EHstvR`6G*$(mg}veHc~H1 z1WT#}=+qPIs0aEk6G*$(SC78c*%%+vcN4*qDgioKu6-;pB%3?o|JKd)x-^3y(?CrHLr9LcS!q!3d#$rUM60C(ZY{Yk*BjW56z7`uSVZv5UR;qRc zYa!jJ#|H6f5N;M`>ya2K<%f+Iq&_TR!rMQ- zLAE1U%X?2G_Lg>ljpxJ$OPKI}981-XU@ad7k$6@56Ku>c{fi|`_;`%o1%WYGC0NTx zb0pf$K1}eu62dz+U%f0N3vY_(KgcWJnHaCX$A0yy%~val&!FW!jtP6`wB8P)=riAd zD#2QAJC2WmHecN#9$*O*(*AhIwQ+7ls1mG&G)f!it6$rE^_7&4B~0)>N(e@TD#2Pv z!$zF1gwVbVf+b9dy;+TVv?Evx=|(-I<~jyZbCxh6ep4ICyDbUULK-$AAuXr`T9747 z*iMMeJ|LvcCsqm8LK-$=zmlG)HqaAU!i3w4y}cd5T3*^nylL~*zvRCxVZ!|uM=gk= z&nXkD1Z%n1BeAQ^SIz^@xp$ zRf4sUhK*G7I_4|XoFz<%-_%C(u8i|j22=^wLK-$w3#yIk?8Ah#zuJhs1SOJJ1MMkO z=R3Xl#jt&fU)|NO3#)LXe|F2tU8in%efmA>JK>Vg-hZ}mqHEEo3eO3@=fr&vmYUb2 zn=aec_lgVY@LY*ANZ-#an~T0 zE3Y}MvzF5+VOEct*8`)qg5$cweSFQ9&L{|#l69g4cYb|0EU6Npjj&aQth4I=j)VO@q@jg0+t#(4+5o|lD&Zvzf!>Ph{#JxtK%}9C zG~3PzmQ)EZVF+^$%J{b5?J&1 zzfl|51w_#O4b?~(Z3FUJpX!X<1EY5X2*&g(>ZB4Zs@VqJU0 zvr15)Ni}qkH!CI6hOxUwsbIRAdOt2QxZaV~Cg|mbSd$yNpEvmk<)oaR& zwQS8`guQ|OZ;ch1udg^S)^e{mR(-HxD@(Nj2@`y-s%z1-PUO5;3u*W&twp5=hZ=0K zgbB$B?;m!G%|z2@~QGwUNA=*6o}ZYatCAsRh-BtwocB329li zk$MS;P$gIk=|;ce_b8Sy;r1GDUj81%1Z#Oc(umSh*_*IhxACE6N80@s--P)MlJjCM z_hEW>Mw|Pau-brx37%I%;C(pJ!akMGGPc8_bCm78*nGvigDhdf_D*cRYDch^?YtOa z`=SB6oGf9&_D*c};eAmiSj+ZgjNsi`mM~#^GB*3PBUlURM!({HAC@rT_F`{uN3fQc zHWIvl#S$jmZ*kP}{uL9f$QHx`@2lAmhBW9 z!Mn~ZVZ!aj*{2=BT5dZMynD_PCfsjv_Gw43misUg?Peb)y#3>9Nlr#}wS*NWzj+~z z^&H-|{Jia#+l`fXH6~b6B|t}F=Zp8#nY!5Yy`CqZcuDh}apv9y(pc#sJ^ZqF^!Jq~ zoFO)tU`dq#9f@t9+)8b{9agP_aLIC41&uY>VxK=(Y=GGCrP=@|P+sK41k(5&blm;N z(*SRftmUWSc<20n!t-JRX^&J1;X4^g%N)C2$6IED3D?5OIDW@_bO>Jvfl|FE1WPzy z{0=%2h%o?x_j5l#M>`{pe35QXu%t>fN@XYR`sU*2=jaVcLknrPozCc$U`dtm5{B?s z+jag}R{DN^{)-QeE|7*6(rh~?SW+dtgz%C^0M_wew}I1p?5e?|IA!N35+$GvBJgRr z6TOZ(T=(Rh&I#8-zMcl*wo#|{1Z#2qGNQ(%@)3+vcD9!hfhA1%j1kYzBNJ=R1Z(-u zOFRuHqQ(;6JHdH2=hVJbOz<0PdxEvxBhB7rFLJN+QpG3>sz>q_BuwzQXZZ zCs^XqLfDP^&q~FF_uUwI)~+6`3zv!s*77kQV~UvY z9*&;D`#!u&74_X$EaCk!&M6}TOPKJSntKTotmP$a?ukA#RQHWNr{)%9iO)XGE16cl zLS8<@;ThF_X7KW&$GJV<9md@L{iR~U=Ps-tT6-6Hu@-wIgu};a99g(@p>cH|AO4iV zldSpq!G!l8%zdDl@TX`9LmnBcYlhyR-&wwJ`%A^KE1p&Mo403yG}c;3uYOlt+x1(2 zFR91zLfmoQB*E$2$Ms^aX^A!`U<+ht=YL+nJ_U_tt8Qoh!$>N;I1Z%ku z)7+j2mN4OddpHcJ*kFRSye~A5T9z>3?SH^S8&qsC!CH6{q0M8IUTl$AbCxjSeR|!k z5sll9U@bhaV54b$67JmFxY`8miECg$$-gc55G-L+za3D&~Q2OG^#PL?n+{llA;`0-kMRBSN8T9{E` zqxCw`C9R0QWA}_UYVKXm%hS-pGpcnxSi(dY|LeRS$p#awg=ZpcG`B}4p?sgaZkQ6O zJ(3M3SPM^T*l6xoEMa2oFMBDG`c<;Q1Z&~R2^-DhgC$JNUSYBlX?!FbOt2Q7)UeS! z&RN35MX#@lMG1{17>^#g1)&sQvAVvQxv+YCgSuaXTWSSvq?3(^g}C$fZz!)9Eo zr+v-yE)%SkpAU)+`6tdLEMel!d3|T29_jf}YelfugmqU@V(sCJS4J)G6!9v9*C<*f zFICOwcC03R*2cQcXH={{G9s{q3En|cqUQBrg0*}`y>8#rDmGZc1lKRO!31mhjJnJt z2SgjGR4ielt*-(Tto8GrI8%2V_EWL((#GePQ{EWW{jTmxbqpFFUMLoSYCv(^DHqM2 zHR%~mhcIf;7dw~5jF10Yi03k*Az@;}Q^(J~{Fk>Gao%Qgil_G+UF>qw*zRv89j}qr zTOYhqf%N;^K3iNlaOGmJ(;vq9PSN@4@?v8%AuiZ^bg{D#EMa2JTOOMA@{7+E6HZ$} zh*i!R-*v7KlNUWcBUo$yzGH5Kja$CyE5y=59J0^oVu}zfVPc0%cD?QNXP+hUunSi%ICR^nuY zcu(q4C0L6~8^Vm`ckh{Y_O{wf+y;8dQR^&QZu8fNwU^{=K2?b6MzDm5+fJRYeE+Sf z)=PAR*j;@u`^x7RonERP_TEnK+M)&HSrHL(15{5y3!ItS>4`=$+G&kN8#2K*>^xHQ z_5KEXQD0^Tefwew6SBXreK(%Uuni_y%lq37!}rf^)L6oVlz}2M*#;A=wcHbD4}-77 zGr5hBOB(r#JtdmzQDcI&#%$ZG6E^;I!le}(EMY?YrZ$>du*L*y_1SrV+K8v&TyvH% zAvIPT-%qfX+g^CJZ`;%Z5+>YUJYC{aabB$DKD_Y9i^-^Ef+bA2-{R>~JA$>mFT@#+ z36?M+I*76;;(1g%g0;L)$C;XmiX`PL_GZCGb3K?~EgzeBN<<4j23f*{_)Tpzw+9of zYUbIqAxt@br%2@~#- z<`!gvwfG5_*MlWY_^jRB6PaMG)vjMcZz461D3&lGJw}Pgb8o|7?&Y^(QVY2U@h;{O)G#JOPJu%EEe>ixMpC2wR~(w z@18pJ_MS1aPJHI3!@Ipyn8V!*=;8S~@f#uL$vSb45G-Nh@INkDuJza>#mRRpF0<&9 z@ua%eM{e@$y8ZH)p38U#zKgqJXc zyDZjuoJ213-U8Cl!u|!@&Iy)O2``~UaM%s$H{_j@_ehY27WQG-c22OQN_YuF_(b9{ z(2j_B;=LZEp@sb6c=8d}&FW7|2wk}BaP4B-Te5V~7# z-t*oY($K>G9^1|dmQ)EZp~Sb_7X;pyST){tL>gMyZ)Mv#kx43qmr!o?+m{gVjS=1p zMH*VV-%9(JIl-l>5?;a(7KkTtHQ3-iU8G%$ZRZ3_szfSbm>Z*BY9ENNcyAhMXrVpW zw%iyYf+bbLOBljQ_Js|(MbPcLIOt1ALknrPof9mn5?(^>iFl{2q3`-`6vhP7&_bGR z=LActgqJXmJ=nk)^j$TKZKR=vG~3PzmQ)EZVF;f}`C;QVnM?TW25D$vzGB-s!ICQB zB@AJXv;%CMDeb~%P)I`y^Df)Y36@j|FQML$RvU=&=Cd@Up@ruM+s+A=R0%I(NZd?@4H37naFsgP#dIl+=D;Ux^=ZOl{h&qp$EdChV5 z>)u70ZRZ3_sswDr6W)7cn};K1{`D5bdA9cwq}g@|Ot7R%z(zc&w!Ryr@7BF1Vh7uM zd-W_m^<5>nR8;~tP{K5#G-}dE6n3zE)FREcbAlyR0yg4)yF3TAJ!CGa`^D;x%h`vMcbY=+?|JY$YwQA9V|S;BJOZNmYWikcN#&^el6d+IT>`%n~N@ z`_AnM)YUyoF6RGJ>_dw2?4h)uiTimN4Odi?^4}R|BgAYq{4W z@kDI%+7R(FOPKKXkGHUm2vvf$y!S+6y}8$m(>|qQ(BkjTx zCiwPx2q0uG8CWG)3u)L$JyC6-@3Mpm{$fE0(sx@Dtc7$oKAezm3p6B5xVL40#5_9 zdG%?)g!kk4G}yIg^E!w>?z~1fc0b^E>~icqZ@Cib8|Hti;9U{9Gg=`Kg-|6xBR&yy z2zv{0$jCi9&N3TJxE9Abgs_|0I9~{saK88*bi7k7RjA4Tv@VEAg#?juh`2x+_o$l) zKuYxe;xAfW#B5Hu<=m9^-_LsY6sbr2Cnq3bV(_?{((#PG9l=^$r`!f>9lF`b0`)+? zh#W#X-YXKO=Jj9+Vt=58h+odBy$vQ1)dM=-m5EHOIp@V%h|vMj9KXvoM07N?@a${f z9xP!3k<1CqAE$$0ii{vXVFJga?FXCCae(in5gxhG2l;ylwi#?LtU`OcQ?CD%uGUsi7N(fD%Gg`={*>%BcjF7LL}88g2T?YAogYkl-Z zPr2M_dzPa%9VFx94>Q;9_)N4vlz&;m#0kHsm&3zer4kzi+D`Yi)*r|cw7pExXG!p`){?0irOmM~%Gcy>=X&L(lD zW`ecsY|?K1GQkoi>^$<{5Ul04v-8@l9*{8M_OkQZCW5uxhuOJv=3PjbaKB~e&P@bs z@o0{o@-}A)6W$lH^K;nnb50%Sti^pgx4{x7?7ZH-Yd|gNC!;#HSqq~}Vn1~J=Qdcv zgvA}$cMaGE6RgFvgzDGaS1!Rxt`j(M^_&o2*1A-XFySRkC)I+*-p+ZkmisU}Mbxt)os7TUaN-j#Lx+ocS%v+ z`o!Uy=j+7266L+`KBIL_%@QUo%DaqF-e`mPk4B^v62qb^FT4qlnSNPHvq}uxeWA@jHW-ClR@%L0H61!v-*+5Q)^#l2vA>#OAA3 zO9GHb@2D0N?d!pLvDT>v9#`(a$a#%YNr~`Jt(zrG@Sa1|g?g1>Eq>pXouX6YcWYPM z>i9Z#CU74ZdltM)!L6ASEU6OSnjzdMXOE-*v0w+je!(`F&TlW@Dn!@e*G>CS2$nGM z(U=p8{pXud&VJ`uc`LfX;xb@^3D&~zW4As}zqX;if}eDz#(o>htM`vDIYZN*TyPZL zyfq!)wv{o0?+Now-}VGcn81BJ*lzx!0~4&prHy6sdf-M4^1@eOa3>OJ><-};4ASun zG+YmsFoD~SAh0u~`Zc$~1Z#1f@=~#c3EXysjkHH5SZog_Sc|<7!U5yrUkt%*a&B{O zXZQ+z8Z9gFSG8&7;5nzwys&croQa9l{vlj!u{iQKg|Zv#td+ONmaCrKf&Ccl%ba*% zPjT|_y~?SRdFJTV zGrxs!ln@JD_k$T53&GZz*tGw>#UqC-U2ZUG6RXF^$3EPFdN9FSd8v-GnhzFY)=Kd_ z6FU=p0*>Ert?ggL9WM~IJ8vB1giDyQulBAsi;e z#}9thF;obaaK79&(N~v#K7R*%#RO}a7mDbsabjc1)$X0KrVuP)f_smTbNshfm($SB zQE!gvzsOS)XTLV2>>N?=Hyi0WkDS{n|7toXI*+`zzfdZHwosn#^mI;$R+2D*{9D^# zg0&>wT&f!C0n4DQ>{@=LQPNRwzI+wZd8t@pHk@v@A*lK)<;5j2+vMtf-5Jfi8`21}UWmQ^CzV1l)7-Dv_^wuKFrFu`?7r4l=}IuooVwzZ#S z?V$uqn2>a8O&L*t-VQTdZPK6>yH{NQg<{dCCeHe=J$n~_`}kW;ckO#Xr~N(*zenP$ z>pLbBp%Nx6Jq&aRH_3g`*Ec@DcuDpwaYs~kIy*6E@F>DPQdxBljC09lLTo3*w?eRl zi8vqE`p232hu`+@mT#(c4?pC&F1G&N<6jiApE2yAKkQnm$5KKd(y&tqt|1e{u6a)B z87IsyrR!}(Q6X5Xd!grxffr3PU;RyPG~TlO?p=sn#=S>53DDV+=N0xy2(yKFK!~cZ zm|!o2(09qM?*HkY+SNzme&jr&kW&k_!LuFP4q;s(t`(wMDkj(-o}6oUPdMj;uBF5V zYq7ojX^?ua^xYAUU8(2fXj^`kytCc4#rP%9w&w>EEMX$Iag(imF0mM4oCAOGZtueF zUASQ%jVXHa@0aQCvI>`Id-QhvbwsRKoIu*OF1qa~{e8J7aKH9;A%1bs`ZGbWgbCCE zCGPccA0bX48%(eke*gH1TZ(AoLTQWDq)on-Uh>!Dh86E^e7E`py~S_K<}qG>GU6K{ zSi%Iym&un3B~Enwvx6tSDY1|oJH{oaJ$ zoZ5E=zUavkCb)hfyl=72u)zdt>F+7JZJQN#@48gR$ahk6t|8Yvk31`7G|dv?Wg%F? z1ZJeh?e+0OVC3TLjtSP{IJpom+w}b6&oXD>RE8x?a4cR3ugL877tD)7u!M;awodo! zLl`c^WFbDP5UiEoZ@Es0tF2VIg!BD5-PK=GMiipq&!2MUpe5EXlJ%Y)H_-I(Mfw)` z9ryR--2lWxSMN2QC44KMbCSCNMm%-MJ~LUu1op`NCVL2f5d!0H?e5+G#sq7L-{|`T z3kq?i5SUX~(u#;@cXNl{-nGQfM;DLEspZ#;pEs;y$n(Xew=O0lG~SBV{k0mtls&X^`9%^&fQ@`Tq49aJ6+o2HgIy-itc^aC043Ugcu=&=L-oFxs6{-%`X=3 zim&SKE7?EnWP9#~eO5nJY@8^>xIAhuivSc`9f%U?tg;uk`63c(U4rvGd8^5(Dax49iQ z=1M)pMwi>bv#1rl)qnp>N_B`3W5mWzLU_KAFp=BXL25o&Y%IOah;H`}`mTE#PiOZ6 z`mqFT34syyp*%TR!UUIA)^I|M5gU(G2-f1#N`%lkAM|V|Z$|h+H{V$1o-y^ZlQllI z*V%_isX*)~1o{kOue*HZPS{!p5_2o56X9m{tw7+@z`&CZxJyCxPLrlBJ2*=p-tWsNst$7wXX+DnBcp%nGO9LZm zxcB4)OPFwb@lHczn)?-Nx!>Xq1twVHqYHNod?spcL6$J#Gf}*6KsIVjuomx3riI)ll?*X+ZSc~^+a>8%O;*PW5$i-b`zRjgX z&1WB$Fd_Tmx(}DWZk!0ewT0f`H2MR)li(+d(N@_WM3N^B3#i?!O1TJ{fr(ZO?S_7zK* zaC_O;bhRfk!CLOa=Cu!NdCl=fhxP8X_9<= zATQSPu@b*@d;ivJ)zOLztkK=gw^De;A+xKlWa290Wg|XVy}SEoi%lzcJol7x;15nL z{Kg1wSK03cewW+*LVS4t*ue{l4VEy$w&gB>5GxMff96LG8=4nu$tu6ZIl}xS@lDxl zg!s)fe;hJEY_NohydK-UGOB)|>{Xxn!qW1^ljqCZx1BN+Pe|M~kQ*q2kjC#JJTUO+ zFi>n5QG$qClaiLuw>F47jgYp0cWe09ZFIc2x#sKk?Dt#oyXZv%iNF%48#ZpqZL}mp zh+3W#=nz&sc2RBf-|ez%)*g0)rx^I+LEeJevLUP^#LD5C>0=v&N|=z-nNr>^i|60l zNo;H+#Fu|sWyWuWV2PY8l(HMrIlJFaDmI1+al+A)X8fvRg9-OS^woM+kCQ6|YkAEh zF+hlZD}K{4UI@!~HcDb8EK&BHSWSrG?=L*$w?eRl3G+e;zlE@f5R(`F{g4S2g0*E>zdq_3b@-*&U<-~_Vye-5vgHNBq5+;0f#aOlXgpd;%ZFeSE%hU1ZZHYJe zDv{gRQ{L#;lz%@F8=NoOlSro$ab&UP+lV&)#R)Gr$`!URWb%IT~4X{6L11Z&w|hL$8J;91%I&{DC43EMldcv0K&Drv_{`t zw^nCT*77uVxojuQZqeCpt@d`?do8g;>uK~c+f~(@fqMFiz1KQ+YgxjC+XEef?bg<@ zTgwD%**dm)|z$XO9iGfFzmC~;QA_kX-)?jrPe4tJ~g5#N&eeoUlQtK>Xf^UqaQ?e$4wYV>YV37m$ z_r5r#zn3@OkND9PtQ!$I5W;+#j&q5f(d!K7rGmuMn7iE5@z$@!0n`x(;94MZEw*8? z26e<5uyrQf)A63L#WU28-fo}iOt4m7KlzIYh5SVXy~7)7i>4Y%2@z9b&)1dGJq`Vf z2n`}MBuwxf3OyghxpRqAWIH)7afWT@-0?Qp|Cv1*o{p!;IH_KI-_a#bssl-w;Qp4* zolA*M$OzW*n#Z1KC+;PkxNAwcgm#v0cggI;y~K$-OPH_|_cF!-SmZ!Skpr3+YgtTy zJ)IHHAdv$lA_rK)ghdVzArTNIML_7>-inSf6BYqcA_Btmg@lRRhDCC~S02fsPc`=f zo@DL?#GS}D8e=4f5-eeYZHI8WwD}@GA6>pE@g?5QI2mKwTQf$aSabsVmH$l(z4gmP zxOHzD!4{o>UXl^4<-H`1fB9PwUGlde{EmAX6EbV-I|xQ_-rMC%2wnc|1eP$t_kZ++ zw@XfV)dp+H>I|`JItFt>PI$ZIgjd&aEMY=cYUyrP2(lLK^0g>SnBcoPavw(staq`d zW(gCr4o2*t%@UUjvAYmhw==<7e48hP5pvQe|JLpO1M!ra7vHX6Is|!}=*DXQ`M3&C z)|rqu0KJtG-zGK{Vw4ac3c(V-|B>4`P>8`oAm)xGOz?e^5ITgwdk(%u#{_HTHQz=~ zMX#6l1Dw8c*~Od53w)m5E6BSV6Rc(NuzF8J zzT+iP15;$RPqDR{m&McSeGH~USX_wfgrNA{CL*_i7~#77y%dTOo{dptalv}8MBdf) zL>#||FjI&Jg@AWi!UUHvgi9rE@M-zWJ%})sr;6lp(*WcZqprgwL|x0%O`q1$#&jXJ z72-u9Si%I`)6E68q$Dv2t%MFOJ=b~PVNX<$WB}{NEw`H$XOG4wc^O)^r zB+46qoqG$3^0rv;S%@Cz_;!o@<3!?MfJ3hThP90`TEzk118A#*zMBp2WHP@;Ve4nC0h>eL%u$HHzjluF= zxTo!VdMxoYN@e#AX2%-}PE0;z$w{t-yjaWA(FXDdg?g~W)5zEEI+zV7#Ku6^LSC%p z>1abd+vDFiWQnI?gYW5t-~`&kwU8HUc{R~r{tW+3-7$0h# z>Y-XzLLHl_=G{~emADpcnBUBX`KsH-hu&9$4c78>tcSIr+F*&NVZ&P1Y&b#fp`~Ii zPe&V=c~E=QgC(AZ4Zfk2`mWSN#|QeT+F&hDCmR@pYJ(-7wt8saLOP8>*qG>A$V*C< zv^<@Bg}KD*p;}c!{HARZZJ?)vu^lex-Rq;#$a8dT4qwgz%-@biz{&gg@0l_%jM={~b@e2GM7UFo`8hcskzm zk_lRC4I3^Y8^b6)Dl#c9+cR0XsF;vJ!p|@!*l?4sZfCnDBJ0IZESo@w;6p zyQlHgcLKjheIsftX+=aExX&Q_8M3Yl!B$IpCl2eKA%A^A*IGy)H~2rPVq>LItIcdhKr3G@!NxctHah<5AuQp1^LijY*zWyg zHFpB_ur+ECOT`3BS`o25@NM;@?d#l3cp6%^3O5@}u%s0cZG0r(zD86gT964(Lo2_p zhVN_Rz2LV$cwoKyQeRzim9UgY#l7#Dw^bx`vI_zgcw#OPH{?KCAgW$^UDs2NSI2>3HuBp8Z5T zjGD8=(}DyI(M(HjxR|@-*(pg>bC&!h57QqEsyL zG)l#{-Q+D*2=vB9p1xojOPH`d4lC6WM!*IWtmWz0OECU0sz9*B()bEGbn7VGk4;Y5SG&0S<(75O=B;V z>G&61Fv~qq9)=qVdh4%B*zQ*mZwYNJHm(q2?!O+H!31mNr5ZeLS|Q)#=sxDy#|MS5 z4BZ(EnnoKq9ryaY9uv3PVP-CA5Ny&r>tXnP9E_#>gQ?VD@1N6P}JE>QEyd-EG(D ztq5qj?RX}9iV$~7sjm6r-kB`ne7#Q5SMtQEZ4M?_(u#<_l4p6{ zpXc&?P4QwJ3Fhfob0*k^r;%@af+bA2?dDQ3!CIb<(QV=<-3N!Sq!*S_V}0Iv8j(j% zL>q`HdR3m#1HPL&oh3|I9FRrny)Oh}GGK!V*7DzDsbp-_ePzk{dKx8>H6ulZF~O2n zM63s5GJJ*1gr}h;Yu^-8rhl&}5iDs%L>uzdte-8<5Y(Jw$C&otV=r-Hnfby1mN4Pz zXyf-{V~5{PD=s($neUxBHD@=l#qBD&vwr#5`U1kxI^0H?pMwn!V)Iz`DihB_HPoM z^0>Z(M^5O^u~A+sS~;oLx))qlua(d)9hjIk;nEf8Z$dTFddES0U> z>sYsk(2y|UaXE3NFV7BqDWrbDYv*(@!CLGQIl+kU2K7Cse&p{TS`Q{XS}18lORb-rf5bQ8 z`hFM8oxJ{PZ>Kh&u-byDot=(v+g^`VUb(P?B}{l}W6ig+QZ4w^V>6gwEiYBvHSqSp zJ_AdbU{A;I6k%0{InlK+<9He+kr9>RS#p9Ut%z6;tSa$jvw1h=!v?8JnX$$Nj``Rbv@|pFg9+BMIk?eF62THC?8(p|Vl|`%S;B;Qw?(O#U@d#XOg|C4%&){qHX4YaVqd9hZ@nro?qNKqC-=zc4D zhKGDqvYTrMl_CP~P{vic#CL+PD>r>smsyg|pVtHHK0A z5uWkG5mADjuwiY*9$F_zi@>3#2hQs>TOvW-6e(LLsjEM>G8Q}I7}L&O-}`#L&-=aa z=e%Z1#y?(puj_Mv@83V4V+jAh|DG7b^olmD2cBBqIO|8#8^?xs?V0-Am!rM#w!7zj zxP8L`{66b=Pa`3U@y~rZdJuKjQ_G_r>Glngo_xILKtcp1rb<*-ji4SSn8V)N?jBAx z5~3^zqO^P|p?PNxL8x9zs7DEES0yh(@Y+>Eqpo}NL$Thr4A0H#N<9lMJv@vyn0)Wz z1DaCzTq&{T^@&c;zctg)v^47DZ+Pn;KXSkq8KqxvpA?1YsmD~I$x z<`BJ)^;YYNqxKR+QG3Vm+(xRQX=xN|y-uh{36^8ly^CF=YIF6lqughsLbnX95j?$R?q+PrG(<;_Q}#bE!}&W|-0T3f I|Ri;ZN&RzwkrFr_)! zW&+sXy7H3dBI~!XPhW6mbF$3?2@%wj6VU6m{+tj|gK2?a6zoxR6*cI|36$?9>-C97 zjbIdL)<~Vu`a#KO+1U8s=SqpItPW?{tXJ32axe-SsF7JV8tMc+%*hU$y=jl$f~o-j#^yxZ5 z52MgCU^AsUK~GLVuhw^K{fbebQE#J<4|))#1Zn}JtDY+*7zG-&j9Om+kCjYUIN10dD|HAzHv&qp{_xxp^(es=4(oh(LZhhd#1CH{h#LRA z`^boTl+gJ&gl>dJ!A3cJHF)xCS4WMW@62qgM+u!>Ljdt-vnOuP35|jc4POnuzVxi9 zal`N4)K-rY>AVZ#KGVnvje;G^5!a9H{hRvH9=ANaysaK3be<2P8=+CKqlT;>P$}B# zQ9@TAMDkxsXcX*@#!veqH6tf93U(|<+*5CSc_3=+c>KtSdJ;nRL?Lt~ zBnmrZXjG#%YG9nJhx=$mr8{Js8Ac^E3N|!+F0t7s5}19|qXhMQ-wwj&tHGSmDCX7) zmi&>&kMyf2A>?G?b!8gcYlK9x)_vbDZQfE3+XGQ-f8Qa4DCd%d&?xpEC#3JT)T0FZ zF?Rh`-<@H7Hz72NqreFnQ7!c-!SOgb?%TT&8pYA<1je8JE3jWwj}n|$5&}>{XcT89 zC(0SFusN}%9wj(GddX!@ObCtQ?CL~0w-+{3x74Eq=Xr0za&DiI6B@-;qUt3r6x(Ko zmU@)ndR6sAtWlUt5<;W6+Bq@oYi;q`?j!x`QG)BPkEoIeIiXQpwX0DZ%aQLgl+gV{ z2+xikXieQZ<;pKCIW{ukdsCX2Gmeh?>VZ|u&W`qi726M7@X-0q2Zyiu_=#=nthXOC z!s;q~)Clz`0sAYDeSRKj)7X1sBrZHUsjVI*E;v51`MI0d%iY{r^MQ?H8xw~Q8*%f#8(Wtxm_4}YrAck| zC;@x@-pLKu5TZrm{Nck5M!mi4#b~1rVTW*zX`o+?yfmrBy!Wlx-e4`jrk)c&w{kr6 z2S1+kGb7Za1Z(8{Lpx1lvT5A4VQJq`Mrf4gHiTVe3%<7GSih#LIb_Sey=|RopqK2~ z_uLPxm-MSg3HF{HJ(@0Tp7bISx)F>*O0->Lk?l!V+RCFIO&2!L zpSFJ3JkpI|6jGw?8rRz1YMbqv)T8Ob<_X!$(T!jfQljk|pS3;Wb*)V!>d|yzch2Yc z&fYM+8^I`~MB6p2+1s$xqv_J-tpQ>qQH(|)iobV=GFScT(R5*>1$lz(PB027(RPi$-9EE@(oRR}(R5*>C;FKaOgDm2NQt&< zl)XJ_(4*2&xQAmllYgh}m*yi+Ty0CfY@csm& zph4S-^|rT~TlQUgG+o%d33-2lQP806#7(wG{PotRI0os_bYbH@$VV;al5PZ}ph4R; zu!O);kETnTw^4|VM4U^QmPRq94pHVR&WRv+TdOw8w=mw3VJ_)LFp72M1oAZB+T%Or z+|DTEN^P_gZt+4`WBsZd!6<0ZhC&Fo;pb{UL<2F5>j98S!!o$JxD1MN@0{YGQ_E1zj>xb=+# z7hZd$amh!%-q<<)odeL|?;)%lvu2QldUAqv)F|GwUFARRy)l-Ydrt1cu>aJQLim^4 zFPgL5cCMRBg6c|em+5;^Qz>3FjWPRNgM>zD`Ml)&d-~d!jq6MH)T)78b#~!kNT??# zSiY!H^jMCbx153CseyY&oFFtMTc5UkZ{NFC>K~T`)s^5L)lUgt-KlUmFP(o&kWfRjZCm)!ZWp+iPoY=nB0fQ?%B)5OfjHcl&Rw?;6Ewd(|Ob++}X zV?BMzsYs)sfnI{s65>0AdUAq#POP@^@uzk=V(&v*O0(ztIqD}b^!AlwFrK4uii1Z9 z*cdmPZ+*jZ_4ogI*I+rKY6PP=qMSg!%9)|X*OOF*Gwm&o}8eb zm)u&gHO*QO#BHm;)I^)3{b}R(=7&Gu^!7OKkz0nWm$cAJ)T0FY!o&L)H@%lYWv-nf z*V+kE35`PAbTmMmGL2Vk3^HAgZR83zX&<$J-9Nm~W`-7K2KBH^q@m%X_9KsN{C1hE z8o?;$sx!`iV7(AC9D2!9yMD8YxmKf~$KP$8T{M0M3H9Uz^-%5*zGgMM(MFYOD2<+Y z*Q?hzeWt$sw=P0YY+*G}j}owFZk^l2O5_?pGUB~a2u7jD(00Q5RXdA?;CtkUF&%yi0 zuWB*s#I|uw>h*3N+eAtr@Vn=VgnDuU0QdQJ$_E_?8b zTh^={dDjT_C;_{p@gEz;3^t889^8hdp3#WT{)&XY zX6$-v_v6sGcEyZ?`jV1p6zWl;Z{@4;WpwkYi)}>tKhKpC8l^8nDWT=inr_-|4>`Qu z*7cO&`v6`MFTQ8$!B|&eNn@+!2KGYBT_lRK z7fNW9_L!(quqSE@YOCotAqi1vZ+O7k8g=!-d!{zE*3)vRM+x@IZ=AX~>sLx>6w5Jh z#f+3F^v&xnTl0`Bteo1iX|B|x#7~WibX+-|@e!qjMrr#e8im&A)i%D7F5b+$)^1Rb z5=^Pr+CJ4#LZjHS{&uJ3P>&KE!CR~kry5FVl-7De#4j^ZTD(pwvC>8rey>j3hI#F3 zS{kKolWH*C9o7q(L(D{^JLeB-s7DEE*S|1TLZg@~KM#7oyd3ILg1yJTFX={T6#JO3 zoJy!i3HHSLOsyUzI4kjcQK)!1l+Y;7L>Tj)CldNS1Ls|gLH(8@CDfw?=lOasQ9`5i zn~+SS{2m75Kna~=x)U0u-?pR#=P1m`oZ+wnbYE-LqXcJHtUj4W`3)4lThJ)2^^{PL z5?lwXeY;`a=1ORkwoR&`y+L~kSD*Uat{x@0cGbUiRzjn?uLkN-f_tL6h7uaZcB+pL z^|0PBwl$@+uGFIh`*eNwQ9`4%SEd^3QG(;czY254+dLuU+p&6Yx6?#FP7~PU;;fIo zGxpK6@jK4AequTO`?t;cb31K6UJ~>ufj)-Qc4vmW$~4B<`9ssvD4ai-QY=Mr`RYAQ zoV?Vdr!Y;)%S}Q(Igy^#${UuLE8Oqkc98coyeY(8hMzzFZo;HFx7aPt7Q4fO20cn( zMBx^vvwoC!G6|tkIK40>FL`+<(^8Mtu4-2=4Y-p@G;)Hi=^DQ>uCIl=SKe9S7EsFp zjn2*86MxmSorHRFf_3QMejM5N9KI0hM^7BM?+=?i8^FdI&O1QA+1Bq%)PuR51nlGn zviOajfz~d&Jy#8-ky~neFCn3xoZuZP2!H8=1p@ERcz1%0cW%6M!PXY6{?Z~6d<`d! z7jW2U55JQsH6RfQdUAsIOo&T0=*bE6_S#<$L=7bv1sXQ)=js|PA)>V8oi@*NMNdxX z7b$5ulwcI-PEQn#Li0--rG>3GMX3foIf0iyew|PeQ9}tvf#ywEQdg0n2T@A!y)7YP zd(e{;c=P0U8ELMRU=-*F?8U^tRg=1k8uTDa3B29%`;t^c2}XhDdt1F6=s)~Qi+4*b zQ~j?})B{@y-hS0J_(ltYQLyAkhTc0!aAjKc3Y z74h~X)u0DaO7M$QA~5C1fxKA&lNq0QbOM#Qw=2; z1)4QdFS*XUT*E04e-Giz6Ja{OkOrY?v17`v;W#o5@=$G{#T)qakRhM+v=W3gJp4#{ABw z`j%ycM)BnBr-}7OAXjsYP>&K?KG%5f=1&blBPUo3$SqGY_Sdqe@$~#teQ#RH)uZXA zb#?U@kHx>v{0sX6LZdWSxW$8>zx*hno}55UJ2Am-K2Y)xT)(2Ngx(I~o)H@U@}q=$ zasnDo9Q%_!@y>R$y@o5H_m{YHf(G6rZ7vZ)Jvjl5iomI`fQAyh%R&@x^g87*jfzlD zPISsK-d?Gpfx1$HH-#uIZYDeJp@e#JqSGGMf>8r)t^{v9(Q3FOhlbzQDxsd7fQA!? z?RzDZV}kWvC3yFaDBSf!!*6SqP)|-k!-?nZyAo(zU~`EQd_zDK-YlX_TL@MFyre+G@AQ>WPfkF?i6^Zcpt0H3C?#Ms3NJ#?@E0s4)RPmSoj7IR zl|W;I^)Ds((u63ym_egAzQie^o}7S&6W_3L0gV?|?K!A~zQp0>4;udWwMwWbC!pcP zgRT+2vT9FLiTp(o8Vlnay%Nk7JUIakC(4qCdu-lPg1JHz>kuz=w)6Jdjf8q~0vb+y z*V{atVe_vNtX)L0FZgSp66(nbXgGnD#@ZubPiXNjN)Fx zYgY;Nye6~7(i4V0z}yYoI+{-t+ef9W0ndVnuHJWa;8 zqU1|*{Dt(LcfUJ?zmVn`5HDCtXqo))o$ubTbO?X%tb|7K1nIYf_`7Y4K|2Y@zaGFz z7#<~Hv(^!de|~eIGaP#fc6~a#dOQjBD8aGmrwIs<&{Zv8ebDp$eC{fqE2fo??eq>n z3H2~n9Kjr29?x7Uk+iwhRV1wKQv$ai@bK0dHttK95^uIac{$WWS_#;xh7z<9r9CDk z)T4y9e@d`+(NdhXabnSyO$qfV!F9z?Ue0*QmCz{N8N~R4b*1Yd39M0CrZiXTQGz*4 zzWs<}L2_pPg~lL(_E>CwNO7tsfH4)pZcjt2`vZPAEy+p!!%dwQG&gs zJ_eQ0DAq{#x`IaujxIkBYB@A5jp7LQQ>qaKdx@SVbl1;1td~PQO6Yz*tt%xoO6ReZ zV5?!(XHUeKU`oCVcgDwudX!+T`+Z3_LZeuR)x2wvYiM0j5B0-Z=#3{x)liQTEV-YA NyAc}2dh>Jb{{Sj=b+!Ni literal 0 HcmV?d00001 From dcd940a52f3b923d934916d34bd403c58b4075d6 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Mon, 10 Nov 2014 17:40:49 -0500 Subject: [PATCH 3/3] Minor code polishing --- apps/operationalSpaceControl/Controller.cpp | 6 ------ apps/operationalSpaceControl/Main.cpp | 12 ++---------- 2 files changed, 2 insertions(+), 16 deletions(-) diff --git a/apps/operationalSpaceControl/Controller.cpp b/apps/operationalSpaceControl/Controller.cpp index ca6d460c016a0..a7c6155685077 100644 --- a/apps/operationalSpaceControl/Controller.cpp +++ b/apps/operationalSpaceControl/Controller.cpp @@ -126,11 +126,5 @@ dart::dynamics::BodyNode* Controller::getEndEffector() const //============================================================================== void Controller::keyboard(unsigned char _key, int _x, int _y) { - switch (_key) - { - case 'i': // print debug information - // mController->printDebugInfo(); - break; - } } diff --git a/apps/operationalSpaceControl/Main.cpp b/apps/operationalSpaceControl/Main.cpp index 8ae86532c637b..1a5b20a29275a 100644 --- a/apps/operationalSpaceControl/Main.cpp +++ b/apps/operationalSpaceControl/Main.cpp @@ -47,8 +47,9 @@ int main(int argc, char* argv[]) { // create and initialize the world dart::simulation::World* world = new dart::simulation::World; + assert(world != NULL); - // + // load skeletons dart::utils::DartLoader dl; dart::dynamics::Skeleton* ground = dl.parseSkeleton(DART_DATA_PATH"urdf/KR5/ground.urdf"); @@ -57,20 +58,11 @@ int main(int argc, char* argv[]) world->addSkeleton(ground); world->addSkeleton(robot); - assert(world != NULL); - // create and initialize the world Eigen::Vector3d gravity(0.0, -9.81, 0.0); world->setGravity(gravity); world->setTimeStep(1.0/1000); -// int dof = world->getSkeleton(0)->getNumDofs(); -// Eigen::VectorXd initPose(dof); -// for (int i = 0; i < dof; i++) -// initPose[i] = dart::math::random(-0.5, 0.5); -// world->getSkeleton(0)->setPositions(initPose); -// world->getSkeleton(0)->computeForwardKinematics(true, true, false); - // create a window and link it to the world MyWindow window(new Controller(robot, robot->getBodyNode("palm"))); window.setWorld(world);