pax_global_header00006660000000000000000000000064125753215050014517gustar00rootroot0000000000000052 comment=cfb4ab19b86d01d230ab0d45a61cdffef14eece5 ros-robot-model-1.11.8/000077500000000000000000000000001257532150500146335ustar00rootroot00000000000000ros-robot-model-1.11.8/ChangeList.txt000066400000000000000000000026171257532150500174230ustar00rootroot00000000000000= 1.10.10 = * [[urdf_parser]] * Package was removed * [[urdf_parser_plugin]] * New package containing base class for URDF parsers * [[urdf]] * Package now only depends on the plain URDF parser (no longer on [[collada_parser]]) * Plugins are used to load other formats into URDF. * [[collada_parser]] * Interface as plugin for loading URDFs was added = 1.10.0 = * Banch from 1.9.32 * Build system updates = 1.9.0 = * Branch from 1.8.0 * [[collada_parser]] * Read dynamics info from collada <> * collada parser fixes with inertial frames and parent_to_joint_origin_transform * [[urdf_interface]] * This package is now deprecated * The stub that is in place points to header files installed from the urdfdom_headers library (available as deb) * [[urdf_parser]] * This package is now deprecated * The stub that is in place points to header files and the libs installed from the urdfdom library (available as deb) * [[srdf]] * This package is now deprecated * The stub that is in place points to header files and the libs installed from the srdfdom library (available as deb) * [[urdf]] * Use the rosconsole_bridge library (available as deb) to forward output from urdfdom to ROS console (effectively making things behave as they did before in terms of logging, but without having urdfdom depend on rosconsole, but on console_bridge, a much lighter dependency) ros-robot-model-1.11.8/collada_parser/000077500000000000000000000000001257532150500176065ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_parser/CHANGELOG.rst000066400000000000000000000026221257532150500216310ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package collada_parser ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.11.8 (2015-09-11) ------------------- 1.11.7 (2015-04-22) ------------------- 1.11.6 (2014-11-30) ------------------- * fix rotation of joint axis when oriantation between parent link and child link is differ * Contributors: YoheiKakiuchi 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * collada_parser: add extract actuators, fix for using nominal torque * moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 * Contributors: Tully Foote, YoheiKakiuchi 1.11.3 (2014-06-24) ------------------- * update usage of urdfdom_headers for indigo/trusty * Contributors: William Woodall 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- * remove visual and collision if there is no vertices * do not use visual and collision group * fix debug message * fix problem of root coordinates * Contributors: YoheiKakiuchi 1.11.0 (2014-02-21) ------------------- * fix, joint axis should be rotated depend on local coords * fix overwriting velocity limit * Contributors: YoheiKakiuchi 1.10.18 (2013-12-04) -------------------- * add DEPENDS for kdl_parser * Contributors: Ioan Sucan 1.10.16 (2013-11-18) -------------------- * fix for using collada_parser_plugin 1.10.15 (2013-08-17) -------------------- ros-robot-model-1.11.8/collada_parser/CMakeLists.txt000066400000000000000000000037761257532150500223630ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(collada_parser) find_package(Boost REQUIRED system) find_package(catkin REQUIRED COMPONENTS urdf_parser_plugin roscpp class_loader) find_package(urdfdom_headers REQUIRED) catkin_package( LIBRARIES ${PROJECT_NAME} INCLUDE_DIRS include CATKIN_DEPENDS roscpp urdf_parser_plugin DEPENDS urdfdom_headers ) include_directories(${Boost_INCLUDE_DIR}) include_directories(include ${catkin_INCLUDE_DIRS} ${urdfdom_headers_INCLUDE_DIRS}) set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake-extensions/) find_package(PkgConfig) find_package(COLLADA_DOM 2.3 COMPONENTS 1.5) if(COLLADA_DOM_FOUND) include_directories(${COLLADA_DOM_INCLUDE_DIRS}) link_directories(${COLLADA_DOM_LIBRARY_DIRS}) endif() # necessary for collada reader to create the temporary dae files due # to limitations in the URDF geometry include (CheckFunctionExists) check_function_exists(mkstemps HAVE_MKSTEMPS) if(HAVE_MKSTEMPS) add_definitions("-DHAVE_MKSTEMPS") endif() # build the parser lib add_library(${PROJECT_NAME} src/collada_parser.cpp) target_link_libraries(${PROJECT_NAME} ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES} ) # build the plugin for the parser add_library(${PROJECT_NAME}_plugin src/collada_parser_plugin.cpp) target_link_libraries(${PROJECT_NAME}_plugin ${PROJECT_NAME} ${Boost_LIBRARIES} ${catkin_LIBRARIES} ) set_target_properties(${PROJECT_NAME} PROPERTIES COMPILER_FLAGS "${COLLADA_DOM_CFLAGS_OTHER}" ) if(APPLE) set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "${COLLADA_DOM_LDFLAGS_OTHER} -undefined dynamic_lookup" ) else() set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "${COLLADA_DOM_LDFLAGS_OTHER}" ) endif() install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_plugin DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) install(FILES collada_parser_plugin_description.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) ros-robot-model-1.11.8/collada_parser/collada_parser_plugin_description.xml000066400000000000000000000004021257532150500272600ustar00rootroot00000000000000 Parse models as URDF from Collada files. ros-robot-model-1.11.8/collada_parser/include/000077500000000000000000000000001257532150500212315ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_parser/include/collada_parser/000077500000000000000000000000001257532150500242045ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_parser/include/collada_parser/collada_parser.h000066400000000000000000000041071257532150500273320ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #ifndef COLLADA_PARSER_COLLADA_PARSER_H #define COLLADA_PARSER_COLLADA_PARSER_H #include #include #include #include namespace urdf { /// \brief Load Model from string boost::shared_ptr parseCollada(const std::string &xml_string ); } #endif ros-robot-model-1.11.8/collada_parser/include/collada_parser/collada_parser_plugin.h000066400000000000000000000040711257532150500307100ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2013, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Ioan Sucan */ #ifndef COLLADA_PARSER_COLLADA_PARSER_PLUGIN_H #define COLLADA_PARSER_COLLADA_PARSER_PLUGIN_H #include namespace urdf { class ColladaURDFParser : public URDFParser { public: virtual boost::shared_ptr parse(const std::string &xml_string); }; } #endif ros-robot-model-1.11.8/collada_parser/mainpage.dox000066400000000000000000000011201257532150500220750ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b collada_parser is ... \section codeapi Code API */ ros-robot-model-1.11.8/collada_parser/package.xml000066400000000000000000000025551257532150500217320ustar00rootroot00000000000000 collada_parser 1.11.8 This package contains a C++ parser for the Collada robot description format. The parser reads a Collada XML robot description, and creates a C++ URDF model. Although it is possible to directly use this parser when working with Collada robot descriptions, the preferred user API is found in the urdf package. Rosen Diankov Kei Okada Ioan Sucan BSD http://ros.org/wiki/collada_parser https://github.com/ros/robot_model https://github.com/ros/robot_model/issues catkin collada-dom liburdfdom-headers-dev roscpp urdf_parser_plugin class_loader collada-dom liburdfdom-headers-dev roscpp urdf_parser_plugin class_loader ros-robot-model-1.11.8/collada_parser/src/000077500000000000000000000000001257532150500203755ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_parser/src/collada_parser.cpp000066400000000000000000003733271257532150500240730ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2010, University of Tokyo * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redstributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Rosen Diankov, used OpenRAVE files for reference */ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #ifndef HAVE_MKSTEMPS #include #include #endif #ifndef HAVE_MKSTEMPS #include #include #endif #define FOREACH(it, v) for(typeof((v).begin())it = (v).begin(); it != (v).end(); (it)++) #define FOREACHC FOREACH namespace ColladaDOM150 { } namespace urdf { using namespace ColladaDOM150; class UnlinkFilename { public: UnlinkFilename(const std::string& filename) : _filename(filename) { } virtual ~UnlinkFilename() { unlink(_filename.c_str()); } std::string _filename; }; static std::list > _listTempFilenames; class ColladaModelReader : public daeErrorHandler { class JointAxisBinding { public: JointAxisBinding(daeElementRef pvisualtrans, domAxis_constraintRef pkinematicaxis, domCommon_float_or_paramRef jointvalue, domKinematics_axis_infoRef kinematics_axis_info, domMotion_axis_infoRef motion_axis_info) : pvisualtrans(pvisualtrans), pkinematicaxis(pkinematicaxis), jointvalue(jointvalue), kinematics_axis_info(kinematics_axis_info), motion_axis_info(motion_axis_info) { BOOST_ASSERT( !!pkinematicaxis ); daeElement* pae = pvisualtrans->getParentElement(); while (!!pae) { visualnode = daeSafeCast (pae); if (!!visualnode) { break; } pae = pae->getParentElement(); } if (!visualnode) { ROS_WARN_STREAM(str(boost::format("couldn't find parent node of element id %s, sid %s\n")%pkinematicaxis->getID()%pkinematicaxis->getSid())); } } daeElementRef pvisualtrans; domAxis_constraintRef pkinematicaxis; domCommon_float_or_paramRef jointvalue; domNodeRef visualnode; domKinematics_axis_infoRef kinematics_axis_info; domMotion_axis_infoRef motion_axis_info; }; /// \brief bindings for links between different spaces class LinkBinding { public: domNodeRef node; domLinkRef domlink; domInstance_rigid_bodyRef irigidbody; domRigid_bodyRef rigidbody; domNodeRef nodephysicsoffset; }; /// \brief inter-collada bindings for a kinematics scene class KinematicsSceneBindings { public: std::list< std::pair > listKinematicsVisualBindings; std::list listAxisBindings; std::list listLinkBindings; bool AddAxisInfo(const domInstance_kinematics_model_Array& arr, domKinematics_axis_infoRef kinematics_axis_info, domMotion_axis_infoRef motion_axis_info) { if( !kinematics_axis_info ) { return false; } for(size_t ik = 0; ik < arr.getCount(); ++ik) { daeElement* pelt = daeSidRef(kinematics_axis_info->getAxis(), arr[ik]->getUrl().getElement()).resolve().elt; if( !!pelt ) { // look for the correct placement bool bfound = false; FOREACH(itbinding,listAxisBindings) { if( itbinding->pkinematicaxis.cast() == pelt ) { itbinding->kinematics_axis_info = kinematics_axis_info; if( !!motion_axis_info ) { itbinding->motion_axis_info = motion_axis_info; } bfound = true; break; } } if( !bfound ) { ROS_WARN_STREAM(str(boost::format("could not find binding for axis: %s, %s\n")%kinematics_axis_info->getAxis()%pelt->getAttribute("sid"))); return false; } return true; } } ROS_WARN_STREAM(str(boost::format("could not find kinematics axis target: %s\n")%kinematics_axis_info->getAxis())); return false; } }; struct USERDATA { USERDATA() { } USERDATA(double scale) : scale(scale) { } double scale; boost::shared_ptr p; ///< custom managed data }; enum GeomType { GeomNone = 0, GeomBox = 1, GeomSphere = 2, GeomCylinder = 3, GeomTrimesh = 4, }; struct GEOMPROPERTIES { Pose _t; ///< local transformation of the geom primitive with respect to the link's coordinate system Vector3 vGeomData; ///< for boxes, first 3 values are extents ///< for sphere it is radius ///< for cylinder, first 2 values are radius and height ///< for trimesh, none Color diffuseColor, ambientColor; ///< hints for how to color the meshes std::vector vertices; std::vector indices; ///< discretization value is chosen. Should be transformed by _t before rendering GeomType type; ///< the type of geometry primitive // generate a sphere triangulation starting with an icosahedron // all triangles are oriented counter clockwise static void GenerateSphereTriangulation(std::vector realvertices, std::vector realindices, int levels) { const double GTS_M_ICOSAHEDRON_X = 0.850650808352039932181540497063011072240401406; const double GTS_M_ICOSAHEDRON_Y = 0.525731112119133606025669084847876607285497935; const double GTS_M_ICOSAHEDRON_Z = 0; std::vector tempvertices[2]; std::vector tempindices[2]; tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y)); tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y)); tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z)); tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X)); tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z)); tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y)); const int nindices=60; int indices[nindices] = { 0, 1, 2, 1, 3, 4, 3, 5, 6, 2, 4, 7, 5, 6, 8, 2, 7, 9, 0, 5, 8, 7, 9, 10, 0, 1, 5, 7, 10, 11, 1, 3, 5, 6, 10, 11, 3, 6, 11, 9, 10, 8, 3, 4, 11, 6, 8, 10, 4, 7, 11, 1, 2, 4, 0, 8, 9, 0, 2, 9 }; Vector3 v[3]; // make sure oriented CCW for(int i = 0; i < nindices; i += 3 ) { v[0] = tempvertices[0][indices[i]]; v[1] = tempvertices[0][indices[i+1]]; v[2] = tempvertices[0][indices[i+2]]; if( _dot3(v[0], _cross3(_sub3(v[1],v[0]),_sub3(v[2],v[0]))) < 0 ) { std::swap(indices[i], indices[i+1]); } } tempindices[0].resize(nindices); std::copy(&indices[0],&indices[nindices],tempindices[0].begin()); std::vector* curvertices = &tempvertices[0], *newvertices = &tempvertices[1]; std::vector *curindices = &tempindices[0], *newindices = &tempindices[1]; while(levels-- > 0) { newvertices->resize(0); newvertices->reserve(2*curvertices->size()); newvertices->insert(newvertices->end(), curvertices->begin(), curvertices->end()); newindices->resize(0); newindices->reserve(4*curindices->size()); std::map< uint64_t, int > mapnewinds; std::map< uint64_t, int >::iterator it; for(size_t i = 0; i < curindices->size(); i += 3) { // for ever tri, create 3 new vertices and 4 new triangles. v[0] = curvertices->at(curindices->at(i)); v[1] = curvertices->at(curindices->at(i+1)); v[2] = curvertices->at(curindices->at(i+2)); int inds[3]; for(int j = 0; j < 3; ++j) { uint64_t key = ((uint64_t)curindices->at(i+j)<<32)|(uint64_t)curindices->at(i + ((j+1)%3)); it = mapnewinds.find(key); if( it == mapnewinds.end() ) { inds[j] = mapnewinds[key] = mapnewinds[(key<<32)|(key>>32)] = (int)newvertices->size(); newvertices->push_back(_normalize3(_add3(v[j],v[(j+1)%3 ]))); } else { inds[j] = it->second; } } newindices->push_back(curindices->at(i)); newindices->push_back(inds[0]); newindices->push_back(inds[2]); newindices->push_back(inds[0]); newindices->push_back(curindices->at(i+1)); newindices->push_back(inds[1]); newindices->push_back(inds[2]); newindices->push_back(inds[0]); newindices->push_back(inds[1]); newindices->push_back(inds[2]); newindices->push_back(inds[1]); newindices->push_back(curindices->at(i+2)); } std::swap(newvertices,curvertices); std::swap(newindices,curindices); } realvertices = *curvertices; realindices = *curindices; } bool InitCollisionMesh(double fTessellation=1.0) { if( type == GeomTrimesh ) { return true; } indices.clear(); vertices.clear(); if( fTessellation < 0.01f ) { fTessellation = 0.01f; } // start tesselating switch(type) { case GeomSphere: { // log_2 (1+ tess) GenerateSphereTriangulation(vertices,indices, 3 + (int)(logf(fTessellation) / logf(2.0f)) ); double fRadius = vGeomData.x; FOREACH(it, vertices) { it->x *= fRadius; it->y *= fRadius; it->z *= fRadius; } break; } case GeomBox: { // trivial Vector3 ex = vGeomData; Vector3 v[8] = { Vector3(ex.x, ex.y, ex.z), Vector3(ex.x, ex.y, -ex.z), Vector3(ex.x, -ex.y, ex.z), Vector3(ex.x, -ex.y, -ex.z), Vector3(-ex.x, ex.y, ex.z), Vector3(-ex.x, ex.y, -ex.z), Vector3(-ex.x, -ex.y, ex.z), Vector3(-ex.x, -ex.y, -ex.z) }; const int nindices = 36; int startindices[] = { 0, 1, 2, 1, 2, 3, 4, 5, 6, 5, 6, 7, 0, 1, 4, 1, 4, 5, 2, 3, 6, 3, 6, 7, 0, 2, 4, 2, 4, 6, 1, 3, 5, 3, 5, 7 }; for(int i = 0; i < nindices; i += 3 ) { Vector3 v1 = v[startindices[i]]; Vector3 v2 = v[startindices[i+1]]; Vector3 v3 = v[startindices[i+2]]; if( _dot3(v1, _sub3(v2,_cross3(v1, _sub3(v3,v1)))) < 0 ) { std::swap(indices[i], indices[i+1]); } } vertices.resize(8); std::copy(&v[0],&v[8],vertices.begin()); indices.resize(nindices); std::copy(&startindices[0],&startindices[nindices],indices.begin()); break; } case GeomCylinder: { // cylinder is on y axis double rad = vGeomData.x, len = vGeomData.y*0.5f; int numverts = (int)(fTessellation*24.0f) + 3; double dtheta = 2 * M_PI / (double)numverts; vertices.push_back(Vector3(0,0,len)); vertices.push_back(Vector3(0,0,-len)); vertices.push_back(Vector3(rad,0,len)); vertices.push_back(Vector3(rad,0,-len)); for(int i = 0; i < numverts+1; ++i) { double s = rad * std::sin(dtheta * (double)i); double c = rad * std::cos(dtheta * (double)i); int off = (int)vertices.size(); vertices.push_back(Vector3(c, s, len)); vertices.push_back(Vector3(c, s, -len)); indices.push_back(0); indices.push_back(off); indices.push_back(off-2); indices.push_back(1); indices.push_back(off-1); indices.push_back(off+1); indices.push_back(off-2); indices.push_back(off); indices.push_back(off-1); indices.push_back(off); indices.push_back(off-1); indices.push_back(off+1); } break; } default: BOOST_ASSERT(0); } return true; } }; public: ColladaModelReader(boost::shared_ptr model) : _dom(NULL), _nGlobalSensorId(0), _nGlobalManipulatorId(0), _model(model) { daeErrorHandler::setErrorHandler(this); _resourcedir = "."; } virtual ~ColladaModelReader() { _vuserdata.clear(); _collada.reset(); DAE::cleanup(); } bool InitFromFile(const std::string& filename) { ROS_DEBUG_STREAM(str(boost::format("init COLLADA reader version: %s, namespace: %s, filename: %s\n")%COLLADA_VERSION%COLLADA_NAMESPACE%filename)); _collada.reset(new DAE); _dom = (domCOLLADA*)_collada->open(filename); if (!_dom) { return false; } _filename=filename; size_t maxchildren = _countChildren(_dom); _vuserdata.resize(0); _vuserdata.reserve(maxchildren); double dScale = 1.0; _processUserData(_dom, dScale); ROS_DEBUG_STREAM(str(boost::format("processed children: %d/%d\n")%_vuserdata.size()%maxchildren)); return _Extract(); } bool InitFromData(const std::string& pdata) { ROS_DEBUG_STREAM(str(boost::format("init COLLADA reader version: %s, namespace: %s\n")%COLLADA_VERSION%COLLADA_NAMESPACE)); _collada.reset(new DAE); _dom = (domCOLLADA*)_collada->openFromMemory(".",pdata.c_str()); if (!_dom) { return false; } size_t maxchildren = _countChildren(_dom); _vuserdata.resize(0); _vuserdata.reserve(maxchildren); double dScale = 1.0; _processUserData(_dom, dScale); ROS_DEBUG_STREAM(str(boost::format("processed children: %d/%d\n")%_vuserdata.size()%maxchildren)); return _Extract(); } protected: /// \extract the first possible robot in the scene bool _Extract() { _model->clear(); std::list< std::pair > > listPossibleBodies; domCOLLADA::domSceneRef allscene = _dom->getScene(); if( !allscene ) { return false; } // parse each instance kinematics scene, prioritize real robots for (size_t iscene = 0; iscene < allscene->getInstance_kinematics_scene_array().getCount(); iscene++) { domInstance_kinematics_sceneRef kiscene = allscene->getInstance_kinematics_scene_array()[iscene]; domKinematics_sceneRef kscene = daeSafeCast (kiscene->getUrl().getElement().cast()); if (!kscene) { continue; } boost::shared_ptr bindings(new KinematicsSceneBindings()); _ExtractKinematicsVisualBindings(allscene->getInstance_visual_scene(),kiscene,*bindings); _ExtractPhysicsBindings(allscene,*bindings); for(size_t ias = 0; ias < kscene->getInstance_articulated_system_array().getCount(); ++ias) { if( _ExtractArticulatedSystem(kscene->getInstance_articulated_system_array()[ias], *bindings) ) { _PostProcess(); return true; } } for(size_t ikmodel = 0; ikmodel < kscene->getInstance_kinematics_model_array().getCount(); ++ikmodel) { listPossibleBodies.push_back(std::make_pair(kscene->getInstance_kinematics_model_array()[ikmodel], bindings)); } } FOREACH(it, listPossibleBodies) { if( _ExtractKinematicsModel(it->first, *it->second) ) { _PostProcess(); return true; } } return false; } void _PostProcess() { std::map parent_link_tree; // building tree: name mapping try { _model->initTree(parent_link_tree); } catch(ParseError &e) { ROS_ERROR("Failed to build tree: %s", e.what()); } // find the root link try { _model->initRoot(parent_link_tree); } catch(ParseError &e) { ROS_ERROR("Failed to find root link: %s", e.what()); } } /// \brief extracts an articulated system. Note that an articulated system can include other articulated systems bool _ExtractArticulatedSystem(domInstance_articulated_systemRef ias, KinematicsSceneBindings& bindings) { if( !ias ) { return false; } ROS_DEBUG_STREAM(str(boost::format("instance articulated system sid %s\n")%ias->getSid())); domArticulated_systemRef articulated_system = daeSafeCast (ias->getUrl().getElement().cast()); if( !articulated_system ) { return false; } boost::shared_ptr pinterface_type = _ExtractInterfaceType(ias->getExtra_array()); if( !pinterface_type ) { pinterface_type = _ExtractInterfaceType(articulated_system->getExtra_array()); } if( !!pinterface_type ) { ROS_DEBUG_STREAM(str(boost::format("robot type: %s")%(*pinterface_type))); } // set the name if( _model->name_.size() == 0 && !!ias->getName() ) { _model->name_ = ias->getName(); } if( _model->name_.size() == 0 && !!ias->getSid()) { _model->name_ = ias->getSid(); } if( _model->name_.size() == 0 && !!articulated_system->getName() ) { _model->name_ = articulated_system->getName(); } if( _model->name_.size() == 0 && !!articulated_system->getId()) { _model->name_ = articulated_system->getId(); } if( !!articulated_system->getMotion() ) { domInstance_articulated_systemRef ias_new = articulated_system->getMotion()->getInstance_articulated_system(); if( !!articulated_system->getMotion()->getTechnique_common() ) { for(size_t i = 0; i < articulated_system->getMotion()->getTechnique_common()->getAxis_info_array().getCount(); ++i) { domMotion_axis_infoRef motion_axis_info = articulated_system->getMotion()->getTechnique_common()->getAxis_info_array()[i]; // this should point to a kinematics axis_info domKinematics_axis_infoRef kinematics_axis_info = daeSafeCast(daeSidRef(motion_axis_info->getAxis(), ias_new->getUrl().getElement()).resolve().elt); if( !!kinematics_axis_info ) { // find the parent kinematics and go through all its instance kinematics models daeElement* pparent = kinematics_axis_info->getParent(); while(!!pparent && pparent->typeID() != domKinematics::ID()) { pparent = pparent->getParent(); } BOOST_ASSERT(!!pparent); bindings.AddAxisInfo(daeSafeCast(pparent)->getInstance_kinematics_model_array(), kinematics_axis_info, motion_axis_info); } else { ROS_WARN_STREAM(str(boost::format("failed to find kinematics axis %s\n")%motion_axis_info->getAxis())); } } } if( !_ExtractArticulatedSystem(ias_new,bindings) ) { return false; } } else { if( !articulated_system->getKinematics() ) { ROS_WARN_STREAM(str(boost::format("collada tag empty? instance_articulated_system=%s\n")%ias->getID())); return true; } if( !!articulated_system->getKinematics()->getTechnique_common() ) { for(size_t i = 0; i < articulated_system->getKinematics()->getTechnique_common()->getAxis_info_array().getCount(); ++i) { bindings.AddAxisInfo(articulated_system->getKinematics()->getInstance_kinematics_model_array(), articulated_system->getKinematics()->getTechnique_common()->getAxis_info_array()[i], NULL); } } for(size_t ik = 0; ik < articulated_system->getKinematics()->getInstance_kinematics_model_array().getCount(); ++ik) { _ExtractKinematicsModel(articulated_system->getKinematics()->getInstance_kinematics_model_array()[ik],bindings); } } _ExtractRobotAttachedActuators(articulated_system); _ExtractRobotManipulators(articulated_system); _ExtractRobotAttachedSensors(articulated_system); return true; } bool _ExtractKinematicsModel(domInstance_kinematics_modelRef ikm, KinematicsSceneBindings& bindings) { if( !ikm ) { return false; } ROS_DEBUG_STREAM(str(boost::format("instance kinematics model sid %s\n")%ikm->getSid())); domKinematics_modelRef kmodel = daeSafeCast (ikm->getUrl().getElement().cast()); if (!kmodel) { ROS_WARN_STREAM(str(boost::format("%s does not reference valid kinematics\n")%ikm->getSid())); return false; } domPhysics_modelRef pmodel; boost::shared_ptr pinterface_type = _ExtractInterfaceType(ikm->getExtra_array()); if( !pinterface_type ) { pinterface_type = _ExtractInterfaceType(kmodel->getExtra_array()); } if( !!pinterface_type ) { ROS_DEBUG_STREAM(str(boost::format("kinbody interface type: %s")%(*pinterface_type))); } // find matching visual node domNodeRef pvisualnode; FOREACH(it, bindings.listKinematicsVisualBindings) { if( it->second == ikm ) { pvisualnode = it->first; break; } } if( !pvisualnode ) { ROS_WARN_STREAM(str(boost::format("failed to find visual node for instance kinematics model %s\n")%ikm->getSid())); return false; } if( _model->name_.size() == 0 && !!ikm->getName() ) { _model->name_ = ikm->getName(); } if( _model->name_.size() == 0 && !!ikm->getID() ) { _model->name_ = ikm->getID(); } if (!_ExtractKinematicsModel(kmodel, pvisualnode, pmodel, bindings)) { ROS_WARN_STREAM(str(boost::format("failed to load kinbody from kinematics model %s\n")%kmodel->getID())); return false; } return true; } /// \brief append the kinematics model to the openrave kinbody bool _ExtractKinematicsModel(domKinematics_modelRef kmodel, domNodeRef pnode, domPhysics_modelRef pmodel, const KinematicsSceneBindings& bindings) { std::vector vdomjoints; ROS_DEBUG_STREAM(str(boost::format("kinematics model: %s\n")%_model->name_)); if( !!pnode ) { ROS_DEBUG_STREAM(str(boost::format("node name: %s\n")%pnode->getId())); } // Process joint of the kinbody domKinematics_model_techniqueRef ktec = kmodel->getTechnique_common(); // Store joints for (size_t ijoint = 0; ijoint < ktec->getJoint_array().getCount(); ++ijoint) { vdomjoints.push_back(ktec->getJoint_array()[ijoint]); } // Store instances of joints for (size_t ijoint = 0; ijoint < ktec->getInstance_joint_array().getCount(); ++ijoint) { domJointRef pelt = daeSafeCast (ktec->getInstance_joint_array()[ijoint]->getUrl().getElement()); if (!pelt) { ROS_WARN_STREAM("failed to get joint from instance\n"); } else { vdomjoints.push_back(pelt); } } ROS_DEBUG_STREAM(str(boost::format("Number of root links in the kmodel %d\n")%ktec->getLink_array().getCount())); for (size_t ilink = 0; ilink < ktec->getLink_array().getCount(); ++ilink) { domLinkRef pdomlink = ktec->getLink_array()[ilink]; _RootOrigin = _poseFromMatrix(_ExtractFullTransform(pdomlink)); ROS_DEBUG("RootOrigin: %s %lf %lf %lf %lf %lf %lf %lf", pdomlink->getName(), _RootOrigin.position.x, _RootOrigin.position.y, _RootOrigin.position.z, _RootOrigin.rotation.x, _RootOrigin.rotation.y, _RootOrigin.rotation.z, _RootOrigin.rotation.w); domNodeRef pvisualnode; FOREACH(it, bindings.listKinematicsVisualBindings) { if(strcmp(it->first->getName() ,pdomlink->getName()) == 0) { pvisualnode = it->first; break; } } if (!!pvisualnode) { _VisualRootOrigin = _poseFromMatrix(_getNodeParentTransform(pvisualnode)); ROS_DEBUG("VisualRootOrigin: %s %lf %lf %lf %lf %lf %lf %lf", pdomlink->getName(), _VisualRootOrigin.position.x, _VisualRootOrigin.position.y, _VisualRootOrigin.position.z, _VisualRootOrigin.rotation.x, _VisualRootOrigin.rotation.y, _VisualRootOrigin.rotation.z, _VisualRootOrigin.rotation.w); } _ExtractLink(pdomlink, ilink == 0 ? pnode : domNodeRef(), Pose(), Pose(), vdomjoints, bindings); } // TODO: implement mathml for (size_t iform = 0; iform < ktec->getFormula_array().getCount(); ++iform) { domFormulaRef pf = ktec->getFormula_array()[iform]; if (!pf->getTarget()) { ROS_WARN_STREAM("formula target not valid\n"); continue; } // find the target joint boost::shared_ptr pjoint = _getJointFromRef(pf->getTarget()->getParam()->getValue(),pf); if (!pjoint) { continue; } if (!!pf->getTechnique_common()) { daeElementRef peltmath; daeTArray children; pf->getTechnique_common()->getChildren(children); for (size_t ichild = 0; ichild < children.getCount(); ++ichild) { daeElementRef pelt = children[ichild]; if (_checkMathML(pelt,std::string("math")) ) { peltmath = pelt; } else { ROS_WARN_STREAM(str(boost::format("unsupported formula element: %s\n")%pelt->getElementName())); } } if (!!peltmath) { // full math xml spec not supported, only looking for ax+b pattern: // a x b double a = 1, b = 0; daeElementRef psymboljoint; BOOST_ASSERT(peltmath->getChildren().getCount()>0); daeElementRef papplyelt = peltmath->getChildren()[0]; BOOST_ASSERT(_checkMathML(papplyelt,"apply")); BOOST_ASSERT(papplyelt->getChildren().getCount()>0); if( _checkMathML(papplyelt->getChildren()[0],"plus") ) { BOOST_ASSERT(papplyelt->getChildren().getCount()==3); daeElementRef pa = papplyelt->getChildren()[1]; daeElementRef pb = papplyelt->getChildren()[2]; if( !_checkMathML(papplyelt->getChildren()[1],"apply") ) { std::swap(pa,pb); } if( !_checkMathML(pa,"csymbol") ) { BOOST_ASSERT(_checkMathML(pa,"apply")); BOOST_ASSERT(_checkMathML(pa->getChildren()[0],"times")); if( _checkMathML(pa->getChildren()[1],"csymbol") ) { psymboljoint = pa->getChildren()[1]; BOOST_ASSERT(_checkMathML(pa->getChildren()[2],"cn")); std::stringstream ss(pa->getChildren()[2]->getCharData()); ss >> a; } else { psymboljoint = pa->getChildren()[2]; BOOST_ASSERT(_checkMathML(pa->getChildren()[1],"cn")); std::stringstream ss(pa->getChildren()[1]->getCharData()); ss >> a; } } else { psymboljoint = pa; } BOOST_ASSERT(_checkMathML(pb,"cn")); { std::stringstream ss(pb->getCharData()); ss >> b; } } else if( _checkMathML(papplyelt->getChildren()[0],"minus") ) { BOOST_ASSERT(_checkMathML(papplyelt->getChildren()[1],"csymbol")); a = -1; psymboljoint = papplyelt->getChildren()[1]; } else { BOOST_ASSERT(_checkMathML(papplyelt->getChildren()[0],"csymbol")); psymboljoint = papplyelt->getChildren()[0]; } BOOST_ASSERT(psymboljoint->hasAttribute("encoding")); BOOST_ASSERT(psymboljoint->getAttribute("encoding")==std::string("COLLADA")); boost::shared_ptr pbasejoint = _getJointFromRef(psymboljoint->getCharData().c_str(),pf); if( !!pbasejoint ) { // set the mimic properties pjoint->mimic.reset(new JointMimic()); pjoint->mimic->joint_name = pbasejoint->name; pjoint->mimic->multiplier = a; pjoint->mimic->offset = b; ROS_DEBUG_STREAM(str(boost::format("assigning joint %s to mimic %s %f %f\n")%pjoint->name%pbasejoint->name%a%b)); } } } } return true; } /// \brief Extract Link info and add it to an existing body boost::shared_ptr _ExtractLink(const domLinkRef pdomlink,const domNodeRef pdomnode, const Pose& tParentWorldLink, const Pose& tParentLink, const std::vector& vdomjoints, const KinematicsSceneBindings& bindings) { const std::list& listAxisBindings = bindings.listAxisBindings; // Set link name with the name of the COLLADA's Link std::string linkname = _ExtractLinkName(pdomlink); if( linkname.size() == 0 ) { ROS_WARN_STREAM(" has no name or id, falling back to !\n"); if( !!pdomnode ) { if (!!pdomnode->getName()) { linkname = pdomnode->getName(); } if( linkname.size() == 0 && !!pdomnode->getID()) { linkname = pdomnode->getID(); } } } boost::shared_ptr plink; _model->getLink(linkname,plink); if( !plink ) { plink.reset(new Link()); plink->name = linkname; plink->visual.reset(new Visual()); plink->visual->material_name = ""; plink->visual->material.reset(new Material()); plink->visual->material->name = "Red"; plink->visual->material->color.r = 0.0; plink->visual->material->color.g = 1.0; plink->visual->material->color.b = 0.0; plink->visual->material->color.a = 1.0; plink->inertial.reset(); _model->links_.insert(std::make_pair(linkname,plink)); } _getUserData(pdomlink)->p = plink; if( !!pdomnode ) { ROS_DEBUG_STREAM(str(boost::format("Node Id %s and Name %s\n")%pdomnode->getId()%pdomnode->getName())); } // physics domInstance_rigid_bodyRef irigidbody; domRigid_bodyRef rigidbody; bool bFoundBinding = false; FOREACH(itlinkbinding, bindings.listLinkBindings) { if( !!pdomnode->getID() && !!itlinkbinding->node->getID() && strcmp(pdomnode->getID(),itlinkbinding->node->getID()) == 0 ) { bFoundBinding = true; irigidbody = itlinkbinding->irigidbody; rigidbody = itlinkbinding->rigidbody; } } if( !!rigidbody && !!rigidbody->getTechnique_common() ) { domRigid_body::domTechnique_commonRef rigiddata = rigidbody->getTechnique_common(); if( !!rigiddata->getMass() ) { if ( !plink->inertial ) { plink->inertial.reset(new Inertial()); } plink->inertial->mass = rigiddata->getMass()->getValue(); } if( !!rigiddata->getInertia() ) { if ( !plink->inertial ) { plink->inertial.reset(new Inertial()); } plink->inertial->ixx = rigiddata->getInertia()->getValue()[0]; plink->inertial->iyy = rigiddata->getInertia()->getValue()[1]; plink->inertial->izz = rigiddata->getInertia()->getValue()[2]; } if( !!rigiddata->getMass_frame() ) { if ( !plink->inertial ) { plink->inertial.reset(new Inertial()); } //plink->inertial->origin = _poseMult(_poseInverse(tParentWorldLink), _poseFromMatrix(_ExtractFullTransform(rigiddata->getMass_frame()))); Pose tlink = _poseFromMatrix(_ExtractFullTransform(pdomlink)); plink->inertial->origin = _poseMult(_poseInverse(_poseMult(_poseInverse(_RootOrigin), _poseMult(tParentWorldLink, tlink))), _poseFromMatrix(_ExtractFullTransform(rigiddata->getMass_frame()))); } } std::list listGeomProperties; if (!pdomlink) { ROS_WARN_STREAM("Extract object NOT kinematics !!!\n"); _ExtractGeometry(pdomnode,listGeomProperties,listAxisBindings,Pose()); } else { ROS_DEBUG_STREAM(str(boost::format("Attachment link elements: %d\n")%pdomlink->getAttachment_full_array().getCount())); Pose tlink = _poseFromMatrix(_ExtractFullTransform(pdomlink)); ROS_DEBUG("tlink: %s: %lf %lf %lf %lf %lf %lf %lf", linkname.c_str(), tlink.position.x, tlink.position.y, tlink.position.z, tlink.rotation.x, tlink.rotation.y, tlink.rotation.z, tlink.rotation.w); plink->visual->origin = _poseMult(tParentLink, tlink); // use the kinematics coordinate system for each link // ROS_INFO("link %s rot: %f %f %f %f",linkname.c_str(),plink->visual->origin.rotation.w, plink->visual->origin.rotation.x,plink->visual->origin.rotation.y,plink->visual->origin.rotation.z); // ROS_INFO("link %s trans: %f %f %f",linkname.c_str(),plink->visual->origin.position.x,plink->visual->origin.position.y,plink->visual->origin.position.z); // Get the geometry _ExtractGeometry(pdomnode, listGeomProperties, listAxisBindings, _poseMult(_poseMult(tParentWorldLink,tlink), plink->visual->origin)); ROS_DEBUG_STREAM(str(boost::format("After ExtractGeometry Attachment link elements: %d\n")%pdomlink->getAttachment_full_array().getCount())); // Process all atached links for (size_t iatt = 0; iatt < pdomlink->getAttachment_full_array().getCount(); ++iatt) { domLink::domAttachment_fullRef pattfull = pdomlink->getAttachment_full_array()[iatt]; // get link kinematics transformation Pose tatt = _poseFromMatrix(_ExtractFullTransform(pattfull)); // process attached links daeElement* peltjoint = daeSidRef(pattfull->getJoint(), pattfull).resolve().elt; domJointRef pdomjoint = daeSafeCast (peltjoint); if (!pdomjoint) { domInstance_jointRef pdomijoint = daeSafeCast (peltjoint); if (!!pdomijoint) { pdomjoint = daeSafeCast (pdomijoint->getUrl().getElement().cast()); } } if (!pdomjoint || pdomjoint->typeID() != domJoint::ID()) { ROS_WARN_STREAM(str(boost::format("could not find attached joint %s!\n")%pattfull->getJoint())); return boost::shared_ptr(); } // get direct child link if (!pattfull->getLink()) { ROS_WARN_STREAM(str(boost::format("joint %s needs to be attached to a valid link\n")%pdomjoint->getID())); continue; } // find the correct joint in the bindings daeTArray vdomaxes = pdomjoint->getChildrenByType(); domNodeRef pchildnode; // see if joint has a binding to a visual node FOREACHC(itaxisbinding,listAxisBindings) { for (size_t ic = 0; ic < vdomaxes.getCount(); ++ic) { // If the binding for the joint axis is found, retrieve the info if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) { pchildnode = itaxisbinding->visualnode; break; } } if( !!pchildnode ) { break; } } if (!pchildnode) { ROS_DEBUG_STREAM(str(boost::format("joint %s has no visual binding\n")%pdomjoint->getID())); } // create the joints before creating the child links std::vector > vjoints(vdomaxes.getCount()); for (size_t ic = 0; ic < vdomaxes.getCount(); ++ic) { bool joint_active = true; // if not active, put into the passive list FOREACHC(itaxisbinding,listAxisBindings) { if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) { if( !!itaxisbinding->kinematics_axis_info ) { if( !!itaxisbinding->kinematics_axis_info->getActive() ) { joint_active = resolveBool(itaxisbinding->kinematics_axis_info->getActive(),itaxisbinding->kinematics_axis_info); } } break; } } boost::shared_ptr pjoint(new Joint()); pjoint->limits.reset(new JointLimits()); pjoint->limits->velocity = 0.0; pjoint->limits->effort = 0.0; pjoint->parent_link_name = plink->name; if( !!pdomjoint->getName() ) { pjoint->name = pdomjoint->getName(); } else { pjoint->name = str(boost::format("dummy%d")%_model->joints_.size()); } if( !joint_active ) { ROS_INFO_STREAM(str(boost::format("joint %s is passive, but adding to hierarchy\n")%pjoint->name)); } domAxis_constraintRef pdomaxis = vdomaxes[ic]; if( strcmp(pdomaxis->getElementName(), "revolute") == 0 ) { pjoint->type = Joint::REVOLUTE; } else if( strcmp(pdomaxis->getElementName(), "prismatic") == 0 ) { pjoint->type = Joint::PRISMATIC; } else { ROS_WARN_STREAM(str(boost::format("unsupported joint type: %s\n")%pdomaxis->getElementName())); } _getUserData(pdomjoint)->p = pjoint; _getUserData(pdomaxis)->p = boost::shared_ptr(new int(_model->joints_.size())); _model->joints_[pjoint->name] = pjoint; vjoints[ic] = pjoint; } boost::shared_ptr pchildlink = _ExtractLink(pattfull->getLink(), pchildnode, _poseMult(_poseMult(tParentWorldLink,tlink), tatt), tatt, vdomjoints, bindings); if (!pchildlink) { ROS_WARN_STREAM(str(boost::format("Link has no child: %s\n")%plink->name)); continue; } int numjoints = 0; for (size_t ic = 0; ic < vdomaxes.getCount(); ++ic) { domKinematics_axis_infoRef kinematics_axis_info; domMotion_axis_infoRef motion_axis_info; FOREACHC(itaxisbinding,listAxisBindings) { bool bfound = false; if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) { kinematics_axis_info = itaxisbinding->kinematics_axis_info; motion_axis_info = itaxisbinding->motion_axis_info; bfound = true; break; } } domAxis_constraintRef pdomaxis = vdomaxes[ic]; if (!pchildlink) { // create dummy child link // multiple axes can be easily done with "empty links" ROS_WARN_STREAM(str(boost::format("creating dummy link %s, num joints %d\n")%plink->name%numjoints)); std::stringstream ss; ss << plink->name; ss <<"_dummy" << numjoints; pchildlink.reset(new Link()); pchildlink->name = ss.str(); _model->links_.insert(std::make_pair(pchildlink->name,pchildlink)); } ROS_DEBUG_STREAM(str(boost::format("Joint %s assigned %d \n")%vjoints[ic]->name%ic)); boost::shared_ptr pjoint = vjoints[ic]; pjoint->child_link_name = pchildlink->name; #define PRINT_POSE(pname, apose) ROS_DEBUG(pname" pos: %f %f %f, rot: %f %f %f %f", \ apose.position.x, apose.position.y, apose.position.z, \ apose.rotation.x, apose.rotation.y, apose.rotation.z, apose.rotation.w); { PRINT_POSE("tatt", tatt); PRINT_POSE("trans_joint_to_child", tatt); Pose trans_joint_to_child = _poseFromMatrix(_ExtractFullTransform(pattfull->getLink())); pjoint->parent_to_joint_origin_transform = _poseMult(tatt, trans_joint_to_child); // Axes and Anchor assignment. Vector3 ax(pdomaxis->getAxis()->getValue()[0], pdomaxis->getAxis()->getValue()[1], pdomaxis->getAxis()->getValue()[2]); Pose pinv = _poseInverse(trans_joint_to_child); // rotate axis ax = pinv.rotation * ax; pjoint->axis.x = ax.x; pjoint->axis.y = ax.y; pjoint->axis.z = ax.z; ROS_DEBUG("joint %s axis: %f %f %f -> %f %f %f\n", pjoint->name.c_str(), pdomaxis->getAxis()->getValue()[0], pdomaxis->getAxis()->getValue()[1], pdomaxis->getAxis()->getValue()[2], pjoint->axis.x, pjoint->axis.y, pjoint->axis.z); } if (!motion_axis_info) { ROS_WARN_STREAM(str(boost::format("No motion axis info for joint %s\n")%pjoint->name)); } // Sets the Speed and the Acceleration of the joint if (!!motion_axis_info) { if (!!motion_axis_info->getSpeed()) { pjoint->limits->velocity = resolveFloat(motion_axis_info->getSpeed(),motion_axis_info); ROS_DEBUG("... Joint Speed: %f...\n",pjoint->limits->velocity); } if (!!motion_axis_info->getAcceleration()) { pjoint->limits->effort = resolveFloat(motion_axis_info->getAcceleration(),motion_axis_info); ROS_DEBUG("... Joint effort: %f...\n",pjoint->limits->effort); } } bool joint_locked = false; // if locked, joint angle is static bool kinematics_limits = false; if (!!kinematics_axis_info) { if (!!kinematics_axis_info->getLocked()) { joint_locked = resolveBool(kinematics_axis_info->getLocked(),kinematics_axis_info); } if (joint_locked) { // If joint is locked set limits to the static value. if( pjoint->type == Joint::REVOLUTE || pjoint->type ==Joint::PRISMATIC) { ROS_WARN_STREAM("lock joint!!\n"); pjoint->limits->lower = 0; pjoint->limits->upper = 0; } } else if (kinematics_axis_info->getLimits()) { // If there are articulated system kinematics limits kinematics_limits = true; double fscale = (pjoint->type == Joint::REVOLUTE) ? (M_PI/180.0f) : _GetUnitScale(kinematics_axis_info); if( pjoint->type == Joint::REVOLUTE || pjoint->type ==Joint::PRISMATIC) { pjoint->limits->lower = fscale*(double)(resolveFloat(kinematics_axis_info->getLimits()->getMin(),kinematics_axis_info)); pjoint->limits->upper = fscale*(double)(resolveFloat(kinematics_axis_info->getLimits()->getMax(),kinematics_axis_info)); if ( pjoint->limits->lower == 0 && pjoint->limits->upper == 0 ) { pjoint->type = Joint::FIXED; } } } } // Search limits in the joints section if (!kinematics_axis_info || (!joint_locked && !kinematics_limits)) { // If there are NO LIMITS if( !pdomaxis->getLimits() ) { ROS_DEBUG_STREAM(str(boost::format("There are NO LIMITS in joint %s:%d ...\n")%pjoint->name%kinematics_limits)); if( pjoint->type == Joint::REVOLUTE ) { pjoint->type = Joint::CONTINUOUS; // continuous means revolute? pjoint->limits->lower = -M_PI; pjoint->limits->upper = M_PI; } else { pjoint->limits->lower = -100000; pjoint->limits->upper = 100000; } } else { ROS_DEBUG_STREAM(str(boost::format("There are LIMITS in joint %s ...\n")%pjoint->name)); double fscale = (pjoint->type == Joint::REVOLUTE) ? (M_PI/180.0f) : _GetUnitScale(pdomaxis); pjoint->limits->lower = (double)pdomaxis->getLimits()->getMin()->getValue()*fscale; pjoint->limits->upper = (double)pdomaxis->getLimits()->getMax()->getValue()*fscale; if ( pjoint->limits->lower == 0 && pjoint->limits->upper == 0 ) { pjoint->type = Joint::FIXED; } } } if (pjoint->limits->velocity == 0.0) { pjoint->limits->velocity = pjoint->type == Joint::PRISMATIC ? 0.01 : 0.5f; } pchildlink.reset(); ++numjoints; } } } if( pdomlink->getAttachment_start_array().getCount() > 0 ) { ROS_WARN("urdf collada reader does not support attachment_start\n"); } if( pdomlink->getAttachment_end_array().getCount() > 0 ) { ROS_WARN("urdf collada reader does not support attachment_end\n"); } plink->visual->geometry = _CreateGeometry(plink->name, listGeomProperties); // visual_groups deprecated //boost::shared_ptr > > viss; //viss.reset(new std::vector >); //viss->push_back(plink->visual); //plink->visual_groups.insert(std::make_pair("default", viss)); if( !plink->visual->geometry ) { plink->visual.reset(); plink->collision.reset(); } else { // collision plink->collision.reset(new Collision()); plink->collision->geometry = plink->visual->geometry; plink->collision->origin = plink->visual->origin; } // collision_groups deprecated //boost::shared_ptr > > cols; //cols.reset(new std::vector >); //cols->push_back(plink->collision); //plink->collision_groups.insert(std::make_pair("default", cols)); return plink; } boost::shared_ptr _CreateGeometry(const std::string& name, const std::list& listGeomProperties) { std::vector > vertices; std::vector > indices; std::vector ambients; std::vector diffuses; unsigned int index, vert_counter; vertices.resize(listGeomProperties.size()); indices.resize(listGeomProperties.size()); ambients.resize(listGeomProperties.size()); diffuses.resize(listGeomProperties.size()); index = 0; vert_counter = 0; FOREACHC(it, listGeomProperties) { vertices[index].resize(it->vertices.size()); for(size_t i = 0; i < it->vertices.size(); ++i) { vertices[index][i] = _poseMult(it->_t, it->vertices[i]); vert_counter++; } indices[index].resize(it->indices.size()); for(size_t i = 0; i < it->indices.size(); ++i) { indices[index][i] = it->indices[i]; } ambients[index] = it->ambientColor; diffuses[index] = it->diffuseColor; // workaround for mesh_loader.cpp:421 // Most of are DAE files don't have ambient color defined ambients[index].r *= 0.5; ambients[index].g *= 0.5; ambients[index].b *= 0.5; if ( ambients[index].r == 0.0 ) { ambients[index].r = 0.0001; } if ( ambients[index].g == 0.0 ) { ambients[index].g = 0.0001; } if ( ambients[index].b == 0.0 ) { ambients[index].b = 0.0001; } index++; } if (vert_counter == 0) { boost::shared_ptr ret; ret.reset(); return ret; } boost::shared_ptr geometry(new Mesh()); geometry->type = Geometry::MESH; geometry->scale.x = 1; geometry->scale.y = 1; geometry->scale.z = 1; // have to save the geometry into individual collada 1.4 files since URDF does not allow triangle meshes to be specified std::stringstream daedata; daedata << str(boost::format("\n\ \n\ \n\ \n\ Rosen Diankov\n\ \n\ robot_model/urdf temporary collada geometry\n\ \n\ \n\ \n\ Y_UP\n\ \n\ \n")); for(unsigned int i=0; i < index; i++) { daedata << str(boost::format("\ \n\ \n\ \n")%i%i%i); } daedata << "\ \n\ \n"; for(unsigned int i=0; i < index; i++) { daedata << str(boost::format("\ \n\ \n\ \n\ \n\ \n\ %f %f %f %f\n\ \n\ \n\ %f %f %f %f\n\ \n\ \n\ 0 0 0 1\n\ \n\ \n\ \n\ \n\ \n")%i%ambients[i].r%ambients[i].g%ambients[i].b%ambients[i].a%diffuses[i].r%diffuses[i].g%diffuses[i].b%diffuses[i].a); } daedata << str(boost::format("\ \n\ \n")); // fill with vertices for(unsigned int i=0; i < index; i++) { daedata << str(boost::format("\ \n\ \n\ \n\ ")%i%i%(vertices[i].size()*3)); FOREACH(it,vertices[i]) { daedata << it->x << " " << it->y << " " << it->z << " "; } daedata << str(boost::format("\n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\ \n\

")%vertices[i].size()%(indices[i].size()/3)); // fill with indices FOREACH(it,indices[i]) { daedata << *it << " "; } daedata << str(boost::format("

\n\
\n\
\n\
\n")); } daedata << str(boost::format("\
\n\ \n\ \n\ \n")%name%name); for(unsigned int i=0; i < index; i++) { daedata << str(boost::format("\ \n\ \n\ \n\ \n\ \n\ \n\ \n")%i%i); } daedata << str(boost::format("\ \n\ \n\ \n\ \n\ \n\ \n\
")); #ifdef HAVE_MKSTEMPS geometry->filename = str(boost::format("/tmp/collada_model_reader_%s_XXXXXX.dae")%name); int fd = mkstemps(&geometry->filename[0],4); #else int fd = -1; for(int iter = 0; iter < 1000; ++iter) { geometry->filename = str(boost::format("/tmp/collada_model_reader_%s_%d.dae")%name%rand()); if( !!std::ifstream(geometry->filename.c_str())) { fd = open(geometry->filename.c_str(),O_WRONLY|O_CREAT|O_EXCL); if( fd != -1 ) { break; } } } if( fd == -1 ) { ROS_ERROR("failed to open geometry dae file %s",geometry->filename.c_str()); return geometry; } #endif //ROS_INFO("temp file: %s",geometry->filename.c_str()); std::string daedatastr = daedata.str(); if( (size_t)write(fd,daedatastr.c_str(),daedatastr.size()) != daedatastr.size() ) { ROS_ERROR("failed to write to geometry dae file %s",geometry->filename.c_str()); } close(fd); _listTempFilenames.push_back(boost::shared_ptr(new UnlinkFilename(geometry->filename))); geometry->filename = std::string("file://") + geometry->filename; return geometry; } /// Extract Geometry and apply the transformations of the node /// \param pdomnode Node to extract the goemetry /// \param plink Link of the kinematics model void _ExtractGeometry(const domNodeRef pdomnode,std::list& listGeomProperties, const std::list& listAxisBindings, const Pose& tlink) { if( !pdomnode ) { return; } ROS_DEBUG_STREAM(str(boost::format("ExtractGeometry(node,link) of %s\n")%pdomnode->getName())); // For all child nodes of pdomnode for (size_t i = 0; i < pdomnode->getNode_array().getCount(); i++) { // check if contains a joint bool contains=false; FOREACHC(it,listAxisBindings) { // don't check ID's check if the reference is the same! if ( (pdomnode->getNode_array()[i]) == (it->visualnode)) { contains=true; break; } } if (contains) { continue; } _ExtractGeometry(pdomnode->getNode_array()[i],listGeomProperties, listAxisBindings,tlink); // Plink stayes the same for all children // replace pdomnode by child = pdomnode->getNode_array()[i] // hope for the best! // put everything in a subroutine in order to process pdomnode too! } unsigned int nGeomBefore = listGeomProperties.size(); // #of Meshes already associated to this link // get the geometry for (size_t igeom = 0; igeom < pdomnode->getInstance_geometry_array().getCount(); ++igeom) { domInstance_geometryRef domigeom = pdomnode->getInstance_geometry_array()[igeom]; domGeometryRef domgeom = daeSafeCast (domigeom->getUrl().getElement()); if (!domgeom) { continue; } // Gets materials std::map mapmaterials; if (!!domigeom->getBind_material() && !!domigeom->getBind_material()->getTechnique_common()) { const domInstance_material_Array& matarray = domigeom->getBind_material()->getTechnique_common()->getInstance_material_array(); for (size_t imat = 0; imat < matarray.getCount(); ++imat) { domMaterialRef pmat = daeSafeCast(matarray[imat]->getTarget().getElement()); if (!!pmat) { mapmaterials[matarray[imat]->getSymbol()] = pmat; } } } // Gets the geometry _ExtractGeometry(domgeom, mapmaterials, listGeomProperties); } std::list::iterator itgeom= listGeomProperties.begin(); for (unsigned int i=0; i< nGeomBefore; i++) { itgeom++; // change only the transformations of the newly found geometries. } boost::array tmnodegeom = _poseMult(_matrixFromPose(_poseInverse(tlink)), _poseMult(_poseMult(_matrixFromPose(_poseInverse(_VisualRootOrigin)), _getNodeParentTransform(pdomnode)), _ExtractFullTransform(pdomnode))); Pose tnodegeom; Vector3 vscale(1,1,1); _decompose(tmnodegeom, tnodegeom, vscale); ROS_DEBUG_STREAM("tnodegeom: " << pdomnode->getName() << tnodegeom.position.x << " " << tnodegeom.position.y << " " << tnodegeom.position.z << " / " << tnodegeom.rotation.x << " " << tnodegeom.rotation.y << " " << tnodegeom.rotation.z << " " << tnodegeom.rotation.w); // std::stringstream ss; ss << "geom: "; // for(int i = 0; i < 4; ++i) { // ss << tmnodegeom[4*0+i] << " " << tmnodegeom[4*1+i] << " " << tmnodegeom[4*2+i] << " "; // } // ROS_INFO(ss.str().c_str()); // Switch between different type of geometry PRIMITIVES for (; itgeom != listGeomProperties.end(); itgeom++) { itgeom->_t = tnodegeom; switch (itgeom->type) { case GeomBox: itgeom->vGeomData.x *= vscale.x; itgeom->vGeomData.y *= vscale.y; itgeom->vGeomData.z *= vscale.z; break; case GeomSphere: { itgeom->vGeomData.x *= std::max(vscale.z, std::max(vscale.x, vscale.y)); break; } case GeomCylinder: itgeom->vGeomData.x *= std::max(vscale.x, vscale.y); itgeom->vGeomData.y *= vscale.z; break; case GeomTrimesh: for(size_t i = 0; i < itgeom->vertices.size(); ++i ) { itgeom->vertices[i] = _poseMult(tmnodegeom,itgeom->vertices[i]); } itgeom->_t = Pose(); // reset back to identity break; default: ROS_WARN_STREAM(str(boost::format("unknown geometry type: %d\n")%itgeom->type)); } } } /// Paint the Geometry with the color material /// \param pmat Material info of the COLLADA's model /// \param geom Geometry properties in OpenRAVE void _FillGeometryColor(const domMaterialRef pmat, GEOMPROPERTIES& geom) { if( !!pmat && !!pmat->getInstance_effect() ) { domEffectRef peffect = daeSafeCast(pmat->getInstance_effect()->getUrl().getElement().cast()); if( !!peffect ) { domProfile_common::domTechnique::domPhongRef pphong = daeSafeCast(peffect->getDescendant(daeElement::matchType(domProfile_common::domTechnique::domPhong::ID()))); if( !!pphong ) { if( !!pphong->getAmbient() && !!pphong->getAmbient()->getColor() ) { domFx_color c = pphong->getAmbient()->getColor()->getValue(); geom.ambientColor.r = c[0]; geom.ambientColor.g = c[1]; geom.ambientColor.b = c[2]; geom.ambientColor.a = c[3]; } if( !!pphong->getDiffuse() && !!pphong->getDiffuse()->getColor() ) { domFx_color c = pphong->getDiffuse()->getColor()->getValue(); geom.diffuseColor.r = c[0]; geom.diffuseColor.g = c[1]; geom.diffuseColor.b = c[2]; geom.diffuseColor.a = c[3]; } } } } } /// Extract the Geometry in TRIANGLES and adds it to OpenRave /// \param triRef Array of triangles of the COLLADA's model /// \param vertsRef Array of vertices of the COLLADA's model /// \param mapmaterials Materials applied to the geometry /// \param plink Link of the kinematics model bool _ExtractGeometry(const domTrianglesRef triRef, const domVerticesRef vertsRef, const std::map& mapmaterials, std::list& listGeomProperties) { if( !triRef ) { return false; } listGeomProperties.push_back(GEOMPROPERTIES()); GEOMPROPERTIES& geom = listGeomProperties.back(); geom.type = GeomTrimesh; // resolve the material and assign correct colors to the geometry if( !!triRef->getMaterial() ) { std::map::const_iterator itmat = mapmaterials.find(triRef->getMaterial()); if( itmat != mapmaterials.end() ) { _FillGeometryColor(itmat->second,geom); } } size_t triangleIndexStride = 0, vertexoffset = -1; domInput_local_offsetRef indexOffsetRef; for (unsigned int w=0; wgetInput_array().getCount(); w++) { size_t offset = triRef->getInput_array()[w]->getOffset(); daeString str = triRef->getInput_array()[w]->getSemantic(); if (!strcmp(str,"VERTEX")) { indexOffsetRef = triRef->getInput_array()[w]; vertexoffset = offset; } if (offset> triangleIndexStride) { triangleIndexStride = offset; } } triangleIndexStride++; const domList_of_uints& indexArray =triRef->getP()->getValue(); geom.indices.reserve(triRef->getCount()*3); geom.vertices.reserve(triRef->getCount()*3); for (size_t i=0; igetInput_array().getCount(); ++i) { domInput_localRef localRef = vertsRef->getInput_array()[i]; daeString str = localRef->getSemantic(); if ( strcmp(str,"POSITION") == 0 ) { const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); if( !node ) { continue; } double fUnitScale = _GetUnitScale(node); const domFloat_arrayRef flArray = node->getFloat_array(); if (!!flArray) { const domList_of_floats& listFloats = flArray->getValue(); int k=vertexoffset; int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor' for(size_t itri = 0; itri < triRef->getCount(); ++itri) { if(k+2*triangleIndexStride < indexArray.getCount() ) { for (int j=0; j<3; j++) { int index0 = indexArray.get(k)*vertexStride; domFloat fl0 = listFloats.get(index0); domFloat fl1 = listFloats.get(index0+1); domFloat fl2 = listFloats.get(index0+2); k+=triangleIndexStride; geom.indices.push_back(geom.vertices.size()); geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale)); } } } } else { ROS_WARN_STREAM("float array not defined!\n"); } break; } } if( geom.indices.size() != 3*triRef->getCount() ) { ROS_WARN_STREAM("triangles declares wrong count!\n"); } geom.InitCollisionMesh(); return true; } /// Extract the Geometry in TRIGLE FANS and adds it to OpenRave /// \param triRef Array of triangle fans of the COLLADA's model /// \param vertsRef Array of vertices of the COLLADA's model /// \param mapmaterials Materials applied to the geometry bool _ExtractGeometry(const domTrifansRef triRef, const domVerticesRef vertsRef, const std::map& mapmaterials, std::list& listGeomProperties) { if( !triRef ) { return false; } listGeomProperties.push_back(GEOMPROPERTIES()); GEOMPROPERTIES& geom = listGeomProperties.back(); geom.type = GeomTrimesh; // resolve the material and assign correct colors to the geometry if( !!triRef->getMaterial() ) { std::map::const_iterator itmat = mapmaterials.find(triRef->getMaterial()); if( itmat != mapmaterials.end() ) { _FillGeometryColor(itmat->second,geom); } } size_t triangleIndexStride = 0, vertexoffset = -1; domInput_local_offsetRef indexOffsetRef; for (unsigned int w=0; wgetInput_array().getCount(); w++) { size_t offset = triRef->getInput_array()[w]->getOffset(); daeString str = triRef->getInput_array()[w]->getSemantic(); if (!strcmp(str,"VERTEX")) { indexOffsetRef = triRef->getInput_array()[w]; vertexoffset = offset; } if (offset> triangleIndexStride) { triangleIndexStride = offset; } } triangleIndexStride++; size_t primitivecount = triRef->getCount(); if( primitivecount > triRef->getP_array().getCount() ) { ROS_WARN_STREAM("trifans has incorrect count\n"); primitivecount = triRef->getP_array().getCount(); } for(size_t ip = 0; ip < primitivecount; ++ip) { domList_of_uints indexArray =triRef->getP_array()[ip]->getValue(); for (size_t i=0; igetInput_array().getCount(); ++i) { domInput_localRef localRef = vertsRef->getInput_array()[i]; daeString str = localRef->getSemantic(); if ( strcmp(str,"POSITION") == 0 ) { const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); if( !node ) { continue; } double fUnitScale = _GetUnitScale(node); const domFloat_arrayRef flArray = node->getFloat_array(); if (!!flArray) { const domList_of_floats& listFloats = flArray->getValue(); int k=vertexoffset; int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor' size_t usedindices = 3*(indexArray.getCount()-2); if( geom.indices.capacity() < geom.indices.size()+usedindices ) { geom.indices.reserve(geom.indices.size()+usedindices); } if( geom.vertices.capacity() < geom.vertices.size()+indexArray.getCount() ) { geom.vertices.reserve(geom.vertices.size()+indexArray.getCount()); } size_t startoffset = (int)geom.vertices.size(); while(k < (int)indexArray.getCount() ) { int index0 = indexArray.get(k)*vertexStride; domFloat fl0 = listFloats.get(index0); domFloat fl1 = listFloats.get(index0+1); domFloat fl2 = listFloats.get(index0+2); k+=triangleIndexStride; geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale)); } for(size_t ivert = startoffset+2; ivert < geom.vertices.size(); ++ivert) { geom.indices.push_back(startoffset); geom.indices.push_back(ivert-1); geom.indices.push_back(ivert); } } else { ROS_WARN_STREAM("float array not defined!\n"); } break; } } } geom.InitCollisionMesh(); return false; } /// Extract the Geometry in TRIANGLE STRIPS and adds it to OpenRave /// \param triRef Array of Triangle Strips of the COLLADA's model /// \param vertsRef Array of vertices of the COLLADA's model /// \param mapmaterials Materials applied to the geometry bool _ExtractGeometry(const domTristripsRef triRef, const domVerticesRef vertsRef, const std::map& mapmaterials, std::list& listGeomProperties) { if( !triRef ) { return false; } listGeomProperties.push_back(GEOMPROPERTIES()); GEOMPROPERTIES& geom = listGeomProperties.back(); geom.type = GeomTrimesh; // resolve the material and assign correct colors to the geometry if( !!triRef->getMaterial() ) { std::map::const_iterator itmat = mapmaterials.find(triRef->getMaterial()); if( itmat != mapmaterials.end() ) { _FillGeometryColor(itmat->second,geom); } } size_t triangleIndexStride = 0, vertexoffset = -1; domInput_local_offsetRef indexOffsetRef; for (unsigned int w=0; wgetInput_array().getCount(); w++) { size_t offset = triRef->getInput_array()[w]->getOffset(); daeString str = triRef->getInput_array()[w]->getSemantic(); if (!strcmp(str,"VERTEX")) { indexOffsetRef = triRef->getInput_array()[w]; vertexoffset = offset; } if (offset> triangleIndexStride) { triangleIndexStride = offset; } } triangleIndexStride++; size_t primitivecount = triRef->getCount(); if( primitivecount > triRef->getP_array().getCount() ) { ROS_WARN_STREAM("tristrips has incorrect count\n"); primitivecount = triRef->getP_array().getCount(); } for(size_t ip = 0; ip < primitivecount; ++ip) { domList_of_uints indexArray = triRef->getP_array()[ip]->getValue(); for (size_t i=0; igetInput_array().getCount(); ++i) { domInput_localRef localRef = vertsRef->getInput_array()[i]; daeString str = localRef->getSemantic(); if ( strcmp(str,"POSITION") == 0 ) { const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); if( !node ) { continue; } double fUnitScale = _GetUnitScale(node); const domFloat_arrayRef flArray = node->getFloat_array(); if (!!flArray) { const domList_of_floats& listFloats = flArray->getValue(); int k=vertexoffset; int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor' size_t usedindices = indexArray.getCount()-2; if( geom.indices.capacity() < geom.indices.size()+usedindices ) { geom.indices.reserve(geom.indices.size()+usedindices); } if( geom.vertices.capacity() < geom.vertices.size()+indexArray.getCount() ) { geom.vertices.reserve(geom.vertices.size()+indexArray.getCount()); } size_t startoffset = (int)geom.vertices.size(); while(k < (int)indexArray.getCount() ) { int index0 = indexArray.get(k)*vertexStride; domFloat fl0 = listFloats.get(index0); domFloat fl1 = listFloats.get(index0+1); domFloat fl2 = listFloats.get(index0+2); k+=triangleIndexStride; geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale)); } bool bFlip = false; for(size_t ivert = startoffset+2; ivert < geom.vertices.size(); ++ivert) { geom.indices.push_back(ivert-2); geom.indices.push_back(bFlip ? ivert : ivert-1); geom.indices.push_back(bFlip ? ivert-1 : ivert); bFlip = !bFlip; } } else { ROS_WARN_STREAM("float array not defined!\n"); } break; } } } geom.InitCollisionMesh(); return false; } /// Extract the Geometry in TRIANGLE STRIPS and adds it to OpenRave /// \param triRef Array of Triangle Strips of the COLLADA's model /// \param vertsRef Array of vertices of the COLLADA's model /// \param mapmaterials Materials applied to the geometry bool _ExtractGeometry(const domPolylistRef triRef, const domVerticesRef vertsRef, const std::map& mapmaterials, std::list& listGeomProperties) { if( !triRef ) { return false; } listGeomProperties.push_back(GEOMPROPERTIES()); GEOMPROPERTIES& geom = listGeomProperties.back(); geom.type = GeomTrimesh; // resolve the material and assign correct colors to the geometry if( !!triRef->getMaterial() ) { std::map::const_iterator itmat = mapmaterials.find(triRef->getMaterial()); if( itmat != mapmaterials.end() ) { _FillGeometryColor(itmat->second,geom); } } size_t triangleIndexStride = 0,vertexoffset = -1; domInput_local_offsetRef indexOffsetRef; for (unsigned int w=0; wgetInput_array().getCount(); w++) { size_t offset = triRef->getInput_array()[w]->getOffset(); daeString str = triRef->getInput_array()[w]->getSemantic(); if (!strcmp(str,"VERTEX")) { indexOffsetRef = triRef->getInput_array()[w]; vertexoffset = offset; } if (offset> triangleIndexStride) { triangleIndexStride = offset; } } triangleIndexStride++; const domList_of_uints& indexArray =triRef->getP()->getValue(); for (size_t i=0; igetInput_array().getCount(); ++i) { domInput_localRef localRef = vertsRef->getInput_array()[i]; daeString str = localRef->getSemantic(); if ( strcmp(str,"POSITION") == 0 ) { const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); if( !node ) { continue; } double fUnitScale = _GetUnitScale(node); const domFloat_arrayRef flArray = node->getFloat_array(); if (!!flArray) { const domList_of_floats& listFloats = flArray->getValue(); size_t k=vertexoffset; int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor' for(size_t ipoly = 0; ipoly < triRef->getVcount()->getValue().getCount(); ++ipoly) { size_t numverts = triRef->getVcount()->getValue()[ipoly]; if(numverts > 0 && k+(numverts-1)*triangleIndexStride < indexArray.getCount() ) { size_t startoffset = geom.vertices.size(); for (size_t j=0; j& mapmaterials, std::list& listGeomProperties) { if( !geom ) { return false; } std::vector vconvexhull; if (geom->getMesh()) { const domMeshRef meshRef = geom->getMesh(); for (size_t tg = 0; tggetTriangles_array().getCount(); tg++) { _ExtractGeometry(meshRef->getTriangles_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties); } for (size_t tg = 0; tggetTrifans_array().getCount(); tg++) { _ExtractGeometry(meshRef->getTrifans_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties); } for (size_t tg = 0; tggetTristrips_array().getCount(); tg++) { _ExtractGeometry(meshRef->getTristrips_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties); } for (size_t tg = 0; tggetPolylist_array().getCount(); tg++) { _ExtractGeometry(meshRef->getPolylist_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties); } if( meshRef->getPolygons_array().getCount()> 0 ) { ROS_WARN_STREAM("openrave does not support collada polygons\n"); } // if( alltrimesh.vertices.size() == 0 ) { // const domVerticesRef vertsRef = meshRef->getVertices(); // for (size_t i=0;igetInput_array().getCount();i++) { // domInput_localRef localRef = vertsRef->getInput_array()[i]; // daeString str = localRef->getSemantic(); // if ( strcmp(str,"POSITION") == 0 ) { // const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); // if( !node ) // continue; // double fUnitScale = _GetUnitScale(node); // const domFloat_arrayRef flArray = node->getFloat_array(); // if (!!flArray) { // const domList_of_floats& listFloats = flArray->getValue(); // int vertexStride = 3;//instead of hardcoded stride, should use the 'accessor' // vconvexhull.reserve(vconvexhull.size()+listFloats.getCount()); // for (size_t vertIndex = 0;vertIndex < listFloats.getCount();vertIndex+=vertexStride) { // //btVector3 verts[3]; // domFloat fl0 = listFloats.get(vertIndex); // domFloat fl1 = listFloats.get(vertIndex+1); // domFloat fl2 = listFloats.get(vertIndex+2); // vconvexhull.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale)); // } // } // } // } // // _computeConvexHull(vconvexhull,alltrimesh); // } return true; } else if (geom->getConvex_mesh()) { { const domConvex_meshRef convexRef = geom->getConvex_mesh(); daeElementRef otherElemRef = convexRef->getConvex_hull_of().getElement(); if ( !!otherElemRef ) { domGeometryRef linkedGeom = *(domGeometryRef*)&otherElemRef; ROS_WARN_STREAM( "otherLinked\n"); } else { ROS_WARN("convexMesh polyCount = %d\n",(int)convexRef->getPolygons_array().getCount()); ROS_WARN("convexMesh triCount = %d\n",(int)convexRef->getTriangles_array().getCount()); } } const domConvex_meshRef convexRef = geom->getConvex_mesh(); //daeString urlref = convexRef->getConvex_hull_of().getURI(); daeString urlref2 = convexRef->getConvex_hull_of().getOriginalURI(); if (urlref2) { daeElementRef otherElemRef = convexRef->getConvex_hull_of().getElement(); // Load all the geometry libraries for ( size_t i = 0; i < _dom->getLibrary_geometries_array().getCount(); i++) { domLibrary_geometriesRef libgeom = _dom->getLibrary_geometries_array()[i]; for (size_t i = 0; i < libgeom->getGeometry_array().getCount(); i++) { domGeometryRef lib = libgeom->getGeometry_array()[i]; if (!strcmp(lib->getId(),urlref2+1)) { // skip the # at the front of urlref2 //found convex_hull geometry domMesh *meshElement = lib->getMesh(); //linkedGeom->getMesh(); if (meshElement) { const domVerticesRef vertsRef = meshElement->getVertices(); for (size_t i=0; igetInput_array().getCount(); i++) { domInput_localRef localRef = vertsRef->getInput_array()[i]; daeString str = localRef->getSemantic(); if ( strcmp(str,"POSITION") == 0) { const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); if( !node ) { continue; } double fUnitScale = _GetUnitScale(node); const domFloat_arrayRef flArray = node->getFloat_array(); if (!!flArray) { vconvexhull.reserve(vconvexhull.size()+flArray->getCount()); const domList_of_floats& listFloats = flArray->getValue(); for (size_t k=0; k+2getCount(); k+=3) { domFloat fl0 = listFloats.get(k); domFloat fl1 = listFloats.get(k+1); domFloat fl2 = listFloats.get(k+2); vconvexhull.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale)); } } } } } } } } } else { //no getConvex_hull_of but direct vertices const domVerticesRef vertsRef = convexRef->getVertices(); for (size_t i=0; igetInput_array().getCount(); i++) { domInput_localRef localRef = vertsRef->getInput_array()[i]; daeString str = localRef->getSemantic(); if ( strcmp(str,"POSITION") == 0 ) { const domSourceRef node = daeSafeCast(localRef->getSource().getElement()); if( !node ) { continue; } double fUnitScale = _GetUnitScale(node); const domFloat_arrayRef flArray = node->getFloat_array(); if (!!flArray) { const domList_of_floats& listFloats = flArray->getValue(); vconvexhull.reserve(vconvexhull.size()+flArray->getCount()); for (size_t k=0; k+2getCount(); k+=3) { domFloat fl0 = listFloats.get(k); domFloat fl1 = listFloats.get(k+1); domFloat fl2 = listFloats.get(k+2); vconvexhull.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale)); } } } } } if( vconvexhull.size()> 0 ) { listGeomProperties.push_back(GEOMPROPERTIES()); GEOMPROPERTIES& geom = listGeomProperties.back(); geom.type = GeomTrimesh; //_computeConvexHull(vconvexhull,trimesh); geom.InitCollisionMesh(); } return true; } return false; } /// \brief extract the robot actuators void _ExtractRobotAttachedActuators(const domArticulated_systemRef as) { // over write joint parameters by elements in instance_actuator for(size_t ie = 0; ie < as->getExtra_array().getCount(); ++ie) { domExtraRef pextra = as->getExtra_array()[ie]; if( strcmp(pextra->getType(), "attach_actuator") == 0 ) { //std::string aname = pextra->getAttribute("name"); domTechniqueRef tec = _ExtractOpenRAVEProfile(pextra->getTechnique_array()); if( !!tec ) { boost::shared_ptr pjoint; daeElementRef domactuator; { daeElementRef bact = tec->getChild("bind_actuator"); pjoint = _getJointFromRef(bact->getAttribute("joint").c_str(), as); if (!pjoint) continue; } { daeElementRef iact = tec->getChild("instance_actuator"); if(!iact) continue; std::string instance_url = iact->getAttribute("url"); domactuator = daeURI(*iact, instance_url).getElement(); if(!domactuator) continue; } daeElement *nom_torque = domactuator->getChild("nominal_torque"); if ( !! nom_torque ) { if( !! pjoint->limits ) { pjoint->limits->effort = boost::lexical_cast(nom_torque->getCharData()); ROS_DEBUG("effort limit at joint (%s) is over written by %f", pjoint->name.c_str(), pjoint->limits->effort); } } } } } } /// \brief extract the robot manipulators void _ExtractRobotManipulators(const domArticulated_systemRef as) { ROS_DEBUG("collada manipulators not supported yet"); } /// \brief Extract Sensors attached to a Robot void _ExtractRobotAttachedSensors(const domArticulated_systemRef as) { ROS_DEBUG("collada sensors not supported yet"); } inline daeElementRef _getElementFromUrl(const daeURI &uri) { return daeStandardURIResolver(*_collada).resolveElement(uri); } static daeElement* searchBinding(domCommon_sidref_or_paramRef paddr, daeElementRef parent) { if( !!paddr->getSIDREF() ) { return daeSidRef(paddr->getSIDREF()->getValue(),parent).resolve().elt; } if (!!paddr->getParam()) { return searchBinding(paddr->getParam()->getValue(),parent); } return NULL; } /// Search a given parameter reference and stores the new reference to search. /// \param ref the reference name to search /// \param parent The array of parameter where the method searchs. static daeElement* searchBinding(daeString ref, daeElementRef parent) { if( !parent ) { return NULL; } daeElement* pelt = NULL; domKinematics_sceneRef kscene = daeSafeCast(parent.cast()); if( !!kscene ) { pelt = searchBindingArray(ref,kscene->getInstance_articulated_system_array()); if( !!pelt ) { return pelt; } return searchBindingArray(ref,kscene->getInstance_kinematics_model_array()); } domArticulated_systemRef articulated_system = daeSafeCast(parent.cast()); if( !!articulated_system ) { if( !!articulated_system->getKinematics() ) { pelt = searchBindingArray(ref,articulated_system->getKinematics()->getInstance_kinematics_model_array()); if( !!pelt ) { return pelt; } } if( !!articulated_system->getMotion() ) { return searchBinding(ref,articulated_system->getMotion()->getInstance_articulated_system()); } return NULL; } // try to get a bind array daeElementRef pbindelt; const domKinematics_bind_Array* pbindarray = NULL; const domKinematics_newparam_Array* pnewparamarray = NULL; domInstance_articulated_systemRef ias = daeSafeCast(parent.cast()); if( !!ias ) { pbindarray = &ias->getBind_array(); pbindelt = ias->getUrl().getElement(); pnewparamarray = &ias->getNewparam_array(); } if( !pbindarray || !pbindelt ) { domInstance_kinematics_modelRef ikm = daeSafeCast(parent.cast()); if( !!ikm ) { pbindarray = &ikm->getBind_array(); pbindelt = ikm->getUrl().getElement(); pnewparamarray = &ikm->getNewparam_array(); } } if( !!pbindarray && !!pbindelt ) { for (size_t ibind = 0; ibind < pbindarray->getCount(); ++ibind) { domKinematics_bindRef pbind = (*pbindarray)[ibind]; if( !!pbind->getSymbol() && strcmp(pbind->getSymbol(), ref) == 0 ) { // found a match if( !!pbind->getParam() ) { return daeSidRef(pbind->getParam()->getRef(), pbindelt).resolve().elt; } else if( !!pbind->getSIDREF() ) { return daeSidRef(pbind->getSIDREF()->getValue(), pbindelt).resolve().elt; } } } for(size_t inewparam = 0; inewparam < pnewparamarray->getCount(); ++inewparam) { domKinematics_newparamRef newparam = (*pnewparamarray)[inewparam]; if( !!newparam->getSid() && strcmp(newparam->getSid(), ref) == 0 ) { if( !!newparam->getSIDREF() ) { // can only bind with SIDREF return daeSidRef(newparam->getSIDREF()->getValue(),pbindelt).resolve().elt; } ROS_WARN_STREAM(str(boost::format("newparam sid=%s does not have SIDREF\n")%newparam->getSid())); } } } ROS_WARN_STREAM(str(boost::format("failed to get binding '%s' for element: %s\n")%ref%parent->getElementName())); return NULL; } static daeElement* searchBindingArray(daeString ref, const domInstance_articulated_system_Array& paramArray) { for(size_t iikm = 0; iikm < paramArray.getCount(); ++iikm) { daeElement* pelt = searchBinding(ref,paramArray[iikm].cast()); if( !!pelt ) { return pelt; } } return NULL; } static daeElement* searchBindingArray(daeString ref, const domInstance_kinematics_model_Array& paramArray) { for(size_t iikm = 0; iikm < paramArray.getCount(); ++iikm) { daeElement* pelt = searchBinding(ref,paramArray[iikm].cast()); if( !!pelt ) { return pelt; } } return NULL; } template static xsBoolean resolveBool(domCommon_bool_or_paramRef paddr, const U& parent) { if( !!paddr->getBool() ) { return paddr->getBool()->getValue(); } if( !paddr->getParam() ) { ROS_WARN_STREAM("param not specified, setting to 0\n"); return false; } for(size_t iparam = 0; iparam < parent->getNewparam_array().getCount(); ++iparam) { domKinematics_newparamRef pnewparam = parent->getNewparam_array()[iparam]; if( !!pnewparam->getSid() && strcmp(pnewparam->getSid(), paddr->getParam()->getValue()) == 0 ) { if( !!pnewparam->getBool() ) { return pnewparam->getBool()->getValue(); } else if( !!pnewparam->getSIDREF() ) { domKinematics_newparam::domBoolRef ptarget = daeSafeCast(daeSidRef(pnewparam->getSIDREF()->getValue(), pnewparam).resolve().elt); if( !ptarget ) { ROS_WARN("failed to resolve %s from %s\n", pnewparam->getSIDREF()->getValue(), paddr->getID()); continue; } return ptarget->getValue(); } } } ROS_WARN_STREAM(str(boost::format("failed to resolve %s\n")%paddr->getParam()->getValue())); return false; } template static domFloat resolveFloat(domCommon_float_or_paramRef paddr, const U& parent) { if( !!paddr->getFloat() ) { return paddr->getFloat()->getValue(); } if( !paddr->getParam() ) { ROS_WARN_STREAM("param not specified, setting to 0\n"); return 0; } for(size_t iparam = 0; iparam < parent->getNewparam_array().getCount(); ++iparam) { domKinematics_newparamRef pnewparam = parent->getNewparam_array()[iparam]; if( !!pnewparam->getSid() && strcmp(pnewparam->getSid(), paddr->getParam()->getValue()) == 0 ) { if( !!pnewparam->getFloat() ) { return pnewparam->getFloat()->getValue(); } else if( !!pnewparam->getSIDREF() ) { domKinematics_newparam::domFloatRef ptarget = daeSafeCast(daeSidRef(pnewparam->getSIDREF()->getValue(), pnewparam).resolve().elt); if( !ptarget ) { ROS_WARN("failed to resolve %s from %s\n", pnewparam->getSIDREF()->getValue(), paddr->getID()); continue; } return ptarget->getValue(); } } } ROS_WARN_STREAM(str(boost::format("failed to resolve %s\n")%paddr->getParam()->getValue())); return 0; } static bool resolveCommon_float_or_param(daeElementRef pcommon, daeElementRef parent, float& f) { daeElement* pfloat = pcommon->getChild("float"); if( !!pfloat ) { std::stringstream sfloat(pfloat->getCharData()); sfloat >> f; return !!sfloat; } daeElement* pparam = pcommon->getChild("param"); if( !!pparam ) { if( pparam->hasAttribute("ref") ) { ROS_WARN_STREAM("cannot process param ref\n"); } else { daeElement* pelt = daeSidRef(pparam->getCharData(),parent).resolve().elt; if( !!pelt ) { ROS_WARN_STREAM(str(boost::format("found param ref: %s from %s\n")%pelt->getCharData()%pparam->getCharData())); } } } return false; } static boost::array _matrixIdentity() { boost::array m = {{1,0,0,0,0,1,0,0,0,0,1,0}}; return m; }; /// Gets all transformations applied to the node static boost::array _getTransform(daeElementRef pelt) { boost::array m = _matrixIdentity(); domRotateRef protate = daeSafeCast(pelt); if( !!protate ) { m = _matrixFromAxisAngle(Vector3(protate->getValue()[0],protate->getValue()[1],protate->getValue()[2]), (double)(protate->getValue()[3]*(M_PI/180.0))); return m; } domTranslateRef ptrans = daeSafeCast(pelt); if( !!ptrans ) { double scale = _GetUnitScale(pelt); m[3] = ptrans->getValue()[0]*scale; m[7] = ptrans->getValue()[1]*scale; m[11] = ptrans->getValue()[2]*scale; return m; } domMatrixRef pmat = daeSafeCast(pelt); if( !!pmat ) { double scale = _GetUnitScale(pelt); for(int i = 0; i < 3; ++i) { m[4*i+0] = pmat->getValue()[4*i+0]; m[4*i+1] = pmat->getValue()[4*i+1]; m[4*i+2] = pmat->getValue()[4*i+2]; m[4*i+3] = pmat->getValue()[4*i+3]*scale; } return m; } domScaleRef pscale = daeSafeCast(pelt); if( !!pscale ) { m[0] = pscale->getValue()[0]; m[4*1+1] = pscale->getValue()[1]; m[4*2+2] = pscale->getValue()[2]; return m; } domLookatRef pcamera = daeSafeCast(pelt); if( pelt->typeID() == domLookat::ID() ) { ROS_ERROR_STREAM("look at transform not implemented\n"); return m; } domSkewRef pskew = daeSafeCast(pelt); if( !!pskew ) { ROS_ERROR_STREAM("skew transform not implemented\n"); } return m; } /// Travels recursively the node parents of the given one /// to extract the Transform arrays that affects the node given template static boost::array _getNodeParentTransform(const T pelt) { domNodeRef pnode = daeSafeCast(pelt->getParent()); if( !pnode ) { return _matrixIdentity(); } return _poseMult(_getNodeParentTransform(pnode), _ExtractFullTransform(pnode)); } /// \brief Travel by the transformation array and calls the _getTransform method template static boost::array _ExtractFullTransform(const T pelt) { boost::array t = _matrixIdentity(); for(size_t i = 0; i < pelt->getContents().getCount(); ++i) { t = _poseMult(t, _getTransform(pelt->getContents()[i])); } return t; } /// \brief Travel by the transformation array and calls the _getTransform method template static boost::array _ExtractFullTransformFromChildren(const T pelt) { boost::array t = _matrixIdentity(); daeTArray children; pelt->getChildren(children); for(size_t i = 0; i < children.getCount(); ++i) { t = _poseMult(t, _getTransform(children[i])); } return t; } // decompose a matrix into a scale and rigid transform (necessary for model scales) void _decompose(const boost::array& tm, Pose& tout, Vector3& vscale) { vscale.x = 1; vscale.y = 1; vscale.z = 1; tout = _poseFromMatrix(tm); } virtual void handleError( daeString msg ) { ROS_ERROR("COLLADA error: %s\n", msg); } virtual void handleWarning( daeString msg ) { ROS_WARN("COLLADA warning: %s\n", msg); } inline static double _GetUnitScale(daeElement* pelt) { return ((USERDATA*)pelt->getUserData())->scale; } domTechniqueRef _ExtractOpenRAVEProfile(const domTechnique_Array& arr) { for(size_t i = 0; i < arr.getCount(); ++i) { if( strcmp(arr[i]->getProfile(), "OpenRAVE") == 0 ) { return arr[i]; } } return domTechniqueRef(); } /// \brief returns an openrave interface type from the extra array boost::shared_ptr _ExtractInterfaceType(const domExtra_Array& arr) { for(size_t i = 0; i < arr.getCount(); ++i) { if( strcmp(arr[i]->getType(),"interface_type") == 0 ) { domTechniqueRef tec = _ExtractOpenRAVEProfile(arr[i]->getTechnique_array()); if( !!tec ) { daeElement* ptype = tec->getChild("interface"); if( !!ptype ) { return boost::shared_ptr(new std::string(ptype->getCharData())); } } } } return boost::shared_ptr(); } std::string _ExtractLinkName(domLinkRef pdomlink) { std::string linkname; if( !!pdomlink ) { if( !!pdomlink->getName() ) { linkname = pdomlink->getName(); } if( linkname.size() == 0 && !!pdomlink->getID() ) { linkname = pdomlink->getID(); } } return linkname; } bool _checkMathML(daeElementRef pelt,const std::string& type) { if( pelt->getElementName()==type ) { return true; } // check the substring after ':' std::string name = pelt->getElementName(); std::size_t pos = name.find_last_of(':'); if( pos == std::string::npos ) { return false; } return name.substr(pos+1)==type; } boost::shared_ptr _getJointFromRef(xsToken targetref, daeElementRef peltref) { daeElement* peltjoint = daeSidRef(targetref, peltref).resolve().elt; domJointRef pdomjoint = daeSafeCast (peltjoint); if (!pdomjoint) { domInstance_jointRef pdomijoint = daeSafeCast (peltjoint); if (!!pdomijoint) { pdomjoint = daeSafeCast (pdomijoint->getUrl().getElement().cast()); } } if (!pdomjoint || pdomjoint->typeID() != domJoint::ID() || !pdomjoint->getName()) { ROS_WARN_STREAM(str(boost::format("could not find collada joint %s!\n")%targetref)); return boost::shared_ptr(); } boost::shared_ptr pjoint; std::string name(pdomjoint->getName()); if (_model->joints_.find(name) == _model->joints_.end()) { pjoint.reset(); } else { pjoint = _model->joints_.find(name)->second; } if(!pjoint) { ROS_WARN_STREAM(str(boost::format("could not find openrave joint %s!\n")%pdomjoint->getName())); } return pjoint; } /// \brief go through all kinematics binds to get a kinematics/visual pair /// \param kiscene instance of one kinematics scene, binds the kinematic and visual models /// \param bindings the extracted bindings static void _ExtractKinematicsVisualBindings(domInstance_with_extraRef viscene, domInstance_kinematics_sceneRef kiscene, KinematicsSceneBindings& bindings) { domKinematics_sceneRef kscene = daeSafeCast (kiscene->getUrl().getElement().cast()); if (!kscene) { return; } for (size_t imodel = 0; imodel < kiscene->getBind_kinematics_model_array().getCount(); imodel++) { domArticulated_systemRef articulated_system; // if filled, contains robot-specific information, so create a robot domBind_kinematics_modelRef kbindmodel = kiscene->getBind_kinematics_model_array()[imodel]; if (!kbindmodel->getNode()) { ROS_WARN_STREAM("do not support kinematics models without references to nodes\n"); continue; } // visual information domNodeRef node = daeSafeCast(daeSidRef(kbindmodel->getNode(), viscene->getUrl().getElement()).resolve().elt); if (!node) { ROS_WARN_STREAM(str(boost::format("bind_kinematics_model does not reference valid node %s\n")%kbindmodel->getNode())); continue; } // kinematics information daeElement* pelt = searchBinding(kbindmodel,kscene); domInstance_kinematics_modelRef kimodel = daeSafeCast(pelt); if (!kimodel) { if( !pelt ) { ROS_WARN_STREAM("bind_kinematics_model does not reference element\n"); } else { ROS_WARN_STREAM(str(boost::format("bind_kinematics_model cannot find reference to %s:\n")%pelt->getElementName())); } continue; } bindings.listKinematicsVisualBindings.push_back(std::make_pair(node,kimodel)); } // axis info for (size_t ijoint = 0; ijoint < kiscene->getBind_joint_axis_array().getCount(); ++ijoint) { domBind_joint_axisRef bindjoint = kiscene->getBind_joint_axis_array()[ijoint]; daeElementRef pjtarget = daeSidRef(bindjoint->getTarget(), viscene->getUrl().getElement()).resolve().elt; if (!pjtarget) { ROS_ERROR_STREAM(str(boost::format("Target Node %s NOT found!!!\n")%bindjoint->getTarget())); continue; } daeElement* pelt = searchBinding(bindjoint->getAxis(),kscene); domAxis_constraintRef pjointaxis = daeSafeCast(pelt); if (!pjointaxis) { continue; } bindings.listAxisBindings.push_back(JointAxisBinding(pjtarget, pjointaxis, bindjoint->getValue(), NULL, NULL)); } } static void _ExtractPhysicsBindings(domCOLLADA::domSceneRef allscene, KinematicsSceneBindings& bindings) { for(size_t iphysics = 0; iphysics < allscene->getInstance_physics_scene_array().getCount(); ++iphysics) { domPhysics_sceneRef pscene = daeSafeCast(allscene->getInstance_physics_scene_array()[iphysics]->getUrl().getElement().cast()); for(size_t imodel = 0; imodel < pscene->getInstance_physics_model_array().getCount(); ++imodel) { domInstance_physics_modelRef ipmodel = pscene->getInstance_physics_model_array()[imodel]; domPhysics_modelRef pmodel = daeSafeCast (ipmodel->getUrl().getElement().cast()); domNodeRef nodephysicsoffset = daeSafeCast(ipmodel->getParent().getElement().cast()); for(size_t ibody = 0; ibody < ipmodel->getInstance_rigid_body_array().getCount(); ++ibody) { LinkBinding lb; lb.irigidbody = ipmodel->getInstance_rigid_body_array()[ibody]; lb.node = daeSafeCast(lb.irigidbody->getTarget().getElement().cast()); lb.rigidbody = daeSafeCast(daeSidRef(lb.irigidbody->getBody(),pmodel).resolve().elt); lb.nodephysicsoffset = nodephysicsoffset; if( !!lb.rigidbody && !!lb.node ) { bindings.listLinkBindings.push_back(lb); } } } } } size_t _countChildren(daeElement* pelt) { size_t c = 1; daeTArray children; pelt->getChildren(children); for (size_t i = 0; i < children.getCount(); ++i) { c += _countChildren(children[i]); } return c; } void _processUserData(daeElement* pelt, double scale) { // getChild could be optimized since asset tag is supposed to appear as the first element domAssetRef passet = daeSafeCast (pelt->getChild("asset")); if (!!passet && !!passet->getUnit()) { scale = passet->getUnit()->getMeter(); } _vuserdata.push_back(USERDATA(scale)); pelt->setUserData(&_vuserdata.back()); daeTArray children; pelt->getChildren(children); for (size_t i = 0; i < children.getCount(); ++i) { if (children[i] != passet) { _processUserData(children[i], scale); } } } USERDATA* _getUserData(daeElement* pelt) { BOOST_ASSERT(!!pelt); void* p = pelt->getUserData(); BOOST_ASSERT(!!p); return (USERDATA*)p; } // // openrave math functions (from geometry.h) // static Vector3 _poseMult(const Pose& p, const Vector3& v) { double ww = 2 * p.rotation.x * p.rotation.x; double wx = 2 * p.rotation.x * p.rotation.y; double wy = 2 * p.rotation.x * p.rotation.z; double wz = 2 * p.rotation.x * p.rotation.w; double xx = 2 * p.rotation.y * p.rotation.y; double xy = 2 * p.rotation.y * p.rotation.z; double xz = 2 * p.rotation.y * p.rotation.w; double yy = 2 * p.rotation.z * p.rotation.z; double yz = 2 * p.rotation.z * p.rotation.w; Vector3 vnew; vnew.x = (1-xx-yy) * v.x + (wx-yz) * v.y + (wy+xz)*v.z + p.position.x; vnew.y = (wx+yz) * v.x + (1-ww-yy) * v.y + (xy-wz)*v.z + p.position.y; vnew.z = (wy-xz) * v.x + (xy+wz) * v.y + (1-ww-xx)*v.z + p.position.z; return vnew; } static Vector3 _poseMult(const boost::array& m, const Vector3& v) { Vector3 vnew; vnew.x = m[4*0+0] * v.x + m[4*0+1] * v.y + m[4*0+2] * v.z + m[4*0+3]; vnew.y = m[4*1+0] * v.x + m[4*1+1] * v.y + m[4*1+2] * v.z + m[4*1+3]; vnew.z = m[4*2+0] * v.x + m[4*2+1] * v.y + m[4*2+2] * v.z + m[4*2+3]; return vnew; } static boost::array _poseMult(const boost::array& m0, const boost::array& m1) { boost::array mres; mres[0*4+0] = m0[0*4+0]*m1[0*4+0]+m0[0*4+1]*m1[1*4+0]+m0[0*4+2]*m1[2*4+0]; mres[0*4+1] = m0[0*4+0]*m1[0*4+1]+m0[0*4+1]*m1[1*4+1]+m0[0*4+2]*m1[2*4+1]; mres[0*4+2] = m0[0*4+0]*m1[0*4+2]+m0[0*4+1]*m1[1*4+2]+m0[0*4+2]*m1[2*4+2]; mres[1*4+0] = m0[1*4+0]*m1[0*4+0]+m0[1*4+1]*m1[1*4+0]+m0[1*4+2]*m1[2*4+0]; mres[1*4+1] = m0[1*4+0]*m1[0*4+1]+m0[1*4+1]*m1[1*4+1]+m0[1*4+2]*m1[2*4+1]; mres[1*4+2] = m0[1*4+0]*m1[0*4+2]+m0[1*4+1]*m1[1*4+2]+m0[1*4+2]*m1[2*4+2]; mres[2*4+0] = m0[2*4+0]*m1[0*4+0]+m0[2*4+1]*m1[1*4+0]+m0[2*4+2]*m1[2*4+0]; mres[2*4+1] = m0[2*4+0]*m1[0*4+1]+m0[2*4+1]*m1[1*4+1]+m0[2*4+2]*m1[2*4+1]; mres[2*4+2] = m0[2*4+0]*m1[0*4+2]+m0[2*4+1]*m1[1*4+2]+m0[2*4+2]*m1[2*4+2]; mres[3] = m1[3] * m0[0] + m1[7] * m0[1] + m1[11] * m0[2] + m0[3]; mres[7] = m1[3] * m0[4] + m1[7] * m0[5] + m1[11] * m0[6] + m0[7]; mres[11] = m1[3] * m0[8] + m1[7] * m0[9] + m1[11] * m0[10] + m0[11]; return mres; } static Pose _poseMult(const Pose& p0, const Pose& p1) { Pose p; p.position = _poseMult(p0,p1.position); p.rotation = _quatMult(p0.rotation,p1.rotation); return p; } static Pose _poseInverse(const Pose& p) { Pose pinv; pinv.rotation.x = -p.rotation.x; pinv.rotation.y = -p.rotation.y; pinv.rotation.z = -p.rotation.z; pinv.rotation.w = p.rotation.w; Vector3 t = _poseMult(pinv,p.position); pinv.position.x = -t.x; pinv.position.y = -t.y; pinv.position.z = -t.z; return pinv; } static Rotation _quatMult(const Rotation& quat0, const Rotation& quat1) { Rotation q; q.x = quat0.w*quat1.x + quat0.x*quat1.w + quat0.y*quat1.z - quat0.z*quat1.y; q.y = quat0.w*quat1.y + quat0.y*quat1.w + quat0.z*quat1.x - quat0.x*quat1.z; q.z = quat0.w*quat1.z + quat0.z*quat1.w + quat0.x*quat1.y - quat0.y*quat1.x; q.w = quat0.w*quat1.w - quat0.x*quat1.x - quat0.y*quat1.y - quat0.z*quat1.z; double fnorm = std::sqrt(q.x*q.x+q.y*q.y+q.z*q.z+q.w*q.w); // don't touch the divides q.x /= fnorm; q.y /= fnorm; q.z /= fnorm; q.w /= fnorm; return q; } static boost::array _matrixFromAxisAngle(const Vector3& axis, double angle) { return _matrixFromQuat(_quatFromAxisAngle(axis.x,axis.y,axis.z,angle)); } static boost::array _matrixFromQuat(const Rotation& quat) { boost::array m; double qq1 = 2*quat.x*quat.x; double qq2 = 2*quat.y*quat.y; double qq3 = 2*quat.z*quat.z; m[4*0+0] = 1 - qq2 - qq3; m[4*0+1] = 2*(quat.x*quat.y - quat.w*quat.z); m[4*0+2] = 2*(quat.x*quat.z + quat.w*quat.y); m[4*0+3] = 0; m[4*1+0] = 2*(quat.x*quat.y + quat.w*quat.z); m[4*1+1] = 1 - qq1 - qq3; m[4*1+2] = 2*(quat.y*quat.z - quat.w*quat.x); m[4*1+3] = 0; m[4*2+0] = 2*(quat.x*quat.z - quat.w*quat.y); m[4*2+1] = 2*(quat.y*quat.z + quat.w*quat.x); m[4*2+2] = 1 - qq1 - qq2; m[4*2+3] = 0; return m; } static Pose _poseFromMatrix(const boost::array& m) { Pose t; t.rotation = _quatFromMatrix(m); t.position.x = m[3]; t.position.y = m[7]; t.position.z = m[11]; return t; } static boost::array _matrixFromPose(const Pose& t) { boost::array m = _matrixFromQuat(t.rotation); m[3] = t.position.x; m[7] = t.position.y; m[11] = t.position.z; return m; } static Rotation _quatFromAxisAngle(double x, double y, double z, double angle) { Rotation q; double axislen = std::sqrt(x*x+y*y+z*z); if( axislen == 0 ) { return q; } angle *= 0.5; double sang = std::sin(angle)/axislen; q.w = std::cos(angle); q.x = x*sang; q.y = y*sang; q.z = z*sang; return q; } static Rotation _quatFromMatrix(const boost::array& mat) { Rotation rot; double tr = mat[4*0+0] + mat[4*1+1] + mat[4*2+2]; if (tr >= 0) { rot.w = tr + 1; rot.x = (mat[4*2+1] - mat[4*1+2]); rot.y = (mat[4*0+2] - mat[4*2+0]); rot.z = (mat[4*1+0] - mat[4*0+1]); } else { // find the largest diagonal element and jump to the appropriate case if (mat[4*1+1] > mat[4*0+0]) { if (mat[4*2+2] > mat[4*1+1]) { rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1; rot.x = (mat[4*2+0] + mat[4*0+2]); rot.y = (mat[4*1+2] + mat[4*2+1]); rot.w = (mat[4*1+0] - mat[4*0+1]); } else { rot.y = (mat[4*1+1] - (mat[4*2+2] + mat[4*0+0])) + 1; rot.z = (mat[4*1+2] + mat[4*2+1]); rot.x = (mat[4*0+1] + mat[4*1+0]); rot.w = (mat[4*0+2] - mat[4*2+0]); } } else if (mat[4*2+2] > mat[4*0+0]) { rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1; rot.x = (mat[4*2+0] + mat[4*0+2]); rot.y = (mat[4*1+2] + mat[4*2+1]); rot.w = (mat[4*1+0] - mat[4*0+1]); } else { rot.x = (mat[4*0+0] - (mat[4*1+1] + mat[4*2+2])) + 1; rot.y = (mat[4*0+1] + mat[4*1+0]); rot.z = (mat[4*2+0] + mat[4*0+2]); rot.w = (mat[4*2+1] - mat[4*1+2]); } } double fnorm = std::sqrt(rot.x*rot.x+rot.y*rot.y+rot.z*rot.z+rot.w*rot.w); // don't touch the divides rot.x /= fnorm; rot.y /= fnorm; rot.z /= fnorm; rot.w /= fnorm; return rot; } static double _dot3(const Vector3& v0, const Vector3& v1) { return v0.x*v1.x + v0.y*v1.y + v0.z*v1.z; } static Vector3 _cross3(const Vector3& v0, const Vector3& v1) { Vector3 v; v.x = v0.y * v1.z - v0.z * v1.y; v.y = v0.z * v1.x - v0.x * v1.z; v.z = v0.x * v1.y - v0.y * v1.x; return v; } static Vector3 _sub3(const Vector3& v0, const Vector3& v1) { Vector3 v; v.x = v0.x-v1.x; v.y = v0.y-v1.y; v.z = v0.z-v1.z; return v; } static Vector3 _add3(const Vector3& v0, const Vector3& v1) { Vector3 v; v.x = v0.x+v1.x; v.y = v0.y+v1.y; v.z = v0.z+v1.z; return v; } static Vector3 _normalize3(const Vector3& v0) { Vector3 v; double norm = std::sqrt(v0.x*v0.x+v0.y*v0.y+v0.z*v0.z); v.x = v0.x/norm; v.y = v0.y/norm; v.z = v0.z/norm; return v; } boost::shared_ptr _collada; domCOLLADA* _dom; std::vector _vuserdata; // all userdata int _nGlobalSensorId, _nGlobalManipulatorId; std::string _filename; std::string _resourcedir; boost::shared_ptr _model; Pose _RootOrigin; Pose _VisualRootOrigin; }; boost::shared_ptr parseCollada(const std::string &xml_str) { boost::shared_ptr model(new ModelInterface); ColladaModelReader reader(model); if (!reader.InitFromData(xml_str)) model.reset(); return model; } } ros-robot-model-1.11.8/collada_parser/src/collada_parser_plugin.cpp000066400000000000000000000041451257532150500254360ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2013, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Ioan Sucan */ #include "collada_parser/collada_parser_plugin.h" #include "collada_parser/collada_parser.h" #include boost::shared_ptr urdf::ColladaURDFParser::parse(const std::string &xml_string) { return urdf::parseCollada(xml_string); } CLASS_LOADER_REGISTER_CLASS(urdf::ColladaURDFParser, urdf::URDFParser) ros-robot-model-1.11.8/collada_urdf/000077500000000000000000000000001257532150500172525ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_urdf/CHANGELOG.rst000066400000000000000000000046741257532150500213060ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package collada_urdf ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.11.8 (2015-09-11) ------------------- * Removed pcre hack for newer released collada-dom. * Contributors: Kei Okada 1.11.7 (2015-04-22) ------------------- * Fixed `#89 `_ Accomplished by loading libpcrecpp before collada-dom. * Contributors: Kei Okada, William Woodall 1.11.6 (2014-11-30) ------------------- 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 * Fix clash with assimp 3.1 in CMake. * Contributors: Benjamin Chrétien, Tully Foote 1.11.3 (2014-06-24) ------------------- * Merge pull request `#69 `_ from YoheiKakiuchi/indigo-devel-store-original-mesh-name storing original mesh file name and location * storing original mesh file name and location * Contributors: Ioan A Sucan, YoheiKakiuchi 1.11.2 (2014-03-22) ------------------- * use new urdfdom_headers API * Contributors: Ioan Sucan 1.11.1 (2014-03-20) ------------------- * Use assimp-dev dep for building * Contributors: Scott K Logan 1.11.0 (2014-02-21) ------------------- * Use VERSION_LESS instead of STRLESS The version comparison routines were added in cmake 2.8.0 * Fix export API detection (for assimp < 2.0.885) It looks like this API was added in Assimp 2.0.885: https://github.com/assimp/assimp/commit/ae23c03bd9a0b5f1227dc0042fd98f7206c770a8 * Invert Assimp version detect logic for greater accuracy * Updated Assimp defines to be more flexible This commit is a follow-up to 85b20197671e142044e471df603debd0faf08baf Why was export.h removed from assimp < 3.0.0? * Better feature detection for assimp version The unified headers were introduced in Assimp 2.0.1150, so checking for Assimp 3.0.0 is not quite the best solution. See https://github.com/assimp/assimp/commit/6fa251c2f2e7a142bb861227dce0c26362927fbc * Contributors: Scott K Logan 1.10.18 (2013-12-04) -------------------- * add DEPENDS for kdl_parser * Contributors: Ioan Sucan 1.10.16 (2013-11-18) -------------------- * check for CATKIN_ENABLE_TESTING * fix for compiling collada_to_urdf, add dependency to tf * add collada_to_urdf.cpp for converting collada file to urdf file 1.10.15 (2013-08-17) -------------------- * fix `#30 `_ ros-robot-model-1.11.8/collada_urdf/CMakeLists.txt000066400000000000000000000061241257532150500220150ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(collada_urdf) find_package(catkin REQUIRED COMPONENTS angles collada_parser resource_retriever urdf geometric_shapes tf cmake_modules) find_package(TinyXML REQUIRED) catkin_package( LIBRARIES ${PROJECT_NAME} INCLUDE_DIRS include DEPENDS angles collada_parser resource_retriever urdf geometric_shapes tf) include_directories(include) find_package(assimp QUIET) if ( NOT ASSIMP_FOUND ) find_package(Assimp QUIET) if ( NOT ASSIMP_FOUND ) find_package(PkgConfig REQUIRED) pkg_check_modules(ASSIMP assimp) endif() endif() if( ASSIMP_FOUND ) if( NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150" ) add_definitions(-DASSIMP_UNIFIED_HEADER_NAMES) endif() if( NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.885" ) add_definitions(-DASSIMP_EXPORT_API) endif() include_directories(${ASSIMP_INCLUDE_DIRS}) link_directories(${ASSIMP_LIBRARY_DIRS}) else() message(STATUS "could not find assimp (perhaps available thorugh ROS package?), so assuming assimp v2") set(ASSIMP_LIBRARIES assimp) set(ASSIMP_LIBRARY_DIRS) set(ASSIMP_CXX_FLAGS) set(ASSIMP_CFLAGS_OTHER) set(ASSIMP_LINK_FLAGS) set(ASSIMP_INCLUDE_DIRS) endif() # Note: assimp 3.1 overwrites CMake Boost variables, so we need to check for # Boost after assimp. find_package(Boost REQUIRED COMPONENTS system filesystem program_options) include_directories(${Boost_INCLUDE_DIR}) find_package(COLLADA_DOM 2.3 COMPONENTS 1.5) if( COLLADA_DOM_FOUND ) include_directories(${COLLADA_DOM_INCLUDE_DIRS}) link_directories(${COLLADA_DOM_LIBRARY_DIRS}) endif() include_directories(${TinyXML_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS}) link_directories(${catkin_LIBRARY_DIRS}) add_library(${PROJECT_NAME} src/collada_urdf.cpp) target_link_libraries(${PROJECT_NAME} ${TinyXML_LIBRARIES} ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES} ${ASSIMP_LIBRARIES}) set_target_properties(${PROJECT_NAME} PROPERTIES COMPILER_FLAGS "${ASSIMP_CXX_FLAGS} ${ASSIMP_CFLAGS_OTHER}") set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "${ASSIMP_LINK_FLAGS}") add_executable(urdf_to_collada src/urdf_to_collada.cpp) target_link_libraries(urdf_to_collada ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES} ${PROJECT_NAME}) add_executable(collada_to_urdf src/collada_to_urdf.cpp) target_link_libraries(collada_to_urdf ${ASSIMP_LIBRARIES} ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES}) set_target_properties(collada_to_urdf PROPERTIES COMPILER_FLAGS "${ASSIMP_CXX_FLAGS} ${ASSIMP_CFLAGS_OTHER}") set_target_properties(collada_to_urdf PROPERTIES LINK_FLAGS "${ASSIMP_LINK_FLAGS}") if(CATKIN_ENABLE_TESTING) catkin_add_gtest(test_collada_writer test/test_collada_urdf.cpp) target_link_libraries(test_collada_writer ${PROJECT_NAME} ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES}) endif() install(TARGETS ${PROJECT_NAME} urdf_to_collada collada_to_urdf LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) ros-robot-model-1.11.8/collada_urdf/include/000077500000000000000000000000001257532150500206755ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_urdf/include/collada_urdf/000077500000000000000000000000001257532150500233145ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_urdf/include/collada_urdf/collada_urdf.h000066400000000000000000000045301257532150500261060ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redstributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Authors: Tim Field */ #ifndef COLLADA_URDF_COLLADA_URDF_H #define COLLADA_URDF_COLLADA_URDF_H #include #include #include #include "urdf/model.h" namespace collada_urdf { class ColladaUrdfException : public std::runtime_error { public: ColladaUrdfException(std::string const& what); }; /** Write a COLLADA DOM to a file * \param robot_model The URDF robot model * \param file The filename to write the document to * \return true on success, false on failure */ bool WriteUrdfModelToColladaFile(urdf::Model const& robot_model, std::string const& file); } #endif ros-robot-model-1.11.8/collada_urdf/package.xml000066400000000000000000000031301257532150500213640ustar00rootroot00000000000000 collada_urdf 1.11.8 This package contains a tool to convert Unified Robot Description Format (URDF) documents into COLLAborative Design Activity (COLLADA) documents. Implements robot-specific COLLADA extensions as defined by http://openrave.programmingvision.com/index.php/Started:COLLADA Tim Field Rosen Diankov Ioan Sucan BSD http://ros.org/wiki/collada_urdf catkin angles assimp-dev resource_retriever collada-dom collada_parser liburdfdom-dev liburdfdom-headers-dev roscpp urdf geometric_shapes tf cmake_modules angles assimp collada-dom collada_parser liburdfdom-dev liburdfdom-headers-dev resource_retriever roscpp urdf tf geometric_shapes ros-robot-model-1.11.8/collada_urdf/src/000077500000000000000000000000001257532150500200415ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_urdf/src/collada_to_urdf.cpp000066400000000000000000000576661257532150500237120ustar00rootroot00000000000000/* Author: Yohei Kakiuchi */ #include #include #include #include #if defined(ASSIMP_UNIFIED_HEADER_NAMES) #include #include #include #include #include #include #else #include #if defined(ASSIMP_EXPORT_API) #include #endif #include #include #endif #include #include #include #include #include #include #include #undef GAZEBO_1_0 #undef GAZEBO_1_3 //#define GAZEBO_1_0 #define GAZEBO_1_3 using namespace urdf; using namespace std; bool use_simple_visual = false; bool use_simple_collision = false; bool add_gazebo_description = false; bool use_assimp_export = false; bool use_same_collision_as_visual = true; bool rotate_inertia_frame = true; bool export_collision_mesh = false; string mesh_dir = "/tmp"; string arobot_name = ""; string output_file = ""; string mesh_prefix = ""; #define PRINT_ORIGIN(os, origin) \ os << "xyz: " << origin.position.x << " " << origin.position.y << " " << origin.position.z << " "; \ { double r,p,y; origin.rotation.getRPY(r, p, y); \ os << "rpy: " << r << " " << p << " " << y; } #define PRINT_ORIGIN_XML(os, origin) \ os << "xyz=\"" << origin.position.x << " " << origin.position.y << " " << origin.position.z << "\""; \ { double h___r, h___p, h___y; \ origin.rotation.getRPY(h___r, h___p, h___y); \ os << " rpy=\"" << h___r << " " << h___p << " " << h___y << "\""; } #define PRINT_GEOM(os, geometry) \ if ( geometry->type == urdf::Geometry::MESH ) { os << "geom: name: " << ((urdf::Mesh *)geometry.get())->filename; } void assimp_file_export(std::string fname, std::string ofname, std::string mesh_type = "collada") { #if defined(ASSIMP_EXPORT_API) if (fname.find("file://") == 0) { fname.erase(0, strlen("file://")); } Assimp::Importer importer; /* { // ignore UP_DIRECTION tag in collada bool existing; importer.SetPropertyBool(AI_CONFIG_IMPORT_COLLADA_IGNORE_UP_DIRECTION, true, &existing); if(existing) { fprintf(stderr, ";; OverWrite : Ignore UP_DIRECTION", existing); } } */ const aiScene* scene = importer.ReadFile(fname.c_str(), aiProcess_Triangulate | aiProcess_GenNormals | aiProcess_JoinIdenticalVertices | aiProcess_SplitLargeMeshes | aiProcess_OptimizeMeshes | aiProcess_SortByPType); if (!scene) { std::string str( importer.GetErrorString() ); std::cerr << ";; " << str << std::endl; return; } Assimp::Exporter aexpt; aiReturn ret = aexpt.Export(scene, mesh_type, ofname); if ( ret != AI_SUCCESS ) { std::string str( "assimp error" ); std::cerr << ";; " << str << std::endl; } #endif } // assimp bounding box calculation void assimp_calc_bbox(string fname, float &minx, float &miny, float &minz, float &maxx, float &maxy, float &maxz) { if (fname.find("file://") == 0) { fname.erase(0, strlen("file://")); } Assimp::Importer importer; const aiScene* scene = importer.ReadFile(fname.c_str(), aiProcess_Triangulate | aiProcess_JoinIdenticalVertices | aiProcess_SortByPType); // aiProcess_GenNormals // aiProcess_GenSmoothNormals // aiProcess_SplitLargeMeshes if (!scene) { std::string str( importer.GetErrorString() ); std::cerr << ";; " << str << std::endl; return; } aiNode *node = scene->mRootNode; bool found = false; if(node->mNumMeshes > 0 && node->mMeshes != NULL) { std::cerr << "Root node has meshes " << node->mMeshes << std::endl;; found = true; } else { for (unsigned int i=0; i < node->mNumChildren; ++i) { if(node->mChildren[i]->mNumMeshes > 0 && node->mChildren[i]->mMeshes != NULL) { std::cerr << "Child " << i << " has meshes" << std::endl; node = node->mChildren[i]; found = true; break; } } } if(found == false) { std::cerr << "Can't find meshes in file" << std::endl; return; } aiMatrix4x4 transform = node->mTransformation; // copy vertices maxx = maxy = maxz = -100000000.0; minx = miny = minz = 100000000.0; std::cerr << ";; num meshes: " << node->mNumMeshes << std::endl; for (unsigned int m = 0; m < node->mNumMeshes; m++) { aiMesh *a = scene->mMeshes[node->mMeshes[m]]; std::cerr << ";; num vertices: " << a->mNumVertices << std::endl; for (unsigned int i = 0 ; i < a->mNumVertices ; ++i) { aiVector3D p; p.x = a->mVertices[i].x; p.y = a->mVertices[i].y; p.z = a->mVertices[i].z; p *= transform; if ( maxx < p.x ) { maxx = p.x; } if ( maxy < p.y ) { maxy = p.y; } if ( maxz < p.z ) { maxz = p.z; } if ( minx > p.x ) { minx = p.x; } if ( miny > p.y ) { miny = p.y; } if ( minz > p.z ) { minz = p.z; } } } } void addChildLinkNamesXML(boost::shared_ptr link, ofstream& os) { os << " name << "\">" << endl; if ( !!link->visual ) { os << " " << endl; if (!use_simple_visual) { os << " visual->origin); os << "/>" << endl; os << " " << endl; if ( link->visual->geometry->type == urdf::Geometry::MESH ) { std::string ifname (((urdf::Mesh *)link->visual->geometry.get())->filename); if (ifname.find("file://") == 0) { ifname.erase(0, strlen("file://")); } std::string ofname (mesh_dir + "/" + link->name + "_mesh.dae"); if (use_assimp_export) { // using collada export assimp_file_export (ifname, ofname); } else { // copy to ofname std::ofstream tmp_os; tmp_os.open(ofname.c_str()); std::ifstream is; is.open(ifname.c_str()); std::string buf; while(is && getline(is, buf)) tmp_os << buf << std::endl; is.close(); tmp_os.close(); } if (mesh_prefix != "") { os << " name + "_mesh.dae" << "\" scale=\"1 1 1\" />" << endl; } else { os << " " << endl; } } os << " " << endl; } else { // simple visual float ax,ay,az,bx,by,bz; if ( link->visual->geometry->type == urdf::Geometry::MESH ) { assimp_calc_bbox(((urdf::Mesh *)link->visual->geometry.get())->filename, ax, ay, az, bx, by, bz); } os << " visual->origin; pp.position.x += ( ax + bx ) / 2 ; pp.position.y += ( ay + by ) / 2 ; pp.position.z += ( az + bz ) / 2 ; PRINT_ORIGIN_XML(os, pp); os << "/>" << endl; os << " " << endl; os << " " << endl; os << " " << endl; } os << " " << endl; } if ( !!link->collision ) { os << " " << endl; if (!use_simple_collision) { os << " collision->origin); os << "/>" << endl; os << " " << endl; if ( link->visual->geometry->type == urdf::Geometry::MESH ) { std::string ifname; if (use_same_collision_as_visual) { ifname.assign (((urdf::Mesh *)link->visual->geometry.get())->filename); } else { ifname.assign (((urdf::Mesh *)link->collision->geometry.get())->filename); } if (ifname.find("file://") == 0) { ifname.erase(0, strlen("file://")); } std::string oofname; if (export_collision_mesh) { oofname = link->name + "_mesh.stl"; } else { oofname = link->name + "_mesh.dae"; } std::string ofname = (mesh_dir + "/" + oofname); if (use_assimp_export) { // using collada export if (export_collision_mesh) { assimp_file_export (ifname, ofname, "stl"); } else { assimp_file_export (ifname, ofname); } } else { // copy to ofname std::ofstream tmp_os; tmp_os.open(ofname.c_str()); std::ifstream is; is.open(ifname.c_str()); std::string buf; while(is && getline(is, buf)) tmp_os << buf << std::endl; is.close(); tmp_os.close(); } if (mesh_prefix != "") { os << " " << endl; } os << " " << endl; } else { // simple collision float ax,ay,az,bx,by,bz; if ( link->visual->geometry->type == urdf::Geometry::MESH ) { assimp_calc_bbox(std::string ( ((urdf::Mesh *)link->visual->geometry.get())->filename ), ax, ay, az, bx, by, bz); } os << " visual->origin; pp.position.x += ( ax + bx ) / 2 ; pp.position.y += ( ay + by ) / 2 ; pp.position.z += ( az + bz ) / 2 ; PRINT_ORIGIN_XML(os, pp); os << "/>" << endl; os << " " << endl; os << " " << endl; os << " " << endl; } os << " " << endl; } if ( !!link->inertial ) { if (!rotate_inertia_frame) { os << " " << endl; os << " inertial->mass << "\" />" << endl; os << " inertial->origin); os << "/>" << endl; os << " inertial->ixx << "\" "; os << "ixy=\"" << link->inertial->ixy << "\" "; os << "ixz=\"" << link->inertial->ixz << "\" "; os << "iyy=\"" << link->inertial->iyy << "\" "; os << "iyz=\"" << link->inertial->iyz << "\" "; os << "izz=\"" << link->inertial->izz << "\"/>" << endl; os << " " << endl; } else { // rotation should be identity os << " " << endl; os << " inertial->mass << "\" />" << endl; os << " inertial->origin.rotation.x, link->inertial->origin.rotation.y, link->inertial->origin.rotation.z, link->inertial->origin.rotation.w); tf::Matrix3x3 mat (qt); tf::Matrix3x3 tmat (mat.transpose()); tf::Matrix3x3 imat (link->inertial->ixx, link->inertial->ixy, link->inertial->ixz, link->inertial->ixy, link->inertial->iyy, link->inertial->iyz, link->inertial->ixz, link->inertial->iyz, link->inertial->izz); #define DEBUG_MAT(mat) \ cout << "#2f((" << mat[0][0] << " " << mat[0][1] << " " << mat[0][2] << ")"; \ cout << "(" << mat[1][0] << " " << mat[1][1] << " " << mat[1][2] << ")"; \ cout << "(" << mat[2][0] << " " << mat[2][1] << " " << mat[2][2] << "))" << endl; #if DEBUG DEBUG_MAT(mat); DEBUG_MAT(tmat); DEBUG_MAT(imat); #endif imat = ( mat * imat * tmat ); #if DEBUG DEBUG_MAT(imat); #endif urdf::Pose t_pose (link->inertial->origin); t_pose.rotation.clear(); PRINT_ORIGIN_XML(os, t_pose); os << "/>" << endl; os << " " << endl; os << " " << endl; } } os << " " << endl; #ifdef GAZEBO_1_0 if ( add_gazebo_description ) { os << " name << "\">" << endl; os << " Gazebo/Grey" << endl; //os << " 0.9" << endl; //os << " 0.9" << endl; os << " false" << endl; os << " " << endl; } #endif #ifdef GAZEBO_1_3 if ( add_gazebo_description ) { os << " name << "\">" << endl; os << " 0.9" << endl; os << " 0.9" << endl; os << " " << endl; } #endif for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) addChildLinkNamesXML(*child, os); } void addChildJointNamesXML(boost::shared_ptr link, ofstream& os) { double r, p, y; for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++){ (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(r,p,y); std::string jtype; if ( (*child)->parent_joint->type == urdf::Joint::UNKNOWN ) { jtype = std::string("unknown"); } else if ( (*child)->parent_joint->type == urdf::Joint::REVOLUTE ) { jtype = std::string("revolute"); } else if ( (*child)->parent_joint->type == urdf::Joint::CONTINUOUS ) { jtype = std::string("continuous"); } else if ( (*child)->parent_joint->type == urdf::Joint::PRISMATIC ) { jtype = std::string("prismatic"); } else if ( (*child)->parent_joint->type == urdf::Joint::FLOATING ) { jtype = std::string("floating"); } else if ( (*child)->parent_joint->type == urdf::Joint::PLANAR ) { jtype = std::string("planar"); } else if ( (*child)->parent_joint->type == urdf::Joint::FIXED ) { jtype = std::string("fixed"); } else { ///error } os << " parent_joint->name << "\" type=\"" << jtype << "\">" << endl; os << " name << "\"/>" << endl; os << " name << "\"/>" << endl; os << " parent_joint->parent_to_joint_origin_transform.position.x << " "; os << (*child)->parent_joint->parent_to_joint_origin_transform.position.y << " "; os << (*child)->parent_joint->parent_to_joint_origin_transform.position.z; os << "\" rpy=\"" << r << " " << p << " " << y << " " << "\"/>" << endl; os << " parent_joint->axis.x << " "; os << (*child)->parent_joint->axis.y << " " << (*child)->parent_joint->axis.z << "\"/>" << endl; { boost::shared_ptr jt((*child)->parent_joint); if ( !!jt->limits ) { os << " limits->lower << "\""; os << " upper=\"" << jt->limits->upper << "\""; if (jt->limits->effort == 0.0) { os << " effort=\"100\""; } else { os << " effort=\"" << jt->limits->effort << "\""; } os << " velocity=\"" << jt->limits->velocity << "\""; os << " />" << endl; } if ( !!jt->dynamics ) { os << " dynamics->damping << "\""; os << " friction=\"" << jt->dynamics->friction << "\""; os << " />" << endl; } else { os << " " << endl; } #ifdef GAZEBO_1_3 #if 0 os << " " << endl; #endif #endif } os << " " << endl; if ( add_gazebo_description ) { os << " parent_joint->name << "_trans\" >" << endl; os << " parent_joint->name << "_motor\" />" << endl; os << " parent_joint->name << "\" />" << endl; os << " 1" << endl; //os << " 1" << endl; //os << " 90000" << endl; os << " " << endl; #ifdef GAZEBO_1_3 os << " parent_joint->name << "\">" << endl; os << " 0.4" << endl; os << " " << endl; #endif } addChildJointNamesXML(*child, os); } } void printTreeXML(boost::shared_ptr link, string name, string file) { std::ofstream os; os.open(file.c_str()); os << "" << endl; os << "" << endl; addChildLinkNamesXML(link, os); addChildJointNamesXML(link, os); if ( add_gazebo_description ) { #ifdef GAZEBO_1_0 // old gazebo (gazebo on ROS Fuerte) os << " " << endl; os << " " << endl; os << " true" << endl; os << " 1000.0" << endl; os << " " << endl; os << " " << endl; #endif } os << "" << endl; os.close(); } namespace po = boost::program_options; // using namespace std; int main(int argc, char** argv) { string inputfile; po::options_description desc("Usage: collada_to_urdf input.dae [options]\n Options for collada_to_urdf"); desc.add_options() ("help", "produce help message") ("simple_visual,V", "use bounding box for visual") ("simple_collision,C", "use bounding box for collision") ("export_collision_mesh", "export collision mesh as STL") ("add_gazebo_description,G", "add description for using on gazebo") ("use_assimp_export,A", "use assimp library for exporting mesh") ("use_collision,U", "use collision geometry (default collision is the same as visual)") ("original_inertia_rotation,R", "does not rotate inertia frame") ("robot_name,N", po::value< vector >(), "output robot name") ("mesh_output_dir", po::value< vector >(), "directory for outputing") ("mesh_prefix", po::value< vector >(), "prefix of mesh files") ("output_file,O", po::value< vector >(), "output file") ("input_file", po::value< vector >(), "input file") ; po::positional_options_description p; p.add("input_file", -1); po::variables_map vm; try { po::store(po::command_line_parser(argc, argv). options(desc).positional(p).run(), vm); po::notify(vm); } catch (po::error e) { cerr << ";; option parse error / " << e.what() << endl; return 1; } if (vm.count("help")) { cout << desc << "\n"; return 1; } if (vm.count("simple_visual")) { use_simple_visual = true; cerr << ";; Using simple_visual" << endl; } if (vm.count("simple_collision")) { use_simple_collision = true; cerr << ";; Using simple_collision" << endl; } if (vm.count("add_gazebo_description")) { add_gazebo_description = true; cerr << ";; Adding gazebo description" << endl; } if (vm.count("use_assimp_export")) { #if defined(ASSIMP_EXPORT_API) use_assimp_export = true; #endif cerr << ";; Use assimp export" << endl; } if (vm.count("original_inertia_rotation")) { rotate_inertia_frame = false; cerr << ";; Does not rotate inertia frame" << endl; } if (vm.count("export_collision_mesh")) { export_collision_mesh = true; cerr << ";; erxport collision mesh as STL" << endl; } if (vm.count("output_file")) { vector aa = vm["output_file"].as< vector >(); cerr << ";; output file is: " << aa[0] << endl; output_file = aa[0]; } if (vm.count("robot_name")) { vector aa = vm["robot_name"].as< vector >(); cerr << ";; robot_name is: " << aa[0] << endl; arobot_name = aa[0]; } if (vm.count("mesh_prefix")) { vector aa = vm["mesh_prefix"].as< vector >(); cerr << ";; mesh_prefix is: " << aa[0] << endl; mesh_prefix = aa[0]; } if (vm.count("mesh_output_dir")) { vector aa = vm["mesh_output_dir"].as< vector >(); cerr << ";; Mesh output directory is: " << aa[0] << endl; mesh_dir = aa[0]; // check directory existence boost::filesystem::path mpath( mesh_dir ); try { if ( ! boost::filesystem::is_directory(mpath) ) { boost::filesystem::create_directory ( mpath ); } } catch ( boost::filesystem::filesystem_error e ) { cerr << ";; mesh output directory error / " << e.what() << endl; return 1; } } if (vm.count("input_file")) { vector aa = vm["input_file"].as< vector >(); cerr << ";; Input file is: " << aa[0] << endl; inputfile = aa[0]; } if(inputfile == "") { cerr << desc << endl; return 1; } std::string xml_string; std::fstream xml_file(inputfile.c_str(), std::fstream::in); while ( xml_file.good() ) { std::string line; std::getline( xml_file, line); xml_string += (line + "\n"); } xml_file.close(); boost::shared_ptr robot; if( xml_string.find("getName(); } if (output_file == "") { output_file = arobot_name + ".urdf"; } printTreeXML (robot->getRoot(), arobot_name, output_file); return 0; } ros-robot-model-1.11.8/collada_urdf/src/collada_urdf.cpp000066400000000000000000002521641257532150500231760ustar00rootroot00000000000000// -*- coding: utf-8 -*- /********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc., University of Tokyo * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redstributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Authors: Rosen Diankov, Tim Field */ #include "collada_urdf/collada_urdf.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #if defined(ASSIMP_UNIFIED_HEADER_NAMES) #include #include #include #include #include #include #include #else #include #include #include #include #include #include #endif #include #include #define FOREACH(it, v) for(typeof((v).begin())it = (v).begin(); it != (v).end(); (it)++) #define FOREACHC FOREACH using namespace std; namespace ColladaDOM150 { } namespace collada_urdf { using namespace ColladaDOM150; /// ResourceIOStream is copied from rviz (BSD, Willow Garage) class ResourceIOStream : public Assimp::IOStream { public: ResourceIOStream(const resource_retriever::MemoryResource& res) : res_(res) , pos_(res.data.get()) { } ~ResourceIOStream() { } size_t Read(void* buffer, size_t size, size_t count) { size_t to_read = size * count; if (pos_ + to_read > res_.data.get() + res_.size) { to_read = res_.size - (pos_ - res_.data.get()); } memcpy(buffer, pos_, to_read); pos_ += to_read; return to_read; } size_t Write( const void* buffer, size_t size, size_t count) { ROS_BREAK(); return 0; } aiReturn Seek( size_t offset, aiOrigin origin) { uint8_t* new_pos = 0; switch (origin) { case aiOrigin_SET: new_pos = res_.data.get() + offset; break; case aiOrigin_CUR: new_pos = pos_ + offset; // TODO is this right? can offset really not be negative break; case aiOrigin_END: new_pos = res_.data.get() + res_.size - offset; // TODO is this right? break; default: ROS_BREAK(); } if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size) { return aiReturn_FAILURE; } pos_ = new_pos; return aiReturn_SUCCESS; } size_t Tell() const { return pos_ - res_.data.get(); } size_t FileSize() const { return res_.size; } void Flush() { } private: resource_retriever::MemoryResource res_; uint8_t* pos_; }; namespace mathextra { // code from MagicSoftware by Dave Eberly const double g_fEpsilon = 1e-15; //=========================================================================== #define distinctRoots 0 // roots r0 < r1 < r2 #define singleRoot 1 // root r0 #define floatRoot01 2 // roots r0 = r1 < r2 #define floatRoot12 4 // roots r0 < r1 = r2 #define tripleRoot 6 // roots r0 = r1 = r2 template void Tridiagonal3 (S* mat, T* diag, T* subd) { T a, b, c, d, e, f, ell, q; a = mat[0*3+0]; b = mat[0*3+1]; c = mat[0*3+2]; d = mat[1*3+1]; e = mat[1*3+2]; f = mat[2*3+2]; subd[2] = 0.0; diag[0] = a; if ( fabs(c) >= g_fEpsilon ) { ell = (T)sqrt(b*b+c*c); b /= ell; c /= ell; q = 2*b*e+c*(f-d); diag[1] = d+c*q; diag[2] = f-c*q; subd[0] = ell; subd[1] = e-b*q; mat[0*3+0] = (S)1; mat[0*3+1] = (S)0; mat[0*3+2] = (T)0; mat[1*3+0] = (S)0; mat[1*3+1] = b; mat[1*3+2] = c; mat[2*3+0] = (S)0; mat[2*3+1] = c; mat[2*3+2] = -b; } else { diag[1] = d; diag[2] = f; subd[0] = b; subd[1] = e; mat[0*3+0] = (S)1; mat[0*3+1] = (S)0; mat[0*3+2] = (S)0; mat[1*3+0] = (S)0; mat[1*3+1] = (S)1; mat[1*3+2] = (S)0; mat[2*3+0] = (S)0; mat[2*3+1] = (S)0; mat[2*3+2] = (S)1; } } int CubicRoots (double c0, double c1, double c2, double *r0, double *r1, double *r2) { // polynomial is L^3-c2*L^2+c1*L-c0 int maxiter = 50; double discr, temp, pval, pdval, b0, b1; int i; // find local extrema (if any) of p'(L) = 3*L^2-2*c2*L+c1 discr = c2*c2-3*c1; if ( discr >= 0.0 ) { discr = (double)sqrt(discr); temp = (c2+discr)/3; pval = temp*(temp*(temp-c2)+c1)-c0; if ( pval >= 0.0 ) { // double root occurs before the positive local maximum (*r0) = (c2-discr)/3 - 1; // initial guess for Newton's methods pval = 2*g_fEpsilon; for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) { pval = (*r0)*((*r0)*((*r0)-c2)+c1)-c0; pdval = (*r0)*(3*(*r0)-2*c2)+c1; (*r0) -= pval/pdval; } // Other two roots are solutions to quadratic equation // L^2 + ((*r0)-c2)*L + [(*r0)*((*r0)-c2)+c1] = 0. b1 = (*r0)-c2; b0 = (*r0)*((*r0)-c2)+c1; discr = b1*b1-4*b0; if ( discr < -g_fEpsilon ) { // single root r0 return singleRoot; } else { int result = distinctRoots; // roots r0 <= r1 <= r2 discr = sqrt(fabs(discr)); (*r1) = 0.5f*(-b1-discr); (*r2) = 0.5f*(-b1+discr); if ( fabs((*r0)-(*r1)) <= g_fEpsilon ) { (*r0) = (*r1); result |= floatRoot01; } if ( fabs((*r1)-(*r2)) <= g_fEpsilon ) { (*r1) = (*r2); result |= floatRoot12; } return result; } } else { // double root occurs after the negative local minimum (*r2) = temp + 1; // initial guess for Newton's method pval = 2*g_fEpsilon; for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) { pval = (*r2)*((*r2)*((*r2)-c2)+c1)-c0; pdval = (*r2)*(3*(*r2)-2*c2)+c1; (*r2) -= pval/pdval; } // Other two roots are solutions to quadratic equation // L^2 + (r2-c2)*L + [r2*(r2-c2)+c1] = 0. b1 = (*r2)-c2; b0 = (*r2)*((*r2)-c2)+c1; discr = b1*b1-4*b0; if ( discr < -g_fEpsilon ) { // single root (*r0) = (*r2); return singleRoot; } else { int result = distinctRoots; // roots r0 <= r1 <= r2 discr = sqrt(fabs(discr)); (*r0) = 0.5f*(-b1-discr); (*r1) = 0.5f*(-b1+discr); if ( fabs((*r0)-(*r1)) <= g_fEpsilon ) { (*r0) = (*r1); result |= floatRoot01; } if ( fabs((*r1)-(*r2)) <= g_fEpsilon ) { (*r1) = (*r2); result |= floatRoot12; } return result; } } } else { // p(L) has one double root (*r0) = c0; pval = 2*g_fEpsilon; for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) { pval = (*r0)*((*r0)*((*r0)-c2)+c1)-c0; pdval = (*r0)*(3*(*r0)-2*c2)+c1; (*r0) -= pval/pdval; } return singleRoot; } } //---------------------------------------------------------------------------- template bool _QLAlgorithm3 (T* m_aafEntry, T* afDiag, T* afSubDiag) { // QL iteration with implicit shifting to reduce matrix from tridiagonal // to diagonal for (int i0 = 0; i0 < 3; i0++) { const int iMaxIter = 32; int iIter; for (iIter = 0; iIter < iMaxIter; iIter++) { int i1; for (i1 = i0; i1 <= 1; i1++) { T fSum = fabs(afDiag[i1]) + fabs(afDiag[i1+1]); if ( fabs(afSubDiag[i1]) + fSum == fSum ) break; } if ( i1 == i0 ) break; T fTmp0 = (afDiag[i0+1]-afDiag[i0])/(2.0f*afSubDiag[i0]); T fTmp1 = sqrt(fTmp0*fTmp0+1.0f); if ( fTmp0 < 0.0f ) fTmp0 = afDiag[i1]-afDiag[i0]+afSubDiag[i0]/(fTmp0-fTmp1); else fTmp0 = afDiag[i1]-afDiag[i0]+afSubDiag[i0]/(fTmp0+fTmp1); T fSin = 1.0f; T fCos = 1.0f; T fTmp2 = 0.0f; for (int i2 = i1-1; i2 >= i0; i2--) { T fTmp3 = fSin*afSubDiag[i2]; T fTmp4 = fCos*afSubDiag[i2]; if ( fabs(fTmp3) >= fabs(fTmp0) ) { fCos = fTmp0/fTmp3; fTmp1 = sqrt(fCos*fCos+1.0f); afSubDiag[i2+1] = fTmp3*fTmp1; fSin = 1.0f/fTmp1; fCos *= fSin; } else { fSin = fTmp3/fTmp0; fTmp1 = sqrt(fSin*fSin+1.0f); afSubDiag[i2+1] = fTmp0*fTmp1; fCos = 1.0f/fTmp1; fSin *= fCos; } fTmp0 = afDiag[i2+1]-fTmp2; fTmp1 = (afDiag[i2]-fTmp0)*fSin+2.0f*fTmp4*fCos; fTmp2 = fSin*fTmp1; afDiag[i2+1] = fTmp0+fTmp2; fTmp0 = fCos*fTmp1-fTmp4; for (int iRow = 0; iRow < 3; iRow++) { fTmp3 = m_aafEntry[iRow*3+i2+1]; m_aafEntry[iRow*3+i2+1] = fSin*m_aafEntry[iRow*3+i2] + fCos*fTmp3; m_aafEntry[iRow*3+i2] = fCos*m_aafEntry[iRow*3+i2] - fSin*fTmp3; } } afDiag[i0] -= fTmp2; afSubDiag[i0] = fTmp0; afSubDiag[i1] = 0.0f; } if ( iIter == iMaxIter ) { // should not get here under normal circumstances return false; } } return true; } bool QLAlgorithm3 (float* m_aafEntry, float* afDiag, float* afSubDiag) { return _QLAlgorithm3(m_aafEntry, afDiag, afSubDiag); } bool QLAlgorithm3 (double* m_aafEntry, double* afDiag, double* afSubDiag) { return _QLAlgorithm3(m_aafEntry, afDiag, afSubDiag); } void EigenSymmetric3(const double* fmat, double* afEigenvalue, double* fevecs) { double afSubDiag[3]; memcpy(fevecs, fmat, sizeof(double)*9); Tridiagonal3(fevecs, afEigenvalue,afSubDiag); QLAlgorithm3(fevecs, afEigenvalue,afSubDiag); // make eigenvectors form a right--handed system double fDet = fevecs[0*3+0] * (fevecs[1*3+1] * fevecs[2*3+2] - fevecs[1*3+2] * fevecs[2*3+1]) + fevecs[0*3+1] * (fevecs[1*3+2] * fevecs[2*3+0] - fevecs[1*3+0] * fevecs[2*3+2]) + fevecs[0*3+2] * (fevecs[1*3+0] * fevecs[2*3+1] - fevecs[1*3+1] * fevecs[2*3+0]); if ( fDet < 0.0f ) { fevecs[0*3+2] = -fevecs[0*3+2]; fevecs[1*3+2] = -fevecs[1*3+2]; fevecs[2*3+2] = -fevecs[2*3+2]; } } /* end of MAGIC code */ } // end namespace geometry /// ResourceIOSystem is copied from rviz (BSD, Willow Garage) class ResourceIOSystem : public Assimp::IOSystem { public: ResourceIOSystem() { } ~ResourceIOSystem() { } // Check whether a specific file exists bool Exists(const char* file) const { // Ugly -- two retrievals where there should be one (Exists + Open) // resource_retriever needs a way of checking for existence // TODO: cache this resource_retriever::MemoryResource res; try { res = retriever_.get(file); } catch (resource_retriever::Exception& e) { return false; } return true; } // Get the path delimiter character we'd like to see char getOsSeparator() const { return '/'; } // ... and finally a method to open a custom stream Assimp::IOStream* Open(const char* file, const char* mode) { ROS_ASSERT(mode == std::string("r") || mode == std::string("rb")); // Ugly -- two retrievals where there should be one (Exists + Open) // resource_retriever needs a way of checking for existence resource_retriever::MemoryResource res; try { res = retriever_.get(file); } catch (resource_retriever::Exception& e) { return 0; } return new ResourceIOStream(res); } void Close(Assimp::IOStream* stream) { delete stream; } private: mutable resource_retriever::Retriever retriever_; }; class Triangle { public: Triangle(const urdf::Vector3 &_p1, const urdf::Vector3 &_p2, const urdf::Vector3 &_p3) : p1(_p1), p2(_p2), p3(_p3) {} Triangle() { this->clear(); }; urdf::Vector3 p1, p2, p3; void clear() { p1.clear(); p2.clear(); p3.clear(); }; }; /// \brief Implements writing urdf::Model objects to a COLLADA DOM. class ColladaWriter : public daeErrorHandler { private: struct SCENE { domVisual_sceneRef vscene; domKinematics_sceneRef kscene; domPhysics_sceneRef pscene; domInstance_with_extraRef viscene; domInstance_kinematics_sceneRef kiscene; domInstance_with_extraRef piscene; }; typedef std::map< boost::shared_ptr, urdf::Pose > MAPLINKPOSES; struct LINKOUTPUT { list > listusedlinks; list > listprocesseddofs; daeElementRef plink; domNodeRef pnode; MAPLINKPOSES _maplinkposes; }; struct physics_model_output { domPhysics_modelRef pmodel; std::vector vrigidbodysids; ///< same ordering as the physics indices }; struct kinematics_model_output { struct axis_output { //axis_output(const string& sid, KinBody::JointConstPtr pjoint, int iaxis) : sid(sid), pjoint(pjoint), iaxis(iaxis) {} axis_output() : iaxis(0) { } string sid, nodesid; boost::shared_ptr pjoint; int iaxis; string jointnodesid; }; domKinematics_modelRef kmodel; std::vector vaxissids; std::vector vlinksids; MAPLINKPOSES _maplinkposes; }; struct axis_sids { axis_sids(const string& axissid, const string& valuesid, const string& jointnodesid) : axissid(axissid), valuesid(valuesid), jointnodesid(jointnodesid) { } string axissid, valuesid, jointnodesid; }; struct instance_kinematics_model_output { domInstance_kinematics_modelRef ikm; std::vector vaxissids; boost::shared_ptr kmout; std::vector > vkinematicsbindings; }; struct instance_articulated_system_output { domInstance_articulated_systemRef ias; std::vector vaxissids; std::vector vlinksids; std::vector > vkinematicsbindings; }; struct instance_physics_model_output { domInstance_physics_modelRef ipm; boost::shared_ptr pmout; }; struct kinbody_models { std::string uri, kinematicsgeometryhash; boost::shared_ptr kmout; boost::shared_ptr pmout; }; public: ColladaWriter(const urdf::Model& robot, int writeoptions) : _writeoptions(writeoptions), _robot(robot), _dom(NULL) { daeErrorHandler::setErrorHandler(this); _importer.SetIOHandler(new ResourceIOSystem()); } virtual ~ColladaWriter() { } daeDocument* doc() { return _doc; } bool convert() { try { const char* documentName = "urdf_snapshot"; daeInt error = _collada.getDatabase()->insertDocument(documentName, &_doc ); // also creates a collada root if (error != DAE_OK || _doc == NULL) { throw ColladaUrdfException("Failed to create document"); } _dom = daeSafeCast(_doc->getDomRoot()); _dom->setAttribute("xmlns:math","http://www.w3.org/1998/Math/MathML"); //create the required asset tag domAssetRef asset = daeSafeCast( _dom->add( COLLADA_ELEMENT_ASSET ) ); { // facet becomes owned by locale, so no need to explicitly delete boost::posix_time::time_facet* facet = new boost::posix_time::time_facet("%Y-%m-%dT%H:%M:%s"); std::stringstream ss; ss.imbue(std::locale(ss.getloc(), facet)); ss << boost::posix_time::second_clock::local_time(); domAsset::domCreatedRef created = daeSafeCast( asset->add( COLLADA_ELEMENT_CREATED ) ); created->setValue(ss.str().c_str()); domAsset::domModifiedRef modified = daeSafeCast( asset->add( COLLADA_ELEMENT_MODIFIED ) ); modified->setValue(ss.str().c_str()); domAsset::domContributorRef contrib = daeSafeCast( asset->add( COLLADA_TYPE_CONTRIBUTOR ) ); domAsset::domContributor::domAuthoring_toolRef authoringtool = daeSafeCast( contrib->add( COLLADA_ELEMENT_AUTHORING_TOOL ) ); authoringtool->setValue("URDF Collada Writer"); domAsset::domUnitRef units = daeSafeCast( asset->add( COLLADA_ELEMENT_UNIT ) ); units->setMeter(1); units->setName("meter"); domAsset::domUp_axisRef zup = daeSafeCast( asset->add( COLLADA_ELEMENT_UP_AXIS ) ); zup->setValue(UP_AXIS_Z_UP); } _globalscene = _dom->getScene(); if( !_globalscene ) { _globalscene = daeSafeCast( _dom->add( COLLADA_ELEMENT_SCENE ) ); } _visualScenesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_VISUAL_SCENES)); _visualScenesLib->setId("vscenes"); _geometriesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_GEOMETRIES)); _geometriesLib->setId("geometries"); _effectsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_EFFECTS)); _effectsLib->setId("effects"); _materialsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_MATERIALS)); _materialsLib->setId("materials"); _kinematicsModelsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_MODELS)); _kinematicsModelsLib->setId("kmodels"); _articulatedSystemsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_ARTICULATED_SYSTEMS)); _articulatedSystemsLib->setId("asystems"); _kinematicsScenesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_SCENES)); _kinematicsScenesLib->setId("kscenes"); _physicsScenesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_SCENES)); _physicsScenesLib->setId("pscenes"); _physicsModelsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_MODELS)); _physicsModelsLib->setId("pmodels"); domExtraRef pextra_library_sensors = daeSafeCast(_dom->add(COLLADA_ELEMENT_EXTRA)); pextra_library_sensors->setId("sensors"); pextra_library_sensors->setType("library_sensors"); _sensorsLib = daeSafeCast(pextra_library_sensors->add(COLLADA_ELEMENT_TECHNIQUE)); _sensorsLib->setProfile("OpenRAVE"); ///< documented profile on robot extensions _CreateScene(); _WritePhysics(); _WriteRobot(); _WriteBindingsInstance_kinematics_scene(); return true; } catch (ColladaUrdfException ex) { ROS_ERROR("Error converting: %s", ex.what()); return false; } } bool writeTo(string const& file) { try { daeString uri = _doc->getDocumentURI()->getURI(); _collada.writeTo(uri, file); } catch (ColladaUrdfException ex) { return false; } return true; } protected: virtual void handleError(daeString msg) { throw ColladaUrdfException(msg); } virtual void handleWarning(daeString msg) { std::cerr << "COLLADA DOM warning: " << msg << std::endl; } void _CreateScene() { // Create visual scene _scene.vscene = daeSafeCast(_visualScenesLib->add(COLLADA_ELEMENT_VISUAL_SCENE)); _scene.vscene->setId("vscene"); _scene.vscene->setName("URDF Visual Scene"); // Create kinematics scene _scene.kscene = daeSafeCast(_kinematicsScenesLib->add(COLLADA_ELEMENT_KINEMATICS_SCENE)); _scene.kscene->setId("kscene"); _scene.kscene->setName("URDF Kinematics Scene"); // Create physic scene _scene.pscene = daeSafeCast(_physicsScenesLib->add(COLLADA_ELEMENT_PHYSICS_SCENE)); _scene.pscene->setId("pscene"); _scene.pscene->setName("URDF Physics Scene"); // Create instance visual scene _scene.viscene = daeSafeCast(_globalscene->add( COLLADA_ELEMENT_INSTANCE_VISUAL_SCENE )); _scene.viscene->setUrl( (string("#") + string(_scene.vscene->getID())).c_str() ); // Create instance kinematics scene _scene.kiscene = daeSafeCast(_globalscene->add( COLLADA_ELEMENT_INSTANCE_KINEMATICS_SCENE )); _scene.kiscene->setUrl( (string("#") + string(_scene.kscene->getID())).c_str() ); // Create instance physics scene _scene.piscene = daeSafeCast(_globalscene->add( COLLADA_ELEMENT_INSTANCE_PHYSICS_SCENE )); _scene.piscene->setUrl( (string("#") + string(_scene.pscene->getID())).c_str() ); } void _WritePhysics() { domPhysics_scene::domTechnique_commonRef common = daeSafeCast(_scene.pscene->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); // Create gravity domTargetable_float3Ref g = daeSafeCast(common->add(COLLADA_ELEMENT_GRAVITY)); g->getValue().set3 (0,0,0); } /// \brief Write kinematic body in a given scene void _WriteRobot(int id = 0) { ROS_DEBUG_STREAM(str(boost::format("writing robot as instance_articulated_system (%d) %s\n")%id%_robot.getName())); string asid = _ComputeId(str(boost::format("robot%d")%id)); string askid = _ComputeId(str(boost::format("%s_kinematics")%asid)); string asmid = _ComputeId(str(boost::format("%s_motion")%asid)); string iassid = _ComputeId(str(boost::format("%s_inst")%asmid)); domInstance_articulated_systemRef ias = daeSafeCast(_scene.kscene->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM)); ias->setSid(iassid.c_str()); ias->setUrl((string("#")+asmid).c_str()); ias->setName(_robot.getName().c_str()); _iasout.reset(new instance_articulated_system_output()); _iasout->ias = ias; // motion info domArticulated_systemRef articulated_system_motion = daeSafeCast(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM)); articulated_system_motion->setId(asmid.c_str()); domMotionRef motion = daeSafeCast(articulated_system_motion->add(COLLADA_ELEMENT_MOTION)); domMotion_techniqueRef mt = daeSafeCast(motion->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); domInstance_articulated_systemRef ias_motion = daeSafeCast(motion->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM)); ias_motion->setUrl(str(boost::format("#%s")%askid).c_str()); // kinematics info domArticulated_systemRef articulated_system_kinematics = daeSafeCast(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM)); articulated_system_kinematics->setId(askid.c_str()); domKinematicsRef kinematics = daeSafeCast(articulated_system_kinematics->add(COLLADA_ELEMENT_KINEMATICS)); domKinematics_techniqueRef kt = daeSafeCast(kinematics->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); _WriteInstance_kinematics_model(kinematics,askid,id); for(size_t idof = 0; idof < _ikmout->vaxissids.size(); ++idof) { string axis_infosid = _ComputeId(str(boost::format("axis_info_inst%d")%idof)); boost::shared_ptr pjoint = _ikmout->kmout->vaxissids.at(idof).pjoint; BOOST_ASSERT(_mapjointindices[pjoint] == (int)idof); //int iaxis = _ikmout->kmout->vaxissids.at(idof).iaxis; // Kinematics axis info domKinematics_axis_infoRef kai = daeSafeCast(kt->add(COLLADA_ELEMENT_AXIS_INFO)); kai->setAxis(str(boost::format("%s/%s")%_ikmout->kmout->kmodel->getID()%_ikmout->kmout->vaxissids.at(idof).sid).c_str()); kai->setSid(axis_infosid.c_str()); bool bactive = !pjoint->mimic; double flower=0, fupper=0; if( pjoint->type != urdf::Joint::CONTINUOUS ) { if( !!pjoint->limits ) { flower = pjoint->limits->lower; fupper = pjoint->limits->upper; } if( !!pjoint->safety ) { flower = pjoint->safety->soft_lower_limit; fupper = pjoint->safety->soft_upper_limit; } if( flower == fupper ) { bactive = false; } double fmult = 1.0; if( pjoint->type != urdf::Joint::PRISMATIC ) { fmult = 180.0/M_PI; } domKinematics_limitsRef plimits = daeSafeCast(kai->add(COLLADA_ELEMENT_LIMITS)); daeSafeCast(plimits->add(COLLADA_ELEMENT_MIN)->add(COLLADA_ELEMENT_FLOAT))->setValue(flower*fmult); daeSafeCast(plimits->add(COLLADA_ELEMENT_MAX)->add(COLLADA_ELEMENT_FLOAT))->setValue(fupper*fmult); } domCommon_bool_or_paramRef active = daeSafeCast(kai->add(COLLADA_ELEMENT_ACTIVE)); daeSafeCast(active->add(COLLADA_ELEMENT_BOOL))->setValue(bactive); domCommon_bool_or_paramRef locked = daeSafeCast(kai->add(COLLADA_ELEMENT_LOCKED)); daeSafeCast(locked->add(COLLADA_ELEMENT_BOOL))->setValue(false); // Motion axis info domMotion_axis_infoRef mai = daeSafeCast(mt->add(COLLADA_ELEMENT_AXIS_INFO)); mai->setAxis(str(boost::format("%s/%s")%askid%axis_infosid).c_str()); if( !!pjoint->limits ) { domCommon_float_or_paramRef speed = daeSafeCast(mai->add(COLLADA_ELEMENT_SPEED)); daeSafeCast(speed->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint->limits->velocity); domCommon_float_or_paramRef accel = daeSafeCast(mai->add(COLLADA_ELEMENT_ACCELERATION)); daeSafeCast(accel->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint->limits->effort); } } // write the bindings string asmsym = _ComputeId(str(boost::format("%s_%s")%asmid%_ikmout->ikm->getSid())); string assym = _ComputeId(str(boost::format("%s_%s")%_scene.kscene->getID()%_ikmout->ikm->getSid())); FOREACH(it, _ikmout->vkinematicsbindings) { domKinematics_newparamRef abm = daeSafeCast(ias_motion->add(COLLADA_ELEMENT_NEWPARAM)); abm->setSid(asmsym.c_str()); daeSafeCast(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%it->first).c_str()); domKinematics_bindRef ab = daeSafeCast(ias->add(COLLADA_ELEMENT_BIND)); ab->setSymbol(assym.c_str()); daeSafeCast(ab->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s")%asmid%asmsym).c_str()); _iasout->vkinematicsbindings.push_back(make_pair(string(ab->getSymbol()), it->second)); } for(size_t idof = 0; idof < _ikmout->vaxissids.size(); ++idof) { const axis_sids& kas = _ikmout->vaxissids.at(idof); domKinematics_newparamRef abm = daeSafeCast(ias_motion->add(COLLADA_ELEMENT_NEWPARAM)); abm->setSid(_ComputeId(str(boost::format("%s_%s")%asmid%kas.axissid)).c_str()); daeSafeCast(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%kas.axissid).c_str()); domKinematics_bindRef ab = daeSafeCast(ias->add(COLLADA_ELEMENT_BIND)); ab->setSymbol(str(boost::format("%s_%s")%assym%kas.axissid).c_str()); daeSafeCast(ab->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s_%s")%asmid%asmid%kas.axissid).c_str()); string valuesid; if( kas.valuesid.size() > 0 ) { domKinematics_newparamRef abmvalue = daeSafeCast(ias_motion->add(COLLADA_ELEMENT_NEWPARAM)); abmvalue->setSid(_ComputeId(str(boost::format("%s_%s")%asmid%kas.valuesid)).c_str()); daeSafeCast(abmvalue->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%kas.valuesid).c_str()); domKinematics_bindRef abvalue = daeSafeCast(ias->add(COLLADA_ELEMENT_BIND)); valuesid = _ComputeId(str(boost::format("%s_%s")%assym%kas.valuesid)); abvalue->setSymbol(valuesid.c_str()); daeSafeCast(abvalue->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s_%s")%asmid%asmid%kas.valuesid).c_str()); } _iasout->vaxissids.push_back(axis_sids(ab->getSymbol(),valuesid,kas.jointnodesid)); } boost::shared_ptr ipmout = _WriteInstance_physics_model(id,_scene.pscene,_scene.pscene->getID(), _ikmout->kmout->_maplinkposes); } /// \brief Write kinematic body in a given scene virtual void _WriteInstance_kinematics_model(daeElementRef parent, const string& sidscope, int id) { ROS_DEBUG_STREAM(str(boost::format("writing instance_kinematics_model %s\n")%_robot.getName())); boost::shared_ptr kmout = WriteKinematics_model(id); _ikmout.reset(new instance_kinematics_model_output()); _ikmout->kmout = kmout; _ikmout->ikm = daeSafeCast(parent->add(COLLADA_ELEMENT_INSTANCE_KINEMATICS_MODEL)); string symscope, refscope; if( sidscope.size() > 0 ) { symscope = sidscope+string("_"); refscope = sidscope+string("/"); } string ikmsid = _ComputeId(str(boost::format("%s_inst")%kmout->kmodel->getID())); _ikmout->ikm->setUrl(str(boost::format("#%s")%kmout->kmodel->getID()).c_str()); _ikmout->ikm->setSid(ikmsid.c_str()); domKinematics_newparamRef kbind = daeSafeCast(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM)); kbind->setSid(_ComputeId(symscope+ikmsid).c_str()); daeSafeCast(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid).c_str()); _ikmout->vkinematicsbindings.push_back(make_pair(string(kbind->getSid()), str(boost::format("visual%d/node%d")%id%_maplinkindices[_robot.getRoot()]))); _ikmout->vaxissids.reserve(kmout->vaxissids.size()); int i = 0; FOREACH(it,kmout->vaxissids) { domKinematics_newparamRef kbind = daeSafeCast(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM)); string ref = it->sid; size_t index = ref.find("/"); while(index != string::npos) { ref[index] = '.'; index = ref.find("/",index+1); } string sid = _ComputeId(symscope+ikmsid+"_"+ref); kbind->setSid(sid.c_str()); daeSafeCast(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid+"/"+it->sid).c_str()); double value=0; double flower=0, fupper=0; if( !!it->pjoint->limits ) { flower = it->pjoint->limits->lower; fupper = it->pjoint->limits->upper; } if( flower > 0 || fupper < 0 ) { value = 0.5*(flower+fupper); } domKinematics_newparamRef pvalueparam = daeSafeCast(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM)); pvalueparam->setSid((sid+string("_value")).c_str()); daeSafeCast(pvalueparam->add(COLLADA_ELEMENT_FLOAT))->setValue(value); _ikmout->vaxissids.push_back(axis_sids(sid,pvalueparam->getSid(),kmout->vaxissids.at(i).jointnodesid)); ++i; } } virtual boost::shared_ptr WriteKinematics_model(int id) { domKinematics_modelRef kmodel = daeSafeCast(_kinematicsModelsLib->add(COLLADA_ELEMENT_KINEMATICS_MODEL)); string kmodelid = _ComputeKinematics_modelId(id); kmodel->setId(kmodelid.c_str()); kmodel->setName(_robot.getName().c_str()); domKinematics_model_techniqueRef ktec = daeSafeCast(kmodel->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); // Create root node for the visual scene domNodeRef pnoderoot = daeSafeCast(_scene.vscene->add(COLLADA_ELEMENT_NODE)); string bodyid = _ComputeId(str(boost::format("visual%d")%id)); pnoderoot->setId(bodyid.c_str()); pnoderoot->setSid(bodyid.c_str()); pnoderoot->setName(_robot.getName().c_str()); // Declare all the joints _mapjointindices.clear(); int index=0; FOREACHC(itj, _robot.joints_) { _mapjointindices[itj->second] = index++; } _maplinkindices.clear(); index=0; FOREACHC(itj, _robot.links_) { _maplinkindices[itj->second] = index++; } _mapmaterialindices.clear(); index=0; FOREACHC(itj, _robot.materials_) { _mapmaterialindices[itj->second] = index++; } double lmin, lmax; vector vdomjoints(_robot.joints_.size()); boost::shared_ptr kmout(new kinematics_model_output()); kmout->kmodel = kmodel; kmout->vaxissids.resize(_robot.joints_.size()); kmout->vlinksids.resize(_robot.links_.size()); FOREACHC(itjoint, _robot.joints_) { boost::shared_ptr pjoint = itjoint->second; int index = _mapjointindices[itjoint->second]; domJointRef pdomjoint = daeSafeCast(ktec->add(COLLADA_ELEMENT_JOINT)); string jointid = _ComputeId(pjoint->name); //str(boost::format("joint%d")%index); pdomjoint->setSid(jointid.c_str() ); pdomjoint->setName(pjoint->name.c_str()); domAxis_constraintRef axis; if( !!pjoint->limits ) { lmin=pjoint->limits->lower; lmax=pjoint->limits->upper; } else { lmin = lmax = 0; } double fmult = 1.0; switch(pjoint->type) { case urdf::Joint::REVOLUTE: case urdf::Joint::CONTINUOUS: axis = daeSafeCast(pdomjoint->add(COLLADA_ELEMENT_REVOLUTE)); fmult = 180.0f/M_PI; lmin*=fmult; lmax*=fmult; break; case urdf::Joint::PRISMATIC: axis = daeSafeCast(pdomjoint->add(COLLADA_ELEMENT_PRISMATIC)); break; case urdf::Joint::FIXED: axis = daeSafeCast(pdomjoint->add(COLLADA_ELEMENT_REVOLUTE)); lmin = 0; lmax = 0; fmult = 0; break; default: ROS_WARN_STREAM(str(boost::format("unsupported joint type specified %d")%(int)pjoint->type)); break; } if( !axis ) { continue; } int ia = 0; string axisid = _ComputeId(str(boost::format("axis%d")%ia)); axis->setSid(axisid.c_str()); kmout->vaxissids.at(index).pjoint = pjoint; kmout->vaxissids.at(index).sid = jointid+string("/")+axisid; kmout->vaxissids.at(index).iaxis = ia; domAxisRef paxis = daeSafeCast(axis->add(COLLADA_ELEMENT_AXIS)); paxis->getValue().setCount(3); paxis->getValue()[0] = pjoint->axis.x; paxis->getValue()[1] = pjoint->axis.y; paxis->getValue()[2] = pjoint->axis.z; if( pjoint->type != urdf::Joint::CONTINUOUS ) { domJoint_limitsRef plimits = daeSafeCast(axis->add(COLLADA_TYPE_LIMITS)); daeSafeCast(plimits->add(COLLADA_ELEMENT_MIN))->getValue() = lmin; daeSafeCast(plimits->add(COLLADA_ELEMENT_MAX))->getValue() = lmax; } vdomjoints.at(index) = pdomjoint; } LINKOUTPUT childinfo = _WriteLink(_robot.getRoot(), ktec, pnoderoot, kmodel->getID()); FOREACHC(itused, childinfo.listusedlinks) { kmout->vlinksids.at(itused->first) = itused->second; } FOREACH(itprocessed,childinfo.listprocesseddofs) { kmout->vaxissids.at(itprocessed->first).jointnodesid = itprocessed->second; } kmout->_maplinkposes = childinfo._maplinkposes; // create the formulas for all mimic joints FOREACHC(itjoint, _robot.joints_) { string jointsid = _ComputeId(itjoint->second->name); boost::shared_ptr pjoint = itjoint->second; if( !pjoint->mimic ) { continue; } domFormulaRef pf = daeSafeCast(ktec->add(COLLADA_ELEMENT_FORMULA)); string formulaid = _ComputeId(str(boost::format("%s_formula")%jointsid)); pf->setSid(formulaid.c_str()); domCommon_float_or_paramRef ptarget = daeSafeCast(pf->add(COLLADA_ELEMENT_TARGET)); string targetjointid = str(boost::format("%s/%s")%kmodel->getID()%jointsid); daeSafeCast(ptarget->add(COLLADA_TYPE_PARAM))->setValue(targetjointid.c_str()); domTechniqueRef pftec = daeSafeCast(pf->add(COLLADA_ELEMENT_TECHNIQUE)); pftec->setProfile("OpenRAVE"); // save position equation { daeElementRef poselt = pftec->add("equation"); poselt->setAttribute("type","position"); // create a const0*joint+const1 formula // a x b daeElementRef pmath_math = poselt->add("math"); daeElementRef pmath_apply = pmath_math->add("apply"); { daeElementRef pmath_plus = pmath_apply->add("plus"); daeElementRef pmath_apply1 = pmath_apply->add("apply"); { daeElementRef pmath_times = pmath_apply1->add("times"); daeElementRef pmath_const0 = pmath_apply1->add("cn"); pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); daeElementRef pmath_symb = pmath_apply1->add("csymbol"); pmath_symb->setAttribute("encoding","COLLADA"); pmath_symb->setCharData(str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name))); } daeElementRef pmath_const1 = pmath_apply->add("cn"); pmath_const1->setCharData(str(boost::format("%f")%pjoint->mimic->offset)); } } // save first partial derivative { daeElementRef derivelt = pftec->add("equation"); derivelt->setAttribute("type","first_partial"); derivelt->setAttribute("target",str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)).c_str()); daeElementRef pmath_const0 = derivelt->add("cn"); pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); } // save second partial derivative { daeElementRef derivelt = pftec->add("equation"); derivelt->setAttribute("type","second_partial"); derivelt->setAttribute("target",str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)).c_str()); daeElementRef pmath_const0 = derivelt->add("cn"); pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); } { domFormula_techniqueRef pfcommontec = daeSafeCast(pf->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); // create a const0*joint+const1 formula // a x b daeElementRef pmath_math = pfcommontec->add("math"); daeElementRef pmath_apply = pmath_math->add("apply"); { daeElementRef pmath_plus = pmath_apply->add("plus"); daeElementRef pmath_apply1 = pmath_apply->add("apply"); { daeElementRef pmath_times = pmath_apply1->add("times"); daeElementRef pmath_const0 = pmath_apply1->add("cn"); pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); daeElementRef pmath_symb = pmath_apply1->add("csymbol"); pmath_symb->setAttribute("encoding","COLLADA"); pmath_symb->setCharData(str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name))); } daeElementRef pmath_const1 = pmath_apply->add("cn"); pmath_const1->setCharData(str(boost::format("%f")%pjoint->mimic->offset)); } } } return kmout; } /// \brief Write link of a kinematic body /// /// \param link Link to write /// \param pkinparent Kinbody parent /// \param pnodeparent Node parent /// \param strModelUri virtual LINKOUTPUT _WriteLink(boost::shared_ptr plink, daeElementRef pkinparent, domNodeRef pnodeparent, const string& strModelUri) { LINKOUTPUT out; int linkindex = _maplinkindices[plink]; string linksid = _ComputeId(plink->name); domLinkRef pdomlink = daeSafeCast(pkinparent->add(COLLADA_ELEMENT_LINK)); pdomlink->setName(plink->name.c_str()); pdomlink->setSid(linksid.c_str()); domNodeRef pnode = daeSafeCast(pnodeparent->add(COLLADA_ELEMENT_NODE)); string nodeid = _ComputeId(str(boost::format("v%s_node%d")%strModelUri%linkindex)); pnode->setId( nodeid.c_str() ); string nodesid = _ComputeId(str(boost::format("node%d")%linkindex)); pnode->setSid(nodesid.c_str()); pnode->setName(plink->name.c_str()); boost::shared_ptr geometry; boost::shared_ptr material; urdf::Pose geometry_origin; if( !!plink->visual ) { geometry = plink->visual->geometry; material = plink->visual->material; geometry_origin = plink->visual->origin; } else if( !!plink->collision ) { geometry = plink->collision->geometry; geometry_origin = plink->collision->origin; } urdf::Pose geometry_origin_inv = _poseInverse(geometry_origin); if( !!geometry ) { bool write_visual = false; if ( !!plink->visual ) { if (plink->visual_array.size() > 1) { int igeom = 0; for (std::vector >::const_iterator it = plink->visual_array.begin(); it != plink->visual_array.end(); it++) { // geom string geomid = _ComputeId(str(boost::format("g%s_%s_geom%d")%strModelUri%linksid%igeom)); igeom++; domGeometryRef pdomgeom; if ( it != plink->visual_array.begin() ) { urdf::Pose org_trans = _poseMult(geometry_origin_inv, (*it)->origin); pdomgeom = _WriteGeometry((*it)->geometry, geomid, &org_trans); } else { pdomgeom = _WriteGeometry((*it)->geometry, geomid); } domInstance_geometryRef pinstgeom = daeSafeCast(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY)); pinstgeom->setUrl((string("#") + geomid).c_str()); // material _WriteMaterial(pdomgeom->getID(), (*it)->material); domBind_materialRef pmat = daeSafeCast(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL)); domBind_material::domTechnique_commonRef pmattec = daeSafeCast(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); domInstance_materialRef pinstmat = daeSafeCast(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL)); pinstmat->setTarget(xsAnyURI(*pdomgeom, string("#")+geomid+string("_mat"))); pinstmat->setSymbol("mat0"); write_visual = true; } } } if (!write_visual) { // just 1 visual int igeom = 0; string geomid = _ComputeId(str(boost::format("g%s_%s_geom%d")%strModelUri%linksid%igeom)); domGeometryRef pdomgeom = _WriteGeometry(geometry, geomid); domInstance_geometryRef pinstgeom = daeSafeCast(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY)); pinstgeom->setUrl((string("#")+geomid).c_str()); // material _WriteMaterial(pdomgeom->getID(), material); domBind_materialRef pmat = daeSafeCast(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL)); domBind_material::domTechnique_commonRef pmattec = daeSafeCast(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); domInstance_materialRef pinstmat = daeSafeCast(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL)); pinstmat->setTarget(xsAnyURI(*pdomgeom, string("#")+geomid+string("_mat"))); pinstmat->setSymbol("mat0"); } } _WriteTransformation(pnode, geometry_origin); // process all children FOREACHC(itjoint, plink->child_joints) { boost::shared_ptr pjoint = *itjoint; int index = _mapjointindices[pjoint]; // domLink::domAttachment_fullRef attachment_full = daeSafeCast(pdomlink->add(COLLADA_ELEMENT_ATTACHMENT_FULL)); string jointid = str(boost::format("%s/%s")%strModelUri%_ComputeId(pjoint->name)); attachment_full->setJoint(jointid.c_str()); LINKOUTPUT childinfo = _WriteLink(_robot.getLink(pjoint->child_link_name), attachment_full, pnode, strModelUri); FOREACH(itused,childinfo.listusedlinks) { out.listusedlinks.push_back(make_pair(itused->first,linksid+string("/")+itused->second)); } FOREACH(itprocessed,childinfo.listprocesseddofs) { out.listprocesseddofs.push_back(make_pair(itprocessed->first,nodesid+string("/")+itprocessed->second)); } FOREACH(itlinkpos,childinfo._maplinkposes) { out._maplinkposes[itlinkpos->first] = _poseMult(pjoint->parent_to_joint_origin_transform,itlinkpos->second); } // rotate/translate elements string jointnodesid = _ComputeId(str(boost::format("node_%s_axis0")%pjoint->name)); switch(pjoint->type) { case urdf::Joint::REVOLUTE: case urdf::Joint::CONTINUOUS: case urdf::Joint::FIXED: { domRotateRef protate = daeSafeCast(childinfo.pnode->add(COLLADA_ELEMENT_ROTATE,0)); protate->setSid(jointnodesid.c_str()); protate->getValue().setCount(4); protate->getValue()[0] = pjoint->axis.x; protate->getValue()[1] = pjoint->axis.y; protate->getValue()[2] = pjoint->axis.z; protate->getValue()[3] = 0; break; } case urdf::Joint::PRISMATIC: { domTranslateRef ptrans = daeSafeCast(childinfo.pnode->add(COLLADA_ELEMENT_TRANSLATE,0)); ptrans->setSid(jointnodesid.c_str()); ptrans->getValue().setCount(3); ptrans->getValue()[0] = 0; ptrans->getValue()[1] = 0; ptrans->getValue()[2] = 0; break; } default: ROS_WARN_STREAM(str(boost::format("unsupported joint type specified %d")%(int)pjoint->type)); break; } _WriteTransformation(attachment_full, pjoint->parent_to_joint_origin_transform); _WriteTransformation(childinfo.pnode, pjoint->parent_to_joint_origin_transform); _WriteTransformation(childinfo.pnode, geometry_origin_inv); // have to do multiply by inverse since geometry transformation is not part of hierarchy out.listprocesseddofs.push_back(make_pair(index,string(childinfo.pnode->getSid())+string("/")+jointnodesid)); // } out._maplinkposes[plink] = urdf::Pose(); out.listusedlinks.push_back(make_pair(linkindex,linksid)); out.plink = pdomlink; out.pnode = pnode; return out; } domGeometryRef _WriteGeometry(boost::shared_ptr geometry, const std::string& geometry_id, urdf::Pose *org_trans = NULL) { domGeometryRef cgeometry = daeSafeCast(_geometriesLib->add(COLLADA_ELEMENT_GEOMETRY)); cgeometry->setId(geometry_id.c_str()); switch (geometry->type) { case urdf::Geometry::MESH: { urdf::Mesh* urdf_mesh = (urdf::Mesh*) geometry.get(); cgeometry->setName(urdf_mesh->filename.c_str()); _loadMesh(urdf_mesh->filename, cgeometry, urdf_mesh->scale, org_trans); break; } case urdf::Geometry::SPHERE: { shapes::Sphere sphere(static_cast(geometry.get())->radius); boost::scoped_ptr mesh(shapes::createMeshFromShape(sphere)); _loadVertices(mesh.get(), cgeometry); break; } case urdf::Geometry::BOX: { shapes::Box box(static_cast(geometry.get())->dim.x / 2.0, static_cast(geometry.get())->dim.y / 2.0, static_cast(geometry.get())->dim.z / 2.0); boost::scoped_ptr mesh(shapes::createMeshFromShape(box)); _loadVertices(mesh.get(), cgeometry); break; } case urdf::Geometry::CYLINDER: { shapes::Cylinder cyl(static_cast(geometry.get())->radius, static_cast(geometry.get())->length); boost::scoped_ptr mesh(shapes::createMeshFromShape(cyl)); _loadVertices(mesh.get(), cgeometry); break; } default: { throw ColladaUrdfException(str(boost::format("undefined geometry type %d, name %s")%(int)geometry->type%geometry_id)); } } return cgeometry; } void _WriteMaterial(const string& geometry_id, boost::shared_ptr material) { string effid = geometry_id+string("_eff"); string matid = geometry_id+string("_mat"); domMaterialRef pdommat = daeSafeCast(_materialsLib->add(COLLADA_ELEMENT_MATERIAL)); pdommat->setId(matid.c_str()); domInstance_effectRef pdominsteff = daeSafeCast(pdommat->add(COLLADA_ELEMENT_INSTANCE_EFFECT)); pdominsteff->setUrl((string("#")+effid).c_str()); urdf::Color ambient, diffuse; ambient.init("0.1 0.1 0.1 0"); diffuse.init("1 1 1 0"); if( !!material ) { ambient.r = diffuse.r = material->color.r; ambient.g = diffuse.g = material->color.g; ambient.b = diffuse.b = material->color.b; ambient.a = diffuse.a = material->color.a; } domEffectRef effect = _WriteEffect(geometry_id, ambient, diffuse); // domMaterialRef dommaterial = daeSafeCast(_materialsLib->add(COLLADA_ELEMENT_MATERIAL)); string material_id = geometry_id + string("_mat"); dommaterial->setId(material_id.c_str()); { // domInstance_effectRef instance_effect = daeSafeCast(dommaterial->add(COLLADA_ELEMENT_INSTANCE_EFFECT)); string effect_id(effect->getId()); instance_effect->setUrl((string("#") + effect_id).c_str()); } // domEffectRef pdomeff = _WriteEffect(effid, ambient, diffuse); } boost::shared_ptr _WriteInstance_physics_model(int id, daeElementRef parent, const string& sidscope, const MAPLINKPOSES& maplinkposes) { boost::shared_ptr pmout = WritePhysics_model(id, maplinkposes); boost::shared_ptr ipmout(new instance_physics_model_output()); ipmout->pmout = pmout; ipmout->ipm = daeSafeCast(parent->add(COLLADA_ELEMENT_INSTANCE_PHYSICS_MODEL)); string bodyid = _ComputeId(str(boost::format("visual%d")%id)); ipmout->ipm->setParent(xsAnyURI(*ipmout->ipm,string("#")+bodyid)); string symscope, refscope; if( sidscope.size() > 0 ) { symscope = sidscope+string("_"); refscope = sidscope+string("/"); } string ipmsid = str(boost::format("%s_inst")%pmout->pmodel->getID()); ipmout->ipm->setUrl(str(boost::format("#%s")%pmout->pmodel->getID()).c_str()); ipmout->ipm->setSid(ipmsid.c_str()); string kmodelid = _ComputeKinematics_modelId(id); for(size_t i = 0; i < pmout->vrigidbodysids.size(); ++i) { domInstance_rigid_bodyRef pirb = daeSafeCast(ipmout->ipm->add(COLLADA_ELEMENT_INSTANCE_RIGID_BODY)); pirb->setBody(pmout->vrigidbodysids[i].c_str()); pirb->setTarget(xsAnyURI(*pirb,str(boost::format("#v%s_node%d")%kmodelid%i))); } return ipmout; } boost::shared_ptr WritePhysics_model(int id, const MAPLINKPOSES& maplinkposes) { boost::shared_ptr pmout(new physics_model_output()); pmout->pmodel = daeSafeCast(_physicsModelsLib->add(COLLADA_ELEMENT_PHYSICS_MODEL)); string pmodelid = str(boost::format("pmodel%d")%id); pmout->pmodel->setId(pmodelid.c_str()); pmout->pmodel->setName(_robot.getName().c_str()); FOREACHC(itlink,_robot.links_) { domRigid_bodyRef rigid_body = daeSafeCast(pmout->pmodel->add(COLLADA_ELEMENT_RIGID_BODY)); string rigidsid = str(boost::format("rigid%d")%_maplinkindices[itlink->second]); pmout->vrigidbodysids.push_back(rigidsid); rigid_body->setSid(rigidsid.c_str()); rigid_body->setName(itlink->second->name.c_str()); domRigid_body::domTechnique_commonRef ptec = daeSafeCast(rigid_body->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); boost::shared_ptr inertial = itlink->second->inertial; if( !!inertial ) { daeSafeCast(ptec->add(COLLADA_ELEMENT_DYNAMIC))->setValue(xsBoolean(true)); //!!inertial)); domTargetable_floatRef mass = daeSafeCast(ptec->add(COLLADA_ELEMENT_MASS)); mass->setValue(inertial->mass); double fCovariance[9] = { inertial->ixx, inertial->ixy, inertial->ixz, inertial->ixy, inertial->iyy, inertial->iyz, inertial->ixz, inertial->iyz, inertial->izz}; double eigenvalues[3], eigenvectors[9]; mathextra::EigenSymmetric3(fCovariance,eigenvalues,eigenvectors); boost::array minertiaframe; for(int j = 0; j < 3; ++j) { minertiaframe[4*0+j] = eigenvectors[3*j]; minertiaframe[4*1+j] = eigenvectors[3*j+1]; minertiaframe[4*2+j] = eigenvectors[3*j+2]; } urdf::Pose tinertiaframe; tinertiaframe.rotation = _quatFromMatrix(minertiaframe); tinertiaframe = _poseMult(inertial->origin,tinertiaframe); domTargetable_float3Ref pinertia = daeSafeCast(ptec->add(COLLADA_ELEMENT_INERTIA)); pinertia->getValue().setCount(3); pinertia->getValue()[0] = eigenvalues[0]; pinertia->getValue()[1] = eigenvalues[1]; pinertia->getValue()[2] = eigenvalues[2]; urdf::Pose posemassframe = _poseMult(maplinkposes.find(itlink->second)->second,tinertiaframe); _WriteTransformation(ptec->add(COLLADA_ELEMENT_MASS_FRAME), posemassframe); // // create a shape for every geometry // int igeom = 0; // FOREACHC(itgeom, (*itlink)->GetGeometries()) { // domRigid_body::domTechnique_common::domShapeRef pdomshape = daeSafeCast(ptec->add(COLLADA_ELEMENT_SHAPE)); // // there is a weird bug here where _WriteTranformation will fail to create rotate/translate elements in instance_geometry is created first... (is this part of the spec?) // _WriteTransformation(pdomshape,tbaseinv*(*itlink)->GetTransform()*itgeom->GetTransform()); // domInstance_geometryRef pinstgeom = daeSafeCast(pdomshape->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY)); // pinstgeom->setUrl(xsAnyURI(*pinstgeom,string("#")+_GetGeometryId(*itlink,igeom))); // ++igeom; // } } } return pmout; } void _loadVertices(const shapes::Mesh *mesh, domGeometryRef pdomgeom) { // convert the mesh into an STL binary (in memory) std::vector buffer; shapes::writeSTLBinary(mesh, buffer); // Create an instance of the Importer class Assimp::Importer importer; // And have it read the given file with some postprocessing const aiScene* scene = importer.ReadFileFromMemory(reinterpret_cast(&buffer[0]), buffer.size(), aiProcess_Triangulate | aiProcess_JoinIdenticalVertices | aiProcess_SortByPType | aiProcess_OptimizeGraph | aiProcess_OptimizeMeshes, "stl"); // Note: we do this mesh -> STL -> assimp mesh because the aiScene::aiScene symbol is hidden by default domMeshRef pdommesh = daeSafeCast(pdomgeom->add(COLLADA_ELEMENT_MESH)); domSourceRef pvertsource = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_SOURCE)); domAccessorRef pacc; domFloat_arrayRef parray; { pvertsource->setId(str(boost::format("%s_positions")%pdomgeom->getID()).c_str()); parray = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY)); parray->setId(str(boost::format("%s_positions-array")%pdomgeom->getID()).c_str()); parray->setDigits(6); // 6 decimal places domSource::domTechnique_commonRef psourcetec = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); pacc = daeSafeCast(psourcetec->add(COLLADA_ELEMENT_ACCESSOR)); pacc->setSource(xsAnyURI(*parray, std::string("#")+string(parray->getID()))); pacc->setStride(3); domParamRef px = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); px->setName("X"); px->setType("float"); domParamRef py = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); py->setName("Y"); py->setType("float"); domParamRef pz = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); pz->setName("Z"); pz->setType("float"); } domVerticesRef pverts = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_VERTICES)); { pverts->setId("vertices"); domInput_localRef pvertinput = daeSafeCast(pverts->add(COLLADA_ELEMENT_INPUT)); pvertinput->setSemantic("POSITION"); pvertinput->setSource(domUrifragment(*pvertsource, std::string("#")+std::string(pvertsource->getID()))); } _buildAiMesh(scene,scene->mRootNode,pdommesh,parray, pdomgeom->getID(), urdf::Vector3(1,1,1)); pacc->setCount(parray->getCount()); } void _loadMesh(std::string const& filename, domGeometryRef pdomgeom, const urdf::Vector3& scale, urdf::Pose *org_trans) { const aiScene* scene = _importer.ReadFile(filename, aiProcess_SortByPType|aiProcess_Triangulate); //|aiProcess_GenNormals|aiProcess_GenUVCoords|aiProcess_FlipUVs); if( !scene ) { ROS_WARN("failed to load resource %s",filename.c_str()); return; } if( !scene->mRootNode ) { ROS_WARN("resource %s has no data",filename.c_str()); return; } if (!scene->HasMeshes()) { ROS_WARN_STREAM(str(boost::format("No meshes found in file %s")%filename)); return; } domMeshRef pdommesh = daeSafeCast(pdomgeom->add(COLLADA_ELEMENT_MESH)); domSourceRef pvertsource = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_SOURCE)); domAccessorRef pacc; domFloat_arrayRef parray; { pvertsource->setId(str(boost::format("%s_positions")%pdomgeom->getID()).c_str()); parray = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY)); parray->setId(str(boost::format("%s_positions-array")%pdomgeom->getID()).c_str()); parray->setDigits(6); // 6 decimal places domSource::domTechnique_commonRef psourcetec = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); pacc = daeSafeCast(psourcetec->add(COLLADA_ELEMENT_ACCESSOR)); pacc->setSource(xsAnyURI(*parray, string("#")+string(parray->getID()))); pacc->setStride(3); domParamRef px = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); px->setName("X"); px->setType("float"); domParamRef py = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); py->setName("Y"); py->setType("float"); domParamRef pz = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); pz->setName("Z"); pz->setType("float"); } domVerticesRef pverts = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_VERTICES)); { pverts->setId("vertices"); domInput_localRef pvertinput = daeSafeCast(pverts->add(COLLADA_ELEMENT_INPUT)); pvertinput->setSemantic("POSITION"); pvertinput->setSource(domUrifragment(*pvertsource, string("#")+string(pvertsource->getID()))); } _buildAiMesh(scene,scene->mRootNode,pdommesh,parray, pdomgeom->getID(),scale,org_trans); pacc->setCount(parray->getCount()); } void _buildAiMesh(const aiScene* scene, aiNode* node, domMeshRef pdommesh, domFloat_arrayRef parray, const string& geomid, const urdf::Vector3& scale, urdf::Pose *org_trans = NULL) { if( !node ) { return; } aiMatrix4x4 transform = node->mTransformation; aiNode *pnode = node->mParent; while (pnode) { // Don't convert to y-up orientation, which is what the root node in // Assimp does if (pnode->mParent != NULL) { transform = pnode->mTransformation * transform; } pnode = pnode->mParent; } { uint32_t vertexOffset = parray->getCount(); uint32_t nTotalVertices=0; for (uint32_t i = 0; i < node->mNumMeshes; i++) { aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; nTotalVertices += input_mesh->mNumVertices; } parray->getValue().grow(parray->getCount()+nTotalVertices*3); parray->setCount(parray->getCount()+nTotalVertices); for (uint32_t i = 0; i < node->mNumMeshes; i++) { aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; for (uint32_t j = 0; j < input_mesh->mNumVertices; j++) { aiVector3D p = input_mesh->mVertices[j]; p *= transform; if (org_trans) { urdf::Vector3 vv; vv.x = p.x*scale.x; vv.y = p.y*scale.y; vv.z = p.z*scale.z; urdf::Vector3 nv = _poseMult(*org_trans, vv); parray->getValue().append(nv.x); parray->getValue().append(nv.y); parray->getValue().append(nv.z); } else { parray->getValue().append(p.x*scale.x); parray->getValue().append(p.y*scale.y); parray->getValue().append(p.z*scale.z); } } } // in order to save space, separate triangles from poly lists vector triangleindices, otherindices; int nNumOtherPrimitives = 0; for (uint32_t i = 0; i < node->mNumMeshes; i++) { aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; uint32_t indexCount = 0, otherIndexCount = 0; for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) { aiFace& face = input_mesh->mFaces[j]; if( face.mNumIndices == 3 ) { indexCount += face.mNumIndices; } else { otherIndexCount += face.mNumIndices; } } triangleindices.reserve(triangleindices.size()+indexCount); otherindices.reserve(otherindices.size()+otherIndexCount); for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) { aiFace& face = input_mesh->mFaces[j]; if( face.mNumIndices == 3 ) { triangleindices.push_back(vertexOffset+face.mIndices[0]); triangleindices.push_back(vertexOffset+face.mIndices[1]); triangleindices.push_back(vertexOffset+face.mIndices[2]); } else { for (uint32_t k = 0; k < face.mNumIndices; ++k) { otherindices.push_back(face.mIndices[k]+vertexOffset); } nNumOtherPrimitives++; } } vertexOffset += input_mesh->mNumVertices; } if( triangleindices.size() > 0 ) { domTrianglesRef ptris = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_TRIANGLES)); ptris->setCount(triangleindices.size()/3); ptris->setMaterial("mat0"); domInput_local_offsetRef pvertoffset = daeSafeCast(ptris->add(COLLADA_ELEMENT_INPUT)); pvertoffset->setSemantic("VERTEX"); pvertoffset->setOffset(0); pvertoffset->setSource(domUrifragment(*pdommesh->getVertices(), str(boost::format("#%s/vertices")%geomid))); domPRef pindices = daeSafeCast(ptris->add(COLLADA_ELEMENT_P)); pindices->getValue().setCount(triangleindices.size()); for(size_t ind = 0; ind < triangleindices.size(); ++ind) { pindices->getValue()[ind] = triangleindices[ind]; } } if( nNumOtherPrimitives > 0 ) { domPolylistRef ptris = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_POLYLIST)); ptris->setCount(nNumOtherPrimitives); ptris->setMaterial("mat0"); domInput_local_offsetRef pvertoffset = daeSafeCast(ptris->add(COLLADA_ELEMENT_INPUT)); pvertoffset->setSemantic("VERTEX"); pvertoffset->setSource(domUrifragment(*pdommesh->getVertices(), str(boost::format("#%s/vertices")%geomid))); domPRef pindices = daeSafeCast(ptris->add(COLLADA_ELEMENT_P)); pindices->getValue().setCount(otherindices.size()); for(size_t ind = 0; ind < otherindices.size(); ++ind) { pindices->getValue()[ind] = otherindices[ind]; } domPolylist::domVcountRef pcount = daeSafeCast(ptris->add(COLLADA_ELEMENT_VCOUNT)); pcount->getValue().setCount(nNumOtherPrimitives); uint32_t offset = 0; for (uint32_t i = 0; i < node->mNumMeshes; i++) { aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) { aiFace& face = input_mesh->mFaces[j]; if( face.mNumIndices > 3 ) { pcount->getValue()[offset++] = face.mNumIndices; } } } } } for (uint32_t i=0; i < node->mNumChildren; ++i) { _buildAiMesh(scene, node->mChildren[i], pdommesh,parray,geomid,scale,org_trans); } } domEffectRef _WriteEffect(std::string const& effect_id, urdf::Color const& color_ambient, urdf::Color const& color_diffuse) { // domEffectRef effect = daeSafeCast(_effectsLib->add(COLLADA_ELEMENT_EFFECT)); effect->setId(effect_id.c_str()); { // domProfile_commonRef profile = daeSafeCast(effect->add(COLLADA_ELEMENT_PROFILE_COMMON)); { // domProfile_common::domTechniqueRef technique = daeSafeCast(profile->add(COLLADA_ELEMENT_TECHNIQUE)); { // domProfile_common::domTechnique::domPhongRef phong = daeSafeCast(technique->add(COLLADA_ELEMENT_PHONG)); { // domFx_common_color_or_textureRef ambient = daeSafeCast(phong->add(COLLADA_ELEMENT_AMBIENT)); { // r g b a domFx_common_color_or_texture::domColorRef ambient_color = daeSafeCast(ambient->add(COLLADA_ELEMENT_COLOR)); ambient_color->getValue().setCount(4); ambient_color->getValue()[0] = color_ambient.r; ambient_color->getValue()[1] = color_ambient.g; ambient_color->getValue()[2] = color_ambient.b; ambient_color->getValue()[3] = color_ambient.a; // } // // domFx_common_color_or_textureRef diffuse = daeSafeCast(phong->add(COLLADA_ELEMENT_DIFFUSE)); { // r g b a domFx_common_color_or_texture::domColorRef diffuse_color = daeSafeCast(diffuse->add(COLLADA_ELEMENT_COLOR)); diffuse_color->getValue().setCount(4); diffuse_color->getValue()[0] = color_diffuse.r; diffuse_color->getValue()[1] = color_diffuse.g; diffuse_color->getValue()[2] = color_diffuse.b; diffuse_color->getValue()[3] = color_diffuse.a; // } // } // } // } // } // return effect; } /// \brief Write transformation /// \param pelt Element to transform /// \param t Transform to write void _WriteTransformation(daeElementRef pelt, const urdf::Pose& t) { domRotateRef prot = daeSafeCast(pelt->add(COLLADA_ELEMENT_ROTATE,0)); domTranslateRef ptrans = daeSafeCast(pelt->add(COLLADA_ELEMENT_TRANSLATE,0)); ptrans->getValue().setCount(3); ptrans->getValue()[0] = t.position.x; ptrans->getValue()[1] = t.position.y; ptrans->getValue()[2] = t.position.z; prot->getValue().setCount(4); // extract axis from quaternion double sinang = t.rotation.x*t.rotation.x+t.rotation.y*t.rotation.y+t.rotation.z*t.rotation.z; if( std::fabs(sinang) < 1e-10 ) { prot->getValue()[0] = 1; prot->getValue()[1] = 0; prot->getValue()[2] = 0; prot->getValue()[3] = 0; } else { urdf::Rotation quat; if( t.rotation.w < 0 ) { quat.x = -t.rotation.x; quat.y = -t.rotation.y; quat.z = -t.rotation.z; quat.w = -t.rotation.w; } else { quat = t.rotation; } sinang = std::sqrt(sinang); prot->getValue()[0] = quat.x/sinang; prot->getValue()[1] = quat.y/sinang; prot->getValue()[2] = quat.z/sinang; prot->getValue()[3] = angles::to_degrees(2.0*std::atan2(sinang,quat.w)); } } // binding in instance_kinematics_scene void _WriteBindingsInstance_kinematics_scene() { FOREACHC(it, _iasout->vkinematicsbindings) { domBind_kinematics_modelRef pmodelbind = daeSafeCast(_scene.kiscene->add(COLLADA_ELEMENT_BIND_KINEMATICS_MODEL)); pmodelbind->setNode(it->second.c_str()); daeSafeCast(pmodelbind->add(COLLADA_ELEMENT_PARAM))->setValue(it->first.c_str()); } FOREACHC(it, _iasout->vaxissids) { domBind_joint_axisRef pjointbind = daeSafeCast(_scene.kiscene->add(COLLADA_ELEMENT_BIND_JOINT_AXIS)); pjointbind->setTarget(it->jointnodesid.c_str()); daeSafeCast(pjointbind->add(COLLADA_ELEMENT_AXIS)->add(COLLADA_TYPE_PARAM))->setValue(it->axissid.c_str()); daeSafeCast(pjointbind->add(COLLADA_ELEMENT_VALUE)->add(COLLADA_TYPE_PARAM))->setValue(it->valuesid.c_str()); } } private: static urdf::Vector3 _poseMult(const urdf::Pose& p, const urdf::Vector3& v) { double ww = 2 * p.rotation.x * p.rotation.x; double wx = 2 * p.rotation.x * p.rotation.y; double wy = 2 * p.rotation.x * p.rotation.z; double wz = 2 * p.rotation.x * p.rotation.w; double xx = 2 * p.rotation.y * p.rotation.y; double xy = 2 * p.rotation.y * p.rotation.z; double xz = 2 * p.rotation.y * p.rotation.w; double yy = 2 * p.rotation.z * p.rotation.z; double yz = 2 * p.rotation.z * p.rotation.w; urdf::Vector3 vnew; vnew.x = (1-xx-yy) * v.x + (wx-yz) * v.y + (wy+xz)*v.z + p.position.x; vnew.y = (wx+yz) * v.x + (1-ww-yy) * v.y + (xy-wz)*v.z + p.position.y; vnew.z = (wy-xz) * v.x + (xy+wz) * v.y + (1-ww-xx)*v.z + p.position.z; return vnew; } static urdf::Pose _poseInverse(const urdf::Pose& p) { urdf::Pose pinv; pinv.rotation.x = -p.rotation.x; pinv.rotation.y = -p.rotation.y; pinv.rotation.z = -p.rotation.z; pinv.rotation.w = p.rotation.w; urdf::Vector3 t = _poseMult(pinv,p.position); pinv.position.x = -t.x; pinv.position.y = -t.y; pinv.position.z = -t.z; return pinv; } static urdf::Rotation _quatMult(const urdf::Rotation& quat0, const urdf::Rotation& quat1) { urdf::Rotation q; q.x = quat0.w*quat1.x + quat0.x*quat1.w + quat0.y*quat1.z - quat0.z*quat1.y; q.y = quat0.w*quat1.y + quat0.y*quat1.w + quat0.z*quat1.x - quat0.x*quat1.z; q.z = quat0.w*quat1.z + quat0.z*quat1.w + quat0.x*quat1.y - quat0.y*quat1.x; q.w = quat0.w*quat1.w - quat0.x*quat1.x - quat0.y*quat1.y - quat0.z*quat1.z; double fnorm = std::sqrt(q.x*q.x+q.y*q.y+q.z*q.z+q.w*q.w); // don't touch the divides q.x /= fnorm; q.y /= fnorm; q.z /= fnorm; q.w /= fnorm; return q; } static urdf::Pose _poseMult(const urdf::Pose& p0, const urdf::Pose& p1) { urdf::Pose p; p.position = _poseMult(p0,p1.position); p.rotation = _quatMult(p0.rotation,p1.rotation); return p; } static urdf::Rotation _quatFromMatrix(const boost::array& mat) { urdf::Rotation rot; double tr = mat[4*0+0] + mat[4*1+1] + mat[4*2+2]; if (tr >= 0) { rot.w = tr + 1; rot.x = (mat[4*2+1] - mat[4*1+2]); rot.y = (mat[4*0+2] - mat[4*2+0]); rot.z = (mat[4*1+0] - mat[4*0+1]); } else { // find the largest diagonal element and jump to the appropriate case if (mat[4*1+1] > mat[4*0+0]) { if (mat[4*2+2] > mat[4*1+1]) { rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1; rot.x = (mat[4*2+0] + mat[4*0+2]); rot.y = (mat[4*1+2] + mat[4*2+1]); rot.w = (mat[4*1+0] - mat[4*0+1]); } else { rot.y = (mat[4*1+1] - (mat[4*2+2] + mat[4*0+0])) + 1; rot.z = (mat[4*1+2] + mat[4*2+1]); rot.x = (mat[4*0+1] + mat[4*1+0]); rot.w = (mat[4*0+2] - mat[4*2+0]); } } else if (mat[4*2+2] > mat[4*0+0]) { rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1; rot.x = (mat[4*2+0] + mat[4*0+2]); rot.y = (mat[4*1+2] + mat[4*2+1]); rot.w = (mat[4*1+0] - mat[4*0+1]); } else { rot.x = (mat[4*0+0] - (mat[4*1+1] + mat[4*2+2])) + 1; rot.y = (mat[4*0+1] + mat[4*1+0]); rot.z = (mat[4*2+0] + mat[4*0+2]); rot.w = (mat[4*2+1] - mat[4*1+2]); } } double fnorm = std::sqrt(rot.x*rot.x+rot.y*rot.y+rot.z*rot.z+rot.w*rot.w); // don't touch the divides rot.x /= fnorm; rot.y /= fnorm; rot.z /= fnorm; rot.w /= fnorm; return rot; } static std::string _ComputeKinematics_modelId(int id) { return _ComputeId(str(boost::format("kmodel%d")%id)); } /// \brief computes a collada-compliant sid from the urdf name static std::string _ComputeId(const std::string& name) { std::string newname = name; for(size_t i = 0; i < newname.size(); ++i) { if( newname[i] == '/' || newname[i] == ' ' || newname[i] == '.' ) { newname[i] = '_'; } } return newname; } int _writeoptions; const urdf::Model& _robot; DAE _collada; domCOLLADA* _dom; daeDocument *_doc; domCOLLADA::domSceneRef _globalscene; domLibrary_visual_scenesRef _visualScenesLib; domLibrary_kinematics_scenesRef _kinematicsScenesLib; domLibrary_kinematics_modelsRef _kinematicsModelsLib; domLibrary_articulated_systemsRef _articulatedSystemsLib; domLibrary_physics_scenesRef _physicsScenesLib; domLibrary_physics_modelsRef _physicsModelsLib; domLibrary_materialsRef _materialsLib; domLibrary_effectsRef _effectsLib; domLibrary_geometriesRef _geometriesLib; domTechniqueRef _sensorsLib; ///< custom sensors library SCENE _scene; boost::shared_ptr _ikmout; boost::shared_ptr _iasout; std::map< boost::shared_ptr, int > _mapjointindices; std::map< boost::shared_ptr, int > _maplinkindices; std::map< boost::shared_ptr, int > _mapmaterialindices; Assimp::Importer _importer; }; ColladaUrdfException::ColladaUrdfException(std::string const& what) : std::runtime_error(what) { } bool WriteUrdfModelToColladaFile(urdf::Model const& robot_model, string const& file) { ColladaWriter writer(robot_model,0); if ( ! writer.convert() ) { std::cerr << std::endl << "Error converting document" << std::endl; return -1; } return writer.writeTo(file); } } ros-robot-model-1.11.8/collada_urdf/src/urdf_to_collada.cpp000066400000000000000000000047071257532150500236760ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redstributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Tim Field */ #include "collada_urdf/collada_urdf.h" #include int main(int argc, char** argv) { if (argc != 3) { std::cerr << "Usage: urdf_to_collada input.urdf output.dae" << std::endl; return -1; } ros::init(argc, argv, "urdf_to_collada"); std::string input_filename(argv[1]); std::string output_filename(argv[2]); urdf::Model robot_model; if( !robot_model.initFile(input_filename) ) { ROS_ERROR("failed to open urdf file %s",input_filename.c_str()); } collada_urdf::WriteUrdfModelToColladaFile(robot_model, output_filename); std::cout << std::endl << "Document successfully written to " << output_filename << std::endl; return 0; } ros-robot-model-1.11.8/collada_urdf/test/000077500000000000000000000000001257532150500202315ustar00rootroot00000000000000ros-robot-model-1.11.8/collada_urdf/test/pr2.urdf000066400000000000000000004257251257532150500216350ustar00rootroot00000000000000 true 1000.0 true 1.0 5 power_state 10.0 87.78 -474 525 15.52 16.41 640 640 1 0.0 0.0 0.0 false -129.998394137 129.998394137 0.05 10.0 0.01 20 0.005 true 20 base_scan base_laser_link -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 true base_link_geom 100.0 true 100.0 base_bumper true 100.0 base_link base_pose_ground_truth 0.01 map 25.7 25.7 0 0 0 0 base_footprint torso_lift_link_geom 100.0 true 100.0 torso_lift_bumper -52143.33 true 100.0 imu_link torso_lift_imu/data 2.89e-08 map 0 0 0 0 0 0 6.0 6.0 R8G8B8 2448 2050 45 0.1 100 20.0 true 20.0 /prosilica/image_raw /prosilica/camera_info /prosilica/request_image high_def_frame 1224.5 1224.5 1025.5 2955 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 640 480 BAYER_BGGR8 90 0.1 100 25.0 true 25.0 wide_stereo/left/image_raw wide_stereo/left/camera_info wide_stereo_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 BAYER_BGGR8 90 0.1 100 25.0 true 25.0 wide_stereo/right/image_raw wide_stereo/right/camera_info wide_stereo_optical_frame 0.09 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 45 0.1 100 25.0 true 25.0 narrow_stereo/left/image_raw narrow_stereo/left/camera_info narrow_stereo_optical_frame 0 320.5 320.5 240.5 772.55 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 45 0.1 100 25.0 true 25.0 narrow_stereo/right/image_raw narrow_stereo/right/camera_info narrow_stereo_optical_frame 0.09 320.5 320.5 240.5 772.55 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 640 1 0.0 0.0 0.0 false -79.9999999086 79.9999999086 0.05 10.0 0.01 20 0.005 true 20 tilt_scan laser_tilt_link -6.05 true 32.6525111499 r_shoulder_pan_link_geom 100.0 true 100.0 r_shoulder_pan_bumper true r_shoulder_lift_link_geom 100.0 true 100.0 r_r_shoulder_lift_bumper true 63.1552452977 61.8948225713 r_upper_arm_link_geom 100.0 true 100.0 r_upper_arm_bumper true true -90.5142857143 -1.0 r_elbow_flex_link_geom 100.0 true 100.0 r_elbow_flex_bumper true -36.167452007 true r_forearm_link_geom 100.0 true 100.0 r_forearm_bumper true r_wrist_flex_link_geom 100.0 true 100.0 r_wrist_flex_bumper true r_wrist_roll_link_geom 100.0 true 100.0 r_wrist_roll_bumper true r_gripper_l_finger_link_geom 100.0 true 100.0 r_gripper_l_finger_bumper true r_gripper_r_finger_link_geom 100.0 true 100.0 r_gripper_r_finger_bumper true false r_gripper_l_finger_tip_link_geom 100.0 true 100.0 r_gripper_l_finger_tip_bumper true false r_gripper_r_finger_tip_link_geom 100.0 true 100.0 r_gripper_r_finger_tip_bumper true 100.0 r_gripper_l_finger_link r_gripper_l_finger_pose_ground_truth 0.0 map true 100.0 r_gripper_l_finger_link r_gripper_l_finger_force_ground_truth r_gripper_l_finger_link true r_gripper_palm_link_geom 100.0 true 100.0 r_gripper_palm_bumper true true 0.01 0.0001 0 0 0.0001 0 0.0001 0 0 0 0.82025 0.188 0.790675 0 -0 0 0 0 0 0 -0 0 0.0 0.0 0.0 0 0 0 0 -0 0 0.0 0.0 0.0 unit_box PR2/White true false r_gripper_float_link r_gripper_palm_link r_gripper_float_link 1 0 0 -0.05 0.001 r_gripper_l_finger_tip_link r_gripper_float_link r_gripper_l_finger_tip_link 0 1 0 0 0 0 r_gripper_r_finger_tip_link r_gripper_float_link r_gripper_r_finger_tip_link 0 1 0 0 0 0 true 100.0 r_gripper_palm_link r_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map true 100.0 r_gripper_tool_frame r_gripper_tool_frame_pose_ground_truth 0 0 0 0 0 0 0.0 /map true true 32.6525111499 l_shoulder_pan_link_geom 100.0 true 100.0 l_shoulder_pan_bumper true l_shoulder_lift_link_geom 100.0 true 100.0 l_r_shoulder_lift_bumper true 63.1552452977 61.8948225713 l_upper_arm_link_geom 100.0 true 100.0 l_upper_arm_bumper true true -90.5142857143 -1.0 l_elbow_flex_link_geom 100.0 true 100.0 l_elbow_flex_bumper true -36.167452007 true l_forearm_link_geom 100.0 true 100.0 l_forearm_bumper true l_wrist_flex_link_geom 100.0 true 100.0 l_wrist_flex_bumper true l_wrist_roll_link_geom 100.0 true 100.0 l_wrist_roll_bumper true l_gripper_l_finger_link_geom 100.0 true 100.0 l_gripper_l_finger_bumper true l_gripper_r_finger_link_geom 100.0 true 100.0 l_gripper_r_finger_bumper true false l_gripper_l_finger_tip_link_geom 100.0 true 100.0 l_gripper_l_finger_tip_bumper true false l_gripper_r_finger_tip_link_geom 100.0 true 100.0 l_gripper_r_finger_tip_bumper true 100.0 l_gripper_l_finger_link l_gripper_l_finger_pose_ground_truth 0.0 map true 100.0 l_gripper_l_finger_link l_gripper_l_finger_force_ground_truth l_gripper_l_finger_link true l_gripper_palm_link_geom 100.0 true 100.0 l_gripper_palm_bumper true true 0.01 0.0001 0 0 0.0001 0 0.0001 0 0 0 0.82025 0.188 0.790675 0 -0 0 0 0 0 0 -0 0 0.0 0.0 0.0 0 0 0 0 -0 0 0.0 0.0 0.0 unit_box PR2/White true false l_gripper_float_link l_gripper_palm_link l_gripper_float_link 1 0 0 -0.05 0.001 l_gripper_l_finger_tip_link l_gripper_float_link l_gripper_l_finger_tip_link 0 1 0 0 0 0 l_gripper_r_finger_tip_link l_gripper_float_link l_gripper_r_finger_tip_link 0 1 0 0 0 0 true 100.0 l_gripper_palm_link l_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map true 100.0 l_gripper_tool_frame l_gripper_tool_frame_pose_ground_truth 0 0 0 0 0 0 0.0 /map true 640 480 L8 90 0.1 100 25.0 true 25.0 l_forearm_cam/image_raw l_forearm_cam/camera_info l_forearm_cam_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 90 0.1 100 25.0 true 25.0 r_forearm_cam/image_raw r_forearm_cam/camera_info r_forearm_cam_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue ros-robot-model-1.11.8/collada_urdf/test/test_collada_urdf.cpp000066400000000000000000000062301257532150500244140ustar00rootroot00000000000000// Copyright (c) 2010, Willow Garage, Inc. // All rights reserved. // // Redistribution and use in source and binary forms, with or without // modification, are permitted provided that the following conditions are met: // // * Redistributions of source code must retain the above copyright // notice, this list of conditions and the following disclaimer. // * Redistributions in binary form must reproduce the above copyright // notice, this list of conditions and the following disclaimer in the // documentation and/or other materials provided with the distribution. // * Neither the name of Willow Garage, Inc. nor the names of its // contributors may be used to endorse or promote products derived from // this software without specific prior written permission. // // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER 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. /* Author: Tim Field */ #include "collada_urdf/collada_urdf.h" #include #include #include #include /* std::string readTestUrdfString() { std::ifstream file("test/pr2.urdf"); std::stringstream ss; ss << file.rdbuf(); return ss.str(); } TEST(collada_urdf, collada_from_urdf_file_works) { boost::shared_ptr dom; ASSERT_TRUE(collada_urdf::colladaFromUrdfFile("test/pr2.urdf", dom)); ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae")); } TEST(collada_urdf, collada_from_urdf_string_works) { std::string urdf_str = readTestUrdfString(); boost::shared_ptr dom; ASSERT_TRUE(collada_urdf::colladaFromUrdfString(urdf_str, dom)); ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae")); } TEST(collada_urdf, collada_from_urdf_xml_works) { TiXmlDocument urdf_xml; ASSERT_TRUE(urdf_xml.Parse(readTestUrdfString().c_str()) > 0); boost::shared_ptr dom; ASSERT_TRUE(collada_urdf::colladaFromUrdfXml(&urdf_xml, dom)); ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae")); } TEST(collada_urdf, collada_from_urdf_model_works) { urdf::Model robot_model; TiXmlDocument urdf_xml; ASSERT_TRUE(urdf_xml.Parse(readTestUrdfString().c_str()) > 0); ASSERT_TRUE(robot_model.initXml(&urdf_xml)); boost::shared_ptr dom; ASSERT_TRUE(collada_urdf::colladaFromUrdfModel(robot_model, dom)); ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae")); } */ int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ros-robot-model-1.11.8/joint_state_publisher/000077500000000000000000000000001257532150500212335ustar00rootroot00000000000000ros-robot-model-1.11.8/joint_state_publisher/CHANGELOG.rst000066400000000000000000000022621257532150500232560ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package joint_state_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.11.8 (2015-09-11) ------------------- 1.11.7 (2015-04-22) ------------------- * Added a randomize button for the joints. * Contributors: Aaron Blasdel 1.11.6 (2014-11-30) ------------------- * Added floating joints to joint types ignored by publisher * warn when joints have no limits * add queue_size for publisher * Contributors: Jihoon Lee, Michael Ferguson, Shaun Edwards 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * Update package.xml Updating author and maintainer email for consistency * Contributors: David Lu!! 1.11.3 (2014-06-24) ------------------- 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- * Use #!/usr/bin/env python for systems with multiple Python versions. * Contributors: Benjamin Chretien 1.10.18 (2013-12-04) -------------------- 1.10.16 (2013-11-18) -------------------- 1.10.15 (2013-08-17) -------------------- * joint_state_publisher: do not install script to global bin Also clean up no longer required setup.py ros-robot-model-1.11.8/joint_state_publisher/CMakeLists.txt000066400000000000000000000003431257532150500237730ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(joint_state_publisher) find_package(catkin REQUIRED) catkin_package() install(PROGRAMS joint_state_publisher/joint_state_publisher DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) ros-robot-model-1.11.8/joint_state_publisher/joint_state_publisher/000077500000000000000000000000001257532150500256335ustar00rootroot00000000000000ros-robot-model-1.11.8/joint_state_publisher/joint_state_publisher/joint_state_publisher000077500000000000000000000310621257532150500321630ustar00rootroot00000000000000#!/usr/bin/env python import rospy import random import wx import wx.lib.newevent import xml.dom.minidom from sensor_msgs.msg import JointState from math import pi from threading import Thread RANGE = 10000 def get_param(name, value=None): private = "~%s" % name if rospy.has_param(private): return rospy.get_param(private) elif rospy.has_param(name): return rospy.get_param(name) else: return value class JointStatePublisher(): def __init__(self): description = get_param('robot_description') robot = xml.dom.minidom.parseString(description).getElementsByTagName('robot')[0] self.free_joints = {} self.joint_list = [] # for maintaining the original order of the joints self.dependent_joints = get_param("dependent_joints", {}) use_mimic = get_param('use_mimic_tags', True) use_small = get_param('use_smallest_joint_limits', True) self.zeros = get_param("zeros") pub_def_positions = get_param("publish_default_positions", True) pub_def_vels = get_param("publish_default_velocities", False) pub_def_efforts = get_param("publish_default_efforts", False) # Find all non-fixed joints for child in robot.childNodes: if child.nodeType is child.TEXT_NODE: continue if child.localName == 'joint': jtype = child.getAttribute('type') if jtype == 'fixed' or jtype == 'floating': continue name = child.getAttribute('name') self.joint_list.append(name) if jtype == 'continuous': minval = -pi maxval = pi else: try: limit = child.getElementsByTagName('limit')[0] minval = float(limit.getAttribute('lower')) maxval = float(limit.getAttribute('upper')) except: rospy.logwarn("%s is not fixed, nor continuous, but limits are not specified!" % name) continue safety_tags = child.getElementsByTagName('safety_controller') if use_small and len(safety_tags)==1: tag = safety_tags[0] if tag.hasAttribute('soft_lower_limit'): minval = max(minval, float(tag.getAttribute('soft_lower_limit'))) if tag.hasAttribute('soft_upper_limit'): maxval = min(maxval, float(tag.getAttribute('soft_upper_limit'))) mimic_tags = child.getElementsByTagName('mimic') if use_mimic and len(mimic_tags)==1: tag = mimic_tags[0] entry = {'parent': tag.getAttribute('joint')} if tag.hasAttribute('multiplier'): entry['factor'] = float(tag.getAttribute('multiplier')) if tag.hasAttribute('offset'): entry['offset'] = float(tag.getAttribute('offset')) self.dependent_joints[name] = entry continue if name in self.dependent_joints: continue if self.zeros and name in self.zeros: zeroval = self.zeros[name] elif minval > 0 or maxval < 0: zeroval = (maxval + minval)/2 else: zeroval = 0 joint = {'min':minval, 'max':maxval, 'zero':zeroval} if pub_def_positions: joint['position'] = zeroval if pub_def_vels: joint['velocity'] = 0.0 if pub_def_efforts: joint['effort'] = 0.0 if jtype == 'continuous': joint['continuous'] = True self.free_joints[name] = joint use_gui = get_param("use_gui", False) if use_gui: self.app = wx.App() self.gui = JointStatePublisherGui("Joint State Publisher", self) self.gui.Show() else: self.gui = None source_list = get_param("source_list", []) self.sources = [] for source in source_list: self.sources.append(rospy.Subscriber(source, JointState, self.source_cb)) self.pub = rospy.Publisher('joint_states', JointState, queue_size=5) def source_cb(self, msg): for i in range(len(msg.name)): name = msg.name[i] if name not in self.free_joints: continue if msg.position: position = msg.position[i] else: position = None if msg.velocity: velocity = msg.velocity[i] else: velocity = None if msg.effort: effort = msg.effort[i] else: effort = None joint = self.free_joints[name] if position is not None: joint['position'] = position if velocity is not None: joint['velocity'] = velocity if effort is not None: joint['effort'] = effort if self.gui is not None: # post an event here instead of directly calling the update_sliders method, to switch to the wx thread wx.PostEvent(self.gui.GetEventHandler(), self.gui.UpdateSlidersEvent()) def loop(self): hz = get_param("rate", 10) # 10hz r = rospy.Rate(hz) delta = get_param("delta", 0.0) # Publish Joint States while not rospy.is_shutdown(): msg = JointState() msg.header.stamp = rospy.Time.now() if delta > 0: self.update(delta) # Initialize msg.position, msg.velocity, and msg.effort. has_position = len(self.dependent_joints.items()) > 0 has_velocity = False has_effort = False for (name,joint) in self.free_joints.items(): if not has_position and 'position' in joint: has_position = True if not has_velocity and 'velocity' in joint: has_velocity = True if not has_effort and 'effort' in joint: has_effort = True num_joints = (len(self.free_joints.items()) + len(self.dependent_joints.items())) if has_position: msg.position = num_joints * [0.0] if has_velocity: msg.velocity = num_joints * [0.0] if has_effort: msg.effort = num_joints * [0.0] for i, name in enumerate(self.joint_list): msg.name.append(str(name)) joint = None # Add Free Joint if name in self.free_joints: joint = self.free_joints[name] factor = 1 offset = 0 # Add Dependent Joint elif name in self.dependent_joints: param = self.dependent_joints[name] parent = param['parent'] joint = self.free_joints[parent] factor = param.get('factor', 1) offset = param.get('offset', 0) if has_position and 'position' in joint: msg.position[i] = joint['position'] * factor + offset if has_velocity and 'velocity' in joint: msg.velocity[i] = joint['velocity'] * factor if has_effort and 'effort' in joint: msg.effort[i] = joint['effort'] self.pub.publish(msg) r.sleep() def update(self, delta): for name, joint in self.free_joints.iteritems(): forward = joint.get('forward', True) if forward: joint['position'] += delta if joint['position'] > joint['max']: if joint.get('continuous', False): joint['position'] = joint['min'] else: joint['position'] = joint['max'] joint['forward'] = not forward else: joint['position'] -= delta if joint['position'] < joint['min']: joint['position'] = joint['min'] joint['forward'] = not forward class JointStatePublisherGui(wx.Frame): def __init__(self, title, jsp): wx.Frame.__init__(self, None, -1, title, (-1, -1)); self.jsp = jsp self.joint_map = {} panel = wx.Panel(self, wx.ID_ANY); box = wx.BoxSizer(wx.VERTICAL) font = wx.Font(9, wx.SWISS, wx.NORMAL, wx.BOLD) ### Sliders ### for name in self.jsp.joint_list: if name not in self.jsp.free_joints: continue joint = self.jsp.free_joints[name] if joint['min'] == joint['max']: continue row = wx.GridSizer(1,2) label = wx.StaticText(panel, -1, name) label.SetFont(font) row.Add(label, 1, wx.ALIGN_CENTER_VERTICAL) display = wx.TextCtrl (panel, value=str(0), style=wx.TE_READONLY | wx.ALIGN_RIGHT) row.Add(display, flag= wx.ALIGN_RIGHT| wx.ALIGN_CENTER_VERTICAL) box.Add(row, 1, wx.EXPAND) slider = wx.Slider(panel, -1, RANGE/2, 0, RANGE, style= wx.SL_AUTOTICKS | wx.SL_HORIZONTAL) slider.SetFont(font) box.Add(slider, 1, wx.EXPAND) self.joint_map[name] = {'slidervalue':0, 'display':display, 'slider':slider, 'joint':joint} self.UpdateSlidersEvent, self.EVT_UPDATESLIDERS = wx.lib.newevent.NewEvent() self.Bind(self.EVT_UPDATESLIDERS, self.updateSliders) ### Buttons ### self.randbutton = wx.Button(panel, 1, 'Randomize') self.ctrbutton = wx.Button(panel, 2, 'Center') self.Bind(wx.EVT_SLIDER, self.sliderUpdate) wx.EVT_BUTTON(self, 1, self.randomize_event) wx.EVT_BUTTON(self, 2, self.center_event) box.Add(self.randbutton, 0, wx.EXPAND) box.Add(self.ctrbutton, 1, wx.EXPAND) panel.SetSizer(box) self.center() box.Fit(self) self.update_values() def update_values(self): for (name,joint_info) in self.joint_map.items(): purevalue = joint_info['slidervalue'] joint = joint_info['joint'] value = self.sliderToValue(purevalue, joint) joint['position'] = value self.update_sliders() def updateSliders(self, event): self.update_sliders() def update_sliders(self): for (name,joint_info) in self.joint_map.items(): joint = joint_info['joint'] joint_info['slidervalue'] = self.valueToSlider(joint['position'], joint) joint_info['slider'].SetValue(joint_info['slidervalue']) joint_info['display'].SetValue("%.2f"%joint['position']) def center_event(self, event): self.center() def center(self): rospy.loginfo("Centering") for (name,joint_info) in self.joint_map.items(): joint = joint_info['joint'] joint_info['slidervalue'] = self.valueToSlider(joint['zero'], joint) self.update_values() def randomize_event(self, event): self.randomize() def randomize(self): rospy.loginfo("Randomizing") for (name,joint_info) in self.joint_map.items(): joint = joint_info['joint'] joint_info['slidervalue'] = self.valueToSlider(random.uniform(joint['min'], joint['max']), joint) self.update_values() def sliderUpdate(self, event): for (name,joint_info) in self.joint_map.items(): joint_info['slidervalue'] = joint_info['slider'].GetValue() self.update_values() def valueToSlider(self, value, joint): return (value - joint['min']) * float(RANGE) / (joint['max'] - joint['min']) def sliderToValue(self, slider, joint): pctvalue = slider / float(RANGE) return joint['min'] + (joint['max']-joint['min']) * pctvalue if __name__ == '__main__': try: rospy.init_node('joint_state_publisher') jsp = JointStatePublisher() if jsp.gui is None: jsp.loop() else: Thread(target=jsp.loop).start() jsp.app.MainLoop() except rospy.ROSInterruptException: pass ros-robot-model-1.11.8/joint_state_publisher/package.xml000066400000000000000000000013211257532150500233450ustar00rootroot00000000000000 joint_state_publisher 1.11.8 This package contains a tool for setting and publishing joint state values for a given URDF. David V. Lu!! David V. Lu!! BSD http://www.ros.org/wiki/joint_state_publisher catkin rospy wxpython sensor_msgs rospy wxpython sensor_msgs ros-robot-model-1.11.8/joint_state_publisher/screenshot.png000066400000000000000000000254761257532150500241340ustar00rootroot00000000000000‰PNG  IHDRÂé ÒsBITÛáOàtEXtSoftwaregnome-screenshotï¿> IDATxœíy|õýÿߟ™ÝÙl²ÉæØ\„„DȤ@E¥D©j¥ÕZ¤-¢ök±ÅÖVíiíï+ÕŠJûÃÖF-ÊU+ …€ ‹6!wÈ&›Í^s}ÿ2Ìε»1!›ÍçùÇ>f?ó¹çóú¼?Ÿ™ÏÌÅÁРσéC&ƒx$HeݺuF£ÑHQW:_L„Aûý4M¿øâ³ ‘ ŽzáÙGV?jЉq\¼xñbÇÅŽŽ¡Ì)˜Y66==%ÅVqæô‘#G¥ 8ØÐ Ï~ícíX*ŒŒÑÙ9uçjOœ8. ɆinnÂjÁ`”Ô«å8N8FP\\\4~BeÅ™!Ífxc0RRRRRRBÝÝÝ­­­4MGMlÇqúôiÐ4}ölM2Û‡_CÖüæ–Ûß°3a4¤Åé,‰ª¢ &¡”””ÂÂÂÑ£G[,‚ |>_SSÓ™3gZZZľy¸ÇƲ,l6Ã0=N§ü¼yÚsûÞ½+Ê8ýÎ^5Ÿãì•)ÄÉ3çš»éÄ8ROÊ8öÑíYw•ïƒ3ÚçRóAe”<°nõ=7OÏI €uœý|×ë¿|áݳÞЋzZÚ0,@;šZº¹|ìµj žž>}úô´´´öööS§N@NNNnnnBBÂþ󟆆†¨‰Íf³€aÔzP†åy¿£¥½—H4©µç¡ Kotuõøy26‘U1¼·³õ¢Ûh¥ˆÀÓTÞÊWv>7ÏÝgË+¦œÉ%+ï¸ê—9E›Ân¨AÒd0 ͪ†½$àYVzÌ0<z1G/EÛl¶òòòcÇŽñ<ååå“'Ož;wî”)SZ[[ÝnwÄ&@­#š+žaŒ¹K6ü­ì´Ýn·Ÿ?ùï7ž¸1Ñ4mž·¥®é¢óè&Yɸy[ÎÙíöý/¬ýõÖò:»ýìþ×ȧš(|ªlïcÀôm-]Í Ÿ®É•&É&ßòì3ó,í¥÷Ž™4÷ÆffŽóÔ¾ö^­nèi]òüÙÏýÕööóŸÿ´Ø@«G+ 'èN8¦YØÅ?ÙòÙ)»Ýn?ûß­¿º«0†½œ iÌ~ÊŒZ233322ìvûáÇýþËÅ///?}útjjê˜1c¢#6š¦Axp©eaDÁ ä›~÷ÁÿÞž]åÛþÑ2îöE7}s¡iaÉOj„ƺN·_8ιgUÓßK·RߺcÒ‚g_X´uQiÛÞÞ:gͲÉ1Ðúñ–õ®ú}çnL_ßo-^6‹€/žÛð~kŽ‹3zjN:EXçë¦bZY<@Þ·~d=±gûŽ®ª6rÞo?øß¥šÑH, ð‰7þfÛÆåIü¹/ÿ¹åêoçî_¿ŸÜ9ëmVs«Ãí#MäH¾eff †³gÏÒŠ9pMMMaa¡0æ‚Ø.MúÕΈ},a»~õmIͯ޾à±Ãž”­oW¾³$ûÞG&ÿlh…xŽŽ{ÞÿÖÒï|Ä|Ípý'«R feÁ›‡wüöWù·-›œï+ù‰ïÿ»—@‘úÒà…¤lɸëÏ:8’äÙË£"-Hº¡¥•$Ìì˜ÏµàÍ–4dܵçöP‹(eÞêeIu/~ç‡/eSÏO8òòìß_`ûç;L`ÌÒ` ¹‘$’$yž÷z½ÊVäõz†!IR½ ·ØÀ`0„À*' _Ã5$æØ\(·{¸žšãM°¤ nô¨¦½¯Uq´Ÿæ.”×öò@ºn0Ä€öy‘_2ÖaYÌw.^hóP±Ùc‰O¼½Sq£õÓ --ZÈØ¹=[`‰Ä1©!ˆøÑ©òß[û¸˜¹Ìñ6ä—ÅÌñÀùÙþßýŽ´´´äçç§¥¥8qBvÊf³@{{»zn±€Åb1€ÉdR9IQä¥#ÆÑÐÎÃ84zjŽù6¹`ê(è½ÐÔË›úæÔ„Áh$x–CÊd$.u³ˆ0R&á"FJ<%à?õÏÏ} 晦®æ¶=kw5Ó`L4-îìÑÞÆÝtCK‹\ÊD""X´Òâç¼ÐÎÃ8táÍïþ`[‹Ð‹ ’m¬ôׯzÍGÕÕÕS¦LÉÏÏohh¨««ݳ²²&NœèñxªªªÔØp‹MÀ111*gb¨¾À],ûóŽî¯-É\ýÁ‡YÿîÌ_¼ÀÐøÖˇ]äü¾V…Œ&±…F“éòí-‚Š1x[;yê†_nzõhCù¦_ÿ£Ö9¡®žþÙg{^˜—~ïß*¾qöXMwLÖ„ Y?˜¸ðýÞÑ=K7ÝÒjÈE@Ï ÑJ‹Ãwíÿóö®¯Ý6úþuÒ;ÎôÄŽš0óú Õk®;ÔIÉb0 süøñ9sæ”””$''···sg³ÙŠ‹‹-Kyy¹ÛíVo`Ã-6`YVÛÂÄPFÀs)ÑbD<Ý iQ>‰ç>»^qG÷:N——æ€ ©˜XkR¢y•1@BñññcÇŽÚRwwwmmmWW—ðè#jbëììD6›-333Ð=núOÿòâŠÂDhÿëÂI–Ççf˜G䀃‘ÐÜܬ:‡‰µ-H„ÞóûÞzî±§Ëzr³bcHÕ0˜‘…ª`èCkçN® Š Sf?²~ýú­ì•ãè¯ÿpýúõëׯt^z”[ù¨!R- ßSþâ² £FeeæÍûŸZÕ>zÅu~üQM{¥ž¦éƒµ7ŒK±X,–”ñ·ÿê@g€ 6$£>þë¦×6pºGÛt„â'¨Ì)ãã„Cë¤I©X1µ0žòŸßõ{ÓóÇ.T—ÎÞñࣻ.Êozó޽?yºaþ«ø²lÒœ§¶ŸírõtzÜ÷›»žþ¯ô;eÊbê Éx£­xÞ-%Wç&QÀ{:j¶ç@u#õã{÷ºy¨û‹öÔ©“²â¸îê½ïm?ÚÊ¦Ýø½oÏJCþO¬èÜ÷Ú¦jz7eM+0Ð]drb|ñ”ô²æÆ‘õ‰aIdZ_Íû;< Þ¸9D0uÕª´¹[Ž»–ÜÙßõÙ†7­Þ¼êÝë/mfȸ~E†p”wóâÜ'··ùbûü‡1éG±ù‹î_2#7‰m®­ñÄMËÄ{9 "ÓÂø[«I…i€1µ ÍWowJÚß½ï™'kzieŽQ–wÙørË]› q 6‡‘¸Ç^uíø€ž£ï¾µuû{[¶Vù&ÏÈRI ü•ÛÞÙ¹{×œhäzjî¯è¦éÈž?Ü}°®Wí02çNGxβ×ß¹¿Ü·àw¶—öüaAjà«’Án+_†÷tõòŒâ3­†/]Œ11Ãt·ËÇ©¼}©¶žˆŽzeì5c Æßõ¸¸þÀxÕ5¹±g+T-&Rˆ˜!U°ö“úµ}ÿ<·/2ݾqOë×n=öÆ­s~5ÅÀ:Nìùœžñõéë9×€óÃEy?]\~à{9$Ðõo¯ºéYãsŸ¾ºl”B ¡É8wÝáJ/@üô;ï]¶äŽ•K )€ž“G/„:!ç|N7@޹áÖÅ o¼:Y©L?nZ6€ž¦ó—hîCî5yqÒa4ˆ ˆyú3o¯u?593cì7?_üæŸÛ€¿vóê‡ÿT©þ…Kwù ý½îü¶G&ÙFÝúN«dÖº…¾·f×–½ ®»:§h"€¯³öЧ»Ëêý|ˆ3 Þ][öyÃÒÙÙi…“ÓhSåká´QÐsôý¿í¹¤CjÌâÕ÷NŽÍž6.þôNlc"—ˆ±02uæ“Ûªž p3O©®1À%aᮋ …ÃØY¯´ð¯hE§,&²ÙlâzÌÔœëV>¶4Z>zyó1Ü^10 ÓÜÜ\ZZš——7Ôy\fΜYXXh·Û…¿*¹¹$zšÝX-="Õ 0A\–L´ñ=öÏwlðMM+¿#'À©þ½ß¿Uíè„0W„à 4Aæ0Ï?ÿü`¥ì?¿cÓëÛþñ¾.¿¦wL„C’d¸[ ;hš&Iù=á+µt‹÷w··]¡´0ƒ Bˆ¢¨²²²ÜÜ\£QíQöð‡¦éÒÒÒ˜˜aód‘ÀI?þ&„÷øN§ßïâwú)вÙlǵ´´Žxq0&lB$I¦§§G÷ÔŸã8š¦e ÓX–•µ¤B4÷Ì€ƒƒÁ„ X0LàI¿ý» Äqøc:Q Œ&Ç™L¦¤¤$á¯t•„p,}!;¯×;BVŽŒ@°`4aYÖjµ:žçHˆ¿!«Õêr¹¢õù7F]0Çáq…ðœA¬„ ŽãD #8 ÇB@la¢‚ H’”-eP ˲4a:›XìF”êËÇ#„âÖ2é_Õ˜(),˶µá…sÃa]LZZEQ>_ÀŠzÁð<__ì/š_4e&AŒÜ1óÛOÄcA‚yÀ9Œhd.d‹ÅrEóŠPxžg¦½½=77WvJ]nD›xÍþÞÇŽÜêÍcYŸÏçñx ;2׌DÂÞn·[yJý¶iøÊñÓ#úÂ+Û=Ò h@Ìð‚çyš¦e{ ¨X‚ ÜU¼%ØŽä9 ˲âXK†RâÔ_œý³,®]ÂDÂ&==]ù’œŠ`H’4`[sEò¹T3 Hn%‹ˆw™eRa¦¨¨hHòŒ@X–•ÍøAkÒ¯ô7v &Bø…>ÙHÿKMp»YØ^Xuø‹‰ðZ2ML&“ÝnŸºˆj~Åéhã¸úúzŠÂßSZFî]ã ¤¤¤´¶¶vvv†þ.BÈl6gdd jÆ0CŒ&ƒ!++k¨s‰,ð ƒ , & °`0˜0À‚Á`ÂOú1ýAxÜ­_ñH±`0a#<Únhhp¹\Ѫ„ÅbÉËË“­(ÂÁ„ Çq÷ÜsÏòåË †èlB ÃìܹsË–-⇔¢³´˜A…çy—˵|ùòüüü¡ÎË ²fÍš7Ê>„‚'ý˜þ ¼12Ô¹\ŒFcèÛŽc0zŒÛÖ”÷ºy¨cï+¯rh|#?˜h'º¿Û/dË>à¼MíñD{ÎÞR¡ø2eöCß—ÌÔ”¾ôn­ÆVcƬ…>05¶ï/ïëºpæ?{>ù¢Õw^¢ˆHµ0|Où¸ïw‡ºySþý¯”>ÿõtùbÀu~üðÄ[ÞÈø“ýÈ÷rH¦éƒ'î}bË‘˜²ozrÓ›?š›|Y$Á†dtÃÇÝôÚæN÷h›ŽPü„‰¯±âÔ©ª&¯)1{ê¥צ(ʈ‰4"ÔÂxÊ~×ïMÏo¸P]:{ǃîº(ïzyÇÞŸ<Ý0е/ÿDÒœ§¶ŸírõtzÜ÷›»žþ¯ôM¦`&`¸ÅmÅón)¹:7‰ÞÓQ{ü³=ª»©÷Ø»×­ÈCÝ_°§N”ÇuWï}oûÑV6íÆï}{Vòï|b=@ç¾×6èÐzÕ½ýÈîg<æ +×Þž –”84½b"ƒÈ´0¾š÷wx¼qs:‰`êªUis·w-¹)þ²¾ë³ ?nZ½yÕ»×?+¸2®_!¼aÈ»yqî“ÛÛüâ 'ŒI?ŠÍ_tÿ’¹Ils婚Ê6nö+çgSjõd2=¥³²¢•%­7/,ŽG¼»áä™V ÷ÜÉãÇË¿lôèØ£Ô n]²tÅ-Ùà8ùEÛÈýRͰ!2-Œ¿µÊ‘T˜FS Ò|õv§¤ÝñÝûžy²ö¡—Væ¨|—”wÙørË]› q fa$>c¯ºv| @ÏÑwßÚs‰©X¶fEaÂäYŸîRÉgå¶wvÖ2YĘû§Æ%g'××ÜŸ:aBz2ÓtdχZs˜>LYã'^zñÄÓãañ&ò‰L  ÓvxçÁŸ­;ý@éïr ž ùIoõ¦•wþë¦ÍŸ.M—J$t ƒÌ‰qzš»žv´¸Àh7©„p6;|Üu´ƒœ°þ˜³ÇÑÙÙÙißúäkþX~à§“L@׿½ê¦gÏ}üê²QŠŽ:ô!ç®;\éÍ?ýÎ{-g{“ ó)€ž“G/Ð0&¤¼s>§›‡rÌ ·..p4Þw¢Só>tꌷŽãc3 sß^¯í!D¦…óôgÞ^{ÿ}“3áÍE¼YºØ†üµ›W?ìÜRýæÜ8ewù ý½®-ö‘I¶GÀrýëÇ·}S–{p)ï­ÙµeGï‚ë®Î)šàë¬=ôéî²z?¯ò5@ÕðîڲϖÎÎN+œœF›*œèÔôÛ7‡á=µ_”}t¼?t"Ó ëÌ'·U=àfžþR]c€KÂÂ] ‡±³^iá_ÑŠNYLd³ÙÄõ˜©9×­|li´|ôòæcN<÷ƨÃ0Lsssiii^^ÞPçep™9sfaa¡ÝnþVTT¨äæ’lèihvcµ`ôˆT 3À™Ã”L´ñ=öÏwlðI„©`åãwä8Õ¿÷û·ªñ6‡':‡h‚ÌažþùÁJÙ~Ǧ×MÒÔy_WÇ3˜È…$I出£ š¦IR¾LëJ=ñàýÝíxS®(Aø¸}YYYnnn´îæIÓtiiiLLŒló’ÀIjêPä 3ÌÞãw:~¿?Šßé§(Êf³q×ÒÒ"8VTTàg꘰A‘$™žžÝSŽãhš–Y,L`Yvdn´Í=3à`Á`0a€ƒÁ„ xÒµôïÇᕯz`ÁD'Ç™L¦¤¤$á¯t‰‡¸´è";¯×;B–½ô,˜è„eY«Õêp8ÄMÒ¥¿‚NÄ_„Õju¹\Ñúð~@P ÇqØ4k„‡$âEöC÷F‡>…ˆjb #@I’²¥ *‚aY–&Lg‹ÝˆR}ùù·–IÿªÀD‘HaY¶­m¤¯úÖŤ¥¥Qåó¬¨W ÏóµñÅþ¢ùESf³ K˜ß~" ªÌ ÎaD#s9 ÃX,–+š×ȃçy†aÚÛÛssse§ÔõàFÔ¸‰×ìoá},þFذdËú|>ÇV¨ØØØ‘¹àE†°7ÛíVžR¿ó¾ò£Gü4®»áвÝ# ‚ðˆT Ã÷”¿¸l¨QY™yóþç£V6„³zA‚Yºáã¿n ’¥Pü„Š!yÚòU_K€·³ù¢—LHË»fZæ/;˜è¼Y5D¨…ñ”ÿü®ß›~{¼á¶Øò§¯½íÑ9§Þ]’‚tÏzõ‚Ù6p¸ÅmÅón)¹:7‰ÞÓQ{ü³=ª»©÷Ø»×­ÈCÝ_°§N”ÇuWï}oûÑV6íÆï}{Vòï|b=@ç¾×6èéY Ü4–è=ýÁ_véf€ŒËEá½/#žÈ´0¾š÷wx¼qs:‰`êªUis·w-¹)^ïlI^0&ý(6ÑýKfä&±Í•§j:(Û¸Ùw¬œŸM©Õ“uÊô”ÎÊŠV–´ܼ°8ñgãÖ{îäñãå_6z”ÓSæÄ´ø¬¢ûÒímipÐØ¼D:‘iaü­UޤÂ4 À˜Zæ«·;9ý³úA‚Ía$î±W];> çè»omÝþÞ–­U~€„É3²Ô¾"ê¯ÜöÎÎÝ»vŸì€äìD#×SspE70MGö|øáîƒu½  £%–º»Óƒ2̈L  ßTÏê Ý sb€žæ.€§-.0ZãM*!œÍí¥€4†Ø÷ð´ËÍ€1!)&2k£Id †J/JrTµùèöê6*gL¡V?Hè‚á=]½<ÄgZ Ș˜aºÛåS»“¬¶žˆŽz|ͧÈ,¹¾0áÒ~èD\zV¢1/FJdÉLù·/2íÞ¸§•å{޽ñF뜕S,¬ã滎v°ªgÕƒôlÒÎ]w¸Ò›=>~ú÷ZÎö&æS='^ aLHyç|N7)ä˜n]\àh8¼ïD§ü>4ïªühï¤U·äÅMZ¶&¿³©ÃcHHKKhßñÇ¿vánF6‘iaÀ<ý™·×ÞßäÌGxsÑo–.¶!íæÕ;·T¿9Wí¬j>‚ÝV–À÷ÖìÚ²£wÁuWçMðuÖútwY½ŸWù jxwmÙç Kgg§NN£M•Nt*=1GßÙä¸öúÙS ²“GÎÝQW~¬Ù‡§4‘NdZdù䶪'ÜÌÓ_ªkUΪéCYLd³ÙÄõ˜©9×­|li´|ôòæcNÜj1ê0 ÓÜÜ\ZZš——7Ôy\fΜYXXh·Û…¿*¹¹$zšÝX-="Õ 0Aæ0%m|ýó[ô—½ôSÁÊÇïÈ pªï÷oUã/lO"t3ЙÃ<ÿü󃕲ÿüŽM¯›¤©ó¾.üDØB’¤òCÝQMÓ$IʯÔ:GÞßÝ>Ò÷µŠ„Û—••åææF놘4M—––ÆÄÄÈöÿœô§¦EÞ0à á=~§Óé÷û£ø~Š¢l6Çq---‚cEE^I „I’éééÑ=õç8ަi™…Á‚Áô–eGæ^eÑÜC`0 X0L`Á`0a€'ýCIÿî2qþXÏ3dpg2™’’’„¿ÒUâFÇ¢‹xìp8¼^ïY™`Á ,ËZ­V‡Ã!nÑ ÅIDAT.ýt"þ"„¬V«ËåŠÖç둺`8ŽÃv°žcˆõ,ìú-î} Õ" Äæ @I’²¥ *‚aY–&Lg‹ÝˆR}ù3 ·–IÿªÀD‘HaY¶­ /ÌD„u1iiiEù|+êUÃó|m|±¿h~Ñ”™ÇlƒóÛOÄcA‚yÀ9Œhd.d‹Å˜Aƒçy†aÚÛÛssse§ÔõàFÔ¸‰×ìoá},~¹~°˜Ç²>ŸÏãñ„*66vd®I¹’{¸Ýnå)õÛšqà+?zÄOã 3ˆ(Û=Ò h@ÌÀÂóuÕ"üŠÒÑÇqõõõ¥¿åfÁw‡Œ”””ÖÖÖÎÎÎÐßòE™Í挌ŒAÍF,˜!Ã`0dee u.0á‡dL`Á`0a€ƒÁ„ X0LÜ%-G÷×Ù0˜Ð.K]#< £(*11Qê..ÖTÄuìÒ…!²Ôe9‘ú¿by“>}—fRæ"+ æSµÞ ð4åKiZå<”õ U]ú/8 RÞd¨««Kù6¸ÜÂð:Öâ‡Øñw>8ÝQÓ›`±&pg?ÞvðŒ)™3*Î:ÿ›÷¸]µŸì8âÉS µj¦óœ3Öbp–ïú¸Ö­ßpúQ­° [áZPu ÅåÊ3ðC²H£F Ä+ªV×!*93ÖyªÍÐõÖÉß(¡¿ýz›7žwï™öÿ¿¿ƒç *Ž9Sú~ƒß”·è¹'Þ>Q·ï@㸠‡J?8ïÂ:õ›¡ØSÿxÏîSÝB†2ëÇÙáÞ‚ É€ã¸~|]£ "ýÏÓ^Çs¹òQÜØ‚ÌøØY·®˜ EðmŸÇÃùÏ…3ç»Ü~ð¶6ºc¬„ßãáüÏú=_/Ô—u7þrɀĠÆf$ ÛóÞŽ ô˜c=©‰AL˾ҿžê•¸!#ÇõMé€G W+Ëp]á¸A7PÎaÔ—Æ _PZîJÊSᢟ¶õÈÚ¯Z´pJ†™$Â7jòìÉ–Ö3Óæ^›KAšm£RbH‚@@ß7c„A –A&“‘$äkÔ z–¾zIƒV‚~N† ! É®TfÔA÷OB¿ &»ºÒࢣ2­[C_ ¾ûØ»oñ7-¸óû bx–õ;Îù¸¶£ñ½íñ·.ùî÷ –C¼«f÷»»êß±ö7©Š]üðêyŽ3Ûþ^¦j`[§jU(¯Žèˆ4nëäJy5C¹ov%QÊÙl¶ñãÇ ’’’::: /^¼8PIÊŠýUZÿWW‘2NY$ªñ ŠŠ"‰~”½4¾º6tâp¥¤¤TUUÙl6‡Ã!¸TTT¨X˜°’DЧª V*-“­%$Õ¦)sÿ"µu–áªHì&¥Žªz¤§ÂJ"ÅnÈN ˆÝÕ¡ê%VV¾êÕÉ­¬,Ê‘…Vq´ ü¶²ÖÂ~U«62©»ª–ô…’­R•U¦u”q”Š´¤¢ú^ª– ¼òhå$h§Ösª ÚЪpË*þEÏõe¹UU…NrHm¤290žÃè—YÚ»+ýHˬšuUý(õ û+’V$:ÁeSЋª•²³I¥UQЄÂE+rA‹xV=¨z–]ep-aÈ:\}yk5Îi¬1Ó¥,`I¿¸µ¥~>d…ÑIU«œZ‘ëÑ/¤NBª¢•ÖV*úEÓ?ÁT$ó:yø*Úк ªµ¤ÕÊûÝ—õCZ éOâ ¢Üì5ø“~YuËÊ´úóÿúABQ ða|­nF+óbyUG†!ªHËÆÊ®ÍW±6A§AKªÚ¸e§T;~Mj5AeZ:¥ÅõR^n­NA)?-ÿ²+Ž£² Fð¡U˜ -iXe)]Äøõ‡þúÕ':ê\Hå8JÚGª^xU¹ÊtzS­*ˆ²øÊø•î:Õ¢štÐÞWßQ™„Ðɲ$+¾ðDÕøUëPµzõ[Žjý(ýk5Z¡=Ë"”¿@&ìÁ Õ†Ö•VMUdz2B­Q“ªg­ÈU{Y"ó,Ó˜¬,ÒU¡j5MeëTúGj°~ݪÆŠv£ìMtš‚N¡”}‡²–Ä’j)GµV•ñèTW(ÙF › ¹ÒxjyF}/ð= 1.3.0 * Contributors: William Woodall 1.11.5 (2014-07-24) ------------------- * Update KDL SegmentMap interface to optionally use shared pointers The KDL Tree API optionally uses shared pointers on platforms where the STL containers don't support incomplete types. * Contributors: Brian Jensen 1.11.4 (2014-07-07) ------------------- 1.11.3 (2014-06-24) ------------------- * kdl_parser: Adding kdl library explicitly so that dependees can find it * Contributors: Jonathan Bohren 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- * fix test at kdl_parser * Contributors: YoheiKakiuchi 1.10.18 (2013-12-04) -------------------- * add DEPENDS for kdl_parser * Contributors: Ioan Sucan 1.10.16 (2013-11-18) -------------------- * check for CATKIN_ENABLE_TESTING 1.10.15 (2013-08-17) -------------------- * fix `#30 `_ ros-robot-model-1.11.8/kdl_parser/CMakeLists.txt000066400000000000000000000027771257532150500215360ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(kdl_parser) find_package(Boost REQUIRED) include_directories(${Boost_INCLUDE_DIR}) find_package(catkin REQUIRED COMPONENTS roscpp rosconsole urdf cmake_modules ) find_package(orocos_kdl REQUIRED) find_package(TinyXML REQUIRED) include_directories(include ${orocos_kdl_INCLUDE_DIRS} ${TinyXML_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS}) link_directories(${catkin_LIBRARY_DIRS}) link_directories(${orocos_kdl_LIBRARY_DIRS}) link_directories(${Boost_LIBRARY_DIRS}) find_library(KDL_LIBRARY REQUIRED NAMES orocos-kdl HINTS ${orocos_kdl_LIBRARY_DIRS}) catkin_package( LIBRARIES ${PROJECT_NAME} ${KDL_LIBRARY} INCLUDE_DIRS include CATKIN_DEPENDS roscpp rosconsole urdf DEPENDS orocos_kdl TinyXML ) add_library(${PROJECT_NAME} src/kdl_parser.cpp) target_link_libraries(${PROJECT_NAME} ${TinyXML_LIBRARIES} ${orocos_kdl_LIBRARIES} ${catkin_LIBRARIES} ) add_executable(check_kdl_parser src/check_kdl_parser.cpp ) target_link_libraries(check_kdl_parser ${PROJECT_NAME}) if(CATKIN_ENABLE_TESTING) find_package(catkin REQUIRED COMPONENTS rostest) add_rostest_gtest(test_kdl_parser test/test_kdl_parser.launch test/test_kdl_parser.cpp ) target_link_libraries(test_kdl_parser ${PROJECT_NAME}) endif() # How does CATKIN do this? #rosbuild_add_rostest(${PROJECT_SOURCE_DIR}/test/test_kdl_parser.launch) install(TARGETS ${PROJECT_NAME} DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) ros-robot-model-1.11.8/kdl_parser/include/000077500000000000000000000000001257532150500204045ustar00rootroot00000000000000ros-robot-model-1.11.8/kdl_parser/include/kdl_parser/000077500000000000000000000000001257532150500225325ustar00rootroot00000000000000ros-robot-model-1.11.8/kdl_parser/include/kdl_parser/kdl_parser.hpp000066400000000000000000000064151257532150500253770ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #ifndef KDL_PARSER_H #define KDL_PARSER_H #include #include #include #include namespace kdl_parser{ /** Constructs a KDL tree from a file, given the file name * \param file The filename from where to read the xml * \param tree The resulting KDL Tree * returns true on success, false on failure */ bool treeFromFile(const std::string& file, KDL::Tree& tree); /** Constructs a KDL tree from the parameter server, given the parameter name * \param param the name of the parameter on the parameter server * \param tree The resulting KDL Tree * returns true on success, false on failure */ bool treeFromParam(const std::string& param, KDL::Tree& tree); /** Constructs a KDL tree from a string containing xml * \param xml A string containting the xml description of the robot * \param tree The resulting KDL Tree * returns true on success, false on failure */ bool treeFromString(const std::string& xml, KDL::Tree& tree); /** Constructs a KDL tree from a TiXmlDocument * \param xml_doc The TiXmlDocument containting the xml description of the robot * \param tree The resulting KDL Tree * returns true on success, false on failure */ bool treeFromXml(TiXmlDocument *xml_doc, KDL::Tree& tree); /** Constructs a KDL tree from a URDF robot model * \param robot_model The URDF robot model * \param tree The resulting KDL Tree * returns true on success, false on failure */ bool treeFromUrdfModel(const urdf::ModelInterface& robot_model, KDL::Tree& tree); } #endif ros-robot-model-1.11.8/kdl_parser/package.xml000066400000000000000000000022651257532150500211030ustar00rootroot00000000000000 kdl_parser 1.11.8 The Kinematics and Dynamics Library (KDL) defines a tree structure to represent the kinematic and dynamic parameters of a robot mechanism. kdl_parser provides tools to construct a KDL tree from an XML robot representation in URDF. Wim Meeussen Ioan Sucan BSD http://ros.org/wiki/kdl_parser https://github.com/ros/robot_model https://github.com/ros/robot_model/issues catkin orocos_kdl rosconsole roscpp urdf cmake_modules rostest orocos_kdl rosconsole roscpp urdf ros-robot-model-1.11.8/kdl_parser/src/000077500000000000000000000000001257532150500175505ustar00rootroot00000000000000ros-robot-model-1.11.8/kdl_parser/src/check_kdl_parser.cpp000066400000000000000000000061271257532150500235450ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #include "kdl_parser/kdl_parser.hpp" #include #include #include #include using namespace KDL; using namespace std; using namespace urdf; void printLink(const SegmentMap::const_iterator& link, const std::string& prefix) { cout << prefix << "- Segment " << GetTreeElementSegment(link->second).getName() << " has " << GetTreeElementChildren(link->second).size() << " children" << endl; for (unsigned int i=0; i < GetTreeElementChildren(link->second).size(); i++) printLink(GetTreeElementChildren(link->second)[i], prefix + " "); } int main(int argc, char** argv) { if (argc < 2){ std::cerr << "Expect xml file to parse" << std::endl; return -1; } Model robot_model; if (!robot_model.initFile(argv[1])) {cerr << "Could not generate robot model" << endl; return false;} Tree my_tree; if (!kdl_parser::treeFromUrdfModel(robot_model, my_tree)) {cerr << "Could not extract kdl tree" << endl; return false;} // walk through tree cout << " ======================================" << endl; cout << " Tree has " << my_tree.getNrOfSegments() << " link(s) and a root link" << endl; cout << " ======================================" << endl; SegmentMap::const_iterator root = my_tree.getRootSegment(); printLink(root, ""); } ros-robot-model-1.11.8/kdl_parser/src/kdl_parser.cpp000066400000000000000000000133401257532150500224030ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #include "kdl_parser/kdl_parser.hpp" #include #include #include using namespace std; using namespace KDL; namespace kdl_parser{ // construct vector Vector toKdl(urdf::Vector3 v) { return Vector(v.x, v.y, v.z); } // construct rotation Rotation toKdl(urdf::Rotation r) { return Rotation::Quaternion(r.x, r.y, r.z, r.w); } // construct pose Frame toKdl(urdf::Pose p) { return Frame(toKdl(p.rotation), toKdl(p.position)); } // construct joint Joint toKdl(boost::shared_ptr jnt) { Frame F_parent_jnt = toKdl(jnt->parent_to_joint_origin_transform); switch (jnt->type){ case urdf::Joint::FIXED:{ return Joint(jnt->name, Joint::None); } case urdf::Joint::REVOLUTE:{ Vector axis = toKdl(jnt->axis); return Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, Joint::RotAxis); } case urdf::Joint::CONTINUOUS:{ Vector axis = toKdl(jnt->axis); return Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, Joint::RotAxis); } case urdf::Joint::PRISMATIC:{ Vector axis = toKdl(jnt->axis); return Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, Joint::TransAxis); } default:{ ROS_WARN("Converting unknown joint type of joint '%s' into a fixed joint", jnt->name.c_str()); return Joint(jnt->name, Joint::None); } } return Joint(); } // construct inertia RigidBodyInertia toKdl(boost::shared_ptr i) { Frame origin = toKdl(i->origin); // kdl specifies the inertia in the reference frame of the link, the urdf specifies the inertia in the inertia reference frame return origin.M * RigidBodyInertia(i->mass, origin.p, RotationalInertia(i->ixx, i->iyy, i->izz, i->ixy, i->ixz, i->iyz)); } // recursive function to walk through tree bool addChildrenToTree(boost::shared_ptr root, Tree& tree) { std::vector > children = root->child_links; ROS_DEBUG("Link %s had %i children", root->name.c_str(), (int)children.size()); // constructs the optional inertia RigidBodyInertia inert(0); if (root->inertial) inert = toKdl(root->inertial); // constructs the kdl joint Joint jnt = toKdl(root->parent_joint); // construct the kdl segment Segment sgm(root->name, jnt, toKdl(root->parent_joint->parent_to_joint_origin_transform), inert); // add segment to tree tree.addSegment(sgm, root->parent_joint->parent_link_name); // recurslively add all children for (size_t i=0; iname); // warn if root link has inertia. KDL does not support this if (robot_model.getRoot()->inertial) ROS_WARN("The root link %s has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF.", robot_model.getRoot()->name.c_str()); // add all children for (size_t i=0; ichild_links.size(); i++) if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree)) return false; return true; } } ros-robot-model-1.11.8/kdl_parser/test/000077500000000000000000000000001257532150500177405ustar00rootroot00000000000000ros-robot-model-1.11.8/kdl_parser/test/pr2_desc.xml000066400000000000000000004176051257532150500222000ustar00rootroot00000000000000 true 1000.0 true 1.0 5 power_state 10.0 87.78 -474 525 15.52 16.41 640 640 1 0.0 0.0 0.0 false -129.998394137 129.998394137 0.05 10.0 0.01 20 0.005 true 20 base_scan base_laser_link -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 true base_link_geom 100.0 true 100.0 base_bumper true 100.0 base_link base_pose_ground_truth 0.01 map 25.7 25.7 0 0 0 0 base_footprint torso_lift_link_geom 100.0 true 100.0 torso_lift_bumper -52143.33 true 100.0 imu_link torso_lift_imu/data 2.89e-08 0 0 0 0 0 0 6.0 6.0 R8G8B8 2448 2050 45 0.1 100 20.0 true 20.0 /prosilica/image_raw /prosilica/camera_info /prosilica/request_image high_def_frame 1224.5 1224.5 1025.5 2955 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 640 480 BAYER_BGGR8 90 0.1 100 25.0 true 25.0 wide_stereo/left/image_raw wide_stereo/left/camera_info wide_stereo_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 BAYER_BGGR8 90 0.1 100 25.0 true 25.0 wide_stereo/right/image_raw wide_stereo/right/camera_info wide_stereo_optical_frame 0.09 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 45 0.1 100 25.0 true 25.0 narrow_stereo/left/image_raw narrow_stereo/left/camera_info narrow_stereo_optical_frame 0 320.5 320.5 240.5 772.55 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 45 0.1 100 25.0 true 25.0 narrow_stereo/right/image_raw narrow_stereo/right/camera_info narrow_stereo_optical_frame 0.09 320.5 320.5 240.5 772.55 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 640 1 0.0 0.0 0.0 false -79.9999999086 79.9999999086 0.05 10.0 0.01 40 0.005 true 40 tilt_scan laser_tilt_link -6.05 true 32.6525111499 r_shoulder_pan_link_geom 100.0 true 100.0 r_shoulder_pan_bumper true r_shoulder_lift_link_geom 100.0 true 100.0 r_r_shoulder_lift_bumper true 63.1552452977 61.8948225713 r_upper_arm_link_geom 100.0 true 100.0 r_upper_arm_bumper true true -90.5142857143 -1.0 r_elbow_flex_link_geom 100.0 true 100.0 r_elbow_flex_bumper true -36.167452007 true r_forearm_link_geom 100.0 true 100.0 r_forearm_bumper true r_wrist_flex_link_geom 100.0 true 100.0 r_wrist_flex_bumper true r_wrist_roll_link_geom 100.0 true 100.0 r_wrist_roll_bumper true r_gripper_l_finger_link_geom 100.0 true 100.0 r_gripper_l_finger_bumper true r_gripper_r_finger_link_geom 100.0 true 100.0 r_gripper_r_finger_bumper true false r_gripper_l_finger_tip_link_geom 100.0 true 100.0 r_gripper_l_finger_tip_bumper true false r_gripper_r_finger_tip_link_geom 100.0 true 100.0 r_gripper_r_finger_tip_bumper true 100.0 r_gripper_l_finger_link r_gripper_l_finger_pose_ground_truth 0.0 base_link true 100.0 r_gripper_l_finger_link r_gripper_l_finger_force_ground_truth r_gripper_l_finger_link r_gripper_r_parallel_link r_gripper_r_finger_tip_link r_gripper_r_finger_tip_link 0 0 1 -0.018 -0.021 0 r_gripper_l_parallel_link r_gripper_l_finger_tip_link r_gripper_l_finger_tip_link 0 0 1 -0.018 0.021 0 r_gripper_l_finger_tip_link r_gripper_r_finger_tip_link r_gripper_r_finger_tip_link 0 1 0 true true true r_gripper_palm_link_geom 100.0 true 100.0 r_gripper_palm_bumper true 100.0 r_gripper_palm_link r_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map true 32.6525111499 l_shoulder_pan_link_geom 100.0 true 100.0 l_shoulder_pan_bumper true l_shoulder_lift_link_geom 100.0 true 100.0 l_r_shoulder_lift_bumper true 63.1552452977 61.8948225713 l_upper_arm_link_geom 100.0 true 100.0 l_upper_arm_bumper true true -90.5142857143 -1.0 l_elbow_flex_link_geom 100.0 true 100.0 l_elbow_flex_bumper true -36.167452007 true l_forearm_link_geom 100.0 true 100.0 l_forearm_bumper true l_wrist_flex_link_geom 100.0 true 100.0 l_wrist_flex_bumper true l_wrist_roll_link_geom 100.0 true 100.0 l_wrist_roll_bumper true l_gripper_l_finger_link_geom 100.0 true 100.0 l_gripper_l_finger_bumper true l_gripper_r_finger_link_geom 100.0 true 100.0 l_gripper_r_finger_bumper true false l_gripper_l_finger_tip_link_geom 100.0 true 100.0 l_gripper_l_finger_tip_bumper true false l_gripper_r_finger_tip_link_geom 100.0 true 100.0 l_gripper_r_finger_tip_bumper true 100.0 l_gripper_l_finger_link l_gripper_l_finger_pose_ground_truth 0.0 base_link true 100.0 l_gripper_l_finger_link l_gripper_l_finger_force_ground_truth l_gripper_l_finger_link l_gripper_r_parallel_link l_gripper_r_finger_tip_link l_gripper_r_finger_tip_link 0 0 1 -0.018 -0.021 0 l_gripper_l_parallel_link l_gripper_l_finger_tip_link l_gripper_l_finger_tip_link 0 0 1 -0.018 0.021 0 l_gripper_l_finger_tip_link l_gripper_r_finger_tip_link l_gripper_r_finger_tip_link 0 1 0 true true true l_gripper_palm_link_geom 100.0 true 100.0 l_gripper_palm_bumper true 100.0 l_gripper_palm_link l_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map 640 480 L8 90 0.1 100 25.0 true 25.0 l_forearm_cam/image_raw l_forearm_cam/camera_info l_forearm_cam_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 90 0.1 100 25.0 true 25.0 r_forearm_cam/image_raw r_forearm_cam/camera_info r_forearm_cam_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue ros-robot-model-1.11.8/kdl_parser/test/pr2_desc_bracket.xml000066400000000000000000000013271257532150500236610ustar00rootroot00000000000000 ros-robot-model-1.11.8/kdl_parser/test/pr2_desc_bracket2.xml000066400000000000000000000013261257532150500237420ustar00rootroot00000000000000 ros-robot-model-1.11.8/kdl_parser/test/pr2_desc_vector.xml000066400000000000000000000014141257532150500235450ustar00rootroot00000000000000 ros-robot-model-1.11.8/kdl_parser/test/test_kdl_parser.cpp000066400000000000000000000060741257532150500236400ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #include #include #include #include "kdl_parser/kdl_parser.hpp" using namespace kdl_parser; int g_argc; char** g_argv; class TestParser : public testing::Test { public: KDL::Tree my_tree; protected: /// constructor TestParser() { } /// Destructor ~TestParser() { } }; TEST_F(TestParser, test) { for (int i=1; isecond.children.size(), (unsigned int)1); ASSERT_TRUE(my_tree.getSegment("base_link")->second.parent == my_tree.getRootSegment()); ASSERT_EQ(my_tree.getSegment("base_link")->second.segment.getInertia().getMass(), 116.0); ASSERT_NEAR(my_tree.getSegment("base_link")->second.segment.getInertia().getRotationalInertia().data[0], 15.6107, 0.001); SUCCEED(); } int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "test_kdl_parser"); g_argc = argc; g_argv = argv; return RUN_ALL_TESTS(); } ros-robot-model-1.11.8/kdl_parser/test/test_kdl_parser.launch000066400000000000000000000010211257532150500243130ustar00rootroot00000000000000 ros-robot-model-1.11.8/robot_model/000077500000000000000000000000001257532150500171405ustar00rootroot00000000000000ros-robot-model-1.11.8/robot_model/CHANGELOG.rst000066400000000000000000000014161257532150500211630ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package robot_model ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.11.8 (2015-09-11) ------------------- 1.11.7 (2015-04-22) ------------------- 1.11.6 (2014-11-30) ------------------- 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- 1.11.3 (2014-06-24) ------------------- 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- 1.10.18 (2013-12-04) -------------------- * add DEPENDS for kdl_parser * Contributors: Ioan Sucan 1.10.16 (2013-11-18) -------------------- 1.10.15 (2013-08-17) -------------------- * remove unneeded deps (fix `#32 `_) * Created new diagram for documenting URDF ros-robot-model-1.11.8/robot_model/CMakeLists.txt000066400000000000000000000001561257532150500217020ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(robot_model) find_package(catkin REQUIRED) catkin_metapackage() ros-robot-model-1.11.8/robot_model/documentation/000077500000000000000000000000001257532150500220115ustar00rootroot00000000000000ros-robot-model-1.11.8/robot_model/documentation/urdf_diagram.odg000066400000000000000000001465651257532150500251510ustar00rootroot00000000000000PK¦‹ CŸ.Ä++mimetypeapplication/vnd.oasis.opendocument.graphicsPK¦‹ CDØ}¤’羬}rÀëåÔznÄÏ­»ßŒò AÚl¢Ñ·Õce»ý•ØÏôk ”Â4W WL¸ß¬¿ã§dYƒÒênf]GmÖ¼‘MoÝW³ß}¬ÿÆzl¯ý/©ú5ÊŸñ‘õœÙ¿í8ígîú#døn/.ÿÁ†9vóA®¤¸^þ2©É¹˜½j¦bºÒÌÊÉôwÛÙfçcnÿKê[WïúK¹6Q ÑP ìºeƒõ§ëvÕêÙ[˜rs®©Ækƒ} í7_g»Ò§ó~ƒßkÿ›¯ùÅÂ_þ2¾²Ùauvãc´s[*ÝNuz1Ç#¨Q¬§^iÒ¿ÆŽ{ÑÔñëË£‡[‹,°+Ò{ì¦ïêz”/BéÝG ©á×›ƒh¿á,±¾GkšZèsÇ ¯c’” wP ìÿÿÓôìÜL|Ü[pò˜-Ç½Ž®Ö \!Ëœè¿âû¤tž¢ÌñuùVQ'—––°‘·Ô>›êÚÖ»Ø÷ÿçűõ‹©]ÒºoQ¡‚Ëqiu•µßGpÒøüÆý7¯>ú¯õÏëþ°bcæd»6Œë=+)sÝ»ƒœ.ÇôØÏOÑÛºÆ{ÙèÿÛ‰ñ¢AÓª -ô.·Ñ0ºßO~hw¦\ÇÖv½oж§ÍÞÕŸõoêoMú¿u™5YfNU­ôýkv¬Æº™[XÆïsH£õë®gt^…öŒ‘uÌÇm®°ýÎ6ìw±Îöl¯³Ôzç¾ }iëy½]ý3¨^s*²—ÜËÐYac~•a›é³ÕüÿÏH p¥D‹Þ«ë'ÕnŸõ†ª†KŸMøäšr*#põ¹¯e•?k~’'Õß«˜Wñ_ˆ_cívûï´‚÷¸ ­ú c[üÝl\÷øÅúÇÕº[ððzu‡í-}–d€ ˆ¬±ž…N~æ³ùÏRßo¨þ.¾°u>¯‹—GQ®ü'°3$€æØ ½+v±ÖÕ³é~å‰T¸.ý(±Åâö ÈÆY¬¹dsöZ¿êl^¼¼ƒüd ßZrYûØÔ¼=_7ÑSÙõ‘Œ@š™ÇîîAÌé=36‡cåâÕu/湃¿vþsü¶.,zût›íæäP²ÆÅ®¡Ã¦ î#ÚûíƒùFº™¾Ïêz•]n}¿qG»ÏcVz/×ZqñÞ\0ú‹hcÉ÷­siØóùÎô/ôì^õã¬[Ò>¯]n;½<œ‡ lwŽZû'uþ]T¶Û¸O©;®uúúµÛŸ‰‹qÉÉÊpn@.{+«ó^ïXú¶ìý5³Óüö-Ïñ®÷ :Ušëmy·5£ÿ>=>Tg¾š i\Ÿ¨?UqºÅÖfç3ÔéøN²ƒômºŽõ~šö;gøk¬÷ÿ7ïôöâã ³ X(¢Ñ²?wÓ‹žÿ5±ŸT±9¹÷Øï‰¶ÆÿßWN™“#á¢è0úÿõO¥†õNŸX«÷úYXÍÆ=ÿBÚÛôk¦ç~ŠÊþ‡©éÂ.“ü\õ‹:‡Bû-î/ÈéÏô Ï.ªñœéÿƒýýi]úõ[lú¥ÔÚîNññc›cé5r¿â¦Ç}¿ª2}®ª‡ŸˆvCS¾lfÿD­Ú^n×+¿\3ÆSË*SUŽ- 2’÷5¿Èe–ؽk§ã`báÕWO®ºñ6ƒPª6‘íxsœÞß🞹O®¿QïêÙµzYhÍÚ}­´3ù«+·üC[ú/èí¯ý¦¸š³~µ}U¥»'¦0ú[¿“Ï¥êz˜ŸöʼnW@ˆè¯”›¾›Öþ¥ô.²öÛu?g½®÷ãÅo{GÓ¦è¤kÛùÿÎÕþ ëcŒLzñ±«m4RÐÊë`†µ£†´/?éãNÖ¹•õ¬fº£•‹2?•f+÷¹ßõ›ë Ð12ñ³q«Êű·cÜÐúíaàS$$4’àAÙÿÔõ7±–0±à9Ž9¤H èæ¸•Ó~ª}^éYNËéø5ÑàG¨%Å¡ßIµzŽ{ioüRŸÖSÔ[Ð3ÝÒÃŽp¡æOWîð_ð»›þZòŸ¨¶çŸ­8c¦¹ïsÞN~® Ñ×~^ãÿmú¿¤ûB|bLIº®ˆ'Q£ìyxX™ØÖbfTÛñîl©âZG<*'êïEè¢ÁÓ1YŒn#Ôp—9ÑôZë-/³csrÅÿVõ*~­9ØN{*70g>©ðýþæûÛ[­ô[vßð_ðk™ÿV绪äUCœî˜).½²MM»s=YÕ­½ìõwìúuÿ9þ !`MýzÕ>‹Õ:?Lêô ~¥ŒÌššw4?–»÷˜öí{ýG)ôÞ—ÓúV0Äéô3¤»Ó`䟤÷8ûžÿå½pÿãfî Ê° ÙÒßê} ´ÃhÙè³!ÍüÝž£©cÿœz?ø¨»¨ÙÓókœþšË0œòH‡}¥˜îwý§oè¿àýoWÓK„ðq_ÑW­Sݯÿns~³å9¦ƨƒý›°¯ÿö1¿Z2Ú\8µ@&ѱ_7ÑÙôQõêû.™çó¿òK;¶twô¬UCAÇynV°oa`w»Æ>[etÜßIìý§ô—³7€¹ŸñƒÐÕº®ÇfüÞžNEræúÍõÚ½ìoúz©J"Z ¤4ÑØè=G©ôŒ\ì6Šèº°[St–û,¢ßælkª\×øÓÂ}½5¢~Å ‡°®Öº‚ç×]JÄÿßXé§:Þ‰e Õ›7âIâæÓÕÿ^¨z¿×ªßô‹Ò3pñóðîÂÊg©Ã]¬=ÚáµÚÿß#‚jù¢ñß⻪ÕgMÈét_‰k­­„êi´îÜßø¬Qÿ­~úîW‹õއ×>¨ueV÷²ª]8N¡íƒ¦ÌÊìs}—Swèoÿ´Yþ5ºëiÚêp_`ëðòSmÿÑ‰ÒÆdx£¨(­ ÔÿŒÎ©V/Õç`OëIͪ¶ŽC[nE¿Õkéÿ^êÕñQ†öâõ á ¾ÆQY<‘@s¬?Õõ26Ö×'ƒÓþ±}têg!Ö:Òèm½AíŠ)­§ùºZ6Ö÷·wèñiÿ ïÈÿH½w¥ôÌ^•ÓèéØcn>3:¸þsÞ÷~u–<ú–-)TcÃvNé›lªŠKÚ-sKÛ\Å­-kÞô¶5Ïbw±ie€=Žæ¸H#Í¥y?Öîõ£¥õ«zÝ—]’ÒíÔu¤’羬}rÀëåÔznÄÏ­»ßŒò AÚl¢Ñ·Õce»ý•ØÏôk ”Â4W WL¸ß¬¿ã§dYƒÒênf]GmÖ¼‘MoÝW³ß}¬ÿÆzl¯ý/©ú5ÊŸñ‘õœÙ¿í8ígîú#døn/.ÿÁ†9vóA®¤¸^þ2©É¹˜½j¦bºÒÌÊÉôwÛÙfçcnÿKê[WïúK¹6Q ÑP ìºeƒõ§ëvÕêÙ[˜rs®©Ækƒ} í7_g»Ò§ó~ƒßkÿ›¯ùÅÂ_þ2¾²Ùauvãc´s[*ÝNuz1Ç#¨Q¬§^iÒ¿ÆŽ{ÑÔñëË£‡[‹,°+Ò{ì¦ïêz”/BéÝG ©á×›ƒh¿á,±¾GkšZèsÇ ¯c’” wP ìÿÿÓôìÜL|Ü[pò˜-Ç½Ž®Ö \!Ëœè¿âû¤tž¢ÌñuùVQ'—––°‘·Ô>›êÚÖ»Ø÷ÿçűõ‹©]ÒºoQ¡‚Ëqiu•µßGpÒøüÆý7¯>ú¯õÏëþ°bcæd»6Œë=+)sÝ»ƒœ.ÇôØÏOÑÛºÆ{ÙèÿÛ‰ñ¢AÓª -ô.·Ñ0ºßO~hw¦\ÇÖv½oж§ÍÞÕŸõoêoMú¿u™5YfNU­ôýkv¬Æº™[XÆïsH£õë®gt^…öŒ‘uÌÇm®°ýÎ6ìw±Îöl¯³Ôzç¾ }iëy½]ý3¨^s*²—ÜËÐYac~•a›é³ÕüÿÏH p¥D‹Þ«ë'ÕnŸõ†ª†KŸMøäšr*#põ¹¯e•?k~’'Õß«˜Wñ_ˆ_cívûï´‚÷¸ ­ú c[üÝl\÷øÅúÇÕº[ððzu‡í-}–d€ ˆ¬±ž…N~æ³ùÏRßo¨þ.¾°u>¯‹—GQ®ü'°3$€æØ ½+v±ÖÕ³é~å‰T¸.ý(±Åâö ÈÆY¬¹dsöZ¿êl^¼¼ƒüd ßZrYûØÔ¼=_7ÑSÙõ‘Œ@š™ÇîîAÌé=36‡cåâÕu/湃¿vþsü¶.,zût›íæäP²ÆÅ®¡Ã¦ î#ÚûíƒùFº™¾Ïêz•]n}¿qG»ÏcVz/×ZqñÞ\0ú‹hcÉ÷­siØóùÎô/ôì^õã¬[Ò>¯]n;½<œ‡ lwŽZû'uþ]T¶Û¸O©;®uúúµÛŸ‰‹qÉÉÊpn@.{+«ó^ïXú¶ìý5³Óüö-Ïñ®÷ :Ušëmy·5£ÿ>=>Tg¾š i\Ÿ¨?UqºÅÖfç3ÔéøN²ƒômºŽõ~šö;gøk¬÷ÿ7ïôöâã ³ X(¢Ñ²?wÓ‹žÿ5±ŸT±9¹÷Øï‰¶ÆÿßWN™“#á¢è0úÿõO¥†õNŸX«÷úYXÍÆ=ÿBÚÛôk¦ç~ŠÊþ‡©éÂ.“ü\õ‹:‡Bû-î/ÈéÏô Ï.ªñœéÿƒýýi]úõ[lú¥ÔÚîNññc›cé5r¿â¦Ç}¿ª2}®ª‡ŸˆvCS¾lfÿD­Ú^n×+¿\3ÆSË*SUŽ- 2’÷5¿Èe–ؽk§ã`báÕWO®ºñ6ƒPª6‘íxsœÞß🞹O®¿QïêÙµzYhÍÚ}­´3ù«+·üC[ú/èí¯ý¦¸š³~µ}U¥»'¦0ú[¿“Ï¥êz˜ŸöʼnW@ˆè¯”›¾›Öþ¥ô.²öÛu?g½®÷ãÅo{GÓ¦è¤kÛùÿÎÕþ ëcŒLzñ±«m4RÐÊë`†µ£†´/?éãNÖ¹•õ¬fº£•‹2?•f+÷¹ßõ›ë Ð12ñ³q«Êű·cÜÐúíaàS$$4’àAÙÿÔõ7±–0±à9Ž9¤H èæ¸•Ó~ª}^éYNËéø5ÑàG¨%Å¡ßIµzŽ{ioüRŸÖSÔ[Ð3ÝÒÃŽp¡æOWîð_ð»›þZòŸ¨¶çŸ­8c¦¹ïsÞN~® Ñ×~^ãÿmú¿¤ûB|bLIº®ˆ'Q£ìyxX™ØÖbfTÛñîl©âZG<*'êïEè¢ÁÓ1YŒn#Ôp—9ÑôZë-/³csrÅÿVõ*~­9ØN{*70g>©ðýþæûÛ[­ô[vßð_ðk™ÿV绪äUCœî˜).½²MM»s=YÕ­½ìõwìúuÿ9þ !`MýzÕ>‹Õ:?Lêô ~¥ŒÌššw4?–»÷˜öí{ýG)ôÞ—ÓúV0Äéô3¤»Ó`䟤÷8ûžÿå½pÿãfî Ê° ÙÒßê} ´ÃhÙè³!ÍüÝž£©cÿœz?ø¨»¨ÙÓókœþšË0œòH‡}¥˜îwý§oè¿àýoWÓK„ðq_ÑW­Sݯÿns~³å9¦ƨƒý›°¯ÿö1¿Z2Ú\8µ@&ѱ_7ÑÙôQõêû.™çó¿òK;¶twô¬UCAÇynV°oa`w»Æ>[etÜßIìý§ô—³7€¹ŸñƒÐÕº®ÇfüÞžNEræúÍõÚ½ìoúz©J"Z ¤4ÑØè=G©ôŒ\ì6Šèº°[St–û,¢ßælkª\×øÓÂ}½5¢~Å ‡°®Öº‚ç×]JÄÿßXé§:Þ‰e Õ›7âIâæÓÕÿ^¨z¿×ªßô‹Ò3pñóðîÂÊg©Ã]¬=ÚáµÚÿß#‚jù¢ñß⻪ÕgMÈét_‰k­­„êi´îÜßø¬Qÿ­~úîW‹õއ×>¨ueV÷²ª]8N¡íƒ¦ÌÊìs}—Swèoÿ´Yþ5ºëiÚêp_`ëðòSmÿÑ‰ÒÆdx£¨(­ ÔÿŒÎ©V/Õç`OëIͪ¶ŽC[nE¿Õkéÿ^êÕñQ†öâõ á ¾ÆQY<‘@s¬?Õõ26Ö×'ƒÓþ±}têg!Ö:Òèm½AíŠ)­§ùºZ6Ö÷·wèñiÿ ïÈÿH½w¥ôÌ^•ÓèéØcn>3:¸þsÞ÷~u–<ú–-)TcÃvNé›lªŠKÚ-sKÛ\Å­-kÞô¶5Ïbw±ie€=Žæ¸H#Í¥y?Öîõ£¥õ«zÝ—]’ÒíÔu ÿâ XICC_PROFILE HLinomntrRGB XYZ Î 1acspMSFTIEC sRGBöÖÓ-HP cprtP3desc„lwtptðbkptrXYZgXYZ,bXYZ@dmndTpdmddĈvuedL†viewÔ$lumiømeas $tech0 rTRC< gTRC< bTRC< textCopyright (c) 1998 Hewlett-Packard CompanydescsRGB IEC61966-2.1sRGB IEC61966-2.1XYZ óQÌXYZ XYZ o¢8õXYZ b™·…ÚXYZ $ „¶ÏdescIEC http://www.iec.chIEC http://www.iec.chdesc.IEC 61966-2.1 Default RGB colour space - sRGB.IEC 61966-2.1 Default RGB colour space - sRGBdesc,Reference Viewing Condition in IEC61966-2.1,Reference Viewing Condition in IEC61966-2.1view¤þ_.ÏíÌ \žXYZ L VPWçmeassig CRT curv #(-27;@EJOTY^chmrw|†‹•šŸ¤©®²·¼ÁÆËÐÕÛàåëðöû %+28>ELRY`gnu|ƒ‹’š¡©±¹ÁÉÑÙáéòú &/8AKT]gqz„Ž˜¢¬¶ÁËÕàëõ !-8COZfr~Š–¢®ºÇÓàìù -;HUcq~Œš¨¶ÄÓáðþ +:IXgw†–¦µÅÕåö'7HYj{Œ¯ÀÑãõ+=Oat†™¬¿Òåø 2FZn‚–ª¾Òçû  % : O d y ¤ º Ï å û  ' = T j ˜ ® Å Ü ó " 9 Q i € ˜ ° È á ù  * C \ u Ž § À Ù ó & @ Z t Ž © Ã Þ ø.Id›¶Òî %A^z–³Ïì &Ca~›¹×õ1OmŒªÉè&Ed„£Ãã#Ccƒ¤Åå'Ij‹­Îð4Vx›½à&Il²ÖúAe‰®Ò÷@eНÕú Ek‘·Ý*QwžÅì;cвÚ*R{£ÌõGp™Ãì@j”¾é>i”¿ê  A l ˜ Ä ð!!H!u!¡!Î!û"'"U"‚"¯"Ý# #8#f#”#Â#ð$$M$|$«$Ú% %8%h%—%Ç%÷&'&W&‡&·&è''I'z'«'Ü( (?(q(¢(Ô))8)k))Ð**5*h*›*Ï++6+i++Ñ,,9,n,¢,×- -A-v-«-á..L.‚.·.î/$/Z/‘/Ç/þ050l0¤0Û11J1‚1º1ò2*2c2›2Ô3 3F33¸3ñ4+4e4ž4Ø55M5‡5Â5ý676r6®6é7$7`7œ7×88P8Œ8È99B99¼9ù:6:t:²:ï;-;k;ª;è<' >`> >à?!?a?¢?â@#@d@¦@çA)AjA¬AîB0BrBµB÷C:C}CÀDDGDŠDÎEEUEšEÞF"FgF«FðG5G{GÀHHKH‘H×IIcI©IðJ7J}JÄK KSKšKâL*LrLºMMJM“MÜN%NnN·OOIO“OÝP'PqP»QQPQ›QæR1R|RÇSS_SªSöTBTTÛU(UuUÂVV\V©V÷WDW’WàX/X}XËYYiY¸ZZVZ¦Zõ[E[•[å\5\†\Ö]']x]É^^l^½__a_³``W`ª`üaOa¢aõbIbœbðcCc—cëd@d”dée=e’eçf=f’fèg=g“géh?h–hìiCišiñjHjŸj÷kOk§kÿlWl¯mm`m¹nnknÄooxoÑp+p†pàq:q•qðrKr¦ss]s¸ttptÌu(u…uáv>v›vøwVw³xxnxÌy*y‰yçzFz¥{{c{Â|!||á}A}¡~~b~Â#„å€G€¨ kÍ‚0‚’‚ôƒWƒº„„€„ã…G…«††r†×‡;‡ŸˆˆiˆÎ‰3‰™‰þŠdŠÊ‹0‹–‹üŒcŒÊ1˜ÿŽfŽÎ6žnÖ‘?‘¨’’z’ã“M“¶” ”Š”ô•_•É–4–Ÿ— —u—à˜L˜¸™$™™üšhšÕ›B›¯œœ‰œ÷dÒž@ž®ŸŸ‹Ÿú i Ø¡G¡¶¢&¢–££v£æ¤V¤Ç¥8¥©¦¦‹¦ý§n§à¨R¨Ä©7©©ªª««u«é¬\¬Ð­D­¸®-®¡¯¯‹°°u°ê±`±Ö²K²Â³8³®´%´œµµŠ¶¶y¶ð·h·à¸Y¸Ñ¹J¹Âº;ºµ».»§¼!¼›½½¾ ¾„¾ÿ¿z¿õÀpÀìÁgÁãÂ_ÂÛÃXÃÔÄQÄÎÅKÅÈÆFÆÃÇAÇ¿È=ȼÉ:ɹÊ8Ê·Ë6˶Ì5̵Í5͵Î6ζÏ7ϸÐ9кÑ<ѾÒ?ÒÁÓDÓÆÔIÔËÕNÕÑÖUÖØ×\×àØdØèÙlÙñÚvÚûÛ€ÜÜŠÝÝ–ÞÞ¢ß)߯à6à½áDáÌâSâÛãcãëäsäü儿 æ–çç©è2è¼éFéÐê[êåëpëûì†ííœî(î´ï@ïÌðXðåñrñÿòŒóó§ô4ôÂõPõÞömöû÷Šøø¨ù8ùÇúWúçûwüü˜ý)ýºþKþÜÿmÿÿÿî!Adobed@ÿÛ„      ÿÂÇÈÿÄÀ   !1p3 A25#7 !1AQaq"2‘BR#$p¡ábr3C³cDTt%!1 AQpq‘"0a2¡ÿÚ ŸÀœ)ÙÎêã*YýsŽ 0«&¦Ud(e¦*Ë“‚\ŒªËñbïë¥ö–~ YEº|v¹Ñúà…œIº£±§ô5–£¶µa{¸ï3ÔvžÑ±g.maöú¥ÚšvpBïòt…+Êû}Ó–vÁ•0´³¾¬f'í`ȽlÜW™ÜrÛÞëœR—ÊK«eÑ«VÿSQ²´ûùæ,­¢ù ùçå|ÈC¼­ØcÎÚxN¼õêôUÛ&ù‹h@½­“©ym¶Íã!$þŒF4è²N3ÈåêuÏ¸ÆØ»#„ŠÀ•F­YýeFÊ^fÓ±Õv‘¼—m~îZÞ®}$â®g9BmåvBÅï=ôÅù‘äòªnxÀïéqŸ›×?ÑÖÍE$ìŸäóÍäãÞ>ìáO-•µaõ”þë–ös§<‡ãÖ|õ”@ÝAʘ¤jºW$9]WÜn]$öªf ΋61±_ —|ÍÅÎã¶=Èç}ãô·=ôïtÛºÕlºbösÚZ¬úš¤üͦËå·0vLóV±µ> YpØCÎÙü{cYŸMS:46]±÷ý´Ú=%L…UÏÎÈ]5!õÕù»(©¶‹~øf÷ÆíW6Œó´jÕ;ÕÕm;æ-;-Åúz©§¤—ñ»ëÅè+mDŽ]6ÙÎZÞÓkIe—Õ¸o65Ùç½¼Û;-ù‹_qŒô{c»×=Nϯ£évwÚäx]õ÷mQç6Ç8z,g‚Êu׺.‡-ª)-w]|»ÇžßV22ƒ ?ÿÚþIæ8ƒñ˜$Ayùçˆà@óÄyøáðcêð>Ú¦$&l~+’“¦~P1rÁåNSДA¡ ª$Ø,·6¾î7,·‡~ 0+óžãôI4¤)©Ò’å7©MUhŠaH\ò›é ‰oé_û¹â%ýšžcñZOS'>•‡d›p¢U©xžŸí¥+•iøE9¡Ì¡„ºáqP¡à(ˆ'˜TO⇲!J*òX…<µAð>!/)0^\LqüÅÿÚþJëqãŽ`Ž|ñãÄ|GÇø}G1Ç‚x š%M¨¨LÁ³ÕV÷ÖÜÀ¼åˆ·[qrF8ÈÚ+µžp^élMo_ñö³o^ZžÊP£Äfݵ؛_2 ÜÙs Ý͘J±Ç±ì×mT±^S´3–¥u ßšf0«\ÛY±wlݸÛdÍêÞèZÙñIWa²›'i륣îîÅßµ ^Îì½7‚=’U¥*Ê”bžèåÖL…~öÅ8ÂÜöÒé%#?Üz¯ªt m§lf¿[[bë÷¯Šn&¿a[&JsÝØNRޱú“ìWì+ZÉõ{zOË_{¡š&°¾ÖœWØœ“pž+ÅôœÑ«8ƒ3ÒnûjûÀYWdé,ÇŠ½„Ü•*¶Í鯖®¸ñ݃wÓ©¾ºñ%/.0Úmj9Ùž?µ/Lm‘-Œ«dlÖèÙñWÖ©³vJ™ŸóÍŸ¯v6ö ff+êõ²kíŸhÙ"¬—Ž[G°=¤ÇWu•êâÊŸš¼ý§\3Kº}aZ’҃Ǵ›JZFùõqLÔpDzlqJ^Øqò¾•Ç^Éð}Òm‹ÂÖ½i ò&RÆDч¶ï­Xõ…·ÃS²­ï’ýë.CijûϯWFyÇ:·¥¡Ì» úÙ"‘° iμÖIÄ7æ «êÖ¢VvF1†/³±“í:A沬ºÄ´î¼Ö*òæcÕ…9ö±„Ìœ¬ãSׯÈ/dÿ[Y¢ÏF<ÊK_ol3”)—)IóÚÝzÇ·‰Ž6/ åÊ”/ëeÿûýþ›0z²¾Ò,ãÿ¦³b8éìÃNݘs@v—‡òBib§W¥ÑiûsœšÏ9ŸM1|Þ#×Ü¥´c^“òSò½Áf¯ZÇ?zà•Ÿ–Ö'”ÎG Ý–û£vÍíkkW²ZçMØUt ź—³ê éZºB½.M……ýlÄÃIØ*ý+‰BѸ8L`\×£Yå9· Uétúå3j4¢ùµ|q¸ŠéY3eó–qN˜h½~«]ùÜm'ÉôÃl~oÂÉ®ûÚJ̆ÁY{eïobб•‹ bÛ«Nð9¬P(w ¤>B™(ë-<Ý×¶­±âsãZŒÚP”&+¶}§sª…hZvÁàAJH¸µËÝ“v~ÄØýं.ü)‰¯ç©z»®ôi™9*t¯ù‹ÿÚ?õbÿ æN:œ˜šzöðY)e=Ë\R'mñ-Â!¤ÊG•ˆìY ¶2 äÈ,”Da ØvþOëý8ïr&…à„Kf¥øÃ]ŠgHÄ2Qd"p…ì6“ø4-Ê [Fqýe¡5ÜâÉEYx’õ$Äm%÷#n¸F×úM„’Ô–?$¿lEÜ‘¸±¢ÉJˆgÕe#ì°¾Ã/F-˶#ÉËn¨†Qcc{V…”9Ðp)^ˆZ—”/aã‹=ÉGÚ“ÁÇa,㹑h„7Šx¦^-æ%æ™ns«-·ÑM£úeúÇÿÚ?õ‹Æb1y‰Æ‡ÙŠ'¦± g‘‚ èÐД5‰dF ’ 4'GLt+5!Òž%K+JÅgíš(R{u!â`¸œAE’‹++F%ñebk\QyžÅt,ÎeŽ[ˆ9,jrLèVt4èÐÓÖOÿÚ?þ’7Ðß®©SQª×o~ºTšhýCn¦¾Ú]o°ïÓU=œIÞ•ü5±®· m]Άã~žÂI Nºüµ¹¦ºõoìRÕù[ÏÉ;\.X]î&'ŠÛæ<ÕL(òã 8P•ÌuäRÒš•$ í¬oȭȵ]¦)ø7È ’¦Q6#…·K%Dž Ùi¥iSM;âMgþG4œ‹"1Ú“)צ#ºÓ,Ò¶ÛB)%\IQ>€k)Â|ŒcÜ2Œb78fîá8àeiÓ` - ) ¤AÜTjÍ+ˆÃÙ~c=Ëušt´wcÂC ÷_’¦ŠH !'jš…5‹aþS»³˜cY­Å6¡-pãÆ—o• ðeÆÕ …£¸BT•$ìjÞß*ãv(O·X¬]ڪވЖJÛm´•Ç*!!>¦º4ó$͉-çÎ8ÒT|Ç-A&¼{Ó_Ãí÷Ôdy-¿È¶°™iÛ·\Pƒ¿&ŸŒ”²¥R´ n‡ÔŽºµç8Lイܪڛsé~4†è!½ø8Ù4"´;H èV¦‡Wx²L›7·©Qï—ù$¹l¶>‘»)K|L‡“_¨r A5?Nœ“qòæDÃÏ(8 YÞæP’)T5 (â+·]3"'”n—Æ™RRõªÿÆè€ܡÁ wQê•¥_#È`·‡y63Jy6@¢¨—&Û[°°É#u4¯¨ ÁP©ÓÓMÝ®ñÍë%½•±ŠbÍ:–Ü”âïud+¶ÃU×Bw “§–œùü2Ĉ–µ* RͲ)$–ÒOúzP8.: E M®!|»ZoÌ~;Ç£b³ Ü£ÃË¬ÖæÓ¨óP‰`Q :‡JAàP5"¢ºò?œynYîÖv¯ÌFQ<.ÈŽ·RNão£ëÄWÓW«¥’H‹–eNŒ’EGzKkSÒ’:Õ–Pµ$×ã¨ø«s\·ØmÍ›®m æìx…Ê¥K$)é vš@m¶è–БŠttÕEuqÆñœã›X­Wã’·9˜aÕ²²Ûʈí¬º”¨}%J@_êûõ縄¥Ë°d1ûÑ ¨í¼Ú¢Û¬¼ÙÝ6´”(Q«v(«$¼Ë43ž²Å}Y‰¤´¹/©.§ O%$šTÐjî»=²V3“c¥µßqyÎ%×ÓßKoÇu!ÖÊI‡qÀ•„„îji¯"ùèëE¦Õhg‹*…(\¹&S©MvWÚIUÜ“ï׈±>á ÚîWw¯ævCíGAPø%“O™Ög™%.9NL¸fEQka´¶‘ð<áü~Ïg 0”9‘Ú&ÚnN$P¼»s¨q’} ¡R}³´.SOÅ–Ãr£IB›‘ä…¶â8©+Bª#¨"š•r²[¥øÖù)Jqr±å!0ÔµT¥Àt)  ;öøjMϺ[¼le*R`0—Üøõþ¥4çÄ!ÚŸD“§n˜­Ê~)Z¥rbZVÛ”Ù¢ã\b:È|ÀXê• µ‰ù"ÈÒ¢ÅÉbwd[Ö®K‰)¥)™1”}í:…&´¥iªžŸ*éxn]å U§"aa QçÄU¸Éu–ÖÛ$Wpµ=i¨—+l¶nùì¢LÑÖ—Zy—$8ÚÐJT•PAÜjÏ%fÐ1FîEBÚÄ’·$Háù‹QÙKެ îBh=úg&Àrx9M‰å©¯æ\äêiÉ·R@SkJÀ? OÉ2»ÔIûhª»é?•·RámDÓPOÒ’P®ab¨)ÜzFÛõÔÛµâ{»]µ…ɸ\e8–™a–Ç%¸ã‹!)J@©$êù•ÚÝYÄ,¬¢Ë…òJ‚Õ2”LžÙ«ï-nû¨ÎòGøxZ“qž™™®[ÇòÐ¥㥤Z©_óؓ괯W 5ÞW+UÚ;±.V÷ÒÓì<‚‡q'b•$F®9.k›˜ø‘õ¸ô)ÑÛ2$Ú;ýµÁ´Ž\ {‰M(ÄõaÄ<û¶iáÍvi‹›Ð?U$-m¤¸¥\G bÉ›gÓnð} ŠÀi1aºèP(,D¤¼ªŠ$/—š°ù_ÍVG¬8ý¡ÆæãX-Á·\#b·JÔG©>È·+¦=l¹\ Óì§ÊˆËÏ3CQÛqh*M¸ê´÷èÛïÖh7¸ PZ¡OŒÔ–J‡EÝJ“_5¶ {|‰áfÓM§­„”€[N¶—u%6´…%I"„v Hö;l°ýâ‚å‹tFb÷T+B¾ÊÈŠúûeO¸ø÷Ÿ:s‹zlɈNºóŽV·[EJR‰©$Ôé(BB€„$P6쌬“´d †"*ç<²Ð]9¾5 ­:êJ±¼^Ñ*`@˜«d&"Cu(îvPŽ\ji^žÂ"‡å¥OȼCŠ]':¢§æ;kŽ—V¥~e)M¡5Q÷}Öã|w–?,Øæ6¥ÜJÇàt*}O°*l}t¹9ŸqÌšZö\ùöö¿ñ?Ù§Äé¹¶ï b,Êjœ»k„ÓàêV?«LA·Ãb(©;ii¦Ò:%@ Høý1ÿÿÙPK¦‹ CÜ<¦meta.xml Dave Coleman2013-08-13T08:50:402013-08-13T10:29:13Dave ColemanPT1H5M47S7LibreOffice/3.5$Linux_X86_64 LibreOffice_project/350m1$Build-2Dave Coleman2013-08-13T10:01:05PK¦‹ C settings.xmlåZ[sâ6~ï¯È0}h§C0lH“°c&l€åb.ñ›l+  K®$Ça}%[–[Xw:-NbKßwtt|Χî>¿{øâ 2Ž(¹Ïä/µÌ$u™Þg†¦‘½Í|®ürG_^Ë.u‘åP9„_Èé„——ï3#e 8âe<ÈËÂ)S’õ´òæèrD¶¼óŽ™ßgfBøå\. ÃËðÓ%eÓ\¾T*墧ë¡>ƒ\B|áæœMZ‡’4=e9zs>¥ô»ÑjÂra‘áM»Ê-ÿ^æ§r©±Y‡z¾´ÙÆ?ø ä £Æî¬ziÕqÛK[¶» „Gg䵜“¹XmîFH2•uü¬Ã¦r·ræòG 詘ºXÝVkºÏHÂò‚á÷hËì›÷ãœâÊa:ƒÀ¤~fýP,|ù‘©d‹·7…»Ü.ÐO·à‹Ø‹žÿt¿N ?F®˜íÃ/ WZbøGˆ¦³½ön®o¯NÅÏzÀÏ"âÂwènsÁpÿvEsd„²Å)ðén™É“±©¨ÈÈÇóDƒ!·ÉWþØ‚·)ÅLå`“àŒ’mŸ½Éø&U,‡à ¢wÁ¶›"ÂÓ#Q×"ð ÅÜôÕ~…Ž0˜¼™:K—Ê—(ÅtqÀq1ä:Á"ÅðU¡+y``:¯>¼=ñ# Ž‘‡°Kñ"r[KÞº¢Û——òE-fÚkò]®4¶hµ-°¥opx}U•F°E¦’;ùs{Ï–®L‘ü[¬iQgÝMÉ} Õ¡ºùßNc;´F1Ý51y°÷ Ù‡'>¾ÊÕO²oWÊeòÕ‰ùÞ – º ü¬ÀM…B›º)¸¢Éh \ÃÈ™›ð]Ô]t°'¡‰j3@¦°O—G‹br€‘ y²> ÷oÂÉbm+ÿJ·¨YSÛ(çÆÜß5t‡ŠÊq\Ui°W½ÆÔƒÿ‡CCr×?4ãKåŒÃƒÖç 71#æoðö'C7¤x=fx2ä£VLJVŠ52zÒ <È€ ,EŽHh$¿°œãùXÇs:ëhòHò*š:QŠíà‘.I‘è)(k‹Rï+Ù£N±yÏÍÍÖÀ¡Ç«nÃþŠÓ;KË‹J÷Ï´˜tßÇ‹!‡ìp~iQEB.ÔT±0ì·4?~ý-ü¾"ÈñU¿äÔŽÇ*• Rî±õT»T5ïLIyVåéëØ+sâ‘>>‹ÍéÆä„/ ÀBÒÄ~Añ3eçp›Í ÌF® É÷íKÞtkIIìÑü+_AwïÅu8ˆ)OC`§Ë¶B=áðJ¨ß0´çþ^#Õ5kÒ, ]˜ ã›5ùòdMz¢ó ‡­qçÍn”æÐ굆šÖù6šÛSÿÍñ0¶Iæ6ð›ýšo?‹s§Ð™9áÓs¡‚ñè[׬?Ùccap`5Œ?ÝIG³Ç£À}ÐÂÖƒÎÛµ0¬yK|«1 ÝÆ´Ô~í=9nM,lËqÒ¾¹åõ±ëáWËÔÞ7ÆÀ¸ƒ»¦þ44ªõ^¡¸ÑU´®ž_w'U‰1½6½R`õª_lRÍ»F‡ÛŸz×½ÉH³Ãjïyìâa_[¦ß¶&}å]¯6õžVê ëÆp¢õGÃú»16JSëµiµ>UÛýÑìÅÔ¬FÌvxƒ£å÷?¾’¦<’1p†éôd"èã-¥xÀCß•2I 1Ï„žH¦Ãbã`ß#·ó›Ü¡omUþPKôgæÉV÷%PK¦‹ C content.xmlí]KsãÆ¾çW èrj]e€x?”•\ëUÖ9hã­•¶ò¸¨†À„À %ºrð)×Tå’Kòçö—¤gðà€ pEi%ÙrY2gz0=_ÓÝóýò»Û8’V˜f!IN'š¢N$œø$“ÅéäÃÕÙ|wö»—d>}|¿ˆq’Ë>Irø+Aë$;)kO'MNÊÂì$A1ÎNrÿ„¤8©[ˆÒ'¼¯²$Ë×Ñèæ\XlãÛ|lc&Ûj‹fã{æÂb뀢›±™,€*6Ÿ“±o³Hž@=NQniq…ÉÇÓÉ2ÏÓ“éôææF¹1BSÍó¼)¯mö¹´ — ü)Ž0ë,›jŠ6­ecœ£±ú1YQ¥¤ˆg˜Ž†å¨cÕ”â D`¸Œ˜ã$¶iñkµÍ®ÕbÌþÑÑ<ãÂmªÁxªØ6Fùr‡}Ýé[¨ä¿Þ^lxEã±}1ÙT> ÓÑÃ,¥Åö„FUÖ œì\]]UÍiùY¾Ù+~CÃSAÜß+î£Èo'qh §MABÆ+Fùf1 ² ôiYÝgÁÎGÿõíÅ¥¿Ä1Ú‡ÃÂr˜d9J6Èdq¶Èî -JÂÑT`²©Cv"nM)N ÍÍÇèEo0Zæq´Û…±ÚZtAƒ WÔ1¦àÎÀ™È«ß|5iE§ýÄô¶ˆÉ]ýP.$Æ‚½ 4uÊdšIâ¨öh¾M1 Z(b¤—ã ¤'Bëv,¡ñí¸Ç1ò“`¾ýÄ-Gàg™‘÷á|õ~ÊêdJ!XT= )„>9«ó…Ò?dÓ¦9a$óeîð³³—¥ãç¿¥ò¿™Ò§“ Õ&UÁÁ×PT†P9E ‡O8`ÿu­»×+D¯uïºj0#@&#Q%à‡"‘ÿ«9ÿ©jB .’—„†?FDEáøáy¾-µbºú™œ¤•ã¼ äF^âp±‚ÎQ”Á$œ““8LšRÕ›²›0`ñ“1#ˆïƒ_ø’àšBÁÈ|œð ¸´8GY?[EŽI ªYVE€ÄB@ôu#žär2¡hâòAMmJ(ÄzŠq"|žEEõD0ƒ…éé„b?føVjýú¦jÑge’"?Ì×uO%qH)cÇç#fDÈë)TÏ•ÿì²ï]'Kw&p'µ]Y‘¿¬;ú$1ïßþÅó†!û©Èòp¾>h¶<œ—±¾€3ƒýóÔ´¿€žçûc&íãÐù‚š³Àï7€îá’ÙO oÂ|IŠœA2ˆdŒèGLeXFN^A,¼™l—7Ú+Ò@R±»†í=à°plë¥g༦oè0Mý-Ù—Œ(¶áÝq2¾ë¬™SÄ1klJD ¡O6ÐzdœU¬Û² ¯jKobûáJÏ 3^ø3è¡éiÞhRË( Q²«’mßDø¶ª?âÎ2åóF\-)Æ÷Ûɬ»ýöÀÆÇ[·ø=JIö‡‹–Ä|ÛIºDIV¶ð)ååN0 }°ÎM˜e-‰4Ì}à ¬OÃrKfËæ>sôVnÌadŽNBüˆaÑ]6òºì¦š‡ ¡1ŠvÂU6*Ëvuõ®Ö ž»Ú7ÕÆCÞI¡GA^O`›ÿÐ]'áüœî¾œ¿è¤{wô#»í$IãçŃCÔÉlŽaauŸú½•õÕCÔ¿êÄ@¦ì£Cùª¸F©ùŒcÇU'¤>NDžGظêDêC¦ÉÃÍæNtRó±Dš«N <à‡›u€x€šÛ¤µì­k”tÒ±=ïH‚£Ó—_«‰Â,ï9‡»Ð&¢@„W8ª¹³"Šp.••¬ž?)?–U2»Gq:ùôŸ5£"Œ™·aËÆÍ ¦YÚÛåòqœ ½„¤ærÏH㉊ ó’Ö®\²ÂµYÀ  šÖ×—}#=ý8d)òá¡xN(®Ax~GCHSôg‰yD„Üg‰u4„tÅ|–ÙGCÈx–ø8ÇÃç™úi÷h™ÏÔO{GDèyúivvr$ˆ¬§å¨…ê*מî¼JWUÌH°n>TwæÎ^ò£vs®<”)ssöYk.€­›s'~ù®:/ËrLù•»ªîÏQ±åGyU¨È@9[¢wį±5I­³­wuM„Öì®8ü!E^^Uæ°ÃbÆbEõ9‘¦*ªaÔ¥lE¢)Ž×¬™…-$UüJ+´»®*I·þ êa¾,f ,|¦”dðïŒä×ìUTÙ„5­í“V`àdÉnRò“çtÍub·Q¿' ª*©’®Ùjõ»FfâòrJÍvó¨”ßþ~+±ÆUóÖc¤Í_Uú»ôgΪŽmÄ\¦§oÛKW\ÍÍå*¦kÞ·¹ Ì_/1 0ÍŽm²ò>šp&Ú\/«ë3ãvå32·Ú™†¢š¢µÁÛZŽ`lMW,ͼ'k?é‰9§0º>é;M¤šÈPtÏìÚȰ[T1\M°‘ªºÃM´¹–)ñ׈N–Ï¡ãÐÏ Š³©¦Š?¯Ýê¯óú¯tûÕ÷¶òSº˜TMK0³í#ÕeÙ’½þãê"F9»,’\4^a7©Í1^Áè¼€¥ À›Šg´<·b8ÚA¬6X ¬ÿðþüÍ}±Öºƒß4ÛóºÙ–Öšöö&=]3_aØö 5Y¬ºNÍ0ÝŒv_ƒ½Æç82‚Ï ¤0‘~ „¬Öý˜Þ¥—÷8&«²‹?­Jžt¬}tÔ/§™iQÍþÚÖ–´¿Ñç‘ÒÇ/µV¼η!—6:É\‡Yº¢[bÀ„E_ 3ë8–þ EiŠ!úþx)¥ÒœP©twÒñiõ.*a’I( ¤{^ò=*†9ãf´6œíÃlmˆa–âlVùÌwŠ5œ‘µ—hw5;I‹\V&±Bb¯üJYN‹rYr<›­9‡ÃdQö8#üÀSV‹aÖq¦yŠjÚmfêc)¶åî·¸Eæ*ýY íÎ^ïÒ#„Èr¿–Œ”z‹eÃ9Ø8–A¤4\eÀ:×:$¿Nyø9ŽÙ¿G–üe™ÔdxB𼯖F±HÊ—¸×‘>iê}ÆÊÙ‘Ü«ngËBUÝjËÓvvïöAkgkÀzPÿâÕ L…|¾tÁTþæ¾–Ò#§©Ùš¦ÃûŸ7MÇå>‰" £®´¿dÚñºϯ &ûÀpûH¢s^¨YŠ« lÜŒ8“ø0+’¼ªZü¬m42;´[aؽ~¦C°×N+ mrÉ^ΔQD\†ll±àA;Fù=¸– ðŽ˜Ó_aÉ8—Ðfoûy{…½!hp¿ÛÔ{¶äTÍn/:t[<ÆaîðÎÉàÎ×—Ò;äD‹_±K4Û3íÛöÑuÅ5ÍãÛçC !£XzàYRéÇÅŽDê©XŠ$ ô΢ÇLî¡fôÂúåò[½g¡xöÆkìDÝÌ [½#¢oÖXµjìí}®»¸Z/¢Ë)‡ÇoÃWˆq±PVËî æÄš ýK.¨µÒ€N“®­4 *œî1sâ—µY<4¨ºŠ¥ë"¨uFÜ ª~¨ÆXP5Ô’mÓ´%ÝñÌh¡ÎauÖ“B·ËÙcÂkö¸ڠv ø¼ãÁ×Þ—ƒb¦ÓBÏQl×Ñsªû^ô¬è}èiz¨"9н¬¶&ë½ø¶.éš–¢mbßþÕùm/„æa´;´@•9v¿w´-ýñàg)ªê‰ø|Â⮾ú¬=ç0ô´ÞÑ% Ô’M€OwÔ\MÕh#€ýÒ‹ev[³•çß,Ìg…ÿçü+EIFçÓ,˜ï¹ÅôTr¯{Ì’Ç­Ž]Å3Ziò¨í²-ðï¸PýôË[VZH‡1ÛWƒ5ì§_þ7ú^Û]|qyþæ©`‡8³µôúÏžö•„»Ýš:‚W–Ùs¯ÀÚÜí¹$ Þ²…[¢Û{ÚûM`OÎ^­P±ï^“¤úöàìdŸ©­ÊŽf¤Oÿü·TmõçaYs3âà}õÏ8ƒpÍå(†Ý1—ª¸®Ó2—®·é=0²~Є30v8ºbæ‹p ÿ>¤¿G4zî7]°vÕ4üû»E©óú%MþµÉ+Ä¿WVW5CV]Èý€IÅ2½o%VVuÍDÏt#Æ{I êãIxdZ¯9÷_ü&úu²¯‹‰,9Þˆ‰î}0U±M«@·µ½ª)ž~u¼(]ðÀ¯ ʾî.ZKERe=@œð³•Ï9É*?¤åíðí·Ÿ¦­w£¦;þw&gÿPKBn…È ePK¦‹ C•Ö£!ß@ß@Thumbnails/thumbnail.png‰PNG  IHDRƲÖÉ,@¦IDATxœí½x×uàïô™× ^Cï…’`§(J¤dQŪ‘%YŽeËVÇåsÖÿío³–“]oòÅÙüí¬å8Žc'²’µ%[’%Ë*–DR¢(ö^@¢—×û{Ówæ5<‚ ñ@€˜ŸÄÁÌmsß{fι÷L–e ¡±TÁ®w44®'šh,i4ÐXÒh ±¤Ñ@cI£ €Æ’F%&KM4–4šh,i4ÐXÒh ±¤¹j€Œ¨þd ™C <Ô¨<2à zä¼2rjh\f+¡ŒŒùãn³.%Š… <ë ²å @BI°÷È e§B¡Œ¨Z²$ÿ|qÇ»ïìü—þu¦µÇ¿ðÊ»ÿñâ«Ï=ów)‹2À´4?MCãÊÌV „ú"±{?õõ½¯þݺ͟ÁMæ¿ÿ§ûžøÖÏ~øßÚë\’Ì}éë‹Là1Ñvßõ‡ÄÖßþEY‘ë¾ëK^}FyTtßüGIŽ·˜è-÷=µ¦ÍñýïýMIž†Æå™­P2ëðý¯ýBìè¾_rœ0ü½W¾O¢i%B ŠÜéý/Aòœ´á®'P½ëþÏWºŒÏ?÷}(«›îüâ{¯=Ã!úS»~"ãŸæ ’¡4CŠïùÿ¾´ïÓ?þj+©¨Oá·¾öõ‘§>7üÍï×Ô›Yâ¬ã®o~ó¾jñÐÓ<­>Å›×=ñçŸêüëGþû`eQ-¯üø_üù6§ölѸ³åÖ. Øg¾ðõûçÿ-¬gp¼µÆýð'¿ôò¯~œM I"Beç¡Ì@@LE…ƒ/ýÿJP0ÉËÊx“¹U·?ñÌ?|wu‡[V†2ÌŒ .jYÿÕ¿ýærJ‘ÃÑ_ýÙÓ;'îúcÇt xÿ{þW¯|û1Ô²ñkßË$ÓИ%³Y)A>Òáнî^ÚèÙýÚzœ +²¡&€.¿å“E²iñ‹Ÿ»BAHr7xY’iV„C;žS í«¶f÷«ÏþC•Ç®,bhÏ÷¿ñ5“÷í÷}ù+•8`§cQÛš7üë3§âæÒK›Y¿BbGÞý ÑÃüQº¶,œ~ëÇ‚2ÎE2]\”íú7IWßþÄSß§ôû@øÜËoî¹gÛzˆ`A86® ƒ %ãÁßò<Ò}Ëã‡ßn†š¢> ‹4Õõš„¹›=ìýç/ý°lK»é‚—GÊiQ‘‚ïÿý×þÌ Æ’-Ÿû«/­Ð_ùᢱęý[  äÊÍŸþðͺŒNøOîýMÛúÇO|ð«lQ”‡†A™K®Ýúà¾w^>öÎÊ[>¿uËM:Bê¾ùÓO=v§’¬yÓãÇvÿ¸¿xúb,‚‚™cÜV ûN„V&ENí –m6c#Ù(²þ¡Gu_ûÙ­ß\k,Ê!öüòCÛ-wëZ7ý—ÐT «aÖ*¢ã©ÏO“ôßüïþö•—”›ušMˆ¢„`jŽÅbÊVðð{Ï×®xNð}ïüdÙÚGd‰üù?}cýªv%þä®_´t?¢<4$}üàK ÷'ÓÉátHN1‡Ú;Jë6HcI3{HýéKôãUõÿâ7ð¡ÇZ•¡&?qdPßÙh¸ÜŒžøÁŸ¾ëüô¶À3ßÝem3D’Í~f½ɇßS‘;¿<{v*ŽUtJKýÁwwYZ˜$µáñZu}ŸS\ K(*ÇÚî²µnûX§å’UU²¢ õ¾`Ò¸±ùO€ÄÞ¿ÿ¼Ó÷|¬ãÀkûlúämßûÑp[—i½£þ¼0l^¾¹©yëv÷ÁçwMŒï=Yû_}ÇÐ|ÛCVõüô7Þ¨ýÝöqñ÷~7ºš™”*·ß4õúÁÔįŸïÜpÛç:+'_zîÃ4éÚ|SÉòGŸ¬ÿ÷oýÏïwuš`ËÇZŽþ¾‡¦åH\ÔÉÃ{'k¢öðþ±×~Í6;’¶5Žÿq¶ßÔ»sBŠ¿÷kïæÇꞟ\GfNý‰*ÝûëyM9ïóc›¾ù¥ú]/ 8å1¹Þ™ÔwVOžïyé÷à3?xz»[{$.-f½¡úªSVÆ®fiÙ´µîÍ]1‰(_n9¹ÿ"’I²SQÙÚý‰uòéAQ’LZO*ƒ_9Þûöóÿw=þåø±w[îú4þáÞÞt׆½¿9s"¥vø×_ר0åFÜçoûøç×›`êXæ¬2ï?}*½jµƒõrŽFÓÉžñ~ÿʯ}®«/ùŽc…mâ0ÀÌM«okÞõJÚYÙÔ ÷x;}ßûã«·®Ø¥Ôê©_|á´Õšžj¹ë %jÇÚ¶èѦõäwÃëWy7ˆ½AÍv­÷/9fÉɪðü¯þKPË+ȼFBTtp?±ûþ#}€ñÔ[±!6 txd<åNyEÁM¤dõ[ÿèAäwÿy.nnqœyíÕ”äŠí}}ÛpÇš©×_{•#›ø¾I~j­·¾úò³§­›¬Œõ¼õü/¨¸ëO?ÁÆ!ã©¥Ãg€ŽBhôÈËÏ>7èy2S1|fçëþtõúž×NùkoéT ‡Ín2_oõÔ÷?”yü"åQ£ 30¤ÄЩ0SM±}'žl¨šñVVãgö€XÖ|ê©5ÓÇOÞ£lZ•õ õpU6´þ±é_|JÙcCEìûÙÎ_Ê®z<=Æ{>÷„+3çB8òÌQù‰U+˜éc½ÞxMvÒÚeç]±ÿÙ?ä–÷IÛ ”r{»ªV¬™‘%[àä@ñ¬¼0JCEk•kâí×ùѱŸlûŸZý/ïŽÓÃ)É&°õ_èzèx,ikûäÝNª´´nÝ]­[Í©7þ¶gï #ƒ@Mi‡‡^>µgLn©Jö)!ãiiÊ>´~åþщ¾Ñ1–D)×#ع’ãþ]bË#ø¹gŸ>ʯ¨ ûøÍ_jŽÿŸ]{”ý”ŽòãÙ,έeïŽÃˆ×ðÉ/8={ä• ÃÖ[‡}¨rFô¶/ÔE~¸{oƒí·}¥¥zÉ÷Óàš€ŒýÞµ=?Ý­ûfuËךà/?øM?SÔ5DmÜt[¦÷+‰}¿==4á‹­nm88•I¹çEŸ~ËÇ›m¿ÙõOlŸÿJȇ¿K™Ö7SèÞô™S¦{¿ÙÞë rpßÀ0kb`ìÍÃÈ×ÿk}YâÀ¹˜lÅõ«·Õ۾؇Øt…,ÒÔA£$F>©¢¢ÒÔ©—{{¨û¿¥”¿¿/Rë õ«o­EGŽx  €&× Fã:€@kiN¿ùÛ^$\¶¦)¼ï­!0%’v|zv)¦[sWëÍó㗒Άô5¥µ‘žÚ÷FpÞÙȄؖ{|‡Ž$W#dScêíN¾+Û?ñˆÓ(ÅÞ;b{ò+MÐ}öÙWý»ÞÚQÃmãã¾Þ‹ê« ©¸œÏ"ë‚¡D­!SýAЮcïDo»3wÆm&É®êÐÈ  ÀµÂ¬ZóµÌNõ}«?ŸÜ¢üûxCQ*´áSk3Ç5öuÛ oÅYTZÔMÝ«ŠÏïûóì2hÃ=¶Éw·d† ÂÚ´i{KÑ¢@¥º¹;sÂÇnùÑcçG>•Y8÷§Ý33-I4X\`]_\u±}ˆ&KM4–4šh,i4ÐXÒh ±¤Ñàr\÷ÙðOg¸¾u¸±Ñà’,„•PJï_Õ¸Ñ@cI£ €Æ’F€¹¡t+èKQrV­Z¤«þçV'Ô`PzRÑUáüÞX /_æ$²rbèdÌÝî".‘<¶69‰™”»Yõ23»”¤h›îbFåäð©˜{™¿ÜI‹û}QµÅd”•¸¤Jôdk~¥j_´æ„(U:6 ÜíMôD¾nÔzäT̹lFý–KT~NÐ`ŽP®âÉ‘´0´”Ÿxû¤ey9Âom®MöFôÐXXÇô„¾!V¯‡±„„ăQÊ@ (-&91r鍿úGÒ0‰J¤»ÆšV{ø‘Cg TܦòÙ‡Ó020·ol2Âäà¡siD@)6œ2Y©x$­Ó#¬Ñ•=||\¦(Ä1+›ÙšóÞ€ä6ò AÇåÊ:Ãå«èjšñ>41*™«v F“¤n¸gÜP·²ŠíIòÑHLNöPr(ì‰Å%tx2«{Ä”oðøH2-q˜Á¢ÆuC*é'÷ á¶æwèpOPHOÓœÏcÕ`Î%õv ‚!!¤ìƒ/-#¨öE8õ"¥‚1 CÕïTg$£”ŪObrT.¯C‰„>5ÕÙu©É!¯SÑi¢2n!D²7|uO-_9È–@&Íû hг,AÝB¥£WSs¥DH0D"ŽÙÆÑ˜ïJÕf¸4OQF†Ç(„“§«]mú}a2VåM©õÄuz…J@Èþ€¢$9k-¥íÝðÙ´ÎnÆÓa£ó8¦ ê±êp¨&(7&'¼97^¬ ÀI³ŸŒ)Ô²áoϹÔMg -…dnÇ9 AåmMù°œ+†ºeªTWH›M ¥Þ‰ 54ºÍ„šÌQ~~‘]Ë®¾æî–Ö*3Z•­ùªjp¥jg0ž˜›n/Tv´\îÔÊ™ sêqš ךšBD댄L»:çÛY^þÝåÊûh0W Æªzã•“Í–ì ÷âqmsÑswª9®ùU0Ç?䣠 À‚FÕL4J‰&KMæ˜9|O÷ôÓOÏaiW|}¾? ”n>ˆ&sûî7{gâÕYunûM¥®ÉGÀÿ^Ý•}T4Xद^þ)¸ãOõÇþî$øt÷j÷urb&yß %ÍR€´¬XŽ!™Cp³ÍA^&‹ìûCH¾ÉzÙ4³)§´h°pHN¾ôs¸ý ù÷?ò¥üéêû*¸=Sh¥0™¬ƒþ¾q¹e~¬™HÞ7Âð³ünЗØ £‡OzBœàÅ–É‘½þ@ˆS’þ@`Á@Dfx6å¦R‚µ ú•kóÆ`xnìPdt ÔßmDO„Î¥QEœÁ…\u›Y¢–c<œ’•(¨c“a·ÑO…i Õ1MíøõÊÙê¶§§þ f³§FªsÌçí?óe ¯h'SoqUÛõ¬Ÿ‹êQ £»0õЗÚ0Â=¾~?V¹L—ð&ËÚˆø.AùŽ‹ãå+pW0-ˆÉ3¼\‡ˆ’„| 5‘"ê>ž)çŒD·ªQi€WtÐÆq!2,J ˜Ÿ÷_š,pÚ?wðâP3 ƒ¹ljðýW„ P9¯Õ€¤I:–a3""&›0´?&†dƒN†k4r ¤™/UTþ/joÄ@Œ8OñN Çe–ä³åؚд ©“XubFPÆuHÂ'2Ž–þ™§ ÀÂ7Ýü]Êß wçnùºä-fÝüç¦yª4­+ëTþvrìfe»\ü°ÀêÇ´®[øñ£±´¤–C­°xHn³©±«¬ynzu³2_øyåè2)MÖ9û-WF€’Á õG¸)ÞdÄ]+¨K©/’otÇnNg°­\'ßæRG“ö¶òÖjLõL;9Ñ+;[2c_9ê;4h\ÙI^ý}qÆÒÊì¾²-|lÎL;eÇvGy=æhgDN…eÊ‚¢Ï;¼hH÷,Ç,ùsë•** “ƒÀQ |=²I—èíC ĺŒŠíOò äc2SǸ+JÛE5(x:™$ĈèŒïy&{âž› þ~ÑZ‰GD[-6öÛ³¾uéTzËy9Эªªíí;<’Œ'%a|胂µ ôÛÖ¾ý¢’ŽûFEŠ®Õî)%½™ž|;àºÙbc!E!éÜHùSÎu«ŠE.»´2ÛÝ Ë,‹§Zd÷ÿò±SçvåJF‘Ðt:ê1µÖÈc»Â£"éÐhÁ) È1­$Ø>X0Eßçƒ<ŸH¢Í÷Z<:qâX*ÅàhRL½Œ©Ù¥Ñý)ÁJRÞDÈÁèÃ<çÂ)hjÓ1!6AÒŽ‚¦¤4‡âÄ,”Íì !Lé͘jP2 EÀcÂ"hG™aå2‰ÉTÇvÊV–ºÜ\QC"V¶Ò&hfâïFYÜèÂ`BÍPM¬$—VÀÔŠ6[x. A·: U?‡²”àH¥äj«·}Ã!k9C!V qÑ噉…^3çéo±¡Ó)ˆèP1.˜”"Q•dˆ06ȼ Gc\œ"t2€:–e•C’Й)ÊÊ¥XDV´¥Ï"¤ 0•ÈdÏød–E‰'ÔCÌB0$7:€ºiƒÙ†B61™Bõ‚ ¢$ ¡ôDZ9$]å%hP:pÓú'Š÷•}¦ÚÙ§z]UªVÓ™ݺ:-93órÕÓê¯8‰—uW¨ÉV9 ÓiºÂYo†I°2Ô¼mõ5Ô’å/>)ÎÚi»©3»[äÃVÜy¨ŠÜâê2€bD·3åõ óÞÈ-YÐùÅ6–.ƒ%¥üÓ_¢¥@€’¡*÷ï¥ Z»kÛ2JñE²—Yf“€ÐA˜ÕãÕþ]¨Éù!Ê#.’è;JÕ/ÇÑù©ÛÕ  @IA0“‘&ÆŸ˜82À´®6ÓŠÆ<ÌÛ‰±“ت[Ñÿò¹¶ƒg9[#íaâ)‚Hœ\D8ެ âÄ–¨?x­÷DÒÖR£k¸­^]F%ñSô ­ôä¾TÍ-†Ÿ›¨©j_ÎýáõtÕZÊ;È&⺵”›Kv}ùôñ—S¦µ¦†™÷&û’šŠÈæÕFKœM`8ÿ^,]ÎAÉÑ…§’B8ÊŽFã\C¤±.£Û¸P\hP:ÌÞån£¼=>1x.š™Œú[k0ˆ‘6É éTõ=ŽZk¹PWG!8ˆœ‹QÕz«‰ rPQúÍl2¥QÂR¥w¸ÐÜi·7 P—ŽâÒÂQµåPØêæ°?Ì–PÄÌ8ù\†Û”±H7$&fëiŒ¡!jÁ RFeB”¶_DÖ` €Ø2Ê=p·¹€Ü`0ïðÑuži%¾¹LÙ44eèÊl—Ÿ8›S²ÅPh ‡§jœËºBúŠÆª›gœ>S~é ¨®;sãWS¶†3)ë4–uæœóúšÿŠh0÷\jê¥ì›<}å\Þ.âÔ¡«¬Ö,(é¼Ë…‰&sÌÎ\Ÿg»ˆKÓ£&Kš«€…°hhiÞ¨JD‰.¨rBW™ WýXµêz:f;xðàu<û FIo%‹å>U"ˆywWÄÄOn]fZ€Ÿ?>ÙY0ÊV3 QR®]¸áw>€›6ÈïïMÇRžõ|ÿ0j¼a>ÂÖ¢doþ¶ßÑ€yÓî q*ޤb:Ø;áèªJœóÑfŒ®©OœNëA1±ç|ÎÕk;«ô×iýßBàrv4æŽ9{d¾ˆX[ñÞ–míÉ€/¨ƒT¹qúök[;t웜ƒ&!;<7[ÛjmÿXR¤’£½!¹ÚDÂhXÛ–tï/ ÝþK͵ ÊÓ§NQ7ªQLKäô¡£|D´êÎ/\Œœ<‚„ñ±.Å}I“[æcadˆH€«¬µ$$€=zyL»õiÌs öî;6+»òßúÖ|L5$™™–(sÁþ“cIu}ˆ¶¬ª*ØÀî̧_¾Æ•ÛkÈJ,þ>ºÈX¼v–&×&R¬o«7U¶Ô/6Ô…„µ¾Í Œ‰B:”‡@dðœ`sšôŒºÚI‘ïé³~T_ÑPsÑì‹”Åkh rOˆ[*=ºÞ»'ôÕµ´Ï+˜¬X,²QÉÓ`ŽŒŽL†ˆºS4!s~Ö]oŒL„1«8ž8KcG•£ÜN0pèèÝeÆJ§‚)ÊHBA$iŒeEÚÕ\NßêPjêåNØR~rnmûd­}É9Ó®Žì;j»˜è¶R"®Qd>4<¢ zÌ@a¢º‚ &3ƒFAˆMaz2)QHC“Q gsAÂhÇ(#Œ!}vŠç0“‹‘4Ì€¡^¶u}úPÜ]³{¿8ùÒ31ï36&Ó «ðƒRSÏ{´|#6µÕ ÁƆ=ËîÝ{鯆]wÅö…™²ä©SxK'1Ôßµ%ù²þpûº4Rœ×OÀ$÷Ò3à>åt?‡Û?Gîùþ¨zÎR6#Üÿ¼P»ájîð:6ÇçÚ14¬]™S„&GDcò†ì[ÿÌR'‡ý¼©UŠþ“¨[Q£cS€VT )>Ôµ™[ÙÆ6e` ‡Ae»GÍ^»Èé ½«lQßýgš÷95 D±mÌåYy'þßcéz’By_ORØ•,«Ö˜‡'Ãýg'OT,ëÆ_’™ðlï/Îû·=c8EäO'GB¾òºûïIù¾ïU.QîYqôý$u)«%söTR¢½¥ìþÝ!¿¾²Âl,¯ÔùÆâŠ>#…Μ T¬Z¦ê?Dm¥”ðŽGRŠ drÑ¡ÉÁ˜h³ûÎŽœíO–U»“‡F$L–õÕËêŒî¦ê¹©Û|/aÞ‡7Î×T„ɱý/#^ ‰p•mîÅ€PN'üiÂè6{D  –6#càüÙ¼>‰Ž@c|"s:74šlãçö¼.Â6m•Gã2̉@ÜZU "¼ÊlsX,VFuâ“Õg½z·³HÿyHBÔñƒ7/n²AÕ$“YN…Ó‹ûr9ó>ìðØþ³9\$ê¬øøC®‚P¬Ë¤¿û‹êvý£JnÞðÇ…Bi%ü2yÕÓ)ÿ¤te=9™N»6Öß³5çFïž/+›ëìð~3€è«›ô8•]˪õ…pwÆ"Rí¶Ü[NGn…FMCñêV»^ÑvLMëª ¹çû¥–U,ÔÕÀ;Ô²º ­3}"’Uå+‰ÜâݵEá2›NRRA޶2¯È.°¤äí6gëׂ‹P÷·-âwÈ×0R‹VÛ¹4 åàÄž‰xn5ŽÃVn’¿‘¬Þ¤ #µM@ŽO¼ùã#g=˽K:´]ý@9}êèî5oX‡‡Â }ŽW×õö§Còíg¢žmÖȱѸiÕÃMÕ©d|2g(4Š2VVd(×ugN4?Ë‚o®ºu´ù˜³B’àKe0Ê36Éfêj] †$Y’ ”â©J=æD—Mò†ÙrÁmÕÊ# ³ëzH6œŠ—ÁHD2$:WÆ´ÙÂæL•ƒà˜Pl(³Ø8Ë‚o´Ö)HYÅ­w¨Ê_}­º[žÙ:•'ÞÊšÍÙØG2šâò•,—du^/Ô9–çMÿ¨vPÜUçÛš>QáPã²hëJƒÌ&‹µù};²Co®ò4pçöqÕsí.ù&N&-ú÷zÎè Vƒ­«3¶{7§ÇøˆÈ4nðÔ”¡Yk?ÍÖt¡´Bùa«%R|:«anŸ.b#c ¼23À•ÓÞQÖVyþú)zò½à†[6 ù¼§û žŒÝµMb2…1Æ\Ä©±]¯§Œ'÷¥êîoªÉ¾«„9ó ˆjIÅn|¿'`ÐA Qïÿ0J4Joþ㡱UCÑŠGÛ¹‘wv¢ý¿èïúò¶xÏ©ñãSîÛÖñgÎA[®ÚšàS“RÍjð(¶Z\Ü:³\ „ûÏŒ?ÀUÔ¡ã!11‰tßÕ;xª0↓Õ4–äXïî“!$36Ù¼çÒŠ2\ÑDôe•ddûM–E'¡m êœ~Õ¼d½ÁÓÀ@ªšº¢ÓãDzßx¬w7YÑ A–ÿá1å‘àZæ®¶@q2óy+ÉÓÕtr’¥”ET‚f2lˆâ·‡@1ˆ¥( ) có6…Ð0€:#]hpY®µu®¼ (WÙ\ÛÒ†ßÁl.'˜8T4�Y'2åzdЦIÀ ô¦Ê:¶¯s ±/e“Åã¼l™O s bu­ÙR8r¬º×‘ÓÝ+þ¸-³“Óø­«ïÊÛÉQß_n½ºÔU¾þ¾ŒøÕùƒŠmefØyÝéÙøyÏÆLh™»èô™Â=ÙÑ…ÆåøÈ0ëe `‡djhT\Vg‰ˆ3æýsa/k÷¸È룧î=#;ëk-uy€ÛJ,²Þ?'S/ &ü¯½(ËðÑ`vËfùÍk-¸Ú…·Üž•±%ÿv"së¾]½QÝz‡úò¢°H@¥¦ü£Vî:ríÓî³·‹ì’Hm©)ÉzuÀ²üƒ]â‘´ºdæÃ ßøë.9½wB'ï~Ü÷DÛèÎ@óÖúŒmA!<×Wªªz¾ëóá‘PП¸ „ä™7úÊoï¼È»)Ö³wÔ½¶Õ¨­#½J´õó…œ7é©“UÕà”¿™Ž }÷¸×è±¾áÍUw(Ižáw6£éÀÑSñž1ѤΠٿó•q¯¹Ü);×m®Ì-¦KŸûÃkC€´w´aÃÃáH51)¢¢ŽK´µ¡W‰¶`ü'úQK#ÒÒׄ (B˜«M›Wªcâ?ü~¿I ìðxÊh„¤‘~UT]­ zW¥y8–9cÃ§Ž±ñ´ÝEdxô(¹ªž48¬ßìÔ {¯ë[¤ÌÅz€,Šz“¬i¨½ôz0=n: ­Ý‘ÛÍzKñ¨›c=À  ®¢ Ç7Ü×d@6¨ÚNk6øâv:›³WÝ”RÚ¨Î4̲‡2‡Ë•l©ÑûìÍÕ­ÆÌw_)vv/çi¸šk¾˜‹—ÄÙ‘C¹Z[/§É«PY¼ ¦/mÓyemN"[›ÿvÎCL­ëMEcÜk* Ò«‹ ¢#†¦õ­×V½%ÊÜ-ˆá)D{w¿7W bn¼áÜÜt}9E[3h]Á¢-ˆ)-Z×_à,˜õ‡ý%)ö:qžvÌÕ €öaòŠh·üÅ…6UpÎXä]Ÿ÷ž$[+£CSÊe¶]CæÃÞÉÑÓÒ63ær(¹¼ÑΨê­8}4¶ãÙ)|úXºÜ4r¶DÞ?–¢ÙH”0Z°tX´4Uãiº±Ý1sEu Ð`Èz³[´]?ƒ˜s½Ö5¯j–{ÎôMB)éJÈ(šŠuí†Ñý»ÎZoÚè:vlJ¦t$ÇC(§¼){•%îCëk¤ž=;ŽJË6wèc){¥nìd´f¹ÝwìÏÞDûÒµÖÀjmC½'F"Íê]&À䌷È\œÓ›œ5mÖ£ïú f´oBt˜K?AF€k"{ןgov¥!#¾¨Á?tè ˜NÉ’Þe·9)ÅDt8VV[11«Ý{<ÞÕœ<ᥔ.Bõp,CI†¥íN15P›U‡Â©ÃdDgSçgGye A J3ÉþS)SSL9𛥾3S='XƒÝS×VcŸ˜šŸÛ‰&…cÜÅâër z+LÈe•k7TÎŒËLÚ­,oS¿@'¹ª £Õ¼isÛŒT®»Ú.’˳¬P™›ÝÛ²¾°ˆÙ]¿l]aR¢§_ÿI‘°ÖÎËüHM®ŽE®è_ÜÑ> ‹BPW³¢åÊÉ®ÄÔÔ^ò“dY °ï©Å+T Õ[ÔšÏlä+2ç ¾@LÿT1e%.éŸ=Ëœ¹ÁrbèdÌÝî".‘—<¶69‰ËÊÉáS1w3ÒÓ47ÑÊþ2ç%^:\ꮿ;Ð ÔFÎ5f™ ¶sÜ;)U7ìyM-%)Ú¦»p–Ê .øN¨ «ôæÃ•?6 ÜíͶ‹·ó% /PŠ_¸ ´ØÈÉ‘4ï Hn#Ÿtð„ßÚ\›ì顱°Ž;é364}C¬^c ‰£ÊK@i1Ɉ‘ÓHG5×?’†‰HT"Ý5ÖŒ&IÝpφS´e.6ÇOöPr(쉅]M‡‡ºžó“þ¡ƒ¡´]ÏÇ9ˆ  Õ¦‘ˆÁlÑñIo¿@GÆý€DRtÓºÊØ™á4"ëkGNQ §1;íï‰#™¦v•“Þ1ši‚|4‚FÆømåºX„¢‘˜(Ÿê ãñ`XiXÂ@‹™¦nÆz$PT46¯ošçI` X”ž'ÉjçƒC$â˜Ýað¥e¾ A¤T0d˜[>JY¬ú$ &Gåò:˜HèSÃQ]—šò:«­Q¿/ÌAºÌ„³¢¨NbbtH@Ù}¶gcN¾á»~ˆ  C–UöÑL#³0fš•9V€:»U/úÓ Œ0{k@‹Qâ”çFD_gæÂ|¶©ýA„vzȀĘҞ´0:H‘ q^Ocªk”¶˜Ò@&Ã¥–“Œf"Nƒùoï,4›ñɨ»¥µÊŒVe‚2³Š:•AXËôxÍí¸ gC!¨¼­)–ýcŸ™¶£ÉUt´DnùçuukÔW5™I\U5&¨©šÞÏNQw渽::<8­n¯u˜Ñ /¨WÓ[íUÆœÏòë6—{ @UõÆù:ÙBëú‹ÄQö¼^£R°`žXh]?‹æ({~XrPÜÝf×/f!×íÆ`i @ážºð»¾Æü°Ð`n_ýÎ0´v-…_ê‹Ì"u”½¿i”ôkãBûM×» 3ñ¿7ÓÞE1‹ÔQölgp¥¦¾v\’÷ÍPÒ,HËŠåˆÿÍ¸Ùæ˜éVzžÉz·~¼>ÃÇõ¥¼^/dŠ››Í',n2ÍÛ© íÇ^/LE®ÉûFÞb–ßU·àÞ‡ÑÃ'½!NðbHŒÄýÇÒŒ<%y€Ý0‘žM¹©Ô€`­G‚~åZ¼_!ùèÞŸôÇÞQŽîá]0$02È,‹Ç~v,ޱa{¹¥Ç‹V “1k.ijìÞ­L®6ºÔ¶Ø…Ýþò¬?m7ª_ãá_JYåªOUüi—9°+8Ib¨Žv$¢£ Û¼X¦´j`8תé¨ÛhŸŠEœ…¶Õµƒ!È… KŠkíu ÅÞ÷ #9Ô·‡¯h'SoqUÛõ¬Ÿ‹ê`B jV)û<”Åà8Ry—îñõû±Êeº„7YÖFÄw "(È‘à¡æÇ-ˆoàW¦êï‡;ÿ×Ù KFd€I á½ûǵ ¨Î´“ÙÕiöV¦0µæ—Ú){ÞŸö@HdBÞ#r“ G¼)P~ž?í «Äá°(ÑRØ‹åšWˆJÞQhU¼²ƒ†áUܶ”$æ0nñ,”Þn €¤I:–aÙ¥®2RþCL6ahL Éýô~D­ið@&H3SzêÐd)ìú!¹ÑSÞó2Œ7YtÙµ!ÉHo?V݆,K©Î´QLÌ„dœfÛ k/p©ŽylYÚ:îM:[*Ò¢êR[/+mß’ådPÆuHÂ/Ú¬…æUZûÂV…Ź¢çX¾ŒÂ11!€Ôàlž•¾4Ü8`ZW¦ÚVï6¨GÛ2¶©7ØÍÊv}Qªìþj[±vp§ú)³ëc%ªnÚøÕ¹ýÕç͸÷[Îìκ¼Kí-ù¨cÇÞìïSöPªn FTU®yÈ9Ã¥6ÈùÓΰ1_ò¦9­ü@ĺʔ7ü­Së_hÞ­š½Ù¶U-ÿêÔÕ†ÒVïêYð ³c»£,…»WÐç=ÙEar8êP6,Sdún# S=²I—èíC &9‡”s´¡}IP͸ÝÀ«äªÇYNgœqxÑÙ£:Ê~/MWxÖ®a u¾”»»b?yæt*JÑ6·³³NŽñD]ÞO^óƒN‚MŠ2^èoNü䉢ˆãï'lå£Ë7ɶv®Ý$@ T6J¦úx}-ÞŸäõ˜£aŠ—qÉJ¡S§sœ—KýÕÂØžÌ©¸àQp--õ,xÈ€1L&ÄΞÝ4…D §vŽŒÓ-¢PÁP#i¬ËèÖ2É,‡Ð6Òiá’B&@'޲ œß†Œ."¡étÔcj­‘Çv…GEÒ¡Ђ+…Ë1­$Ø>å©c‚Ù @e¾|ã,¯ ‚ ïÃé?*7tÓ(‚ J…ñ‰7ÿñÐèê¶ê°Pwbg,ö“gb­n[O"Sa˜õ“·÷õ³{ú¼â'Œáš:ÉúÉ{빡Íe䵚Vºet ©­eÏœƒ&~üवBÍIŠÚë¨øéØXLŽJ0İD׺¡ÚÚÙv °ÞQÉÒIaŽ·ëêši(‰q e3$Ïî`éºLCuèà@|4€Ø«pæ%3Cœ¯8WmîŠLN¥ óœ$q@ŽŽ ƽ.=+I|^$`f¡\8* ÊÝAŒåâ$¡#$žÂ©´(S˜rç¡-À‘Ý„`“)Tï ,ò§'Ì逼…²—#S¾Œÿ q™À¤‰‚¨$C„±A~àU8ãâ¡“’„lŒKÓÅÈH¡üY €êìÑݪ›Úw"JùŒô«î눔êî.´KWpbgb¦ýäÁc“ÞÃc¼ÛåFxûò²¬Ÿ<)É“v<™’ó~òÊ(®ŸÇêjÐÈ@Œ®ÑIÎúÉ‹ö³t5¥“Ðì$OiˆÒˆ$H(iÄõ(ïåâRmíl»)CsDÒŒY,3Y‘]!”žH!ŒÒÙ†ŠJFu„à•hˆP3sA,sE|Aõ^†Y”ÑD B؇©§Àá¼}¢_ðIg[æmйº Àœy*MW­Íï:sº©¥Ë`É‘æ|$Ó¦>›=«²3é'±vÚnÊ)°Ôt¨:ÕMÏäutß+Ø\ªrîY³Zd§ê˺°Äuå´»»¼»b?yùš]¦ÕOÞ¦/–_ ØÛV}ñ–œ×½ŽéPÕOÞÍÓ6µ?š“<ˆXZt–¢€ª¦Ân¶Ýh÷ WÑV¾±hJh¶¡ª ÕkŸª;á™KFÎÈåÌ\õšŸ«ù#ÔøšXðPŒ"Ë£­ôR‰ hö0;60°I•:”ä©ÌðÀù˜ÌÔ1îr$xŒ%j°„:/SæUWØå.¬ ÏŽTa¸hmÙtz2¯â'ƒ‡v„¡Ý¹|LNœ™”P§;›·PŽõì!‰IÂu©bç9~6ŽKƒÉ~^6äT•$Ê"eÊ“yFråºô+åJešQÙ©“ÂÇc+k¡§GW¼|óÅ¢€óy_ê\S—€&*<Òèþ”`%©‰ð±1²®ê;è¸@jxØÚ ÍmyÕfd#;<0%{C!”¤TRHމSûRQÄÈ\º?K$nìùÇjk×Ü\S™~ÿ€`o¦GŸ=<ÒÚP‰ë»7 “^68ÌÛéÈÙ(V®7¬¬iq!¢o|ïkýã5Ëȉ·_ ºoµ„?ìU†à¿t6¦“ñ@b84ùÞú S"·Ø¢˜„¸NO&e¢´˜ó*Õžã`x =º—õ|ÜNÄ“ bN&“Ó—Æ-%)eL›|; ꌞT"`×Q=áž),ÎÒ4˳º¦áºIÂâU¡„® &X­è™ª***z*†c˜É*†"²IQ4M85ÌeRgÆ,êpBÞJ9åÌð€S† ¤«U†q”å „d†º«P÷¯¦ÂD¹>Ô[ï† (K Žrx™¹, qf€àÖLæ%õ™…‰:d)[Ö .WTz‡”âÉ2‰JÙ!:0Òf "íVFº’¹Å–s£1&øÂ€ MõòêGǸ 1r,*iŒ¡! f~iñ¥A!N„8‘%02‡ˆ¡4¦Ó!03*˜§×=—`Ñ ŠW¬Å,ÏæŒjŠÛ™rõ‘JWeÞLçÞ‹Ë„~ Šj›dÆÓÃ-[Æ(˳Kóf¯î_E…=U›n×™úhÕîÄ˺+T½eeMÆÏ‹³LNENNpt™­¾1»|S¿þ O..kOjMU~HàèR@ÙÑK‰Üb£(¬Ig/ºE« (‰I€ÙpÌÕmvugB«3CµœA zúÒ(-ß¡¶üyÖZò?ŠוE Wœ˜ðƒDæ—Ç/ž@ †ç¾b—âòS/¹áW"™©¾K¦Ñ}“§s&Gç¶n—á2íÌN‚ ¶*š¼B™ÙK³Yè°è,OÍa…çÓäè¢kç¹b¡ €†FIÑ@cI³@@y"/äEzR¢Ú–ºW#—‚*`Qi¥%ªj©Ç‹¨…KÇ€EDé(Yë÷Åh07”¢W•è  •&4˜+Ò£Güöãèé TÕLÓíŶ¿ó)ϰ5ËÊ0Õþ»@Éë>+fi¢ ÀÜ“±6ž±0nî™4”eccUèlkpUèýlyÎN/“ƒO#T"”6ê½Q†SÉ8¤INet«žŠöîoî¬7Í‹³ ¥‰&s®×E†ã¼ÑF&0ka<ÌAÊbÕùÒ2¡£PžW »Ê )íúiÒE|¬ÁIõ€77E™i.Š[Ìɉ©€R¨Ýª›Ÿu!KMæ Ôܸ,7¿¨ªìü¨ŒöžB@!e&vm²u¯S÷§­·»ªÕŽ__ãÖì7–M(šuèùA€vû/5šh,i4˜c©uè%‹&sÏ4³\jË‹M®#ªiep³ìœa³:~Q+Ö—‰Òø(h0oȱCÁsIâ”IŒe )«ŽHU’gB'‹ n3ëCqJ²äB°–é3æåäÈÞÀP£ô“ȼY·¾ÁÑ`¾¥àZµÝlF„ÁWr†”û¼hFd€dŒ'R)¢îãªÉåd6$Ȧ†ï‰MÊ6…UÝ©g}©Á1¬éù²n}££ À|‹K<·7<,“·4’5¤LglŒdŒ'cŽË,ÉgL.‹¨Èâª9åpÖw˜L@ÇjT±Öä³ÏƒuëMæ h\m[žÛ§ÏsØý±²œ ‹‚ñäõ&0#@ó…Æ®³”Öºõ Ž&%@–G †°”áúb+Çshµ‹vž-å"óÈ—7¢&Kþ㜡ƒ"g|5ž_Ë‹—«aâ•¿þ‘ôÔ¿·¼8#?qädÏþ‘†ÏÜSÅþô]ç§‹w²i¤È¡çž;‚„xÙŸ¹£ŸÅÉ”bõ†E§ØBH’²?Æsa1¦£N!Är‚Šs ’vHâÔûSI½MqªadŽ·ÄT2]Îè‰ñ¼…@Ã"`9¾œ!ýœEÄDFï‡ù¢"É3…Ší¶¦ 9•G”ø¼eÒU s6phÒ°õa†Ð$à²\SÇÂ7o÷üê-fÛ-ƒÿçßÇë«©ûš÷Rn7#o=»Ë;þÁ{±ṲPyûrÀö½øÓ"[z´S8º›Üþ…‡kÑø©þí91þÞ¯½›«O”­´öK·Ü2ð½ ·uY‘Ö;êßøÁ Ãæå››š·Þ*ï;ïÙ9!å»o_uöÍÚh0ºWlÝT>!º.dM©¡²$N5@-¢‚ªgå†å8¦Z¥vg #«Ö’¥¬YµTU³j€ƒjjÆE%»™ÐQ5Î\TBájT›v¼ l,ãH»Ù¬(]ï–Xø\•ðûbå` íjöbÛ:+0v´g<Ù¨ÆÊ€00´4•¨Úr׆÷~ëãÅà©“)ëò2v*"]îa,LkºëOȽ?Þ¹zëŠ]»ŒæÝû÷O "‰‘$;•­ÝŸX'ŸÕI0‚¿ÇÛùè“x>1ïl4쎭ënï1°œ'gÍ\Å\ð]*å¾ ‡B•çòF­):ËWßÂT8Ô‡cÙ²™Æ®UÊ­k/¬1ƒ«~ü`ðÖÏ|v5<ð³ßG‘“û\«Mœ‡àF'R²ºæiðTš¨$R“ï½ù:‚Ô܆÷XÛ:âSñÔ[1HuldÿýgÏša$†"¯½*ÂfwæcQÞ‰=û|÷ýGú@&å:<2=˜½Ù~æµWS¹ÄRZQtxàðÛï—ßó‚–pvžUñ¾P5¿ÐŠ,O%‚$AM±Â…žW b¬§B§$  èE³kÌš«¼ú¾'3WöÊvk.øAu3ýnâÁûò{›Î³iZñ©/¯˜>|ìauûä=êî_}CÝÏ™¯l:ÑSŸ—ø^eÓ¶,$iZ;ÉŽvpâ唩›Á ú}€—S\Â¥³Ä’#Ü]…*ã_EB†©*c­ 3^$L\’c{"£r¢G¼d@Âc•X¼šÇ‡ÆèeÝšàÙÜ ‚À'Y|î \߀|Ô·@üäþÃQ,œ®ÛÖiºpªÄîŸ0g÷7®¦”»”k«èâÂbíœ@̌ӠýÞ„r2 b’“†1Á$ï!D/ÆPRxL¸$„¸ s–II"ëÌ&ã\%³ê­H‚$æÕ} æ(ë«R&öð)·øè8‹q ºÂÇêUsû|Z@)Ø÷Ö1¤£E:~Ôo¨°€ðç~sJ|¬%pfœnŸ{ñl㣯±,º7:Õât±vŽuÝy¾%dU¿Ïù\Ékù™×ÿYG—N\ýVМˬ1eÞ‡ŽàÄ+ê1¤àt¦¬ î—Ož÷©Aã\ ôŸÕU»ÝÜ?˜@(»Ã@1Ÿ/íõnu Š2TíÙCÀ'L™ÞU?uŠê> DE°$ tS/³°/c[ãj¹*‚ekî¹wMî «Ly ™5°ú5ÛoSÿVWd‚;Öß\œyõµÔr¡M»_\”` pùá†ÆBbǾÿ¹“ܶQ>¸”ÌGih,læn PN¹<ÒQ/[©Œ2Q3g§ÜДȈ§f´ÔÌá4o}Duóº|É­¾+]—Ò:k©Ñfƒj,i4ÐXÒh 1“ÉmÌuHM4.‚ûîR=²>dçÇrÌl¾Hj ±¤™ˆ¾Ý¿Ü·»»nYë,Lj““½Øq±wn^ã›ñ&…Oì5­¡Ž}¬³ñÖ|¬Ï$[mLr·ÍÌ“kÄ^þOùñ/¬Òçßš²C¿û×=RíÞxÏJ¼÷—_<(/ß~{óÈoöe»­ÚçµùCòîØÍéàÀÌk¥ã$ô­åÍÌäÎ÷Òt…gíÕj‹89Ñ+;[ܳº42;uš7Ød™Þš5pt¹œr¼—Ek°ÈpÑjÒ:”Ï.-NXX;*‰Þ~ÉÖ8«é—³| tyW›}ïï~~Pj½©NøÃ›Clu˜VÞ²=üÖk‡hâä‹ûΡ÷;ˆìÐñãçø¶{îÛT Ôß§Ö’ŸØñò}Á¤7vLøDåT@Ž|øö¸kÕú›(¿NÏíÝ™’޼3P¶éî‡o-w45µr(b¨kÀøp»;–¶5æ™e“8æZWëšJ F:á‹'%À¨†Œdàgú=Û¬‘½£˜h߆}Þç¾Õ9%jt¡#éºû›êÌ—¼f?òaJ°èx|\$åT‚T¥3ŒÆƒêâÏt @º’ÖI2w<™Äpþ½Xºœ!}ì¹=Ç6˜Í!–³ëêj¤Ñý)ÁL þÄ¡AÌà¤Ý¤È‰s)Rjìð‡Qœ0—±1Ê´·4:­Ž²¾ý;Þ’A"3¸F’qTzoŸ]/[Ì€—@Cbß¾°ÉJùG…d‚±#AÁH˜ärÈOž2Œxf|‹eê¢AÖÛ{àÕ¡ ÃÉw ûߎ؅c[LJàp]ûòFIiøÙUZc.@°²•.ÐM¦el š$fïr·c¡2‰È ’$¤cYÃQ ʪ­#Æ¥c.æß¢›ždQ‡& ’êlx£’ ·øÓˆëq5Zú™þ 3 G%¨ÜR%žÄðÜQu†8€9KÚ—3¨=K³Ú³HY,4knݲ®šVÐW[³áuw6å“ܱ>£ÞÜ´—Ùåu·ªNFR~]Ów5%?÷ëúoýÏ{Næ\àÜY©yËö-·ŸBNm¬Øq CЭøâ7¶££§üѨqÓ²Iy|`îøÆ·ÌD£}gsÄ¡·Þ7ß^}¾7®"–ìR„9±¹:m4N¯ðìØbÍüeÔpPµé2G«³S AEr)#'][Q¿â÷~ÌÒeP …¨)W ^7uf£²KC‹/©ë±ÆŠÂm/[×^”Dðl92i>›ð %`v$gñûf'iÒ'Nø‡>xí$k*7Éï¿1Õ¾ïí‹Wo»ÿ&kðèþ{ç}q$µÞùð×ûš¾ý×[Lb*8¾ç—¿|s`‚hÛæÕ{ŸûÙ[ÉŽZï ³Ñ´ï•7Þ:HÜñäF8xf×ëgíLß®ûîš¿zû¥cU÷5~øó“U­:¼u[·~òø‘QÛª4KËoýü}ǃ÷Ö$°zqjÏï^ët=ñ³çú«nÚÔáHFåàŽ_öTlZãq¶wÙÎþá•}|Ûæîô+ŽëÖ1+'P—N)÷Õи³|š6miš>nË.ÎOø7¯S=vn¸'{رþöPßñ#úš7­WN°uC!㊛¦ éÚpwæoÕSkîWÿÞžMÖX·f“ú÷¾‡ );¦WßžÙ ¡¾SCºÎO|÷~3&§Z=ŠîT·v¹+·>\HÚ¾þnU³Ú=ÏhV³'û¶¾t,sí¥ù€Y:/f¤åCºzÓöêK¥¼|¬ÆÅXR3ð´aKM4–4šh,i4ÐXÒh ±¤Ñ@cI£ €Æ’F%&KM4–4ÿcâ©ÃEÛÝIEND®B`‚PK¦‹ CConfigurations2/popupmenu/PK¦‹ CConfigurations2/images/Bitmaps/PK¦‹ CConfigurations2/toolpanel/PK¦‹ CConfigurations2/statusbar/PK¦‹ CConfigurations2/progressbar/PK¦‹ CConfigurations2/toolbar/PK¦‹ CConfigurations2/menubar/PK¦‹ CConfigurations2/floater/PK¦‹ C'Configurations2/accelerator/current.xmlPKPK¦‹ C styles.xmlÝ[_ã¶ï§¤hhý±÷víœ7h{Rà6h»Iƒ<-h‰²xG‰E­×÷%úØï×OÒ!)É”-yå;ïîes@pâ̈3?ÎÎX÷öû‡Œ9÷D””çK7˜ø®CòˆÇ4_/Ý_~þ]¹ß_ÿá-O‘EÌ£*#¹D¥Ü2R: œ— C\º•È—´\ä8#åBF ^¼ZØÜ ½•YÑ/+®™miIäXaÅÛ‘Å«ñ;kf[:x3VXñ¦¶xÂÇ ?” %E<+°¤{Z<0š\º©”ÅÂó6›Íd3p±ö‚ù|îij«pÔò•`š+Ž<ˆڬô‚Ià5¼‘x¬~Š×V)¯²£¡Áœj!H ,`®òËq/²e:þu¿í]÷똣‹Ñ~¦™»®2Ç»Ê4¶e3,Óó½òn€¨ÿwó~çW"»—âí@ ZŒ6ÓpÛòœóVU%`‚]«úþÌ3Ï÷æ(ûFPI„Åe0‹ZÄyÖðp r¯\¾µ;£l´ÕÀ;à$8§£¡W¼®*øƒ^x‚\Èd|Ò…]Â6e¤2cÃ)CQÖµˆã^VPgêAú€àE÷”l¾q;Õà¸#Ì÷A§ÖÇD4“{ ¾§xÚð-Ë©ì³ãçyІTi€äWW'«"†îuSþLÕ»~«^ a)>áè¿+è—î_„à°!ä…Bä¯üaéúŽï„¾3õÍ:$,€5¨µ4ô?¹^ý¾R þ‘ —©ýÒhNîBÿXýí.¼º»Çâ.œß¹†3¦eÁðí$Ãîü ÿ\sÕeVH6r\–Øh?"FòµJ8ÁüòÛÝû%ÎU‰×‹ ±É×1IpÅêÛ€cÖ á±]ºk‹”FnÃ[?£BÀQ Iáö ©­Ž8ãP0¾¹òÕŸzÛ„2ÖR¢„\&®“ðÅ^…xaJCΑzÞ)U`õf­4I1•äe•54&ܰbV¤Ø­ÙŠ*d¥cS¿{é–4+”ï:”T‚V‚`(» ?UxŠÊWPåQÆcx=H®RÂáÚDó˜¨àTW(ý¥ˆ¾j%˜•¤ \@åE VyÃfµìÊ®k«’ ¸sÄ|ƒôæ5’RTDè›ãú#.xùÝ{ u[îÜA³Ú1Á 5ÉÒ±àÎ;•øx5ÛìUÒO€J8+¤^c8_Wx K$× ¯r)@™_nû¶„$‡óFÓwäþwåÜâ¼|TÉF²Ü–’d‡º6ôƇRºa0ª×NPkßÐ>¥ ¥6£!üí§>ÕTý`äá³Ìie j9†MjYzj©)Ý7«%ýý'wçžTÐø¥LnRy$Æ"vOÏV’„÷pFc×Î «¬åG™ûhb1©t…[Z+8 •è!=‚`U—Y¡ˆä#âŠÚ'¬ÒZkÁp¢ÓÙ2 J¹ Ÿàð0ƒ\E×àWªRÒd«#§À±êؤ ¥J^(e,ŠK©.D}4F© Ø'ºN-Š9€ÇúÒFãX…­µˆ J–D¢‡.]â¶—¸wJ×ou£Æ ì #>d³1¸Ï1ÃŒVcD:†¨Öu‰Ó†„Ôý|éþï¿ÿiÎz‰åsZ&£9bx”ö¬ß€ÞPöÝO­·p‚·ÛlÅ™{Jf6Ùrv¡ë­wÌÒp¿]4ÑŠ@Ï@^BÓ³!?uÍΈÐÕ«Dèâl…“Ù«DèÍÙš¾J|.χÏ+ÍÓWgChöJóôüŒ½Î<øgƒèâ÷•¨-rݱyC×ѹ ì ÝÎZlºˆº…¨›¢»jº”îZÛ ÔËz:’#øþ·zU#Gõüİb:7KWRmØöiI+"SÁ«uŠêZÎóQ#”1ÝügLP‚«z‚bÖD†Ù¥¦Q3ºZUŸ0ç>k65æÍûê8 úXmm®ÇU6‚ƒ3š_IþÏ ç¿Qç†F‚;?ú|³’MÔPS»ÖY†aèŸÜ¼ç)•Îàd#Œ;ïäfÀÄ–>lä‹ö’)6ŽfûŽ„Q’ô8¿ïó©>†:wáh ‘ñÕÉ •¦Í¤½w†ÔLq±h©F“ƒ/3M‚‹I“¯ÿë™$µ?™A]ŸA™°AMMF<M“*žÎ:ÝÓ’j—~’©ÑgXy_ÍÞžÆôÇ|ÃÌu¤ŒV]ÅÒ3ø½ ß/ÒrÅãíKjzüªUÒ7@O¶J ^JgØÏgÝЕÌüÎÕŸl¦¹f}½Fžpïì^›ËøH8¨´ŠðWêȳÙIެL ^¦Á=|ûç™g+ã£Èà±Çž~á“× ö–àï~ÍéœA’DÑ|þuÁ˜ 7»ì·—“` Ál =ç{ZÙ=ôéIÅ$%8V÷á—Ï,@_£9 ‡à ƒñ F/’ª^¤n{ßôã+ÎâÓ¡{¢´òÕB7뙌P A})¢Áe%ž#^›Î³´–}ß'ôÊ |Õ`m“Ò!¡W9•u_:öŒÂ¾àí}bW?ªµÔW’j Îk‚ÞB×9¥ÜønÏ×({˦½¨YÕûÕÀ…—“ùÌ^oF™a0¹˜Gíä§€á‚î¾ufà.e„ »ß²LöЛ¸8È”õgçH½ Æ^<ðÂŽ>®¯À Ìy­¸ˆUi|´ôϬ&d¸”Ú/·»¯(Á(µ¤fÒ»gûûGcuû•ä}§ïÓú—ì8ªàìGTvÕ\Þ¾”ÚX…qç”Þ™¥v cç¤;¶>ØDÖáz;÷°ôúÿÆõÿPK@z÷ÁYà1PK¦‹ CMETA-INF/manifest.xml­TÁnÂ0 ½óUîM€C1´w`¥¦%N”8þ~-ÐiQ\bÇö{/Ž•Ùâ`M¶‡µÃ’øe€ÊUë’}®ßó)[Ì3+Qo Rq6²¦ãÅ-Y X8u,PZˆ©ÂyÀÊ©d©ø_œ˜.^GÀ˜ÍÙ•o£ äM}8^³7ɘÜKÚ–Lܹ[¨´Ìéè¡dÒ{£•¤&Mì±â'Á¼«“×Aú­V‘‰>:>´¢ ŠÑ°»VÓŸýeõ¶O–¯¾óõ qÚÊÄÎCÝÛIÞ´÷,ÁDøt`åÚ>?w½Mö ¥6QÐÙäï7»÷bY9Üè:…ÓűJÆuA¨Âý›ýëÁ™Ž [ º» DQ0‘# DEA1P±;°;ðU±Å@±E_1P<[_[1^ ,¤ãàb¿™Ýã8ýÐWtÿ?]fgžÝ›gþÓó Çq@¡n€A%¥ ”2(eP ”A)ƒÂOWlïâb€ÑÅA´~‘ƈĀFÃ0B  o(Ô2JE"&4wïçÞ¶åÚES$ †çä++q»Œºyj½½ë 9Ózwtvtºu!Ž|ŠÇãñùüQ>Íà[۬šØuÐaÐÐfß¶è)¼«B$e¨tÿeÐ ²&¦§'ù”€ä Nì{+î­ŸêÚ½»%ðÝ Ë±¡|þFø8ËyyâÈ £>@ð°Ë qDá$ûg(e|˜*ŸŸL:·ñ}Ê|ä >ÕÞ;ù]+”rÚ>2ùÞ†tØÛZ.¿Qîq{táXŸ˜ÿœ¡˜Q+ÅMó;ˆ©)£@0UgPÌ @)£šXÕ3vÜ@€1å=y¼ï°S²0…îO šß`OHl¯­}YÌ*†Ëx¼X>?„RÆŸƒÒDË/]Íc¹ðb/ÉÚ)ì9(¹î«^ÒïHÈØK¥«Y‡ÓÀú‘©ü˜Dêï†-»É! ¯  y­òÝ3@•ÇÛŸ|,„RÆj^IMðù½*É/—÷ùü`’4dŒrŽŠµ ²ø¢ê ”2(eüT„ýÇçß½{§¯¯O)£N >j¢*C˜0:`èVÄ4ø¿Äì½ÖÇîk¡bâJ i{ŒÇ€ª z~çV÷~¡Ð‘%ô A{®e9j‘nYhrr²««ë歷­1{Bº¡Öª>tg€ã‡½§>áê3t¯æè<;¼s@X?¼à‰D©‰8ý$Ë´3.6lbb¼}Þå DÉÎÎVWW¯ú’\@SÝ7G«¢†ÅlÕåˆ\úAõH &^'nѳ6zP;ûƒ$n%‚vÆì ò5) ahvNžºšÊïɌа ikÖ*-¡£YÞ…n'm†SX?äVjÂÀ0Ù‚n²³ç†D!#ì¾N Ä š*¼تÛrZÀüíZv‡ZÊÆÞƒàUƒ¸wÑe€2M Z8ö#“Uþ!4Áb±þè:£ž.­¯gʈùç§6ÚZWö‰ŒŒÔâ¥þ¬øGz É‡óç2#v3UEƒ1gœ,8?I\Dªƒ%íúS‰rS-–Ø¡‡n¼Ô]uG­<3?SR–@LzÏ‘úümoŒØ"(ÌÔáÂÛäó%¥w3:Œ7§š¶BY£è?&.¼jµÕt0Uî3Ë"î¯ÜRwœ¨¢”öiÿðºPðêêÎîæ¿1U 0CVUwJ—.]NžÞzZL•¦˜¼þì»áíõáÍú3™ÃÚl[¾-tâÀåË—6WJy^xÞfâ07ÙC5W…²¬W» Fq–ë‚è{…¬ò‚Ž ˆUtÚËhzu’ÕVËÊš@7Ã;H{:Pð:qâdx5ôí+ ­ÕÌþð‹á<—¨ò¢Iò1–¦Sy}æ‘}÷º÷¶ù[SuxÁ‡{×|ú”ë1ý8¼}¹£‡iÿðp|‘'yv=½c«[ݺ˜ *NÙε¼¦oÀüc/òW÷œåÐL,xõO†ahNZfë:¿ƒ2 p „×'Ww–6dåçnR;_LÒ¢ù]h„B'ļ(¾tò~á¾Až£‡ašþ¤ä£Cü63CM@w§iñÒÁ «–hQtÝÓÄÿWFÔî'¨ÙܤŠ.ú0ûPñ›ŒððQPD×>îèѣݺu«…O¯P:q;;àpT^ ÍŒ¿U1U¥”ˆº`xÅŽ…¬ŸQ£š¨NÏ qãÆÏž=û=;}d׺¢Ÿ>x}Ë µà °Ÿ±<*jb­ôø¾†kŽg¿±Î¹áí§1þ+ƒl³l^¾ÓqXÿ{WR‚:4½þ!ïzÜ>% 9!¼uE¬†“»·ƒ·vêÐ…¼ÚK³ö¸ˆEǹêZ¥¥"´Ç™tÔ°:t(¼jby¯p àõˆ¥éFAÖŠ˜u‡¦ÐÇQWÃqìpÙ¼ü„ }Ó…ë8¡B›§æ»^Éù)Ê{}‰«±IÕ¡7ºnÜ( mé7º¥ßïÑ´e™vüb,¼œLCؾr4¡6¿;"""’øðUeøøøÔåïþÍÔPÏ:}wîÜiÙ²%ø­Q”Ñ¢E‹û÷ï׎&„¯1ýn‚VŠ CÒ‹ð¶*ØÌÈã~“º¶R$EçæNºá9Z;UPx(¶Ú=i„êÄ5ôÑ‚‘ )‚aæi+ïêwTû=•5Qk€W2Ý À@ÕŒó#ä-£pò£b:ÝKmîÀ—ýaMüúb +ÛbôÙðû/Hø.¬Kê_MÉèsýþ¯0¹åDZ»Ôð‚„êyu ÿåuš¥8Ü˱1üïÅ|ì8ײe ’‹HýÆÒÿúÔÏ ·“È~Ì­E©6íYW^J^mOŒüî­%•&_cÇñB¢VvËÛ›¾6žÓÍÛ”TŒìök«ª«ƒú€Å%ÛYü%¼†¤Ê%÷öd¼1Ôíâʬgʨ”§œ¦£[TÅGþÈ&9MÐäWë´¼­•œ˜ì¶ÊU ßûå‘hÅ™&Ыm‚Œlê>3>¢ë$ÉÌ¡i•uG…§sT…¢×—3E¹%ä̽—§jó›¥ ¾²V Á«)©êÑbïfS¥F(soWmƒ:n $ºJÿ§+ý˜s!xù«É>þu1Z…ž›ôZµ`sk®«)e@M”àÒEJéñéiïAfÞsš™W+psÙ+‰„‰>—àE%Ÿfç<˾ýï:\ýl|aA!Æ ›0Ñæ¥ª¾jbÿL_P*ÔrèÿáŸýjîË;:å`Š-c'õ€AHÚºR‚¡… מb}út'FµµKѣݧ7 Y•¸†à4˜µºÊ/gé¨<;½°@—øxš)ž«êa JŠI™¢§Ÿ?jÜúøž¦¦@“hÝgÔÏìÂêt·±¦oàΖŒÎ# huª˜"5s–©¿š©œ¿Ý$si?C,¹Á¦—¥õ˜n&ÁAÇ0ÕêÄL®1@èX®¤e‡IUÁkæÍ•­ÂϤ>Ä–¢†CŽ‹q `="dÚÔ°àÿ,°÷ @öðüœÅ6íi|é¥$] ä ýHZˆ…âK:ÏÀMûùÞÂ}”€³y#È¡±èWr€áHƒº^gT93Åšh7Í ©í§Ìâ€Ñ´ìÆ£òJA®7÷ý‘g_ÍÒðBK^œ€Ã«³@3²¸˜gÞ|«hgè5¤y®ŽÖßÛ¾®>ª± öÓ¾ÜCÞÿ QŸÿë(ã_¿{œ¥ Jµˆbe<À Ùµy[‘D±‹yIV®ˆð¤ç°®†/HsÒÒù­ÅÉ@ÙuRwÞ²#?ÿ DÃ^h¤Úw¶¢œš›rŸŽ†ß¼Sî Û¸À¥lÎj^=g»]Íê3:G'#{ɽ*¦¦²K¼ôT7´Â‘€Ç:>¾tî jôwÝ|"™=« M¸»2Mßè d<ȸpXÜ1\«DÌþˆÑ®­ÿì?AS ùábþo:o$É*¨<øŒ½<­\P¤á­¬ØÕ#e\*¶ `ÊùÜ¿‘kÓ‹*,:ù ãN)ô°ª3Äïâ%"Ƥþ+F¿81ÀÇ°í°’â¢í zøô]ž°kèÞ7ÊPOœþÓ2µØº 7VpÇ”hŠMO/ óš3rËsîÙi/‹„­ÇÚÀÄ¨Ì ÝxÁ L v#GRnê‘ymoï…ñ2Ù}©MÝ•ž]-∙% qëø£§hEϱy/E,&ÂÍu0Õ>¦æDMüá\FoµêSt]ï^C'%öv(¢Ró.oÆßì1H 5q³_8vïáM]†&¨oö3|á'¸yÿ‘Õü•³N Ŧy-^•ãoÇî°¼l>w”ßìc¦~B G¬k·¹vJXVòµæ]h®u\.‹Ñ&û¶MìÛ’yBZ˜NF.ß {ü{#`ÍÝÊ}Èu{¾³*CZèz"M|9ýõ•bЦrx :SçÀiךgxDLM2(†0$¤7}¨{Vø€¶Ž«p4a.tt€ÿÍ-SÛ‘\H¨áº¤.ë`òôˆ×y|ÈDûÒ”™Ì_R:èËx`ZÍüT©Â êŒ* À–šßÍ"ª5E5m)PÊ ”A¡v•QO´£˜AR¥ ”2(eP ”A¡ZÊHDN4HF§I$ Cãb4M‚ 1d ‡KDè/F§±&•ƒVŸÜ»FO[¡¥kß{—öÚ{…^?ÓÆ}øíó1o3rF„Ï9»ÂÖ#ôö¹]˜DDgVˆäI Òðòù|Px×q2ŸXjÅã•yR¨¾2Ä8``’œ¬lm¦H$ ˆÂxùæ³m]úÜ»´ÿøîuÉWÐ$Àžç÷ÏåCUÆ ¦>ÿÔRYê'ñùL*½¿W°(ºžC£qp€?¼rúÅE憚7Ïm3s!Ž‹ÀxÖÿ\Øa’k·L3XþqÙöw’Tÿ'eH€¤{à”C»WÑ¢…˷͘¦¯¡ë†N=GŸ=¸Î­K˜¯Û¤aÁëclØŸ¿Kö`¥‚ˆd¼¶í·d•Ö?¢ :`_C8Y3&#Ãƒ×sGÍÐä“Ò‹F†ô‚ÿ*Mòù+UFQMÛú¯ Ïg[_náñ<¯Ùë<ï4ÐÓsÈñ¤íjL H>š&,|šê´ä\T[B¾oò¡>4í.<ž ÿTT)³µ§ÏÄäÝ¡|4mB ÷¿%;ËZVÇ/òoâEÜ·æó×ï«Ú)eTÑ’⟞[æS¶â˜¦ùe •_VsðùQé†\[&¯-ØÉï*_ŽI·HÁ¡˜Q7‹©˜:ð a”2(fP ”ñ]¸[l•*{žËÂ=5°2Ãn•±64vôV9+Ú ìÐ’Î=!±½¶öe11Jß á«‡¶šêòF¦£úÔæ!¡ )ß¹—ÏáñöóùÐçjk =ñBŸç×OÕÜbâÞœqælÚá4°~d*?¦AÁ%dáSɹ¥Œê‚ib-m†­3­*©dj ÆT~ÑT }7oî ÈÃiŸ"°ëÐÞ þ#eêˆþ:鉿¹~l}£*pJê2Â(eP ”ñCˆ»•ئj[§ :™q¾q|Õ·O¶ª>*Ûõ§)£ä^üÿ0 ¢‘|Àé7ÂÌ7¹AŽZ‚¬×ÌŒ/~@¡ÂŒ¤»W; úžk™M3h*- çùÔ̪»2ÿáÜ.–~SÀBmå—b™Í|ÔÕ‘)õìì쿟Šýs4ŒKe°¡&a<£o» GÝ{1‘tÀ_.µIä}2ÓB% EJº[h‹*hñcçvU¢…Žsy‡ª$ÈñÏ(¦¾—/_ÖÓ/¯gʨÞXfàóÿz—QyóýzVM vM¼†ŒùOüã¶ BÏSÓ¤[™2??É»þVRȼ^Jâ‡ÏÏ G£]Ƨ¶¿ï8@—°U ºGXÜ;úÁ¡‡¼ÅL4ðWY?f‹ï÷*¦^Æó^ÿ5pèÞƒ¥’œ<š¯Ý",>–+o]à-!ý;Ðû|2=p¦ñÍ÷ŒsK»ôÐ%oã6úCµ}Æ­4±?Z!+×—<¹O›Ü»%38²Âé6²<Îe“i²cÕ4;£QK;dr ÊBÞŽBî@õU)ŸÅ/Ç52ÛZ¢ä;Ÿ;Í }±pË2Ù½6Ù·Ùe{–Ä; ëI§cO£C¼Ãwå_èŸ|‚í³T:­ SÿäÉ“27¼^^”fn¦XRh´cK2}g¿ “{æe0p±Mc±~ ™T=%Å'£>{Ï2"íÞ}«h‹Î„ª2êgælTòµ£²~7eXÁÒ|iù<¹?™s厔 íJÚI šâ/­ÓÃÑŠe·>n¢êܹ³ü-yàà"k”P€8C ÂgÖÇ(±¹g—ãJjBŽIÜ?…R”Þ!°n B+¹?ùÌ®¼<û ™ƒÎ<,°k¢¤Æn9'Ñ”»/^ròú§ÎZÅ7†9㨜{­€¡¸pÎ÷¾ ÏÎÝ·*ËÍSQÙY'qIšßT¤¶ƒ‹ÓL v!F?åÕ3e0å7 p[4!ò³åÒ-Ërº 97KcÚE÷(ëusBË…˜m7öC‹¼þØ«1uÕÀHiuBj¢g™ãOTÆ@ÛŸ—mÄïÔR§/!!á?Fíãã(ü\fDí~‚þ¼9 0NO“’†SP[¼èGÁ$*jÂq¡]YÚM—DE줯Ԣß/ÿIõô$“êSÄ1„áááò~Ÿ˜&ÏÞ‹ÂÃ'DEE±µ›FEí†%ÿÆQ¹»f•Þ·©üí¹sçàÕÞÃÓS=K*)< j²Ö…±©·ðꈱ頿m½cв%í=—UÂÒê1ØÓÓä?Úº|Ó IC„8À_g™tݽâ/ÍnýÍÕhµúõ¥8`ýè:4­2¶ ê¶^#är‘²õ Ih!Zg‚–O!×Á§&W鑇LËŽ &5»xx¿fšÞƒ[1ô:д|.nŸí2`®ì‘ŠÀiÁyX›ÄŽë@î×N°®ʰb01\—Šï>˜Xê5z t‹³®Ý:|ùÂg0eDÇ廳œýôùÑ¦ÝÆÖìèS•éÈT Y•$ï!Ó §ü²ÇHuÖceÈjo…¦Á!e5]ÃÑa£áž4”ì\­…/Þ5-¸ï¢Ý44Ñ^Må»$º’pÜxÏJú«³´¨—Ã!xiîµ÷™½ÆV:ǧyX)¾x/Ä1Œ œ¼žYpl@À‚(ðòÔv¦uä'‡ã7NÌÝR¤ÌQµêj½½ù]õX°¤@)<|ä—K¾ŸÆ/·ôŸXk_l¥¡Ùƾř{¹çgŒ²ž”ØB);–úâTï΄1ZÇÖŽö+Êõ‡LÉ^Ou]› öõ¶Ó‡Ô€Æë›Kçñ£6_ƒ¿/|HÛ£G>yò¤¥"xwpÛs}ß!NšPX€Q;%?mf ‹6ªÀ¦r¡Dš&ÊP£ŠÝÀòëy?£rÊbქ«º ÝnU ÿdTãpöߺÓwèÂ#?·fßÈâ¿b×Éè¡s—® ™Ÿ3ÉòMøÚ—Acº¶ivñIÞµ t„NoÙ¸aÀó$àÉê÷šM°²·pV£ÕoeÀòvõêõJí›åK¼•ÇÒ<¨Ï»+Œœ¤Û BEŸëÛ/ß–¯´ª¬F$DFFjñRV:üÀz¸_À Á½·G•üØv’/Q$ ´*Üÿÿ—Ó¾ûE ¬ÊõUÛô©ëÅ”ðé»›‹mÚ³ˆD b»KÝGÏÛîû>&y ÏuÞÀl “#vœ 9Ÿ;ŽG:òÄàֳ·;V¹Já»P,\Âö(«´°¹qk²a­Ø2H¥±:¶/"Õ¸]O£þ)ƒi©ï49íË=˜"®KP¢­b¤ -dSÜ0{X)¹ïÓ© Ä9bËEàõÿþñµ§ ˜Ùå¿òc!ÐQ,2fv“ôq6 Y‰ì¹÷òTmT¾uÉ?€-`’_pz¢o‡…BVë+Ç_'͇*i÷¡@¢«ôÝww½ÉH£užiPé㳄àôüòßur~†L拟üƒW(~Ö…ÕéB&f3ô0á“7¸Ï,3%:]^€*Iø±g UM8Ì[l‡˜JÄb:Òÿü0û–ýìë̼'¹uåËnÌÇXš6„Ø5m$‹–8 –l¢´S§þUÆèPOO|ýøÙã´RŒÛ RÅ& îšÍ½_'Ìð™ð^xSlùÕ*M -ï·ð`gùñ,EÌo’å›CQé¸oÜí£ÉÆ‹¬äøâŽ3 áï*ÁÁû"Àb€œ,‘•>³SncË[ܲ6Kï9(ï´›®7_ãí;²o¾g=+U†Ö¾¶gudlŠ‚­¾Ò`'hAÓA{ß+,ÌÁ%€­éÛ ºî™Ø?hùŽkgG…¬Šâ7€ntæ^®‡ êúØL@F«¿¡ ÇÁ&¤#GXÒl°ž1àj²«(”šÏ4(*\KŽ3Ë> ¦‡ôõ™u·Î(–€ó R—q÷Þª4»q0×síLÝHTû𸑦ÔÙ©Da…I‹£;󼂖Ÿ.W±2¡ƒêDÞl$ú¤oóªð³§r~¾2ªl_Oª4Ïö£;µ¿\0î\Å5"GNÿð—¹G¿Þwú(PÊ ”AáOVFÒö‘xõë hÊûï‹lQÍ|aGŒ[`¨nŠ=… h­:zåæä{¶Ð£”Qƒˆ‰‰±`ΰqûI¢¤õ|;°=›ûæÓKq‘ ,,øê¿¹ùŸ?@)£&V>á¡ [dþä=aÇ$,ÍJ95Rû}7XÖ7XYYQuFm :“%#£íª#¦ÀR輚RÆOCÜ‚WÝ‚T¹æ¨ϼõY«fÜœ´À9f·® Ú8pÞžÿÀÆ™Ýz°¯¾UiÂS2PÁ(fÔg˜$ÞeoiòLCýz²jâò‚T%,R4µ( Œ´>}n|ºxãÓÏñ¦”QÞm  Ús²  4BEDB´oA-Ðh<ÓRß#’ª3j°ŸqyQzq©Ø`ˆY #ÚÓ,¼½Æ¢]X•Ù`œ‰1(‰i ,qÅ'•@Sû&tÀÅYùvf”€‚b¼PEÙz ¦¥VŸ”‘““еÛi~2 Øz „¿äo~öÞ¢¹£Èò“²ë¨¿3?,ìñ¾Åœ„°·ª6ý\É;ÚçoóW7ǹÿü/¦×åìD²"³FnÓÈ¡oE:a÷¨c¤2)¿ ͆¹íx•zÌ 555¨ €ÎÙ*×ïâW0\¦Œ¬EwÒÊg79åg¾¹×ÐGǯÌj¢®¬ˆBŒ Óž¿:Ë*HÝZ÷J£9ë&GϹíÒ¢ô÷fÚ˜…. õ£AÇÀ‡ýiÙŸð&#Íë™2Æ^*h¦A kª@Þ®º•;Êäæ%N{7 ɹ@Ssû…í?^¶@:ë?–ôÁôÍàgâÆyšŒ@Ò_¡`¦[™±Ú¹ÂqSãÚÀæc{R¿P¿Ö8ׯdÆX%‹² ĨC×û¨¶ ðË™îç@%Õ´¥”ñ£z¶ïËÖúÍÙYÿQÊø*bÇñŒ 5\Ž¥kyÄŽï²òÄWE…§s¼ZÑ+-_;±>‹í¬ê¡ŸZ=Zj?ÈŒn¾“»ª0DJŽÃWqf6 I0eA~‹âö<pfÌÚ·/¬W¿­›g o6jùë¸EŽô§»on>ujpÇ.F†šj3Ö‡5©×ÊYÅ?å+ÌùH×P¤¥ž¦ÒéùÖòË…GÑ«ZÓ¦Œ‰~wÓ«÷˜":ÍgšÞÙûbÂŽ –Ÿþ´vù­[w¥GGrmG›WWí{ÚÁ²þ°eÕ¨s]ÚÏfÞ˜­ä01³çZøZ+N¡FàŠ%sNöP×1¼¿jíŽMïæôh½zWÿYá;“¢#oå'ïsëw~^<ãZ¯öóPVÒœh·üîÀ[_ ôv{è|½Ð‡{ø1™ÛѾE™¥žª.WfHÓÓvHùhm®©¿òm…† lGk|3F{]©¥e‚– oòG#ÕPÜä¯ü@Û U0œ:vÎCë—vî@{“ÖxàyXÚD>$µ‘º]M™ ŽkÂÕ¬²‘³«”ù{X ú"Hzò@UO}5ˆª3*ÃRó»±Òw¡ZSTÓ–¥ JjWõt‰ T)EE (bP @ƒŠ(PÄ @á%†b‰ÄÍghÒ±uŸsŠ|z¿™¼kî¿N½výün€;zÀ%8ÄqÉ‘]QÚjt:-¯HäÞm(çHð¢ç¶Ò1:À%>½&½Ë/ïÙ±í´ }iÒ…zI &Á0É¥“N××·ÏÇJ6gÚè铉$˜D,¹}n=ŽÓ ³•Ë ;·ö<=ïÝ«;çv€VN·özýÔ†9óV¾þüþÞùm€ÆÀ@Õ&™x<žl+΃(渄&ì žRwáµÀ8¸Ah¿Ø¨Ž¼Â€ÍÛB-§xð$ñ™”n)Ô1p1­µr¼wm¿XÈhåä{ÿÆ„W6í:|bßZR¦¶äõe±˜BŒqãÜf ‘<~˜žtr#d¹Ø±TPô0%mÞìIsgã¥4 üé«ìÛg6±èß·±.q{£Oñ![@(ŸR*…Z$­XTJg)¨Â¶Rô†m8[ˆé³¬‰¥E3Ìú4~çâ^àVm»û 9uxë½+{Z¹…ªpñý»W{x)åØ64lÉë!sîY9yLXèØôªlëC?QÙÇHÈåW<Áɸè±WÔñJ¦ìÜv”F)ÔrSŠ«ÄwÎoÅ0lâ¨PøÇñ{W邌AÃî^ÜB,ÅR®ƒ ;»Ïß.ÁE8Ž=þg/ C¯»séì’à°if¦ó0y+­*»¯øå¿¬ù$s4'=MÑ1®lm«¢U>a”pIUiP¨-bH³?±^Zþ*ËÕòa”»i˜©•2?dÃ(P¨ÿÄàñ|øü„7ú7ÿ 1 yXLùýg@Ó$wáó/Æä…l+ëC·ŸÎ?»P&èÂë{‘¿«âÑ#®<^2¿ZõÀ—1TŠªâ‡Šþ?ŸEŒÿ'N.¼ßõþLX.ÀTaV\·³«µºî¶;ièúKÅ;õ$qc[…&þ¼þûU[èy“Û¸‡|$1ÿª2ò·ñÇŸÉ%—QöeÐF<žº@ò H€aÌóÿ‹?B–Uø³~;ký èJ¤LÔ¶N Ÿ`VÓ4=x<ÌóݰÒlùÉ+*ýŠ¿?IšžøâJªÇ:>Ïu?q0à4í¼àÞ¡6ƒy¼]ü3_ÛF"FÕˆ:ƒŠí3å~i|z¾T`ò´°ÉÓÊú;ÈC©mäz ‰ky»²ƒè€,õ@VþIem/B˜`EÙ#|YüÄ_©™Œ2æh“ýõJµJy„¿¶“6 ï0%œ“Ñæä ô»¾Z/ÅPy…ìÊLƒªÆ @E (bÔxíÏ‚’L>?pΙ‚ÙöùÅ*úG¥ó×™òF¦ƒûùü©ïŸß :¦\*y3mÿ~Ëç÷uïwûÜ_&9 ÚÝ\ãù|ÿnQX §ãahØ ‹”+; £×-þ6ðÁ}cûí I+î=%5q‘~&¦ÐÃFâ1!UxóòᩚZ]:óx‡ùÉSJÙaŽñù¾=ŸÝCFhœr…|ïß‹ôò:Ü¿«kt_Jƒ1jI[õ˜&Ä!k4LR*dbM*j0%•ž#<ïMÈ.Ä1ã—€];q~1^RÌàHMÃ2Ø aù%è!ôú8å>|”pDK¥*Åë3{ .¥>Š5¦‰5é˜ã©HÚ:æ'wD×uf˜ÉÄÈêSÒU…e?Q•É™h4¡¯ŠnÑ€Þž!`Ó€ÈqFŒ©‘ñ(Ù!ÃÉg×£—ª•Erz‘ !e/ „Wkˆ¡€ÖI(8³b„e•˜’sJ}1(P ˆAEŒCØ/ÿ‚+W®899Qš ˆA¡(VPÄ @á;œœìêêJ£àÑ‘MB[wÞ­C mzvËÈajji0ؼÿ&HÑtöúüÎ|ÀTÄK¹&tÌ0Ç„\nÚþï•<´Š ¿¶v¾@QEÃÆyòæ‹7÷jâÔÀÚÅVǼEnA WYE (Uá°¡Àæ=‡±‚Ïm”õí»AªÏ2r®$?ù/•@žKâ1 z BI^nVŽXÝDIø‘ÆÒ9yõéçB®¢Žj»OŸ¾¡W[Ø\™™©¥¥E¾èÆ¿Y¯î\+È. ëg{qÿi»à~¥EÈ?+;/›©ô.Oœù±>þâÈ.(PT(*i %Y¹ôyEðGi³€u+}Õ¦è4é ÎÍ{ökåØ[*M}ƒ&v9yBUFA>|VçÁ³w¹bÅÏøØÂô¡jŒz+Ÿ]0…6½Q^4Ð*ë©´ %é6vï'ÿÌ­ ÐvH«Ð gѨóäî—ÔÔTsóòÃ5T•Qb¬€Ô£Rµšu;ì¾ïëi*ªZ*E8ŒYÞù¶³, 5”É`-m#Ù‹œj€†Òc]ú¡ŸÌ%üõÔUôà/R¢ÕòÇU‰ÙEŽ"‡ø¼ª18(@þV8ðE™xÖÕJÝXû“éÃb¥SĨ 1~þÂu###yVÔ4þì=d1jß{tÙ7°ñþ#|—ñÅ"##µx©µ—^_;¡§*Ôôi¥1êbÇñBVñÏÜÉîÐRý×~I\Dj`¤E\Dz`¤©ì¶šOUVÆjFUÞ åp(büIX“2Æ^Aj$C츮!«¤¶QU¹µÊ-ƒ”à¼úH!-0ÒŒ 2dR~[R ØèÃøÿJÞ&æŽT}š[ªÃüNþ ‡1 €FŠ@"nhpoÏ›”§¥ÊÆùIoɨ./H•…Æ­É£ihØÐŠM5¥þt@V”] Á Èxu²øieäš5kÆŒ#»_ÀeWÂAä]²Pw0ÁänIðÒ@Cth£¥:V©…DŠUªl‚Œ¤û<]; …¬øÒ“ª1~ì^v¸IqtëY‰ßJs\ë)G'tãuÔQw_RÊP ñ„ØKƒx_Šßž×¡Õ¬3ߎê«ÝŒwï<==SRR [ž\.*òY,–©©ipp0,¹ßqÙ½&ãI ®ò­ßÀ%"ŒV­ ':3inºÇlS㾈TóΆ/O¾5j§ãìJ[ø®÷÷4´(bÔiOê@£ǦŒò]M^ËzŸÒ¬ÜmÅQÒÛ lF²"½˜*”=,ú0VbEÿgX__ÿñãÇUµóqùÎ7¼JDÈ'a]F?íF*¢;Ï0»–œG{^—¶ÔÏü$éàÂ:¶ä•RW£ÏÒý§¿;ÿñãÓÒwÙL·@…ËO™z¹ÙP¬¥ãÐ’t¿ z /,¾EÄprÞ[¬©JÁól Îè=Íàð´nÓÍŽD¥ûM1>›Pؾ›šÇ £¸yé³La]qsÙKP¶vÿ˪ƒª1ê7öNå4{Ê»xÑéCCŸÇç£\æGœáã· ½Ó*IÔE ]\Þyqé†ý̳¯‹Á“9»'1ñ—œžË¤IŠS–úÏÞÁª+v¥s´]Ûèî_ˆ2q ß7³[ïùGã¦z.:|z¼KKÉ??ŸXÛ´yqa›¥6Õ¾÷›ÛÍæBŸ‘Ä_¦1 Ó,½”4Já;™ f™Kp ßÞ@¿=h‘‹©«z6dÓ ÂoŠéÙâöͦȵ³E>gžœŸá?Ó„è15¢üÂQ?²yÑéd¨Ý$s»ÚUEŒÚCŸÅó¤¥rá ׿oØ=¥EϤÙfŸ…2‹Xþšnè1[+E¤Þ(wÄ¢ày»+EÞ ™1…¬@eêbØ`^½ÑDa»Æ8¯©(ëbCV|Ú¾y™ ¯2±Î3 ꬲ(bÔ ÂZ-Äø÷ëÐ:¢:RÕ™ë¨ ûE¿˜d»ó×bòäÉ ñ(ÐÓÓûõÄhݺu5%£¢¢ÂÃÃWFEÿ¹ýùógŠêAS*j÷“ðà&ð Þ…d )AYOóx#ÄŒ˜àL†¨ƒ#++ëà<‹¿YþÒ±;*ªWOSvÃ@JCÒf91€e}…:J 7•›[âß‘té”ñ¡QQ«ªœ¢TfD­<>eÌÞ+õy!Ùü-¤ÿ?H‰ÉáS #dôd±ŸR ƒ Ú¼y3•õŒ]C¤N4ƒ‰±´ÃÃÇIGŒäýÂT + «ÏÐñˆQM¥‹F£¶áámIimSÿ«‹Ÿ¸ˆÐ~øæŸ›"· 2 ãpZ©ò…µž=½Kg˪íz L³Ðñ7mhÜÐð½¥Gc v)(y… K Àæ5ÇJ$Y£Âß €%‡œ)ç”`11ǵ„y,ŸE)u\ŠÓJÿÞÓkThìοBú¨¿éK®ùƒ×€þ-öïùµæÄæZ©mý6ÅŽkßgÕE™b—¬nÙ’Y‡*ñOÃm>Ò<}­÷ÃGGz^J~ÿæÎ¿!«¶í[<±ôýíUÿYìb3•Ï{K#ÏAÏ/\ó»èœÁÆÄ%8ýõ¦ŽïÙ-Òî\õëÓDÁaÓ•íK9*ÃQù¾6ˆÑÃŒL¥éQ+·›Î&F©­Ç —áNcŒ˜2y$ƒ8뚥†# F´§‰{~š2º)z}Ë  ¢c=*^ªdE}ljcLFÈÒý¯6xt–tc6ø±`»²Bêg\²ž;iá!«æÂ¼Žµlys}Ÿ{ÿ¡ò2öê=õ(}#k4™_IsŽ]¤ŸƒíÒfÐJ%€}˜ÁÕÇ…!«–¼¼#]NÒ`ÌY:È£ƒBm4¥HÀ&ÐæKUSöu8ZM±dMôö1#ƒÆ‰ß´úoß°q쨡0`ëŠØjÛ„N”=~;W¢óè@1 qÓwÉç2vw4ªïéK®ù#¯&ÃÐÉösIϘûIºõr`ŒlŸ…,[&ÿ „‘CoÔæ\Zv> MÃü-{V†Þe(£™4ØÇ Y^¸’Ï$J+b†M•Neû †Ï7Cá%´¢¯üƒ}»“ût+Û×)‹Žpø–Ýuíó»$ñÅp^z 'dU"(¹uhÆ¿e»²„àÂñ?¿&0÷K>ÆâÊÝù‘!lt°Hv^‰º ûØ”QÃW¿ü7§“ƒ¬„Ÿã™šþèüœ’[‚‡;9-—홷ų…²AèÉó)îVJ"¹× „Yr+aúšNcÚÐMÇÑÕ?mëœåsôÙ’ðÕTޝ)b$$$üò¶±±166®/IìUVسíɬ©Á~~Ò³oh:¨¢p[|„¼…¬@ű¬°‰¦&éI°ÉÂ8­‘•Πˆ‘À²¢’™„˜Ïr)HIظ¥XQkM)ùé ]C£6ÜO¯8æ>ÜÉñ`jIXw/Y§ ÇÖíºâi))5o{eë²Na“ÎÇ,3i ÇëÑ?fY|V”ñ¦a‡×Ookh¢Õ1pPÑ?qI©¸n[¿–¹§’^2^•Žíe[S9qrŸÏÚ~Þöjö8t>¥ÐUóP²ë0÷ß/l¡ÇÄxÿô®~ O2‹/®óß7²:ÙkKÀÍéÞ.‹Kˆ5¶ùIý”]çLéxÔV»¹W“ó'n¯:zuãÇ¡ÛÁçxŒàOþùþÊî;à‹€¶…jŠÒ˜Ä›‹}èæ•þŨÃ@k¥!È—9ô &ææºAbh¶p5ÒV.¥·±wŠÚtUöÕé';ûöjþ¡@D>{::Ê­¥N‰ÎoCFÌåÌìKéĬßêë@Ï¿¨×©ì½t/ñן(ãaãßw ª( +ˆzï…'Q8i†¬@Np!Öʦƒ”=vJ[™Ó¤ÃJÁ„!æ¶ÒZ@VȽ‘ès“‘{*»×1¡՞°Ò€Õ>Ùù–];1 OH±qááJFSáCÚBUBÇä æðª«Ä å½F¡«·!Ê(aí´@;2ª±d š6¨‰Öú¿ÆÐ¢E‹û÷ïSÙ´^ŽJN+íaF/z¼O¡iÏÍËv{Yæg´uyßEÿÆeß±4tl$<-Jý ,ÛxÃVt½ýÈI²yŒÒãØ {,_¯.d+5ì¥Ûeìž“éí\ŒmÕhLØ™¿áàâü Ÿ'h¿öŸaË78ûv¶Õ)†oDä¡'§7騾ﲿŽKÌž{ò6õ×#5#õÖ­´;îˆßt³ï²µ°^0dkŒ”T{²³áع7W£iSž2€1,¿[4Ñ–ZQöëˆæ1Ph¯ƒ'¡!)‡»ÃVC¹ÇR¡)²Û5i(*:,‰i Øä%DM+;ÎÇ U2¾¦åÉß3Ý`Ç:lãF´ÇºYÑE¶å`è¹qÅ4¤‡Þº55†ÿHwôˆfeÏ î»l°Ô‰)V”D㼃aŒe Xñ‹‰QÖ…HLm€)¬\½šaê;º;2 –}c‹º}ÿ»£?wugï:†©Ïèî `-!ɺ¶cûsr#>%»“þg%UÃÓcï³[·_P œ¸ÿŸ`ÓúžUÏy×÷µtl6»¤¤DZbp8AAATFü}‰Á’–ñãÇŽ•ù©Û‚׿ÁhÝ”[™?¬%莡É[+u(ˆºÈa,Ô0oÚ€6_{†Õ³Á•õë×8P¶5YÆ ¿1¾=ÁGA†lß¾t>œJ?µÆøãѸqãgÏžÉne¬¨Ïâù0åVWžd)šj$=+~»}›-ýÁûA‘Ë/žmæÜéøC¦ùÉÞSÇÁÎâ½beh§– Ÿ9fÔÈ5Ñk&MŽTª–6¶um”ÑÌ5äÈü‰ðÁ)£Göjĵõr;ðÁÆS”p%ùQŸyÑ#'ÎâÐË—.Å÷×fÑåu ΰFY@”8Mœû4ÃS~Ðk!0fRĨÛH!àççGÞʳâw²þqj‚¦Vll¸`%±#€˜2ñꀦb†!cêѤ=)ŽdlfBÿ5ÑëàuÙÒ¹òÑœ»\Šfÿ‡›ÇÜ®[.µY/ÓÚ‘M L YaX[c11¾fffiii¤ÛŠ•&àÿ™aû‰ QM©rüÒsLæF.’·ÿ cÅï aFF.GMSƒQ‚üĵgŸsiJúÚ0Å$ F>`¾OÏ/”`­)M}] kœ¥Ã ©Ÿ½ ß]¶gå Cs¼zC¥ê “ýeÊ˦¹|3g7\"D§á¨)åçKSþ͇<òÙ‚lÙñ13>¿,ä¾{þnpç_0½[ˆQëç˜Ìž={î\i .XE©õ”ô¤"Á»95–%8ù§iUÙ[èØ#ãlþ‘šC(EU>Ùí¤‡‹ce§á(ËRÞ‚C>+aSMô¢F¿fÑC½iJÕÄ9&®®®ÉÉÉ•H2VÔ¡¶Jý1†P‡æPĨ ™‰.òŒàºß@¢Œ!PĨë’úÿÜ£ÏI÷IÝl¼“´ñ¿Dõ£}êµ1„Ú>Né'¥9Uc|e'ý¤öðç>, œa¸'K]£Ô¾³a\ÄË^&礷Fñ©ÆVs_ƒóQ©ÖÞš/2MÔzm5Uk0UûO,ùP²bcüŠY‚××BV%Ih'ðBV9¶nIî‹+„ñ€©õ\¾ ú54w±“[>#¹²ÀWTl7îDì8i(íÞÈjšM¨!\›!Ì,ÁÆ”o„ѱȗ½"-D¤*1€Ï,‹}[rô,`OºÈÆ´”[(xóVì<éÈÐŒe×ßèÑÁ7˜²b«Žêu'ýÎM) œeò&ö¥wˆù?ËRAg´åýî×e·@b¦í¨·ø#¶vR}ñÆ2Ò(ñ¦ÈÛ®¦’åÓþ€€©Ç®Ìà}Üà?ñ˜àN¹5º áÝ}—ò÷ã<·÷Ê–ðaìyŽ;ãhÆ:’˜ÖÝÛL&ÉîŸØÚˆýª—…v6dTßlÂO^\Ús´:N ûÍ1e EĺÀ»EX@J,2ÀÕ—"°òÖ}–;£c–@ƒÁævÆØ‰ ¥y t=õ:•y~CbT:³Ç(-gl=‰ô”.è"o{TFžSuÐ!BѸVͱB;à¼:-nvå´\Æhå¦Z®Ì²VÀÑ ud!+äÌ&,튖™™(b&ŠÒPVƒ¯›M¨ñ.‹à+·ìË9 eIMVt:l8 MØŽ@VЗ³Yo»¸Á‡4¨>ÆÂáCEn¾ I‡‹{úsÉ’Ì\IåêÊ×jƒM Õ1þé–š…€£xú¶8ëhºUoã‚£oÛM3+,.>¾øäŒàî[N3-ÀdÃrîÜ’L·É†0çi¦7nÙ7Çqˆ4d/¸ŸÁ±Ö?·àM“ÉÆÏÒ%ºš˜¾šÜ+ªƒ’»U)XVò1–­ÓKün]»ý±éË»DEßJ8˜±a.)I_Å6EK-OOôõZ~ /ùgWø¸ UüKO‹\-™ÃÉ£Æø{æonôz:»äè…ÈqñÍt™D œì¼’ó%ôN“\aä{Ÿí9>øi>“Ü!Ht${ÅàóÝìÛÿá“âÆ£ tÀf}v…”WUÂŒ¹ 4;—¥¢èÄK‰óøö¯Ï ®* ¿?³%ÛwˆÚ‹",mû#ô$÷ꣿ2ËÅ0ïÎS†™†°ÉHsظ‚5½÷,3RÅÿæÙë@q!à*RĨ=üÐ8L2P¶Qƒ¦…Š"˜§IßÎe[A9(½ZÑA+¢êhŠš"Š\.Y“pl˦@Ø\ÏYƲìíˆ"°,Žh=)`hI«üŠê€ ³± »tý! Ì܃™tdS–e!+а[“uˆ«%ú™9… ™ƒ@û1dÆÈÔUØò{Yƒf¢W´(ÏE˜ü+~š¶êЖû ­J)~¦ü±DY~2°ñ‹ª…¦  )q,†eôÓüÇCOŽk{™ŠÊ³Q‹¬ø}šR¥¸øÁªŒÖãOÎËph-¼›FSéjkê›±oÚ„ì\LU!>¦¸™ðsÓÑæ7_áv¥@,,ÀPSãã¡´çO¬R ûîÊ4ÍafêwÞœ¾(òöSKc(7³ ×Ì7çÞ7Ô~vܱÉ#œÚ¾ûç¹¢jïͰíTnÜ@½Ýž7š—F7Ÿ~6­7SÂC1ǦL´™}ouˆ»¦ì:/#i;iá|J¡…©¢Æþ'OêÒ7ø%£SóÆ5ÒD9¾ð}×éz‚E5  ~g¡~;®sZFlšAˆÙ[€µ«ÒŒ& À™‹"/CÉQV#P5ŽmD—1ݮ٢ôO Síó _[9³/ž+vnøZœÞe°[KµàÊ[%'ÃZ\hòûƒ…Ñ!+:ÀŠ(ãËüíB“mDIæ? Ö1hªÕÎm”ÿé:~f:enÛñD7×ÉÈÏ ýmVƒß¬ Yj¥¡¾M™¿¼qƒ IÝa':̈–i耬mL§Å’ò"H«„™X›ìèí†þ6¯±/‡¬@Õ©®t‡ ?iYYªVQ»Z¢”'Ó©š®d¶3E‹ݧ#•¸Hü¦J”œ~½¡½úAŒZ·® üwc¿õå8¥?‘qqq@Þ§¸¸XþV>´Ò¶¸oì’óò’¼ª|à§üm¥ JçYU US“žûø½k«Ølö×n+½ÂÜÜük¿N>YªŸb²x¦NJÞæää|#(bÔ™×Àúw@½.heô¦@íÇ @"Fmááë^a{b6é±pa§·Æx…¢,ÀÐý$ª pänn»O ;„Ê$8¸K¿P ü˜ÿüzò•Ï$1쥄vƒ<¼ôw––Ó‹P¿%,ŒJ^Šõ0¯ÃkPØi¯&”ÈÍ ]xÑ&’<ÀV•ÜÞPI0 ”›öð©¸ã! lbJJ t¤¦¦RiKƒ‚?Æ0ÌÇÇG¾ÿM"F}ÅOÜý7gΜŸá>KãWâ{÷3 æ‹$hYá—þU?²1/p¨Ê÷~˜‹}¢ˆQWqö¾¸} ´Øäô?"¯ÖŒ¸ˆWò¡ùŸ…‚ü¤×2JHJÄ©;Ó‘Þž½'noC—ÑælDªk—i©."Õ“ØŽò5.Q ˆQ§ÑN© n~nàL­¢¸9Y‘fÄÚR„¤UiIozO7Š‹HCË%qÉþ…¯§ÞL“Ø™¡ ¥áûO'î0€ˆ‰¥vŸmþ}~í#Šþ;¸ª3Ñ".Ž©JàÔ"ËxØŽòg¶-È=$f¤<$¼ÚI·^™³lQª¥>¼xTÜŽB¡öˆ‘_tOYÁæl–¤½†VocâÅþÝ#€D´kšqÿ•—/$ìºôìÜòeW‡€ÄÎ1É<ž+ŸN¿ØØ`Z6W‚ƒ£ßûu~¹vÕ#pòÂ>ÝàitOËQñ¤ðÍÛÛ[™5wëÎçŸý§œž"'ÌçÇͱï…JÜh·ÕœºŸÄ§ç¥µŸ O£‰öo(aåäq˜LsRAWÓO9xûæô,!xòZÒV³—ÀÂ^‚©*œzgdÉiä§óºs^\„Àf%.Íô­R”^Ä?&‚1h1‡:YÐÐf Çó   Æfß]™ö¹ˆÆ¤ãÆ£LŸ®ÊÀ6æ4I¦r|M£ÏÖÔ½¡6{úó‚6o[p[F“Ç+ÿZÑßÛ“<&«ï‚Ûµtž½+Ú8#V'û°Ec–¯\š”)ñТ5²×#p¬IÎíí§ø§r[èÜ[ËjNñùc/4[à ÛÏ/z¸æ40Þ—·tÁtòÀ²J·o+±}ƒ±ÚÔ‹$öš…Jö‰ŸÆɶªÁLoƒ––âLŒÈ¯Ê²&û4“…€djq5®Ü§›í‹L5j§Óq¦)Iftô †á¥bq°¥tu0sb烼0…š"ÆÞPTGí@5À d×ÔÖº9àó“*‰ÅÆo—¹åÎ~Ã’âV“®äØéL'Ý«•€3ŠPÁz˜LØ)Iº;§µÂ—ÂKë]Bg<)›eÝþ¤``Ë1—fl€‹Å8~dñkÝ{¼Æ­gX3…ÂLµG;^·› »o»‡(\~Êôì¢$,…9Ÿx„ ÐÝMéêj O›k欓vé#¼*Pôô3|öÉþ·œ¡ÑNËY·¾.ÿÂgX½<ÎÁºM7£˜QƒÄˆù·ôÑûR˜;7>,¼÷Aô—§j%…—2]õ®Ú+2€0ó²Z°›R! )ã@øñèðÌ•fÁ+þœÄ­°ZÞã«b£¿ "OMê‚.¥Q¡ëTïªbóªêYfS™¼VˆÖ¢-ïC­G|È \r/nмÀtg-´EôÐÕ0ÔH ª{¦n·ÍºTzSø]‰áçÛÛpÒæµ.ʽÚ{hO9X‰>;9y`ôòäõãí¹¬FTSø#ˆqèØ>ÒqàlR• §NÁëúð`*q)üAÄ ð§!22Rß§fV…µþùVX¿«AVú.1(P¨ÉCü.ž®ï/üt-vâÊ ûB'$(µm9Ÿ5G§Û¦‚k³ï$<4÷mùîìC0&®RÑøGošÙŒ·Lõ±4ÊØÄ´Ò¹ãtí>aÛ $ÁÐ!…KRÎ<4ß§C‚; ƒŽ¶ßa'OZ¹ôVä‰ þÎůsÌÂt4ˆQƳ™Åíµ¤»®Ýyîçùç)åý*\ 祗€UѨŠ$àÜØÉCV¹8Õ»ÝôÅtPrKðp'§å²g65¶ )¾1”k3Bðh§U_±Uf#ÏÔŒö ±¸}W®½èÔÒ,·tNs=±\]ùº@Ä gÐ|¦!K%9"p+Eܾ9]˜™ÃÔR‘dæ‘6àt†™¤§I:´DkÉJ2sÒ$ª÷ârL‹s&ã'²^™ÚŽ¡;Q7cÏ òøÖMð¿’ã\q:±‘tBÑߟt¡)§¦,ÐFœ“§’ÁþÒBfÙÙI#Wh9ýHKÂå¶,Ò ýßà äL7ÊXA±â×Bf†æ!+ÿâD©'ÛžÓe’\{dRžÓ*ú[ñÊlä•™cƒ©ãl)‹èœ ÆÝH¨1dÊ–„õ7ypÕ¥ÖÀØZj–0Â1ê2ƒqÕ9fä{šR’ÿÁcÝ Œ†¬Ùº|UÊk‹QMþn=jÁ¨ˆ3½'ú»¿‰â42tÑUfÚž@m(S €|–MZ饵“ ÏÒ™ C|Tï·òM)X7*ìÀÎEÃ]Í{¼Ï–Ñ3f-;%¯­ŸÂµÕ¡]¼;çµ§…¹î­uƒöœš2¨«§†‡ê†®ºP2pÙ9Sb©‚èCsqÁó53§÷ô,ñÄ*>=v’C½ÉõS'¬m†±é8:[W¼sc8”yÎl½h•­)Tçœøï!M-þàÒ9w™ÃP¡¾}²% 4¦ÁËÆ™]ËljI¡‰B,çÑkàŸuˤ³×–ŠÀs÷&yùÑ+ȘYŽÃW¡¿mÁAi(tÓÖò™2RRÆi4vYŽsÀ Cž‰Cr­.iš àhõ.MŸ!<0 µÑŸ¤Ã‰G(P¨·Ä€™¸C·P}mím›Ú»ö‹^>áU{ï¡7ÎlElÀ%­Û‡Ò0€AžHÔ¹ø©Ã1 :]$wž•ObñÔIA=¼y4£T x^CK‡‹^:»r…N§èA¡žÖ¸8+¿@‰«ˆá¸à%‚Râ´L$ttŠiÚ¥ÓÑl&¬,°¶žý<»„^ø{‡g—¹…‚[ç÷æ–àÞ¾cÝíÛhh(´õú÷Á5:êÜ=Îe~ÎÓÑR„Ô•0mûÔw½–·•ž"Áãñø|þÞU¡T`zt|'=2ˆô>cePÇ62yYTa»“BL˜”š)ÔX±nžÙ [E°9t/:D»|v3ƒ¹•Ìy¨¡Dƒm-vüÀêöÝ&à˜$G„Ý<Gg04™ fåhoÿñ·’¶À(Ô”X±¸Oϰjg’Äç“oº±ª÷ðWkÖwEÇ ‡˜¼”ä))sP P³ÄÀ€¸¹³Ÿ"~ír¼½ÛÀ!>ÃB{·v ¾q~›ˆC$¦½ùÀ ã§ûOtwjŽK踘)3necÝXÄÀ%¸ÄÝ¡‘W[,ž86( ‡¾û ûq±ÛG€®‹ä¾unkð€ýÛ (¥R¨ÍηضYSkë†ÀŠò=<\aa_*)fÂNÑÂpZPÿ饴|€+ÏžÔ·—¯ô‰Kì“/Áh4¼T‚Ѱ% &/À±Gÿí7bv䲨”Ë»`%Sý/–”æ»zv>u±rÀj4ðÅÈù `¥T µI æ®M asIŒKî\:$4˜›Søûð²òö7®œÛÂa`-œ{oܺ/ [GØÖ‚Âb¬˜.Q€ÕÆÒU[„Å9èˆQ ƤIZ43»“´³©ÛrĪbõD‰¿úÃ:t>y‘¯ø•ðÜjí{S¥PËoдm_.Ÿ´µE»o‡óÆ7ux%q»š2jù‹%¥¨8Çñ»—â­yƒÅ@Œ‰K›¦m½Fm[?çÂÅ«;]¾õD ,Ûps4Y8g¢W×Áÿcï:¢8ºðì^áèHï (öÈ""¢"Š;+Öv¬Ø¢b 6Å®(¬F{E‚¨€ŠôzÜÝî?{{bI~1¢ó%.³SÞÎÎÍ7oÞ쌇Ñ#¼5ª9Çlð­Án€¸D?¶â àu’I&äÍ œ{ÎB¦··1¨³ÆX[™²)¼]3Û%s&’¤ÈÜHME‰PÂuµU}T54#„¦zXÐØ¹›×/ü}åì«Wïù UUR¹Ÿ¼ ‡j#ÿ±ÃÅk˜‹ç¨¶­oÝ8¯®§ágcgK—8&DÒÞZÁɉKùž³‰Ó åÇ R+þã}½KzûƧH’<±ÿw¦­ÇëlâïÅ¢(ŠÅâž8° Çèÿ iœ;µ|ô眾ÃÍÀaâôVœ¶<(ð‘­§Í»DWyŸ¥IÕõWïHœîø±Ñ'¤7¾¥Q]ƒ%_«±Z_åp( “Æ©ÄfÕþ’À’Þ¡¡ÁãK!`Ž›§|nKÅ/OÆwŸEœ_€ˆyÜÖ4áHKIçŠÌ¸–\ÄGné$Tevn`ô±œ’b€³>.¡†¨/É­3p ±Õ DŒ>4Ald=׈Ín_óÇéÅIN9Sç{Œ'ή­Š9(èU¹ùŒq\@•Ì}lCx;”ÏÑ2"ym—P©x|ßXÍ»^ZY=ß ã ÜÉ10§å‹U°48˜ëdÆIÇw[OÀ$ ü5Al+•ª€w³ L»@ ¤ U`fø.‘,{z6D—°«ÁÚù–ÁwÓ¥5Ú,ƒ~0ôè[må‹ðO‰¡øZØÓH<Î^ñ,^uð&®1þÈéµ}ï•Øéü@uÁ$½5@÷¨xð¶µ ’VÓ%™!ˆù7 ØN'YÕ•9V!v ¼î'|ൿ«?±U „Äø–Ø0õ…ÈÈÈðpTW$FÄ@@@ã{GÿÕïMÔåóc "ðѨ‚tLÃÐ_âkĬ3áÍ2КG¼ö<~¬Ýb¿ÅN u>!‡ÄÔÅ—SÇäå D@Ĩ/llöÌ)M&òc÷°¢Ç…hù÷Ê>œhЯ§Oȃ£ëšËÇo.©œçJ~kW\®f £Ç…í-0ë–ëýcC÷ÓA£¼1ì]“8x<%K·_D§î<-g6 5ÔÖü󽸽6«%}T9h¤{ïü>%û®j÷âõì쨒ǯ‘¡®¦¡.€þ£‚lNýK½÷ ìu«ØoÿP4t»ž'îñKã1{›ôöëPq6õ¯×²‡òXœV†œs¯…Mzö€A»Ïäðñ½ù(8Ä€ûÅúÂÁË]ïÏíi9$Æ¢–èZ8á&ˆy4ÖvÝ»ñõØ)oEðA×’_k6npZ˹rĆVWLÍ ?×ÌëÁ¥Gw_ñêÂ$ïÖÖꪙ™É .Kz§³'̺¬.y©ŽÖš9bWNrœ,° rDÀ^Ÿ0pW‹¯xñ™Ð½3L{>UÜËö*+a)èjÂòA£AAIö£à_I?*ÐÃIâ)éGAVÈG„µŸþÓ¡ö&ŒPð`æ8ÇoÞ¼i«I§ÌÌ<÷r-?’t<`<c是yl}×O+‹»ìÕ°W"ö£$w’+Ç^4$K™GCVÀ«3}õrR#9«Êº›»ú5w•ú3ÉtÙÀktŒpeÊà ^™—êCÏ›!ÿ::PL#:û®°%9ñUóitù b4$÷nüµD :tçÎ...ß&çŠ\¼qïàŸüçCÄhرc$ÆþýûQQ b Ô€——*DŒ17¿š¨ÞóN|EiÁ­å:NŠ=k}ÒÐoZ^žßKÕ}ŒÏ{²¾'°!b |7 ¾£Ó¬1È24ß&â¿?˼Œ¹{Ò_èéó=™[¥/ØÆ­X TYŸ—¬„#b ÔY. UuÝY’2\Åyû¡5»ûOt7£Ü4=LÁy-I~Óœ”üñZåãÒ?_+·7¾½.­Eˆå¡ð pïp“ûi”QV\Õmþ•¬Ôwœ—¯ñ¾n‚Ó7¸eiEÖµž=$ÆUgÊxþ\Üc–åÑð4]…Fª¸øäŽœ¢Œ²€HK™(Y(÷qÖ‘#¢~ÃU®ý!Ê|XiŒˆ …ǸÁ âªƒYG`¶ºŒü/sb9Æ’]YiÆ´ëzJÀÁAìÐVz{æ,¬¸†Øâ4Œ­è=T;)¼¨«ú³‹iTè¿Y(ÊT™â‚ó3 4È :LN²,´ß@nÀ\S2¯øMfù7c"Æ÷ % zÊàÉøg~Î’{^ûÛi%CÔzìøºúìlv¶mgÞ®lÜ^rV4‡[I®°°% kÜÒ¬}UÚ|Ás+1¥N~ªùÅ1? êŠ#áiò¢d¡ ‹þèþ&ƒôdty~šÓ\KDŒŸ,³Pxõ‹¦m 5ºSŽ·²T–4+ÚÍûšFaa¡††Æ§˜ÓÒ^ÿJ×H‰yÀâ —§@ëi´§ìÖo:ϑҺë&qD֨ʌßÈ„*t4RÅø’ºÞ'²†(Y(°¥wõ5lE#úÍXˆñó«?þœ9swJJ ó}}Ö¬Y .üZÏŠƒÚ€a»­¾ï@¥Q>ˆß•°%¼›-|°óà °€}tÌ%eF7çEñW¾~=µàȯújì¦c–±Ô™ÐcÓC¼—®û0EÕñ @.˜üð‰NNN—/_†yu‘™™É8îß¿4è:í9ËRCrÜÀ»R «,§jî©;¨ÉˬAFiŠHïÿe¬8_ìÞ‚Ö,÷¢Ó‹K©W• `–AÜ¢l‰uNsÌÝÝãÇ7·è¶3ÊwÆxs&j°ºÿ–æ¼JIç!÷ÒÐógs”…Æ=—Ñ,¿Üéo:<±m[;Ðr#àØUd]a©ò],®ë*ïÂ¥$ îz:ª3Ë-*rò´|¥È’ãQAXž¶ëp—tv÷‡;³l"|‡·û0CDÕñêOž<‘yvèÐ!??_F•õI °.^z%î`tuÕ+Q¦ZJØí×T¬ „ºy¬P˜Pè1Z×R9¸¾Ä;Hã]¦«\MP1Å%”† vpUž³Q‘î`Ú°S€‘ÝBh¡ÊOG½ï:B‘e¬}pe®“a±bó:KæäÀ†B‰ó[ å"b|#h©uÐ’°¢[Øn)]˜ ×þ®ÒhÎKÎT§áÐ ëx†ªî¼%&‡ØÒIäôÏY!‹p…^3ã™›ðÿE'?›13³êó,,,>ìyͶ¼¿3ÃÄ\]—‘ªˆ“»ÍLà k3ZYbOÓÙ¸®zò©’žÔÓ7ÔÃ/_q=ƒéÄñQ}ÃÌ`´~3Í{z[9úŒÀø¨—Œ„sk_ºÐ¹þ8Žk*‰ÎîåÍ»òD»tqºRoSó슣͋×fDš‹åÃiýòsU'+ü=ˆÀ4’ºÕ‡-ÁÆÖ½¹Ê'"|E0½ –A4yÌ|«ýau‡W¦Cãâ¥.åaducY!‹¦h«ÙÉVêï;ÔqtO;Ú¶ mÜ÷ ¥¿v± ‡ôÕ<¦Ðiõ$X ŠLN +ñ〶–œ½„e×-ÕS_”à ¾q¦'¯ÝÛ{îï–®÷›½ôL¤§Ûo§“WpÝvp^ ïo±âìÍ,÷csWy/ZröÀÁœ«[<}øÏ/ÿUxüY‰WÖ‹ÄShåCåÜ·pSß_Ý|çä |âf¡gþé‰<¿…ñCü$œù+À3|žªß—$)€KûQé%À¢sÅBÀâÈîîF§7e¦ òýžx†ˆñmÇ‚)‘® Ï]½[ˆáÜÞ›nعìl›c73* +(@BVH;ÓT%»×'yôóɾ3—­¬*®¶O<¶û–ßÄò’.ßµoñ™³mâfåèŠÃ\ž¹v¯²‚n¤oâ¼ú~52¯ðìÆR ÍJÛ±tìì-QÉÙ×½f˜Ÿ[÷Ú¹Pé žÎaeÀõœkDQØ…è7ÎnäÙÔ-‡×oœ"ÆOÆr€½Ÿet‡çÊý\s3 ¬Ê6Ðq]EwK´¸–Z y¤í(Ë`$¼ö\º‰¹mýÛiɤXÚÓoˆc ¾ID ˜M¯)X$fõt”û:ÁÒ¬÷Ξ¶†ç顺°pdGºäb\Õ+«6`ZN2oÉô¸~‘t̾3V bÔ/8™-çÚRëûÉ$ÚÇ ã[cx˯×Ã0ê›ÏÊç¶ó;-Y7D „ï_c¬Zµª¨¨è?Ï4Ú~áû"dEëÖ­Q©! bükPŦ\òlõiñ$_[TÐ?1 ®oÕh;²ðævõÖÃJßßãh;ì[¿Â¾ïXk}Åe¿F½d1£¢¢Ô¸Àyð¤f:ÜUK£š¹ôp4f’ìX³\Ù¼Ý oç䣻ä)Œá»òH:ÆbMò6E?3–ÏçË&8!4,åª9˜Šs†Œ›‚Q1Z)ÁMåcŒ™¶RbzØ„Ðñ÷ö¯Žatªœ?`¼Žç8û vàv%̸ê~!P5$…:± ’öLP\¯ªPžtIòG—`Š(pte”Ïä°ÂR M‚)Ú進´SJfÒy ­Ô°³ªzèça@’$äFtt4*ІD 6#`)4 I•H½mk—9öo^WÅÞ¼z©SÐd»FdTÔòé¡CN¿ªloDÏ1ý}U”ŠYÛ!–Z) »oe‰'Š~yÀ~*„†×• c˜}ÇOcn=BÂ.]¸ –‹4qzU’©ðêi"õ;I*Á¥÷`f‹Ö°‘ítÉ ²‹¿š´Á«RêiÃ5„o`cÔ×.]dî.rn„š•€k¶|ϣƭŒxêJ8xÁ –F¨%°¢{E/Ÿ»ð&G¤ê0|H« œÌ»¶ssж"×{BèßÀF2[G@¨Â;Æ-þû/ž–æúó:¼Š¼±!=~°B]q,p²óÉ ¼Æ.ÿú’§Ô1b»òdàd´ûí7Ö”h¨Ó[¥ª¸d:dN¾äBalÎ E{^áòJRA #0‡§Ð઼ƒ×nÈWÕo¢€IÂèR½õ°íåOZFr:6äâ (¶&P¬ƒkc mÚeže` Øc®^©cP=]v-(!Y[”}90šˆ õä‚Rÿhb÷imMn÷ß. åë5µu±%a*_Ó¾ÇÄõ2ãü…n”²r§Ð4Bù!ÌÕplûF­fü›t÷øÔéÀè¨Þ×?1¸ôB-6èfUµ ^ÞUˆ¶5ÔÔ›:L£Gk]*ȱ4;Œ˜ÜqOš$ó‡tÂÔ÷ðvV,Û3eZÈQÐT±È­»-a}–o£Ûõ¶Þ€[=³XÂ3KºyxiIê1IbÏ«>ô¤Ÿâ²¦ö†n9VÐh>ã’ $¥–Öx¤àf`ôiIJ=ÚÚv x|j=ªôßÔÆˆŠŠb«Nû™–n]Ù~ää'À–WÝ‹{&°VV ©¶¡ÑðYW’@{ 0C 9¶+óûÀ¦ÝG»¥éG¹æß•„ u¤ý “ Œ&`ïóaލwræ•W(8î^+áßÙ‚ÖÆ Ö¦J™5Ú, z¯„Òk@±ªèÿ¥ñMqËíUjÚoÛŠ81`‘,^Ÿþ{Of„zë—=: ý—oú«¥¨úûÃ+VõIÉwÔÁ9£ o`ê­aHeÕ^ š’ýÅ aœAŸÐ0”fEf]“m¥“#ì螘$ÌšŽf:ìfãi#AS]!0ºö÷o;ú ÀT“H¦…3qè_W¹¼J /™?·#FcÿI>o0ãÕ«7©bª`ÁJiÛšÑA¢¢v†…Bÿ€¶ZÏRk/ó2e ÔMÆp\ÇD¯Û4!fÅêµk'Žÿc½àÖØ»î3nßAÍþi+ÊìÝ ¢“?éâ²¾œ}B#QEÿψÑǶï´59qâ˜ZAaaCeþÆ’¥ŒL? «2Qè~”52šIò#±Z½ýVJ¬æSpü=Ðd”³ìBVxã¸zéL³·GGèùl“ Äè¶Ÿ*a*ð'ä|dSÎÓâQÿÄ@ !þe'“¢7»‘QÑXS|6…ç»8{lî7iÀhZˆ3¢Yf¡ñS÷].ÝõÓèxmÿÞÜ/]MNäõLÜËÒîMK°5橱(Ãè³èEÙŸw3;~ãžfÏ»MÚ¾eŽöà“0Z{sÞÕËvt‚=7L˜{£å›_$h¤¦€~‹z!Fddä÷0•­gÏž «”s …WVø‹)ƒ ÍqâþYþ‹úøg 4Œ•Ž. ±ê?$uþD;[póÞ»Ööº•€[5.qvRHy8ÙšÇp`v_(¡ˆ÷Ì=üÌÙ=ý&ÂX>}±ëo—€‡’±&œý["‰Ö~ñúW‰áíNšÝÓw2­±Ï.öñ_| ÕøÿÀøF¨Œ½kº¨ºWY¯JÍÇ2#Óf3èÑØs«G«˜]?¬ƒŽÃk7;‰—t‹)VŽRs—æt¡wñ^¶•i7¤q–œ®Ž ŠXñŸƒ^Ÿ”uhÅCmß¾¥°¢¢¢d“© 2*ÙãMQQëÃÂÆýøå-ü[P¡÷†¥FÛÂ'‰³WÊvǸö¢¢ƒqfÊœ±Ì¾ÎÐgOTŒIþaÙ¾§o1[ÖÖÆ…CÛÌÞù±^ܧö{FøêÄ_Ÿ”´u)dØÊ¨5°;}‘.²¶®±)KÅ“=¿3–C„dÇra6¼¤F¹ßÈq8 `Ù%zÞEg3û:C‡»Q“|©ˆÉ@·lCèc‹½gƪ2né¼F•Ï‹È{óC-ÕS­f“mðm•’û‰'Ïæø/< £„-@5þ[j Ì~X§2#,l‚DcS%àÚJ·F kò¨~‚gq ÖέméõVM€¦ “V›Œ5…cCVбiQ&T¾hÒ„žÍ~6KèaÈièåÌ•t~ª÷ñWrí¹Ôþµ«ŠÔѶ&6òû:ë >!›¼«;­.¥BÓ¬ K–+«îVËÖÔþa´|U]}™£+¾18Šôýìþ;hÓß,8º (ˆ²Ûè3-Ú·P1èÚé}#YUŠ>~ÅRȇ5PWp ‹( &|¸ÆnÞæª Ð…ÐPˆ¡ÜœžýÑzÝ´K–a(Òc#UÉ2 ù˜2CÁ:^é]%æG³*-ð2æ€)t´ ’Èj-\z­†jõ”Ć^¿ŽœŠŠŠ}ûö1‚¢PûÐðG¥#¡1þV­Z5iÒ$7|øpH T Š•Q«â>¬úµ|^•Q&J˜¬+Eæ]ciJg×¾tiçÅô)ã†ÿLÅNO;ùkr‹Ù‹z”‡M^µ~Әѣ×mX4v̲^+„ojn˜z#K²àªzæ-ès䵰甕¬Ü‹¨rÿÇÄ`>SܼvÀðñ»¶lìÛ–ž¸fÍÄ !+7j¥ü¶‰%~|ëš,M6Œ½nÓDfBÆfÌnÕ—Ù¤ž™;8nͺBF仨ð&ÌOŠö@ü–®ôˆ*RgŽÝÒÉùéÛRhm±1ú¸G—îmoêYÛ†,¢µÄ†-÷ßÈ4†P&ä]âèщá%1UÀ¢u¥›æ@ËmtcŒsqC\—9QýþïˆÁ5czM¾A´º2J:ƒpâ„ ð:ùWiÃÖ´jž53MP~¡’†Ó'i*ÉÜAÈ xuTÇ¿Í1„ÿ0À’ÃZ7éþâÅ è4hD-Ћ] ]F1Š•!Ϩ–öAUntHÔsKGfbÎqrq`Ï UîïÂø>ò¢ÒUD4²þÌvÌB%1U5J[×B%ðs|¬õ÷÷ß¿?à „yTj×]áù[wþQ¢*Ö"‹Ä9þúoŽ{:©»øÞEè/Tsê$s|& gž3 •JJJ`·á›1]t¡Š  oàô±Öx?ä‰&©©©ðjggYêßO z=†¹üÅ'¶­á?u =ž¯Ñֲʟž '¿C… ¬Aañ9è#¸dÉ8øYÁ¨H Tí~.ñÿ@½Uà\Ê7~úô)R?,1ÐB¥„‚‚‚“'O8²•Ò`ذa;vìÐÐЀ¬@¥ˆd* D zªßöíÛÇŒYñüÔä wÌÍ'¶Weg뵘¶oɸûÉåK£&·‰\qæma©>׿·µS·<(ÙèŒ9u_eã–Ó‹ Žûß±á#ç­Ø¾lAȰ¶0ò¼¥Ë§†-žØ Љâb«–/›:+bÙ¢bõÔf®÷fØ÷nº;­r°é; *¼& .åjë)6{±yÖ†àèÕŷ׫¶‡ˆÑ0 ›êYñƒ½Úˆá-O\Í¡](!K$ÄXܶékÜ¢f“ï/Ì[2kù„ÕÅ̘µÙ"Q ÝÞ™½·sÄø2‡ðÛž¬ ›#’D.¾¾jyÔìY‡a˜ÞÓÖ=jù¢ çQC¦3ß ‹óMN¥óã¨ÀÇÎvÕÚ”ZÄåL~T[}»™”ˆÿ¦¦¦/_¾„¬øQ_0yîü°eséZbHÏ\˜»v];µéo¸¸ä:uÝ|xÝýýåãȾò®E¿È–DVm;^×-êdËÒ%#öô?eÇu‹ ƒ¦¶W ,øW;­‚£[ÁÛã‘á½Â—"b|¿މ‰¬ø±_sœ„ŸÅ¨¨%ß&?ߌß51 ý:lذï*K{÷îíܹ³djñý] iGŒÛ°à”]1ÎC‚ežâª­]?†‹»¶uò™Žiö¥ºŽí1µ&¸dË‚:㘛›¿xñâ'{»‘ÐF“)pæZ+Âg‹†0 p kùÁņǖý"r%ˆñÏ³ëŒ –¡û²'Ÿ7à]ú_ºÆ†€c\@‚äkOs ñÝ­cvœ•€ÅÖ¢ÞêpAsGõ¦]Y8rA4ŒÓ-‚{7nè­ÃÏ;\ËÐH>ZÇÇÇÏSý0ú\Bê{ØNJ}ŠBQ±_›Í‹Å-[¶¼sç4f¾óá&’$!7¢££Q}EĨ÷ž ÄÝ»wJža? UVDŒÈÊräö¢¯%íõ³¼U§q¸R3p}ÒÐÿGZïVaÆšÖtü)È.þzñª”˜›_Ïø‚NÙÿY2õ‡÷„å7XôÓi ckMÔ" bH·©( Xù쮡úÒÛÑjßCÆ$'Õ'—‘¸þ¡ƒØ× “³NÖtÕ1w¶“blhõQöÍš[?|ðì칌¢T`täóëIׄõþC!z #¯m•¥ŠEnÝmcÏ«>ô᤟Ⲧö†îúf„Š+óLð¸' R/ýNSÔqá/" ±Åi8G1`®©ðI¶÷Pí¤ð¢6®êÏ.¦¼d3¸ ˆõ>æ$$&’Ì& GŸ²nT‹êƒe·¶-hû»âi¯¹â7;gàʼnóN{]yVžqæߦ;PreÒcb*Ý7Žâ=ó€RÆçÒ4g¨ „Ö1õª´f¨dîÆÀh¾ÒÃQ%îä<Ì+¯Pp"Üý¼”Nw“&öP¿‚”¬Bß¾ª¨Z]QÄü4¨œ„§}ŸÕèÔ*t…çÀš¢]ý|iÈ, ¹[Ú‡×ÜH+‚ê‚nȇ[ÖkÞO¤Ïíîd­Ø)¤;t.šü@£ƒ9­j|º™ƒntÇIÖ}ò«ËÒð¯8ƒþà ´5Óa7OOÄÐTWø6V d]¤‘&Ì­¬/Ê8üªn9¶tQ»Ineqú0·ß™ÐB¥Á­±vÝG倈A£Ö—ï+ Ó^ ñ€óÚŠr`BG¤j»týÕÖ@x%êõ«Jº}‚6·ç,ËÓ‹ÒdÍÕùûb÷u,+xW t•¿æ “†}P¯Cê -¼q\½M¯Zž·ç»=Ȳ4š œ6)0:²B³ÿNòdàÓýòÏFø"ˆ2Þ“¦ÚGç§ùýfù±’'ßâÚ2ÿÜÛ™Z­Œ`wÒuòPù˜ä»EWŽ—xÍ‘[³!([”íiYgÇöëþ.?ÆÀq¿)z÷²xöú'çeµi&úë×\M lA‡–—U<+äµÐ?6?Ó{®É‡©! /½bÁ"Ú%¦Àí×Té!~ýže¬ý®Œz_Ò6dCáÆã,Ô wÞåáZ*Tq¹àué'Q§ñm:æŒÆ ï½óJÝÌŽç÷8~7áf§í?/éÚ\ n\Û¿7÷ÄKW“Ã;:µ¯!‹«.éP¥ìYv:Ôô4$]öª1ݲ«@ÉJ íâ§î»|·¬²J„«ÀGÂã-ÕS_åë©u¬û_R?̴駤„¨üBJDRbêÔæ ù’‡—ƒ«òœŠ »še¼ »¶¢Ï31bîd…\™ëdX|ýoSbPÖH|_€k«Ý8V0ºabV‡É6ä'>=/³Ûx5æq@CãêªW£Lu•1DŒº¨¡ªÈ³çY–©€a7V»ŽÅÙOè’J\ŸeÕWǶ…Aü’W¶VØíTQ+;¶Iú»³*(ãx@¤¹þrái^³-MH'+ºn¥,NWêmõ’¤Øù´÷ß[ù4ÑT>-È´ŸfÞ®#€Âo­}Ñy’ùùÇJÜÒr玀Wó_˜m‡Éçml¼þv‰Æù^C"ÎEú«úm¡JnüùˆgÕ¸ÄÙI!åáäÂÄðöN§aÎNFtsœ|®([àbúÖ–ª¯ýQq¿ùÌÛtIˆõàéMÈ7ñ:´6¶àæ½wïÞ–vïjñ×BZøÞ©n£ö´w!ß>ÄK¹_Gü ”‰dCô„F¦pd%oÍöô·rô 9˜ìœÀ×»^Nº½¼ñ+O´­¬òa‰=;ôªˆôëê‘…/,±Ç鬸¥}§›É·_ð­áO¬ˆã²ÇÝ‹}eb ®®ËhiŽˆQf2…‚õ™f\姪+t1'UÇ}g˜Êâë;ëI>/i0V)Ó}bXá=WÒÚÙWÅwf$(ö ­ê¿¹êVètuáÉö˜–Ä—ÀÅ–¶õ•šÿêB/a°§­ÿÌ´öv°NƒvÇ¡«›ý¥óŠ ©ôÕ`*Gy\ZoæÑi}f0"›v|íh´[A*|y¼ö\gØSº DþÿLéÁÆži±uõ@Í’×àhƒNô~ À‘UËïbMnÀ­˜2§wÑè3›þ]ä;g´dÅZ?1ó¸–A4Ì|‘ñOprAV~ê‡}íRAE®¡¬ ¿Wœ½%VRÇZŠòïÆ·¤¥lª*7ÆH\”ýi™ÿ'ŽM©>í»Î<)¨Ê˜¯,°ˆk™ž.4-Éw±¸®tìÓ· éÿ!„–ɱS?-ù«à^6e¥>Tª×NQ)é¥ã=ºN ’±À:ð¡9wp~¦×PµÅ^ÃnAÆ÷ÇÁår¿(òN½¼‚éõò”þ*•¤øÂúL¬€å9ÇððïïóÅv¡†?y8²eÍ&aÊÙ› z þ<•Ìéô /ò áõð’¸…xœÝ'¼p)2÷Hßd°¨oŸ&UyÎ=„åi÷\º.né<¥Ü‚fsÖ=ÑC˜¢„ÿ-+ÀóC¹mÃ;ÙU¹ÓÆZÚ ÿÇàb9V±ð‘í8· ®öôúªËž™Õ­ß2ÿßo™»ýÜÄøôl<Ô•j0(//G…€ˆQ¿(**JMM­¥7äç‰Ô úô­ §OŸ®6"kžeQ«Zײ¤åCkA93fÌøïXKΧo¯^½ú/^ü³%&ï¹dÉ’Zïõý×àzZæúýÃÅÅ¥>ÄzzzÖ_ž-,,þŸîâ§{;v¬ï2ÿwôFáŸ#...  aåùöíÛ­ZµB¿""Æ·…Ì\.¥3EúÉåcÊ­{*b[ÜÖj¢Wžž^ööaðp/fW} ¼:æó?Žaö=ÿzô2 yÌ¡»¥y :q7½_K³˜˜­@r¸Dpð×ßà ‹#b|;È>ÅY;yÇÆÄ ¦gjʸZiÙ•uÇ4ÿÅ{ëž?Ôl›¤W€ þ›cþܵyŸŠ}WÉL i¬¿rÅí´X¨x1*²ÿ<}3G1 —˳”£Co‰‰jÒÝÿ¬[Û@u³-Îwh€|LYÚû»b,‚ƒ50gÿ€¤;¹€ª”-ND¬@Ähذéài#qØ:ûÉa–U!ÒI~Á#jÅ„U>xÐ/´« Ùoh¼ì@/ =šö™5kV}t¥1êõúå»Y³fõ!Ùˆ ùùù5JNNFEˆP ===Tˆ?þxwnÏ“¯%MYY922òkIûÛè#b ÔwE/´ù_mÿÉÉ|'ÒP©"b4H|áÒÖ¡ŒÇ"Ó>Ünú+Õµð­ân&Ïáÿ]ºX¯Gº!b üc$,Js ¶0ÑÆæ§éñõ:¸V¯r>‘fÖݰM{ÞÙåé–L Xïoäž?^$[ $ÇPôîKïÿp#öõ«¼ÏxÃûÊųæšÆ-Ì 7C%ŒˆÑðð`MZïY´f¸¿:­÷\Kª¤D>´ÏL³´] µqש  ÆÐn£ÕÃBíD²°‡ ½ƒò½hZ±äžÈPlVÙ:и w²)ñúp{o©€p“Ú;–" b4HN(¤””)·žûÊ´N³-Ki¦PÌÖ˜°’ÿ‘Fþb )!dâ’ýöÅJVýi9 ôwq•."FƒEÓñ–G"ÓZ1o>Á2aašI7CǪS$:Í2 O˜etý5çýt›Afúú âØË;n†%I¯ ­gZN¦·©î7L°¸·ö¼Î,a{ÖOEÅŠˆñ}â­•måÖ{¶Ô-ìéñ´-ÑÖ€éR£Â-Ôœæƒ}µ].³Ñ[2f¦aŒ¥·$lÜcôÇ}ùFÄ@@@ÄønpýrI['•9T3º!QÏ-¨Ìòlu¨ÒRaNùùÝ•:þz"P‘+VÔgÿbMïôM¾/8»6O] WaVôF¬ Á²7Æî§‹ Y\ PN'LÚ^#äW²"¡^S§µäHJ²á>ÞHdLpÉSˆØò.9½á+c´3ÿ‘ÉÈ [}·|~Ý=‡®ºréØ*zÙ®Õ•Ïßt&åq¨óªTp† n”ËsgšZ1>Ykð¶ç»GXÚ¸£ÿ¯ƒùüÎAÜ}~aFøÙ’Lq1zá­RÅÝ£ad÷‹=v0Pºï:m—ñ¾ÁÞ[.ÊG>µ;ŠÏçŸK!üW>L˜Òìû/â¦íT¬Í·î£Ž‘8b’"+ik»<µ ¼Bú…‚ÅÆ¬[rÿ~*®îq4U+K€ËÃqŠƒaÂJÚJçá 4µ &”Dxÿžæ§ÖX#ºLò P¨º×#1:n::íþ k¿Øí¿t"u[¸¸0£ZÚmäL;pŽ ø#®Xësäz¸¾Hˆ1{¼öÿu˜/Ÿ+:TÂ’èÞF  ìölÇVü‰täö€HYk×¶Æ©û€¯„Õ‘éóS”yh¬€Pæ¿ñä}Xº”t%FE#%¼œªƒdÛèãÚžÕ[èJ=Û7‘:”Û)à)Iht÷}*¥×Ʀz©&Ù²_vË<ÅÍ Õöz#Fîىó/]¯]éóhVÔŒ<¶Ÿ;üŸq׊ÜÉtj×À šaEe~!WÒ–ŸžÿÚ\S(ò3ç(`ÄY·—Bõ¹g’ûÎ-|]ÞJÛÛ‹'¦õFUHG¢l(ô£^Å.5ò}¼Ödgy­S¼D¯ß³µQ]GÆ÷wŠø¥}‚ªô}ˆx°.#WsCOß`Î=K |g™ˆK…]g ÊèfU`ÓB\¸t&Uâú,óΊozÙ{´Æ‘…/$œŸÞ²þ§˜…%)Š.9B­O¨ú ê‹´Í÷an#7ï^üêuÜêä±¥;^‹* ˆß&¾¹~qÖì|!î¦yüÌäýiB]U¬¢XøªÅ„fVê~F?ïªeÙas2ûÁV.ÔWî3NU?ŠfÍ"<`®)ûvÑSrÆWó¦´éÂÛa"9Ë«-T¯­Ìäû[¸’ÜjõA –ªAÉ£DÀ³âJaÍþ´ª´ÂS8—Ga¸‡¹©ÞCõÍ1!»ì l§¹ïa íÀŸ>Ž c»Kdc|bà:=UtÀŽs´[ÏŒíòsôzxô “Þv¥Ï¾# h­„JáG·1D¯ïlü­eȶ:Ç^(|>¯ï™ä ¨ˆ~£ÛÜ•ÓU4;Oü#9«eˆ4hÖÊó‹&» Es›†¦K怶\z •/ÂOA ޹ßô5§KYÓcù˜e -ä‚ +èF.½ü'òrïëL?ü–&ZKý³v¥põ¥¡ ”Þ,lCØ }Þ*q?Ú:ág¶111ªs³~åg'FBÛl}ÒÐoöF_rR3"""B=!6”oÕoó/N¦±“ºF'œîæ~^O‡þ]$ë«H—^‘ïbqÝÀ/{ýÕÖ@ØÕÛœ|dZ¾ÄBÀ¢÷zUL¥×Z¨ö¤H€á_Ÿ·ËAÅÜž6Q‰F.ˆ7ßx `ª¥ÀœgÖýˆR‡凋N¿\²cC·’Þ}¶›Mš²¦ím æú¨8ò·ø5½Çœ7ðáot+2êâ²m#8—§Ç®¾11>)M(Ô¿ñ(á‘Qä=–téYg~ç‹ÄEè¤Å…ÜvyC<çUä\ß!ÓÕÄQýü/¡¨¦º'b dE¹ #+ ‘@ ”ñÀhâàî¿újw#£ÂÖ˜§B'Ù5„Dd`Ë…G¯Ý-l×BýÒñÔ¾}í>!™™Nl~¦÷\“we”®2–/ÌÌ|ùhgægºô¼fÚWç:—t5;œPÑ®7Í*¿SS‚„99ïu›f"AUÐL‹NƒágoŠjØà-;vŸ\\Ôeá¥3c&O:bËt ãœÒÊikpÛŠ¥ /ÌÜcë®QƒüQWH'j_y`ÊÐ˱[fËt ̰ä˜Åª((‹H>úà®MSô/í¼@SSmr÷ •§6š~hu ¼]º]‘h6n“¦2ÚOì?$Àµß\EžŠ u܈›üÔ´ê×ðÜn߬¾bÊ ˆ÷ÌmÌ`kÁ¶;›N™Ù±ÏÏì¦pàβ^]§ÿ˜X“ôwgÿTpwG¾llź*z÷ºy¤ù½ ncÌ×gYùØéJŸ¤£,ä9˜ž?VÔË¿òDÛàAŽGÝ!=!ßÂ]©³~Ãn­æ–ª÷³¨çû3}&ë°¾¾ÆHŒ?¯»6®en!+肘¯#;n×Ý´˜Ç„ËöT¥qަÃZoÙ¯á¿î½èÅO\~PZÜMšƒ•‡ÆKÜË÷ÑÏÁ LСC‡AœAõò{@‡y—$ ¡ìXIÈ X/sÃjØ:t,tHwr<þ ™úÎzú‡l"}«HsxuOϽgfÚËà8™rïMÇìb /*ðŸ*˜ÈEóš+­„&ŠX‹IÆ´@Cìë£Wg¯„‹'p²Ðgâ-cŸÖ뺨QÅ·ß)9jc,œwî=ÙXê1EÐø]C†ÇïÚ9¢âÞâH¦gåÅé=.™îDypú†\Ýîw~Çê>û“4n…ÇV ŒšÆ½¿x³ïr‘r»Ü­ 7^7søµbñÀõµ=]6÷W986Ìã÷Ü{‹66¥EuÓ„¹z#ªw#Ê"8ÄÔ•Ën8íLjÕWy(}î2íµ·ØDÆ?jÔÛ™I‚€ð5‰¡£Í»š#Þ6ÑGEpS¼*ªÀ hÀfïÞ8¨8µÔÄ'¥hÐ4ÔÇ4hÔpûÊ·Œ SIzVA£¦úk `'jÔð1€ÝN­}ìAÍ5*vÛâ×Ïr&†ÎÜ0R‰9jø¤ÅÛv³X­o^p?¡­ËX0¥å5ã^V¡¹hÓ_eÅäjì Ø)F°ƒ7bÖhÛ4:cÇò×g¤©tŸ°ûüÕœ!A}µ nb.è÷FøúÄØvV‘¶ÑG†I|vÇíª¦ bwnaÜ›·I? ðìgJ{Vþ;«:Q»kõ – ÒƒW÷Áü%TÇUiä_¤Âº4]VÓ1.“ˆ’ ~ÏfIv»®Œ—uöºu–FØ4GÚmŽ~íóÏDí»ûåûÊ'1œAϼt³ù©ªw¾øaÿ.®Eø lµ¾ÅSì œªÆ@@@])D D D D D D D D „ï‘ò3IPO ) ¤0Â@@@@@@ ) ¤0Â@@@@@@ ) ¤0Â@@@@@@ ãŸÒ 1é!ž"p@Ÿ‰QÀIx‡Á88¨>>S²¢˜ÀpÆÙöˆx-ù02†atLÅH’àuæ„’ÈÅ|,ŒŒU¥ƒX¨ ü ƒbœb EBœ…–Tª*òp’,’ÂØBŠQ$ÂI6ÆÁD¤H\Z ¸,(l5©j ›sWX›sœ¢Õ uZ`ÊÊŠ,\%œUu>3Ýâ“bÞ¼/.ò4CPQnffhfªÏ&q1I²9l©¶¢sF\”[Tùøùë¢òbkC‡ùÄÄ$ΆB0T¾ÂÀH… "ÒÕc¬˜M*‰È” 1Šœ:kqë•¢¬l[NR¬Ö]R, 6 b·.hf¡VeÀv^ìÙ'S—–²Ù´€“Šb«(©  AÛ³NK*6I‰ K+»ySŠÊh5ˆKIG(¢Ä‡…‘~ží§„gA}hÕÁÍŸbkT‹‰Å¢Š2GIE 8ŠdnÊÙ%Â0ª ßNaÀZ<uùÜÆò2Š"‡ö"ÁòÅÓBRH’J\¨#hóázR\y…@™Ç‹Š«´ ´.H °)h¨ìë)û”Ù@L÷ûéá+L îý1lìbwÿ±w’¶C±W®Þž4{Åæ\:²VQ‘ m®d¬I$»õ±ÿÄ£ /'Åál0~JD%[ÝÎB{߆pÀ†š†3 ®¤„b±ƒ†T1Ÿ50„/v¸nm·ôÔŠŽ*µ‚îGõ›X¸ù<ÑD¾îÆ¿*f²Ñ±ÊÒüÌw´‹Û"åÂïÒG•^ã{Nʺ<:NYaæÛ<&¤ýèõËÛËä3uõô>Ìãеû{ Q5„¨0pÉ× cU „™oÞÚX™²qŒ‚Í8À‹KKÊ+*¹:ô(”À6ûù‹w–¦zÊ J5TH±J`Iý=Zc§?Ï I ãj…‹1ŽÚž ó¹Z´GèfŸËb'ŸØaßy¨SËÌ)21P›9m|¿¡3<ɵçø5hHàÀ^*\6›%dq0¯’ݾk×6K9ŸïáÜ}>qj®ÌËÈwÉ®‘–µÔî¾38’LhËe-îÐ!d! ü8 CLAM ,+§œºŠYʘðêå=%Z¸4æðÉë›g¥Ëß³‚ÂñVüpåFP•Þ½ÚÒX¡º±„ÿ‹#ÛvÂóÄ\!.¬cÎ&Y@CI|îÒ>±¸š¤ˆ KKC• ý]ƒ’~¯8 -‘ˆâ<ù;ÍÄÀQ_[5åÄïÅÓ"¢7oß·iç1…C5AŠJöýn¬¯Îfóp¼ÞËZ˜~^5Ýû~."¶/%‘ïܳϠľa¨Ž" ü˜ “Ì€â) o§ì$ J ÿp ûÛ @I‘ÃqŠ}ëê>6ôÐü Éš(ø ”_¿«Àf‰ùüy¶ÿÈéB‘øäÞUFÚpçA± < ɵvN3F£¥z*Ia"œM‰Y8&ìØÎžÂ0hD°( £¥±cí\(uÉz•ï1 ÔgðÄõQÓœÚ;‚¯ýÑÛϯm~éµ9“L(}‰fb>¨T|Z Db ¡Ž¾Ö# 4D…Ô€Ä<Κ¹tÏÖÕJŠ•€ž£¤¸fc\AqÁ¬ #YJ¤P$ã ãÆý6<°§öX …!±€t\”­¥ÑmË|OõôŸqbÿ3#M¨e  8sdS§®A»ö_Ê|•·jéT¡°”Ëá E¬r¡ Ë`%µ~ÝÛ*±èá01À·èöøÞYœþZA’ôl_‘¡¡6‹p‡ÇS¾à\sŽNSx}œô tlY+èQ¯& 5<“¢zIðœï>Œê)}™s(Ø^£vNü¨@„¯0€Ãx•6pÔoÎrñ¸ñÇ!1EÎ _~ü°³sò6­˜ÎfsZuòê7ï-?¼oµµ‰¦,=lºEâJ æH´ 06ïÖ–ú‡ö,ó œÑÓwÜÙc1šÊ,.W¹‘ªÊ½?ãüŒ¿@ܶw^)ªàPl‡CR"»|j½Š‹‚æ Þå)©©·î2LLOÂÑ_á1Ž˜°ùž7ó×6-­èÙÀŸ- åv§ÖùwÏ?ÍØ´§KS}¨/X9sm ÜyžPþDZ+‚HéËwæóO$$šQ¢ÂŒ3CïCÂ}:å¢22~`…´”Ù¬l§è¥tùkɼ©‹ç‘ýùšù0Nݽ|`b&YKWe]`€M‚{Ww3Ký(Lò‡^hìLõï&oÇXŒýã´'ýaüèþõôš&ù™”=oîä½lᕽ˜ã“Eqlßh ÑZé eÉ¿;zˆCcQEG@@hhUÈïä7ó7ý'§^'ÎL~ïŽÿº·huWM HåûŸ&ކâ;»Ï^jôöÔ¢?l/mìÉ÷˜Ü9 ×˜­üzD,]:öÆžyy~»ÃQõä»G.ÅîíÜô~ÀéyÍ?xF)ŒëÒô®ëìO¬ò^/Z3¥ë’ñSfœJq€Ê«òIXÌqG›sˆsKûò]úG¬Ð{s:âx£ËÝz ߺcmc ¦ˆÈþ|—¾³æ¿K\’Õk×ROÝŸRq/ªÛá.g"[×Èÿ:'¾GlËËév¬_B¡e÷aãºw±ª —asvS}8<üî‰mC™<È´Š|‰}Cjæ¹%u¾;DáŸQò/þ~š³ô¡î¶üΣF/YjuÑÂ;¼©gåïõ¨ÿ_ Ô_8¼å¬)s&¬¬‡Ò¢°2@„A@@ £>€ÁöXvSQ\ÉcK¾6SÆã»Áƽ9¨X ­0t{mÔöâçt!†ºÿšL$ Ó¶¼mÚÆHù®u¤÷C•êóFúÀ¿Ä…u7¯>p³`XˆÞ”Em 5SŸ‰¥ËXö±|D÷ãÛn¸¢Ëòå'ž!ûçó''b:¶UTp/z%¬ã¿~²IÐ}ÝÀ.´;²‘/0 €G7‘d"|¾¥†vwÝ]?ö ai1OMQ˜¶µFþ9fòÙ®%'é8Ø´óÀ<…žÀn:Σ%-[–o,7œÇäá±$¬òï9Ì!‡Ô,ÌbÔÔ/©PõPªP&ƒ;X€–“ Sî¸66 'mÞò¬Ù»¿¬mÇih›NlÍIÎ!}Œ­¤E€€€Fý€K§·DŒÝyá~#3Çõ[ŽNãa€ÔuîÉ$>Ÿ¿ñAO¥²u$øø€1c ô—îÜËe²þõ𰱝¥5²hçg§ pÅΖœÙ'ÍÚyÔYçÙ°-O?–ÐÃÄãM¾•sÉ‹CüOÞÍêè7‹Øâ ÄÙ@U7:Ä÷ðÝÜé;Î[)íéqÀÓ9D a¹ùt²Ž{[¾å{N$NÎB8VÁ»<÷vá‡(˜uˆ]Æ“;¿ƒ/Y€máèùûª ¡³YÍü×È6¯!§®„=iÀáï`–ôp“‡iÆ’µS3‡Å_øKÔzñ¤qË>¿KPÐÊ1«~Kï6Ù­¿»‘$-ŠÓ«a¨'à£"~!ou¨É+'3fR5jÏ‘_‘ j×+ñR¯ª;Y|²ä„ÏÛy‚qu— ¿w”/ù1™&£ãJ3×íŸ)óe ôŠÐ* ¿Ó)~²ði;ÏMc²*ɤ¦ãÀ ÄÀZ¥Wk!E]ù5³]CŽÛúªä¸ý2PTèª}¡ä¡®Ö.Ì:ß‘.ÿâÕ•ý¼¦D,½Ž×ó99þuH!ª$÷ü0A´²£j3x R@ ¡ž4¬Öç?¯ˆŒ$ÂÃѰ‚<”Q …€€€€€RHa …€€€€€‡¨xz§ëÈ'É„¿l›•|"Å{V>Aôþ×2©‚tç^—e·*úZsWyübü±ÊOñù»ã“u¾x£—÷'NöI°%b¬>3ëÐ ÿÕyç‰@…øL–°S_ú C¤0 x[Év|~쮤@ Ø;*v¯™A@®˜zòèŸùê¦zë·x˜)‚ÌýÇRì‰õf0UöáD¿¤ÄzSذ&Ävèxí,Xsç2E‚è/»9ëÓ´ûÑIÚŠe .Î<ðTF¹ÂÜ->–ôq^9·M¿ž+À=Fòç3½:mÏôkôéÂÎ+&U?…Œžqê𕼦nö#jíÄOæ½ð_M&Çwt០ˆ2Mpâ˜Çÿ³o s¶÷éfÉÉ>˜8èz« µû¿ŸÉ1ko»¼MçµÀüŒžy#‡Rš¿ÙÛÕŒ&òý„ëÓV>.%Ù>¡nSúé},‡µÞ7÷Ô)Âa²~êâƒYúÍ-ã6tB»þ# …Ðp€+D`ˆ[ì]!˜~`p¢„|·ãÉDàIø~l‹më²8è³°^èÙ„ÍAåC†—4Ñdú‹" b²Y»N±cmhË"‹«µûÄ`èqŽ}´i jäÞkƒú=ßDÒî§ñùñ1HŸ;ãL`k%Ø—¤—HK!Cë~+¡KoâTJ ŽMýît {y.Ê” x¡¨wèl tLr‰}´aàP5–ðQÆ€DÏs(~Åç"ˆ~µdm{}¸oü™&òž-z·=޵śÜÊ› •xïYVwk½ïU¶àq¦×¢.^@qÊY×ÁˆÝÍQD@ ¡!aÕŽVnƒÒ{ÔѽKN㢕)=½ä]õÆeºu}®¸k—tùý~¬Á´NØGÄ2àÊ‚)ÀaØÊ“UÏ‚®:Žñ’(:ItiXy¹HQ±š_¾ü¸I«Hš†öoÖ9v僓›³˜$ *IÀ®9F‰Äu>‹ÍebÆ-ˆÄlö|ÏXÖâ€È6<%Þ‰<@}Á1õÕï«,Ý ™>ÝòKR" …€ðý‚£{ôÑÓO¾š§kk¼ùb &¬¹6½Æ<9Åçšü  nU~¡°mDà¹éûøë,‰øöuˆ•4àfÂ÷>§2+ìàbÌû{ß}Ú·ëŸ9•lßÉ]¢Œ³~¾m¿n±§øLgTG J‹š˜x«¨‰Kó˜Õ;ê+èÙ­¯œò‹¾8Ïßëw‘6bô+Þê{úe)7bÏ€.¦¬¼ tŽ®8·âèóŽÍRhó¢v#¸;ÐófjO×…¥ˆï.`Á™€ ó³Ä~ë1f‡×>ÏcK[|Ã:бä-ª^Ha 4taÚœ äÇFðÐ¥=jö œÛ}à\©›ØL_SˆÀ:ª4,ÂBÞ§ëÒ]?*#$BâN×¥éÐ8þ\cy]×vÑNâô’~’xØêÞžÊî»-з¶KòÉ õjÚ{N®iYŸ)]}¦ÔÎè!{Ðim—xÉN®x8köÈî’¥åPGk½¯ŠSW©7Rߪ4¼fêÖè†J) ¤0Â@@@@@@@ ) „o}TrÀP …€PÂÃÃQ!0HMMµ³³C倀Âg`aa ) „Ï ;;ÛÀmŽ€·EdddƒéJOOop #... Õ·ÿÉÉÉ...Ha ü\xüøñ/¿ü‚ÊYß^ŸÛ®Ûu8Wôvï ÖÀÚuÄfÅÝå´ÑüžRxçeï§Ó[£ ÿt´W¯^¹=k$íˆù{WWUÒÅç¾ÇKº;E$EQPA$D[ATlÀÆÄ\ÅŽUìE \;QĤC”xýÝxïñtÝýÜ]Ðùÿ~ ófÎÌœ;÷Ü9“g\FG¿ñ“5nÒ¡GÃìÁ÷•õCÁÞ•þ>´¿Îõ}IN#[/îGpÂßq$kl MË*ýY3ˆS•]ÝKsÅÊÜKu¥Lþjí}G•]ØZQ®RËZø¦,A…ñÿbwÒÁ1Á4&zá¯j³ŽÑ`ð°›‚Ê3÷“º‡<Ú—Ô74‚8IGžEøª³ë9XóVxþ!³Ÿ£ öáîM:0*BhìoOÒþј5§I‡Æ†º¸KÑC55)i@D„àã“ËŸÌûé Gó­ÆZ”ïËŒtÑø‚~´KRòýþž}ôU¥Ñ†#³·/¥scc¥·É½œÕ¥Ø…i¥ÝÈÞìΤƒ#jHFÑD Ù$µdÕ”)™*ûø¡1Ø#`OÍ-»zéÙKCŠ•wö­ª×?Qóœ’Kh½ÑÚË;»]Þ#üñþ$—‘C2Öøþ~7"PïH¶l |ÉÅ]Ò}B%Ÿ: {q(«WîÔ¤pUþE5žÝÙcd„;ÿÄ•!æ2G“vD„~¸yhXÀpT'¡Qͪ´1m§À¼—“m')d€S,YzÖÉ{Ïær‡0z,QîÞ$ ²P§}`²Ø¥òÄ…•BÝ‹÷µì¬ è!4)Pò¾ÒP ÈXg Á;“zJ ´žOzy‰8Ò˜¥ªË [— ÝF“«³Î³Ì=zwäßz]&_z½ÁÒß­£à^~…>ç…Œu´}#‘$z±‚¶w%F 6âR4ìc‘¤g•?Õ·²V¤|Þ•t†[rcÜ¢-áx: ·yg›[·¯¥§ù†“¯péa¡£zÉ ;ES3g÷YëÀÞDÔâÔ”%Ÿ´%Í’©hÊõO‹+)¹×ЕÒìþbåöøni—äÝ_¯ØÆÆÆoP4ºf%_ïìÙñnµ@hå‘âUÔ°´dÇ_J¡æy°´¹QÊ%Ì'ŠŸÞ‰Ów†xwÏÞ™bâmòÔ­ˆðA’OtS”B÷»9)5=Ba+/õe ü^O÷2Ò*zpæ½{6AÖ¢t<•]öŒÎ-n”óõÆhã,…úˆ£:ùFpÊ®$%½?fÏàð`G¤9€"™ÊÚÏPgqåå24\¢¬ ²¢ò‡CÇ^;z+‘…ED;¡n¯‘DqRÃ{à˜;tT+O=Ä'‹]%Ь„ùP |M±ÿD¿>Ô˰) ¡KÒvU;o”Â'ˆŒdéÂT$…ˆ‘Ø/®£PG©µÚûèÛÙÒÊÛ!„ ô?œZ˜7.?½p™Ò³ÅO¢Üfd¸,Ñt›äçüùóPa@@üHdôG…G´Yöø|>‚w;]\\mñ höŽˆèÝÆ+¿›G`·_RêÚÅÛ ¢ýÁÒÒòéÓ§>>>°*  Â€€h+HÓ¹Zu"k 9Í|PTdO†œt¡à@@…ñë¡àceló-VÛä­,5Þé+§ þjnñññ*ιPÿ*2¾v•ÅbA…ñ‹ƒ¿?ÒÅom&“ø57ŽÄ͘-6ÎÖ a@@üøtuÔ©¬Q!SÝPÝõ1'‡„LuECÀìYGW¬–˜)Å)=·dde-Õ!ò‘¤x‹Ë•W|¼3ÏþåêK nA!96×;ÖU¢Vår‡:èµûC€æ6`¡‘,ùäó§\ñ82å'·èÄÿ¬!©Q’8pßîŸ9zDb&Þr°îàÑ:¯™.t掾ØÃˆþS>ÝÍâÔ… 0ÔÿùNqÊ3Ì6²¦ã mµÐšà'Çæ‰3¢¢^nK•Ùj¬ 96Ï'Έ×ãÑØ\§9FªeÇòƒâ±ªé±¹R¾ú}lÈ€ÏMŽ/ Š7úooË6X†h£ßVp¹R9p$Æjcö»S¨AQJüOùˆ‘v¶ïí¶Ü7]ôúÛ“ZrUy¶•´œ—(Wœ x=T[<Û[;È ‡!&•yŠtÒÏ¥A Â€€økÀºË>ág¬‡3‰IÀMgÙø¿`ýM~cuBo²PJ%*EŠÒM1‘°7e~ïšÏt‡È#hKôõ'úÓ“Þ^'ÝÔ@zñ½ .¹¼Ž¤E͙ưÕÃ:øZé¥oxÍ[öVci O/::FÑ·•}ÿè·ƒ²Ÿ1‰óò¢@±Ua¦Fnº°›7fÙ+¨ Ú W­¤•äJÙM'Èíg–|¨0 ~ |øðN§·º}3==A¯O1 RSS% H$ÒÈ‘#Uœa¥þr€ â§Âó<œ–ž;ºýÐX0†r¯Ê©|­§ûº Êç«™¹VŽÌ½o¦¾^âꕘù0®¯}Ü¥”HgÂoýG®MÝ{êÜ߯÷B“ó××g÷ïµ"ðëN̲öð¡˜ùÖ`œi”-^…–hO±ëí.%Ú?ÿÿÜ“î{Ö¬Å>¹¨OJ¹Á<öïOXFE±·˜ó=ºÈ£dyt]x>}Ö÷•'®Íõì=&ý¾…góf9ô·|.fûí’~(W'm;ñê‘«.îì­1ü5¨ªªJN=åääxxx M~~þðáÃ8Ð2ÉÆ§NjlllhhøîݻÇ‹ï* ÷åùNs П÷VåuiØð¬"-¥NÓESýÍ»‡e¤€ŒµÕl²OŒ.19“{ªäÉKNG?ÍgûKtüõkSËY@àÊ(“WÒ–b_y+åHª9›ü±Ó=zf1šƒM´@ëÙú<‹i†ç–—¢ÄžC™çŽÕj¹j:v£ s е0ÂvAÕ¿¨LO©SꪦUüþA 🣷n‚Ë_òpvY)]™ÏV‘óô“G]\eî;CíôÚR>ƒ6xª+·ZX½TêòB¦…<ßP®¯%VPÆ¢·…˜ùˬÄ<ËHÛ¢J@ùì<^ãbZÏ$ÐØþHªî â'TmN‹w[íç;ã¤àUܱÅþ n©ÔŽhKú9ë@g»µ™E|Þk."êA ýT:$Û‰Ñ x’/@¢6Èc“žîwï>··Õº7±Ï’ŒKǸ.A}Iõ¯ßp}øÜ0!1#àÕ“ÈXLS¯W÷Jõë¥P•Bj¾»“èµóŽ˜tïÔ!Ê¡^’mŒ+ŽlÇÎ(qå“kÀ½û·þ3 MAAá_±bE«4Sp|Onl¶¦œ–ÊóŸcp}Yq”Jc“ý¼¼Ã}Fýb½.ÆŸÑ`m#ïøªJU)JOKòùÓßùÚü÷Õ|p­<5U°ÀðóŽt–CþÖ2L5sñ7ÀÈm¨öŸ%´U,ÎÍb66t6 ˜©_~$_9X³,ŸB4m¬< \~Ÿq:åGó??¯G™£±>1ú7ËÞ³@f* jxTÒs–‚ ñÒ áÃÊ2øÄ{Õ§¦a— º¶n€„û©<>•ñn±… âçIÓÆIÌc矀ý¸rêJ÷ØÝ9Ðg­3g¨ÖhgÓiÉE,ZÂï€M¿+YêK< lxÓ †þS賕°Á×wiêz­NÃ#;ŸÛQœÄ²—Âî(]·MèOWÔ /^àõ 1\$OРà ÔuO8ºnËRQ·ƒÄC4åšØ8W^ÁعßÒE_cø_UÏxÏóÌÆìÅúÏVÇjl.ÖÎZ0ÐAÍ´—4IB&ûÍÞâ·Ñ$5E<žÖÛSÌÌ»´* šƒÅÌè·m´¡˜ØªâHä…]“¥ˆ•ÙËXO3oÁ¾«J= –Gá™Pé¡)YÃV›ý§÷µØÏ4$<® Ä•€(Ê9b)=ñ‰HK÷ÆE¤zvø®šüÿ÷@…ñ×p=ƹ€…ï·8E­þ÷"™}æŸ$ñ^¹é/‘½¢_çÙ¿¥°”{ç<ùH/ŒºÅš6x¨µ8‰ç⋚¹ òh.ůƒZˆþ·éxÅçŸÈS[^óµ`%@…ª fHb:¯öщS÷ý°ËÀÉ™S}Wmx²¤Ÿ‰»«ë6î“óÙDÓü é¤P–vŸá®±ÿnQ÷î=D¹ðy™}÷N™Õ‡M®Þ½¢¯ùì ‡–ì ž?¶¾'l´Ë¶—*„ëRò.¾Peí?p͆{ãY¶[Ÿ-Î*¼Ðòà’D’Æ“ê­6+Qêï}!ýlËÀU;NϘà³ú·“³c|W$|1·Ã ú í>½úüáàØI¥»¼ÔCφOd†ìÕÙƒü4DEÈŒß,&H‹2pbÆˆÞ w*ʵû­ÿüŠši…ì¹}ãŒî­Ì²êé÷¨ý»óþ(gr޹ÌÕ¿¾¼ÐuŽÞµ¥½æé§,*8QæY£œÉçÊl%rJ±˜à|l^Ÿ8Cbãñº|›(ƒsKJ±ÙÅ©²· Zõëe­Ë?êiHT Œ•™$ø!A…ñË€,g0ðßc›ö»»ðS×NÔ¦ û•gcú+öt„³(´ AH ©¸ý6§èŠ©ÿ‚õؽÝu÷,[a88îÍÉhvÙ6~X—Ô·[Nò¡&ÒÂu²FàÝC_Ûú :dlnƒa·:m–³kè¨A 6ÄIè]×ßX2°Š­<8~ïÅìBÂÝæUÈ𠤙7PÞv:Ú~°-¸¨QßÚ y«½ìÕ¢/I‚ަàÂòÁÆÃövµRû^$…&…%YøPžiÂäÔ× (øž-mSìØ|9Sáóù<.àc÷WñÙx•J õkç!¨t„$Cc4 +L#@–Ts“¿!¨0 ~ˆÖðÖš˜Ø¸i (Ä¥(¶ 6 …Ï-kyaã •ÀM÷!2݆-Ö»m&BÌb.¡®šûš wÉÑŒ¼ß’ÃB?±„€È Y•! éz¾Y’¾óS ÏÀ•¿áSaPwðŠ•_ ”$¸¸t¬0³È”®" qÄ:eøË¿UomÍT*IEA]|]Át¢pÁQ”Ç}÷.èįL‚éÅ@|ébp<ÖÀfuÕúbuÑDà!±>/$g¥ì°Úds4^[·F*êÿÑ#Ã{ÿ "º¶ÕY1ÚäÙî®±?03rE¦”ÿZip„ñË!zÒ|X ¿  Â€€€€€h #>>¾k×®°–QX[[ëêÂ2! ZÁ„  Â€€€€€€#Œÿ‚„„•gÅÈ"àò–„½§™1á‹„øoáááñæÍÂolŒ3ÿ„€€ ã£æÞÎm¯œb†cæt>>ؽõEwÔŸ £ã2i¸#ª$Vvå¬Iýpï8äd)ßÐ+Ô¢ü-ÿSª-“fÅÐß]^³/VL»VŽŽvU—j*EPŸ°rcÔ¬*ÊïØóÚ2f„õþ• L÷0?ÞÇœÕ[SfÆÌâ¼>”xªrÔ´IT óçÏ‹í¹¾}ûVGGÖ Tÿ6‚‡9bÿX¹,ÀDµêUµ2V~gò0? ìIÖF¤¼aùÉÒ¨¸tã®¶’Œ¾2xýö£«ºrS)sÖ´Ñ·­)þȈܸéÖ€õ¶T@úÎÑþ”¶Ú.(ÙCmÑ\ØÂÂvî܉zœ¯_¿+*Œ 2:zàÊ}Ðoï¥÷@çËì4#)P­˜å¢C+¼ºûû³ÝþûíèŽvÙãÏ`Š1íáÎòÝBúõÔj(¹}O@®¯ú €²˜˜_ó`UÒÓY³¢QUðéå™-›ÎÄDzkÀè;&°«à}LX½µ·.äB±h;vìØµk—@ èÒ¥ ¬ ¨0þI>4ûÅÌ"¼ä©11„/FäA;ÿÑ"¿žkhŒ«0Ô}rÌ·³À¦³BÕ$²rƒ%CÛqT¸c³RH ]cf ÷tÉšzÇà·hó@–RÅCÉh|>AÄÄDXPa´/ úâ§BÊ+Pö©ò¶í¾ éA[dLš†[AÙhï ƒ]p²TÓWOpù÷-fC#µ¨ß¸* ß^8à¾û£FÕ©Åùû;;×v ›Ž%px€Bnž wÍšáSF Þgí¹K6Äìû ƒ€€€€ ã?‰Ö'dҚïÌ2w߬#¡úÞŒ·7ÇF/»´YÞÞá-¹«¥Œ !a NåsÙÁÎJt»0yÜqÞ­3—³?ÔT6̘ÖÕš{;E9 dU×ÌÓ•/²íë~ð†éøÇ–ý¡ÓCîïZÓ5[®à]0q”Ô)tP/8€Ù®5ûB£G¬Þõ`F¨]Ùå-@–ÆÄÊâ®>˜;c˜æîû<ÅÛ‡O÷úøzCï€Ì*µÞêð8K›Í%S›ÞKã½ñG¯{…D{öóý³f…$¦þ¥ü9<€|¯A¡&ž!  Â‚ªïk ôE5À$Ê^³cíMÔÕì; uq3œHLÌÌ–v÷Û]èw¢ &Î@÷±Ñ„‡¬äˆ]ê5=õÛ… )º^Äݘ222AQá¨'4z$ê¢Ú+½ÏDq]ÍFÙcÐÌíÇ¡žŽ~S6z>u¼å¿wdïÀu™4l(ÈÛéŠú‘ìi‡w‡$GÛñ’]ý2‘ÅAc°Åª—éÙ€áõ]môïÕ!‰˜Z^AâÁõ¹!k7?:¯jíAÃLŸØ5dDb&çYS)YK?^pîˆ]ËVñú©¢±eõqŸ &Oè‡eøxæÑ3BŽßél}ÉN÷k¶³ùû#],c2l4±mâÇ"í_ÓøúcÒÀ§ýQ^C3©˜=öëæÏó[› î…ÿÃ7dºZV—yW:«Jôh¼ãâça´†±Ó‡·íÚ#Mfñ½=˶iÁô§„†ñÿÍ‹FpkÂoÔÓ(ë;—4 ».€ð˯ì]ê»Ækéì~Á—¥XÍËÄõš—/z•Sˆ¶æÏïUéŽíIÄÒmV…Ø36Ñú“›ŒÔ„‡Š4 ¯¸Aã¤ì(Rq/"ãÔ2^W‰ø´±Ñ ŠÄO«0ˆ% *àUìyBÝEîØöe¹qFï_PV¥騗óâ"Ãjˆ¯­Bò¶M8ŒÐñþ‡!¡ö ©7 œ2EL_uÿÄÑÕ¦¤š~ØÔ¯êö¦ã­e•ÙÕL‹q~v_Ç)I.P1¼¶É>,šÄ)>U¨âXuŽHÞÇßéöã·ô.Ã:~¸¶'=[Ëz€¿³!¶ ½¶ÚàHÜ´®.6OÎÝDð¦\rÝÉeÙý3Ü+ 쥪hôè üïÊ)ß?{ds·ou›—H$ô#¹¸5^‘û´®cŸñûú^ÖMäçBÓ.¼Ö±îé©@Ž‚€^ Ç"Ý©ZëhòŸ>rœŸÑQ…ò=%g¯êõY³?ëÕù*n—3éÆ{_}L@³·Ô¬Þ9¸ƒÙÛ2ˆ_}„ñûúC£¦O©Ï9è:•XÆFøüÀa;Ö;}lRâ±z«wØTu)öú3ïÆß|÷šæ8qª½àÀCÕ㇤o\õEkÀ熌¾¿kص\Ôv‹ÞôÛ% •>.L{õ%ar„,%ïl! ÖB¢'OÎ?È‘T(;m33‰!ž¹ÛQÐúñ¨OJ?$1SLl×ÿG5ÿ“ )£‘èÿ#…Ã$2^B¿¸¯]!Íçº(þ¢$΢ IN¾ëY×ñ¹£yÂщýÖû¯<&:~*f÷Ø™(Øf¯>¶]Kè°=Ä¡yYßS.D»U¢%áÓ§ .Ó,Xl(*tú|žjêFDúc±x‚iÞzèIDMôÈŒqØ×ÚŠpÙ£ÕŒ¦Šv~ºBOðzPf9R29ñ¹FOpE]ŸH(7?+Ämô¿Ò_mÙÅ:‰ÑyF<øñs( %%¥öU#£çÏû'²Eà&Ý ×g÷Ç.gå§d"ƒ\ÕÒãU±Tü—(8þ(»ØdÔ!k¹+˼+Xêƒãv×;7X"ï´žò|.Áá]^2èb1tÞJ֫ݱSÏŽh†/ó½[ ðîž~4]¥û<7ÏngæLevÀò­hì阉tµ¶ÚA!â'J›‹,š#fRœ§žë¥.Ld¢Ý(ŒØØXXÅÿÈ:õisXJÜŽ“Ï1Ü.ht ÞnÌ«J^hê_i“ªÐ4Õ/8y”¼:£î]1ñ3õ臠é1>Àõ´ßÒÔW£ÊYÀX”ÜzYœP듨´®3}\BÎÝ£ªQt\º(Z †-9eQùXÚmc9Òg%i ÓC%nBlªfØÆœS"×5rù' ‰ ˜Ž]YúFóì‘}Á‹N—íñä‚4@\Ž–ÅýÜ?z﻽žuY×ÅO$&1)¸r´9 ÛíCaÀ ”Ä€(ýsÀ†8†&,G]ü¦éQ ÂÛMú—ã½àXl·´Œ†!úè/[ŠþtK¶æª®ëDJH˜…÷ÊM¨Ûójy9à€YM6O¸¨€(àQ ëÂó_ð`° /Z†Nj"‚Ò±·Ú«Â8цºEÚ/Zu4Faá2âÜ$&[2ÐŒmˆö4%ñ7@è'¨0¾ _€$æû›®Kº°);xº—å¯fydU‚ô}ꟗ{ñïñŸ#}æ°þ«¥Ïâ¾òĵ¹ž.ËÒ0)â¼¾òFëÓî˜3ŠdBžÄM6ÄõW³j Wôí»öÚ­¹½Wœ¿ãí–pæÊ¿¾Ëc 7n—Û9Ð÷í¹ò2'‡cã~݉aCÖ®šðáˆlÀé»sú‹G9(øåûŸ4úuú´þ{b“G™¹VŽÌ½o¦&Œ@9¼3-èDôX¿5»0sf×-—~³˜MÎŒæ>Û÷ü} Ïþæ'gNõ]µáÉ’~V“¦ÝÿàÜ©jQõꬅÁhMQÂQb‡‚¹6=tï=¨s·mŒçëAü$ ãk×%ÙŠvÓB+!!qÚ¬:vz¢â;õ ªW&ÍŠ¡¼MN<þ9&& Ëùáî­OmcFÙTŠöß—^Øt°ÚmÆPs¬ÅxqtãUÕ˜ñ®å6WW’]D²2ÓDýOö&<²š0Ú–‘°–àJÐøæ·ý&†FCÐBep3UkV†DǨÁ1ÛDÀÂ\ü-òùÏöX, v¢“€†";Ù€`G¹u;[ ãöow.¶}¹;ÒaTJöI"µA¾‡8‹†¢ K‡#-ûl @ŒŸú¬ívÔfUðY8‡üwÒþg>¯L˜É{Ó!Sª8Ä# &ݱï‚.(G‰ó*ØV@Àaq />£DNÌ/ Òi$ÙNŒdnL ˆŸn„!yÚ–hnÙè·D£ß!Yù/ç¨"Ü!O—cvƒd̽ìÏ&~BÓäÌN1¾,WÏN¸Ló"ƒ 8 À®€Jp…Ð'†v"#l/š °Cü'p_}s0×m™è¤±N€*°µ ñ<³—½¾pIÀ,æêö[quMGĉò£ _¼ýgžš–I¨Ãc§‰2t݃ñ-Ö’Ã Lf5ÃlÑqد؆ï>k±=Ú8‡Ãb›¶Ób9—5Ø?“™¨¨iâÄR„çjÌ<ÉàÄk¨ÛCu–Ê HFáÄžØ~(%Kl{ySn?‰ÂPèâ2vžÏ¬‘ú-¥Ao~—jà¦ÃE;ï:h¾ÍmDÄÆþ.´¨ 9i·Iwߨ›V¯UÔ1V!å¼.ôˆ˜a­Øú)YC#ÎÙ´´óÏž<õÔ®J;rßxl¨›&:ÑÓ×-,(² šÚG_Ü#4ĸ“yMÞó ’qÌT?(Rÿ\õÁÚñm±+W®¼zõjܸqm´â¬à®Eˆö8 «ˆ.«À ùâ£|Éë+ì‡Ïhy|ê›×%!-o7¢‰ü>Q1>"ºI¢RÄ&@%Ë!gƒT<=b4ÄEjA1_²¥`ácAä= Ó¿YZ[Ù±““cccóâÅ CCÌZ Ê‚ p79Tퟲvý¡â¡Eá×Ü^¸îàÔ…ÔÐ&ëÕüt™%Þ­X®¼ºLÚuî—[rª$âã±!Ž™™‹…­LDoÉ^3^û^áwl—|·0cÛâ¿ÕÃà”Fïý°f¬5|•¿ªÂ™ÿ° ö>•m'/¶¸7ñw¦»Q©Ë§†[¸ù?³š[ÛSup ØEåHÒÆR =-¿öÅÅ]çŸ: ÓÏ;zù-zjøñ¿bPPÿâx¡®'lªùc#OžNÞ™x¨pG ЙÔZ9œž½{]h4‰]p¦ˆZYEc¯x~Óúþ“§ÁcÜ휢ØÎkÇ m:gBBɶåbÇMß¶ùðà ðÖ*>5¯ÔmÉñ™³¶­ÜÚj¾ìý«.®`L?çëåÙYYœÚ*5­ÓÇ“&o¯ä×ÜLÈê4§—Òém[‚-FsÞŸÎÂŽLÄ_xë®Vx|N•Dzg±ã¬Ü¦Hj7?}ÛŸVtØûR4O„[Žæ¹1„½ CU]'®Ý¼ÜiÁ5Ý%ÞÚ/÷L§_›9gœ{Â65ŠÖ2—ôc…æþzp#Ä/>Âà±ètr}Ρ&kƒÜÆá£Â Î$²É= ók‚éS&£QõÏw ¦NfÕó»Òë"#£Ž¯Ûd;Á½¾Î¸¡)‡ï³?H’b³xDÔÅ­»ü#Ã>wÊôk~»F˜¬y®*²rX8-túú=÷I\Ö”±N,rJQ!ÃnÔíø«Z3aòo¿aËÝñ¿-¿òÆÖij€Š"Hd ã§•••uw´sŠÓ÷±6Oº˜‰¶Ð3¦mÞ´m)«è:·Ña5p0±ýTÁÇohlBà?x¾¾gKÛÞJV«ÍY ‘§ŒM¤ì²q%ë·lïH+`\u ˜àÚA´ÜÅ âWV"óÓ$[6h²6ÈØ£ïíD!v>MšþgšÇÉhL2ˆšæ‹úü£0E‚_ ô×ì"tã`ÑÕ³rˆ´05HX9ÓFÛ ëNÑøY‘'´-Ý^@Ñ·Ý‘^fý›è¼4Iaë,ìâŠmóLFzö B€­êÉ/(Á)0y±ZH¶ì˜ÌlÂ~Æáæo‡Ì˜º›'©¡îo° WGý†A ˜Ü ÓR·%ФRZr>J2OîçŠK7ŠûÍÝ‚)y‡9½p¥Õšxà–͹j½6/ à£ÚøJdy3Oùï%†(µÈZí/ò?zôÈÑÑQ¼^½gÏžÿþk”V Z°å›škÃáŽY¨0Ä-iTæ¤=UêçÂ|‘R¤ë¥™—Qß¹øÀúQ1Ñ6L™ºaËÅ©ÃÕ.TttW-8ùN¯àœécì7nJ›z‚ŸcÒÔqðwzAó «úÙŒ¸@…ÑV@¬Wß¹sÇÌÌ à÷û’HpCZ¿êú#Ýn¯‹­£6oiæ–œÎVò±¦”®ËV¬KZ±`s<¿âr:Ï¥gabµÍ =JãìäwËú¾½z÷V¬X~‡F9xa†v´VðñÎéO]­®Í×¾‚Ö,Ÿí«lZp!~r¿ØSæŸÙ´Äçs]#ÿùÆÛ™º”ƨíùJOŽn“|3E9O¦l•XV÷,‹H%<UgµaÙ‰MËý³·F™Œ_9ÿÌæ%>Õ ¢­”ŸŸbËOmZ6äÅö(Ãðu߸RD@•!®Ð±\?ÞŒŽr=iñ±~PÓT wa.ˬžë¬ÄÁСC;uê$6ä×«Û H²z9/]¬£d#¡Ûeùüq­¾‡fλnçÊ7u$A©À ËÚOß³pFnunÂ2ðñ-Š„‚îf +ÒJQDÞ¡ëå¹o=–­’d>¸]ü>,dqwò¤Iî“Wxw›¾kAta£ü’• ×NqÎ’%J™=¦2ÑO™½lªÛôèéZvÁ2½GAäÌy½dDÖèÁÒI.ÓgÌ0í7Ix]úˋ¤ñ ôí‡ÌÛ4¾#4„ áe|Jq\?ð(qÚ8¬úݼ wRä©mÛÖ s«e¬× Ž0 þ>vïÞ½|ùò¬¬,:³û׫Û+(ãñÍæöC6Û"Ò+V/ú7ÎÆôŠJŸîxÄ”E«…á•9N8­ÆLýxbóQºC–éŠ3o‘OŸ…ØÍWŠÖ~›6 G3Ó¯!< $šr ©D‰TDk¾vÐ d¯©‰^EV¬"ù¬æ^[ÅdôNãÍp¦qƒˆ<·‰)#×7%cZêÿl¯*Œ¿ƒ¼¼<žÄŸ¢¦¦ÆÆÆF¼^=¬¨0 0 ùáÖ™àz5Tß{WúûÐþ:×÷%9ŒhÕ mÆž$—ÑÿŸ­[þŽ#Ycm~‹-òdÍ NUvu/Íy+s/Õy”²'nÒ¡GÃ쿇6hÈâG‚Sšü„d§ÔR¿SŒ¿N&Ìç«)|lYBX*|s?*Øï®ÂüUáoMæ¿U.øÌC…ðc_|M%—Ðz;ªóÎn—÷¼?ÉeäP„ìbïïw#õŽdËÚÈ—\Ü%Ý'Tv& ‹À¦k¸eWîÔ¤ð/4ã6¹—³º»0í±´{ãÙ=FFH±óO¼Qb.s4iW@D臛‡† Gu%hFŸ¶S`ÞËɶ“2À)–,=랪äÒ]Š+Z"§‘KlAõÇî¤c"F`F³¾ÎÆál™¥£Ü,:˜¶¤ç=IûGG`Æ{v$ê¶ïÁHÝIÇ`HcÒ¡§Ãlæ[RËÈüŠ´Ÿƒ”H˜…ÂÏ.MJ¾ßß³¾ª4§5™oµ\aV_~t¼ºÂ“©×këyêýÂ=~5ÔPaüP4ºf%_ïìÙñnµ „Hñ* jXÚ@²ã/¥Pó< XÚÜ(åF¶/=,tT¯"t€wâô!Þݳw¦˜xÛŸ¨&’¢a ”•BÝ‹÷µì¬ è—d1x4E`ðiðÅ'úFXå9úVÖŠ”Ï»’΄Žõl)ó­– ZùèÀ™ƒç݆ßK¿Qð騕 @ûU,ÅA…ñ#@V´QþpèØkcGo%2p5©ÁØ^^xóŠÖsÄðx æ…dèÁ>:€~-ÁXì2¨ˆˆÌ Åör„G4åC5ðÅM,¢=Ô õ2lŠBè’ôDNÕÎ¥pÀÉ"#Yº0I!b¤;ú?®£PGÉ÷ë ääèé›$&&ÊÉÈÙF†ü¾d…‡‡Ç›7o¿±±1êŠþ}"­ˆ‘AèÿcšD—ðfb,)c ½Gb7ŽuŠEàd=ðý½Fà´jaÞ@œ!ÿzDÐ3Ï4Øsm½úï?”Ìe¨ŽnOGì¿-í@øÅM\˜‰o„¦Û§?¾+47]ÚRæ[+·ÕÎ7 ì?D¨kæá⯡›G`·ŸâAšò+,,„/÷{pþüy±Aâ·oßêèèÀ:ùQ Éè €õÄiiéúúzCCÃÜÜ\ ùý8„……íܹõ8;;_¿~VTš-z·HÞÉ‘——§««[TT ùý(ìØ±c×®] K—.°6  Â€h—(++ÓÒÒ¢R©––– ¨‡Íf£ª¢´´466–0ËñCÀçóQ­œ˜˜«* ˆ¯¢´úåÉGËÚ,{›.lFœTÏßœ1ê?dÌÇ6FGÑü¯¦JyÊ>µÑªÞv_Ô&ï “¦€áV? ´‡¡âœ ?ù¿„ŠL#Âî2Tp„ÑæÁãÈ”¦•‰Æ'%§nË“Vò’wAñ_?kŠ…h¤‹ßÚL&IìùNúì²¹dê_ù0<€î—”›ëkÄäµ"ÕúQ|/>'¯­ š§? ¨0~0þÝEoArlžoœ~6Hè'½*;~¯‡~¥Éy7uÿ¡L4úõU ËJ&n5öé‚+5Ê£eP?ë廓G‘ ùêè7imÔA>Ö^[14Þ-ðõo¹…½ôûtn—íч#Þ—?σmðÏ\žyôL‡…ã÷G:›E_²Ó¥µÿŽ;yQiP¼îçUŠJHrlþ8#¼ÎÙ­~>qFÄ•MGcsæ©4}œ—¨Ÿ÷HÍ•òÕïcC|nr|aP¼ÿSc~bdÕÛÛm¹oºèõ·—â}„¦  Âø‰¡*(ä½hÓ ¿a7jvÖT­Æ¾Êæic4CyÀyGøÕ1 ª¨DAÜúÿÌüö5…/Vk… 9/HAÝë?ê†9 3ïØ­\ô–»{â}Æl¢5§Ñn]#` -¬)ý¯’}Fj£ÁyÅ œô¯¤ÕZá¶š—‰ºÜš—/z•S¸.óù½*ݱ=‰XºÍª‘m$-ÚÏ Ìd*¡-JVÿqºšb£1Ø ­n’¨Î)ÍéYh‘ÄüéÐÁ›b¾ªÄGÑ$Í ‰uôññ ~*Íy‡KÑT …A£þ—Äb¥N®)³éNšQˆL÷ˆá£›¼8¿R—A©iP³£7‹n5Öižá‰Ø¼3ºLU¯àËc¾ÑOYqÎ+.ŠìwP¹“çUu­îˆÄ½.Žì{Ü §³2ÿyΠ•×[T'ÐêÑ{0áVò÷·/ ê\›cqÀΈ½?²ŸŽ¹yqÎ'â´Jf¦Mo•“ìU½>kög½:_Åíb&ýùS+i;HÐWœ M»ðZǺ§¦9 z%d‹t;¤j­£AÊúÈq~FGÊÏóªüÃqù4uºš2‰‡êMC* IÙêaíŽôÒ7¼æL4†§ëÛʾô‰ÛAÙϘÄyù½¥iÚ1ïüp÷LCÞƒ:Oú§Óe¯LuMè€]syWiïP-xÑ#TíæŒˆDœD×=šj™Šß!e‹‰m]‰nM8ÕÛj,@†ˆ»‹¢šÈèÒAñÒ¾Û£ö|d™>,1³YK3Tâ,ÒÇ!Â’ÐÓmu~j¿{Ð|Ô Á­D€©fÍòn•ì+°žu_ó˜Gü”n5­öú !½Š×®¯fyPü›sBš?]û푆ŠÄ¯‡(Ì4Ìд‰&^ÀwÐrÀ}ƒU…$ñQHúÝšäŸD9ÓF#¢uóVÃ$_xl†)ù¥@@…ñÃÀf³a%@|H?O³¬‚Ž?–ç;Í1@=Ç–•ûÏU»²¾ð#›ä­{yE)]™ÏV‘óô“K]\:pÖ³õyæÃK¤”ÞV¤¥Ôiºhª¿y÷°Œ£›¹± Š-5`ºvÑé’'/9t-Œð•çÆÏ÷>0íuÀe_È"K§e¡YužfxSTô½Uy]§jÜ,¦õì@’ø§./dZÈó åúZ’.¯-¨f“}fj_T¤ã¯o‹T<8õÀ§Å9œÓkKù š…ëQÉ?Löùƒzª½æ«ÍeçÓ ®®/¨DèC&)^T¤ÕK¶ƒ“ª¶ûÊ[)åZ‚øÝï…­?Åwèô?¡`=¸–oæbÊääÌ­0Z&÷jËÙ£é*Ýç¹Ú>ö(7ïÖ×§e*¶—*„ëRò.¾PmØ7Û{åºôøAU,ÿÅ+“£‡ê<å sæô¾S:«¨Çã&ñ˜æóVs ¢½ÝלA=»ÙÌZu/ póÎÞf °/!Š ÏÞU—M íµ"]’µÊ«s3®é“ʺͿT÷(1õpš¦ÇzÍœY÷‹™Ã–î¿@ð°ô±çÍÁðGÙÅ&#Ödm‡²ôñh< °‡Lí*æ¼'éà©]ÉǤ_ As`°Õ|Wmx²¤Ÿõü‹gæLE‰qøÚSü£¨J+à+’)VJ9åtGC¿žƒ0)iKJ=&0_<ç¼ù£Á¾;íî-Ö Ùzç¾)ó~a²¥Ò Ê•é)uJ]Õœ­Y¯^rÞÞüì4Í@º¼aIʲ˜(³nRÝØþHÊE½îܱZ-WMÇnÔÜSBëÀûx6ùc§z沟9|³¥ÌcãùSvÁÃFç)Zç–a_{ºÜÕŸFçâÆH[^ÊPá×IË –’á_Žø+ÎH(eO„t³§kxÖüF Â€øKðŸ«Þø´Ôf’¾¢ÿı:—ßgœNùÑ|.Íq¸BÊ´TžÿƒëË Œ£Të˜ì§¥Öõåñ¦Õh°¶w|U¥Ållø ÈäÚ*>Ð% XlYE&ŸçêÚºz’ÊæµrŸRÃ㲞³ —^Öóòcô  ÷J¥T¥(=-ÉÇVy=ðQ?…â£_q³Œg®bÎa"äZi'-CðJÄyãÓ2ëIŠ$>‹OÂs* ¬`KA‰µòJÕ¿ö?³eš@pð^tºl'‡,eëãÉNÞu/À“„1% YYs;N>cÄ|p»HI¢ãÒEéÐR0lÉi"ÖoiꇫQå, +M9æg⎩ÊZº¸>ÓçNóZy°J„Z˜÷‰ÊÔmÁ?ýF‡à…ËîÌï’¤ý´"=#ÆÇ$vzc­[ÌCA££¦ƒ·óª’lÀYRNMf¬ÜÆ+Û)æüäQnðꌺwÅ2£°r×Dáo{ÿ$J¼õÐÒ=_{ŠJž˜´ð?5Ú ËŸ>åñ”ðI&Dº‹ê@³š2…AªÊE[¾&óøˆžMCfê—Éç’iVª.<æ¹wQhY®€Ç§2ÔTà?K8I%’±ŠšTÀÃÏ8„¢B‹Ù FŠÚ7Áñd!ðçNK žÀ5\çå–<oöí ¢.þŠ™<ï|mAõÇfO÷GóÇ# ˆïÑÇö‘-µðN2iˆ?ãÜì‹RÀbÑ®êÚFcÇ­ÑÆFw6¶#³×\Lô-¨~¹÷…Lö·³zk|ÖWZ¦;š/ Q”sTü¢h§ÙXÎ=;|ÁÃV›3Õ×u5pRt°À¬½ó—àA •˜EB|»¨¬I‘PQÐ…µÆ‚†††˜Û¹ØÜ>±FWçYö¦ò»h3K*ªÔUÔhÂ(÷x£'kòlÇ«Ý.¤Û1ªóä”óÖç÷‰3oÞ}ÔÓ.¨+_]Vê9IúR6£_Wîzí¡¯ù:'ãò|‰]_.{¸wf“³µO?䩨Ôí) Æ%)2õ¬È—!¡x¼.ß*D¡DZáéšRÏ©²· ZõëeóUùE)ÝHùÜsL»xkg"Ý×fÞ[Ø×ÖÓˆç˜$]¸ªBk&1iƒFy%f>Œëk7cþ\+GæÞ· Sß.éç¾.y1»Æh¹ô›ÍÀlò¥Ù“Åô:ÿ¸«g÷Šk…wDx¯Úy$Ê=03fÎ}³¸Ts¾ž´p6BPuúÎ;çnZ¯Ú}:0à ‡"™7ñÝΜˆë;«÷“F¿NŸÖ_cO¤Nú­Áo0ä¼¾òFËEùJÿ$nò ¹näÚôн÷ Î=oßö¡±¯¹êا}}2׿w™nPr¬ TCÙ¶‡ŒIr‘@pd×çÀád‰5¹¢Ðy66¾â—W•É+kc=Iï ™ç«QŸ åЖññY£œÉçÊl¥¾–äo|PÜü÷ïÔÕt$ºÿ×–ôš§Ÿ²¨Ø{!¶ðU=fê_]Và2WÿúòÂ^ári÷i^NüŒ747Ãúû¤»ª5üQÊp6#C…ñŸvðFFÚ^ûÁÚ‚J­þzMQàð@CNM'kíOw8•Z@¡Rð©RÀ4d)A5GHilC4¤¾VÀ`Ù5Í¢Ò™yÉï»D«½>Rfç¯/>xÀ¯hÔ6AˆÍë ¥uWÊå¾cæ•JGH24F£@Ömk‘ªçŸÁ?¦0þσ{-AFÐjA¤’îÆûT8o`øe=s‘ú¬ívÔfUðY€Ú‘Š€Ú÷¦ B¦4T ë1±7tÆç <öùˆ7HϾ8péAöÓuY ¤· I€<Ž””˜„ÿNzÂÿÌç• øl´H>›Oøõ:§‘d;1ز;£ T>¹Ú›Âøð;5’#pò–!5°ŽìªŒ õþp[~ÿ0CÀÿ¢¦!Ï#V¥²F Êú€b£Hæk8MrøôÝñÙ‚?ý ¤ To/*ò˜¥C®ú|æÀ硳ÔË™²ŸÏçq9EUoiŠN3ñq)~ €¶)Æ™F$ ÍŽ¸€/ K!¿rKF˜ªÂÇÝgVž/úÔU½¿“Ä, Õ Ž³°† ;ÑSÛ¥ŽO¶Ê:b« ÀHE]4Ù%žó­#Ó.Ë7ðÁ‘À™Øk§`bžF89«Ð#PÁÇ -™€±X`³á ›(,›_ÆK±ÃìÉæÚÀ\ÓÞ1íÆöŽ7¾½µç’‹§FÔ:.à&1EAµFëÙiÉEÔ‹=UŸµØY|m@Îe F`2­no| ¯<-/ð‰lq(fAðïâ·¼î(ößa–öoPwl‚ÝÓYY¸v‚Ö¾þ ¨' 1 umÑ?ƒ8ìªÏ.Mx6{c‡>°Y5}<¡¶è«d©,ƒ±Œý–.jwBÞöÙ­UàÒE¥NÁº„vo()–Ø`÷b±î8Cá}Úr²V˜È)÷Æ~ eý§©*”CT‘`‹zºj}ÿüƒBüâ/]Kfè,ì=âK&ƒã1®:‰ˆzÏÁ/–‚­·yà¥öÆ µÇ6OÉöP„SRÿ7Ôå*2ÿïS?ÒF–˜%䦀n.Fg¿Qï^|mþ€Z/ƒ¿‘ÊU¬]ñ\ã!ÕÑ‚s²,õ¤8À¾—jYêßÉеWOð~WYjSÈîݻnjÓF«ÛêXØ–U!ÿ=QwèüÝÂL7ªûÔýÿ¼¶ø þ+(©KC…!1×A¢üöîÛdi ÍÖv\\ÜÏ- Ó'͇G,4l D›ƒÁ€•Fû†¬„£G†•ð/ΦB@…įœœœ#GŽ ýßøøøÁ]±bEdddbbbKwüøñÄö§VÝaÆn°9FL¢ÉÁWDsÔÔÔ(* íÒ!2pàÀ””X-Pa@@üKhG'½ÌÌÌrrrP¿ººú† ÚQ=766Baƒ€ âßÃóçÏñ›€©©)±_* ˆÖQ]]íëë{åÊXPa@@´ œz¸¢¤&§mòæ¿@osƨ6È“ª0¦çz(<Pa@@@@@@…ñ £ÙIïɱ¹Þ±FLR“ç;é¿OJNÝ– ÷ßï¾…'½! Â€€hü÷ÕG6¯‡ðyÉñîóä+«þV¯¶ös ´{7WT¼’Ê£I Añ:¨?=6W}¼¡&r<6×$ÂÀR›Ts«ôd’ù°ß¼?±Ÿ)'X@K <›«è§×ÃJJPßp8¡Ì/μ,;~¨aHœGbsùJòAÓ”Ÿê¯® Š×ƒ/* ˆ™[«Â ±VœDŠÇ–„…cƒ.“´^-)ÞÍï¬ h<ûÁ•**d5PòŠk£Äá2ª-ÐX…îZà|nëdš”ûòóñãç®3 ²ÖuÃ7P!ÈÀÁ´Ów`ÕäVØ—ˆ0¤Aæ ¾3šº2×5*èŒTÂbe™¼€À·Ä¿çñŠG6t‰3ðÇç÷™g„‡Úá#ŒÛëKe{é´Lõêxµ´“V×ÞtVQÍK€°*¹€Æ$^V!ßJôþbñWÉÅnª(?æ©%vñ:èø&å> 1åïæSnK)~íç·ŸA€‰ÿ¾(¨0 þ þ‰5 ’šbP<~$! ÅG@€ã áØ‚|ˆ=æSŒÌñŸ4]÷) DT€ˆF­ŸNP?ð5²/ž¨³FP<Á9P”ÜSä!ÉIÅ‘M5ƒL…IÜâÅÃRP¼Ñ?QÏðàTPa@@H {sžA„!£¡áäY¾Ÿ¿Ô³ª…ê×çùyœKÏI}-›_¢qnI©×|­ï*/à#I\‡ÕJ‰_.5œ_Râ1_ûï=Ý“Ä<ëÈæçÆ€|ým(¶ª¢]*ŒúGËžŸ±ïJoÅ?Ûu(¨[³53z\7g÷5™—–5ÿ¤#œU3»1[ÿÙ2¯(Ï^/5{sët5yG™É”skÿ‰§{–¼^Þoš.Ê҆Γ°ö´±JÀ)g.꥾»þþa»î/0^Ÿh¬_nÉÓ²¦ºëH2ù 4õ,kà\½[I¥lž@e°.Xw³qÔ‘& Žì®ÌͧÈ29#U§‹¨ DÀx/0Dß3¿êc‰´Böa¶&cÔÐÑ´é×¹hŽª3^Uy,ÐåÖÄ'F<^/c«°Äʽ¥Â&Ûú)`¼Üóyz])â||‡2pÝ€þÙR8Q¾*­PÚQ¾TJÞPUBhr-BÏ¥.70Fõ²(çÚ(íSa4>í¿T.3åÚpgg»ë™ÒUÜâÁÕ îÏÖ„üástœöÄIk¶lžxeÎ}VefÌ9uòª0ð” _D]]‹ývº¨Û0Ý÷©“fÔÎÂ‰Ž„9«­ºæªD*;5>Q9!ÁYž(vFï^Ó3;â·¬…Œž¼Ý7ÂY=ñZRÉѰ¥ŒþiCR}N­uW.Ø?bŸåö‘îq™J$àãì|43óÔ—9÷Ox¨wòvíqÎΉ™™è§|nÏžþ£Gç^:¦í=íʘoåu…ÁMà $p ¦Vð÷.tù¢ƒORQ@ÓèJd‹—¨ã×CL‚EÉôhêãKò QbS`~ƒÃCÐTù`°‰2@]T[ ®’§žˆ14OŒabT4pŽÆ9/Ð…òÑF£s¿é«W/¹sçÎÔÕ˽zygfžÙ í}îƒãò©¥™ÆÜ¢ß_0zâ) ðj$Sr‹N´Œòéƒ}cÊ]\Š×!×^ƒEøÝišƒ·&H$Ÿ2Æ`Úú§fv%~îà¾éè Œ«;¸¾Þš‡zü{`m·’®BEoÃÕ Î.×ôÎvæµEÎÉ`ŒVú¶ÌLbbâøîÝFŽ&òÿvÎ$%Ï´Ù§·×ÖíR÷µó„’÷]:à¿;¸÷oŸ_²Ž4øO g±XPØ Ú‚Â gf^ÿÈÌÄ€UÌ+´g”±+^wxÆj¢Û¦”™¹ £¹°sñù¨fQ^IDK ÈZ«0*ô¯ÛõÌV Ö¹ÿ”ÄÏ­GQ7IØÖ)½‹Ë„9 uÝDÙɼ¶Eœdó—9»mnViç5,Ä{Gæ÷ä,üÙyôõ-Pêþ1ð8GÉÙkõ2þœžR§ÔUÍÙŠõüA=Õ^ÓD áWÔ”H+IÍEêcv06ÚŸÊúÓRyþs ®/+&òµn‚ãÉ ¾}±_|ûGª¨\ÖóBfJ¥T¥(=-ÉçNƒ³iˆð逸qyŸýŠ›eïY@Eâ'P>@ðE@nñÄk²VÛüǹø7zCœÂýWkE/ĵ…žƒ!ý†í¿{X¿,ˆÿ€(ìh´z æ¯?|eíAKܺ+ 4s |bˆi¯ 죰yEiUt|@Áˆ–°Ô$fÊü§*JMQ'ÔÿáØRJOüÞpDZº·À¶:êöš«Žu˜˜Aü‚ü –ØVƤ¸\Õ&fˆ• ñV.â隭ШôЄ2Ñ^'wûµðž´¼iwT?ÆMßs)©øÐHrà>M Ȓ-ûÁëʱ-.àjê—“‰mÅÉ£È{5ÉbËmÊô™Â$w÷Åo¸ð¦´ 6#ó¸Û˜S»ýyàUNVË«·œ}p¦¾ãŸ24E-“oQ´Üs*h‡ÆAÓ‚¸‚àßÚ ûQm[aPŒÂñekÃõè¿KI¨OgØ>|ê@Kúœ—$žEx¢¢šu‚ö~é¡elĶ¿ô#BGÆ)¤Dµê†¸„º›ö€¯ö'FßÎã`%ü@ÀEoˆ6¡0  Âø.HNIU-[Ø)çÖyúªº󬻿,™ ?xóžh«ov~ †øMbË™Ÿù=.˜HØupŸ³£Ÿ .ž?ç› ~š‰Ë€ÏF}d.+åâ¶Ê´qËRÒxÏ&þ¡ !=±mÁ?þ¬ÞÏB´¯…¦"5õÙá¨K'¢D ߊ•wiAmñC +â¿W£0Wì¿)¶†qqêSö܆íÿ X´\Ãë˜&m!‚ÅÐuÂñ„@>Á¾;ˆŸj„T߉øøxÍí{¤,5žXÈÙœ1ê§|Gnfafš½ Â€€€€€€# ¨0  ÂÀÀ+;š¥` ¼gÞKÝäÿ-RN~èöò]í§ \›zŒkx×h§øý–oj¯>§ºšÓ±s‚¯ÿÇÞyÀEq¼}|v÷GïUA) bA=APD¤Y°Kì]QcÔX£bÔ1Ä‚ v9{ï%öF¥I»¶ûîÞÇÑÔäÕü-Ï÷£ÇììôÛ›ß>³;3ƒiÇÌÓw­Q Q:<­t…Ÿâ`ÜോWPOàjlH³Ø]òe%=§ÍŽ×SsV+FL9.ußùg×èéGf4qŒ½ÜW™lp»7jæ¬MJZwUÏ(é×ÚÀEúd¿öóÒhÇÙ^ÎÓŽعãƒôO\ò4þøÛÅÁžóS™Ÿra™ŽO=ü–É¿ô˜7=-®k®È(ô×lLvlv×Ì1l°Ó+­(Ý‹#‹š/Õ{ô{êÖƒæ–zxÔÝ3%X£E4iãÕ©¹î‰9oE¦A±kØÿt­²âK9üu0$¾It¬S¨Z‚þíþ×7HìÂêðN3+Þk‘„|I|ËôòEòÅw”‹Ø·mÃeŸ7&±Æ†²;o9®fíZ0«Üç~Á÷©ËEdêÜ|G]²žN;ÍBÅ:ù-mKîÞß;Qâ7ÕF«€Yßàqù’øJÿ~ y|¶¸íh=ùþžûçdð I±‘ŽŸI‡Ô¹–Qäl¡q3ûÔ9q ©Ó°z¢»Y% Íô?kÿ- \úMÆäÌÝG°®«Î ZµjÑ­b‚c|.íÕÖ1öÊïåÁŽÑý'ÐŽØÅ'ô®½±pÿO˜¹ùÓÕ½¢7ré7ç;NIìùÓ¸äeƒ¶f½½|7e¾Kìu; G¶ÿéûSJ᪠UŽG«”dùb^ðOûv¯êÒuÊY-Kã-#¬H$ šxH÷­ÑyYÉÓ¸²§õÐÍâR‰"…1Þ^2#‹‘Þ^;·‘¹Í~ðs7=+M›a›¯Oíæ6g­(×Ï=9d/BTß>mÁqò2òUìˆ'a)/ {±{ÞîˆØæw…÷¶Ö~@¨w)EÝw3kób²ŠŽ‚ÀêEÎS¸Å ^” ¥Ç¼Y¢›íFìµå_9ÿ¼¬Yî—˜DQIÖî¼7/Ïÿíá‰%oωœ—v<¦[ ÏÄó×4]ÙÍC·ñ²«£]bRõˆUP‚(Ì%Q‚‰µõùtqUKÐw´´•Év.|×}4³âý«UÌ’øj‹äïQ-b߯š®¥ç +ù6ºuRçf¡Ìƈ§/sºú¢Òk™í&ÙèQeGï£ÔT¤X'Ÿ|[Âv2kOíÜZÌL8«X³×ã:wi­wøºÌ×•É “’Þ?Yeo&Azùo%—žh‡´AÛ®pÂÇ›^œÏìáÆmbrä˜8À›óµ aæ"wLݵEá´šÙÍh|Sy§lo¯ Ésœ ÷C: [Óÿh‡Qùü>×òÎSèûqÉŒç_uQ³Ee,}öÏ@Ú±*¨Òto–UÅ{‹SW„ ?L_Šûæ¶SœZ駉ü:)ã&Òæ…Ò°º™þl=Ÿâ0þX¥]’ZÎÙC•=êÕ_¿ÙUO¿]žuÛÌì½sZ^9y¯¹'S#—aAò›G1‡['8V ]ðc¢00à¶òí‰;.8¬ðg×Ó„ùÙ+'æªÔB^×y¡-ó×½µ B6Ëå¿y-¾ET3„šE3K¾GÎù•þôš¿‡*:yíî;7î ë<Ãeÿ~16Ï[Þ1ašZîõè~©-AÏÈI÷ÉÌ}ª£rT,‰ïT±H¾j{TÓ6ºŒc¤ÖílÊÑÅRžÙ0ØI¹N>n¤×Hžmwf;w f¡{µÔ*ö V†–oñF7 bÒèÍØfÅ…ÒÏ3"qkÅË.í¿!)ò]Ú!©·¿qáèÅKÃkØ^˜¢jXºFè~× _uŸêJHdzIµˆ»V†§åª†¡èt6»#j2VS€ú8¯ArÒºŠ’ç~¦í[]{aTFí%Šì*à Ža,\¾gn-cbÿ/>W:ð-‚iy¶e6lÝøó–ÈwRùl…ÔÖrÔþ éøWìB¯&Ì“…èú #cNjjA}¦åý¿ˆ`àúq:eýçûw÷xÓnË»À©—ñÂ÷)ËÝG“do?µýÏΑË'l¬ªègoÎ}ï8¥ð/åðT±4€ À)g5™‘%&=q¥ÀjVÅ9"y˜³šŠa(IDü=Õð×O;NKï©!€¢óµ–§Ÿñº¸‘¼%—¦IäcPN‘­KÔÒ|ŸYJ§ (UÖÂp»0¤- šxD5º%âòó°OÅãæfÉÇÊ Êu\Y2­ <Í"Çñ£þx*/}ƒÂVUA5&F§óâY¦~ 3|çà·–ƒ9F¶¦+(Ýó“bX¯ÓÈVjõÍù+ÂR5Ž÷úÅ{{&â^>Ü2ÄbXšè?x^ÀWoa œ'¿±ÆR*²$O§å¯£‡gÈ·Zò˜°$W XÙ”‡Q†2-78fJ¥(:}£ò|ù-f+Æ |Û³*i*K³Ma¦,TÝbÂoÑH½šò±2S¹¥X‘¦"Œ¼T3Õª°Þ®¼Hö®Êá;Õ8ØJçÌæmÁ«TÃzjt–ªTU¤õü´Óúöë-Y°~3\Ü(ÍìólŸõM¾VûóÒßú÷÷á*TûG„ÏN ‡ßðò=,vÛ\Y…á^‰ð…~o‚€` ‚ ‚€` ðÆçZö @0 Á@0 @0 Á@0 @0 Á@0 @0 Á~LÁ ¥pà“ÿ•!ÆS4ý#1ªü”ú BRº`†)ÓP‚¡Ê!é`’ÐN q“VcIäÉ"&¬ÒÓ)cWÀÿL01 dòÞÃH\ÞƒÓý:…0eׯèµ1RFQ8Μ¯Q”]¼zª†+’UùÒ)‘2Âp ')$ŠT„ÄjH–.!÷—Éu‡¯à&tN߸“R$Á1‚– FH©”¢oå‹Ê$Z|NÑ÷õtŸ.F8§TBrq1›ÍWÄTØ…ï‹%†S%mdÐ];ãr8\ ‚ Ér äÿZ$hµ 1éÃgÙ/^êêÔ¯o©Íå°pBF‰ œC‹‡¼@´žˆèT?Ïxôú•¾–Acks]]MDá­9Θ;WÀhaÈ»ßó7ŽšGJ©C{ŒõyˆED œü,ó!:š„#Y©˜ðð‹ XZ#÷ïÕMݘõÛ‡O?àá’±*HF0ŠE¢²ÂÈn^Æ&(F‹†H’¶.ȵÉ{V¬ÙÎçëK%ˆ ­BfjÈÚœ¸Œ‡Óú"¥C!Câm»N-Y¶‘äò%2‚Íaãd&)ݲaµ¥)ÁX'XmcYÀ— y·?{Áˆ¥G[‰‰ÛÇ CÿÑ£,)O`lF$Ús਄£G`¼Õ‰ÛT‚ÁŒ:Ñ…ˆ$X”T\,‘ŠèΞÔ¢Ø$Îfãú;œ¿tùÆöÄxŒÅŒ;‘$5þçy§/}Cuðéu"uOƒ)CØÞƒ§­ÜDËŽL’«Ãã‹iû‡+akDôŸ°bÁÄ–®M0Š zðŸ EN7pôô%²’â^=ƒ¥RD°q +—oKE%oØ'1*À¿ã¯ñ‰,Ù#¼Ü¼À(ŒþO̬I#Ó¤?çR´Í@IåB‚­ß´ïÏÄ/߈3²ó,­Œ1yëî³³Wâ¼ðŽ-ƈ1#Vø¹«ÆÆÌ!1íð¨ñ{vÄS$ŽãÔ¯sd|í®¾®±†â”LFQyùÅû95iؼ©#­<“~´)z¯!ž¬v¦L ðAÆaÂ]£˜£âó‚N«ak ü#fŒïÇU“¥I^‚sµoBÓ u{¿!#²Ö®ü(¾Æ•X …á"àÛ §ïéÝ[9œÞ—@‡À0ºǨ/.kp9ó‚àsdWNl‹%²z$…IH$C2‚y>cˆ6<ðþ=»-ÿk‹„0ܽÿàðÁ=ÆúiÄTŠ­ç`c4zt_Š -œEQm]¯ù3¶ÿ¸ÌwXfV¾•™±TF!.‡$e†Äe"Šàâ˜ÌÀ@ûjúN’’1c[K†É>ópMóz&¼r•e<{!ܳ¦ãž5?­=ÒÛŽW©Ë¯WgDV–óòÅéƒ[褞ڣ[¥@S}vÕ\¸VpðíZ…±9HÄâà2R‚QlœÀ1\†“2m¾¢DÎh‹dÓ¦Kƒ‹Q¢Jrü…äA°˜'´K‚ãlæí[‚ää{Rö6ï=NQe&fq™hù‚él6‰—¿òDßœ7³«OŠ ¤±:qwìähÚÂÀií!Ùg/ÝómÛ“Š£  g³—¢>s;X†ÍÛ0ж² <V ðë!<¥nA¬Û°A]²Î%„MJ ðh$=§fŽXö\’\%A€oZ00¦·§û|îë79|G_‹Œ$qE<|üÚÆÚ”C!‘$*(*yUàØ¨N5Á¡¤Rm.03+p1¦œ‡‘Q$bÑý»‹cŠ$NŸ½À<ÐÆq¾&‡Ž¡þ‚$É^Ý·ì>vD;¥?"ÙÚ|vFõËÌe 5Ä«W-±25`cFIè4qœ¿ŒKa_ú-)\wiGÍÑG‹o•¡f¼ZC™¹GN }£7ùK;¾Ä.P¾[Á`Þk"É?Öîݰ3•’ë~mdgFQ¬#J¥Ü²²üÛöQHšñö}`ØHÄb5w¬³zÙlõd2f‡X*}üüÜÌ )„ç彟0e:ÎÑ@’’ÿöˆÄnݼ+“"}=>¤˜|@Jõf.­1íÜ[&í–¾/eÞÉÅÑÎMË;uX*ãä¼guÏ"KÚ×›?kœ¹‰­.A`ÿÉ;µš|„ŠÅäG‚iØ1C›².Ï–!?˜XÀw+Ìsk ;tødq)‹C‘{ö™8¦· ÇJÄ””Íãj‰Å‡…?{I†X qïï•õ†±Q(RòàIvxÿiR’Àp3áã’®+™5eIJ „ççÑ& '(Å a1r¡ìõ1 ×ÖáÑJ@±0œbÓö‡¶6_xr릭{ÿ\»£¬LT‚x÷Ÿæt‰ïbo±îyr‘“áûK·õœm9ô§3ÿã!‡5æ_§^J .Q¾WÁ én\¶â÷݇°ØØ¡½¥t.“F†ú%nÝÛ¤qÄ–Ò=z÷n~$$½Î?~UɧjSRR"‘á!“àl]‰DÜ¢y“yÓ2Òד¯BYZÖEØ•â’÷lœMU-üÑã׎Ëç–3OLh£‡…Ë¢"ºF†w).‘nÝyà¿6R„æå{o­X?ax?ô…-Œ7O®Æü4ú BV=Vò>!¼¹ºžó€ïÚÂÀhÁÂŒõt2F÷׋±jâèô?)’˜|mŠ#0FM¿ºuëε.$ªKNЦ‰¼lݽ7¨kÆÃÊÞã>]ú]<™LÛ(8³Ü‡¤Ž¡öËlñØIK.žÜˆ£6‹LB²ÂûŒÇXÚ’âwÞí[É;sjÆ‚•ÆÆfûtå2F†ZWðgoHÅ$Êha}¸—Y&‘á˜L_OgX¿¨ž™¥Ø)‚ÙÎéãƒRØfaú²ÛŽþåwô/•¯GôâÙQ->YËe¼¯nÊác?qÊÛ¨B ¼‚*ßÈìÍ=êÀpß»`àŽ0œƒÉÖ­ŠÃ”›±(JÖ¾m“vm–áÌw”üM(læ”QN1K–wÇò謸©Ãqœ ä^Ч ù¦IÂÚ6w8°u)ÂHgaå;ø±16G‹æ gál™Œ’ï´Ag‚V1ŽÂa×17N^µ£óÃ{ï)ž¬c‹óOZ¹|ßÈÑl- k<óKªðµÃÇ…Ÿ”gí |ˆQ¤jr&ßWOõ–3ù—ïžWÓ}=FRRL\f7=ù4ly4&$-'˜rôJ+y„ü)¶\pŒªò&“bÕ&8&!):‹™-¼ڋ0Ø4 à+òW;ÄÊMLu(ïÅk¶Qp‚§¯P Ty×êÑh›£<ýþ*²“o«z¬«‡þ‡‚€`‚|»‚q/>8ÅkËgÅ4±@ÐM(%r»Ù¯ý›M?mû© [! ÝC†óFŽŸ|ðÄëôÇ9œ‡%VMŽF3÷þvw YEþn;mæê“´êÚå1f_ (AAÔ­Jå?7D ^ì¢Ëjé¤oóô×!²ëÐ>A—†2¹dŒlÈk:/~òª!=|Ö—(Ê`aìçÏXæ«•0ýí¤öêéQëbV•+¾¥ <Ó»cKóæEG„FY»öþmR›ÈÉBá¾Nè¸ØÍÄUo{šÝî|ySðau+ÁøÏÀ ÿ}™•!3¾iì’Œ>³5~äég(ÞùÖz EÛ²ûØ1úöxÝæQÝ\Ÿ€¡¶ Öv¶$æ,E&fÖîÞBïPf ÉkîùÖAsÚóNåÕ]®Né\¾H“æÊýÈœýïšÅöôn‰PËÄ?Eˆ ÿß7yZ‚¤‘ÞsÏØ]JÝ“.ÔÃPÒæa~3/ýnÂygk§ê"'ŒÝ³K(ÔAHèZ[í(G‚~­\þvo*»R:T*“ÎXa”ê¹ü÷úfø¼5ã½æœ_a¥(C¾² ÔKxþçÊéÑV«¦º£»&U®xU¦÷ê±èWS¬«ê¶ð'c²C…e?¤X‰Ä«ébÝJÖú•šŒÏ Á&J%¤Úø‡r@C—Ët<Ì2²å+xxÆ.ð˜”ÖnÀeç)KèÃB„ž+ "‡žè‹ÒÐî';&óãj ªÙÜð¦ÇÜŸÉy™¥ù£§úìآ'»O ËËG-œ¾pâÌI¿­óŠdÈЖ«âÄ¥!´‰i®ê6ßV=È’¡j#^w³‘µym?(jì!‘Iƒëƒ]g,!„Æl¿.\›9cb¤ Âæ1yÉ1U Yê¡g¹²ª‰ÉËSå)Ȥçu¬†GXëhµµMmõÕ&TCqˆ¢àê@0€o3tú©93—+YT€–¼s+jAä§Û.’\¼B·vFâ5'+''WÙÍ—Ñ]ª&âв!¢óPhÆÃ<äjFTOÚÙx,BNLjR‘TÆbqËC‰^#‘áöuþÊâæ>õè–†ÂC™ƒ7ojÈäUJç¥4޲ÄÈT>0ô456"ªê#G[½<¥¥R *ç!Énì Ï,7î4#€`ß½ç4]Ûg¿¤[8¡¹ƒÎÕéÓ…îúé;ó“ÙT–uøô§'Ŷq 2º8ëuê/–5%+W¡ü‡J[7Ð@INó=<[¯B3ÇzkJs^ÜCh¹=%Pi‘zÊ‘³š%ôÙWÖ-’G‰¼;n[q$ʱ\0â†ßqŸ¦ ‰ÔÓB§OæSÎôAÁã%mñQâx¡F;E€ñco]éH•¼»‰Ð¯ ²Êvél[„bRòéÝ\³xª±p[#„$¥ÒÀ¨1¡ÇÅ¢Û¬ª%¬¹¾‚|O°ë9ïY΋ðIÊ³ÂÆùmîÆŒ;íØë¾q‘„;uu½ÓÝå§¥6~g÷WÇF¹Ö”¬¨HÆnãu{ùáþ{³íÚ;šmE{nöŠŸtP›kÒÈjω(fX§ž“½îM×ÎÇCÊ é´+žÚ!©€ÍÝé¨zv,{Ÿ^Š{Vz–©9hô½==jÜúÞÊ#ƒR²lÜÒæÖUXM›æšõòßø¢˜»©‡Žr«U!QØkþè}‚E…=Ów»Ð>k'5ômŸdPßjËžÐ]vúz¥V+a õ à›gcåçÆMî:ÒP݇Ð7ÝyD¦³"p;a»’ZYå4ÎW=”®ž¬yhÀqf¬È2hb¥8ctS9•„Te"ªÔŒ›Û§ž´¯š=¡]ýx£á!Âá(7í9-Aã}‚ÆWNZÇhÓÞu÷ë,ô«”$fi·µ(v][ »¶RZ‹º+"W/aõú¦«•-½Z9Á€o•é &„Û|Á@0Á@0 Á@0øŒh d­T&šªã,ÿ –-[^¼xÚfÆŒ@h j%??ÁàãäååA# |œÂÂBhÁà3¡«« €`ðqÌÍÍ¡ >ǃF@0ø8ffßÃƸ¸¸3fÀ· €`ÀD__ÿ;¨¨‚|?_ŸàÑ/š»Ó7$´í£t Ø¿æÄ†µú øÄ`zzzUOH2’oð"Ý >{#džLä úŸ?¯YêYH³7_&z¶6úH°$ãàkƒÎ6¼ÿw0i–kÑ=ZÛº&¿qh÷¦º5·Þ'ð‹íù‚`Àÿ¯~щצ½àgõ…³"ó\;È]BØÇ‚1E" ÿ´Äÿ›*|V ƒmé†^YgâÓŸó…‹Qpç´»s¸¼é?Ô¤ÁªP5–ô1éÝô«xíƒ×üûí„ç"üí÷<Ô©gôõ¤„v‘A¤L$%™“ûÏ¿!oÚ¤ìÌ¡{DDw¯5ŠŽBe/lÛ9Ð÷•EöÞ\-“ÖW„?¼&Á-$²àö!Ò%ÔžÅCÒ¬{gääKnï˶élC>:œiÓ»5z÷P†M§‹{vøˆÎ9‘¨:Õ£KQ^é¶z1ž¯ˆÕ»­VÂÆ =º5=þDÔY€2„›yÙQ÷.“n>OcW±0–µ%ï¾øÎ6:Ô’6äJtÊD*yr<£AÇ‹);:Š>µ6¡ã€hI¶ÝŽ6U¯5_Þ;¾<±!ÛÚ—ÿü„¸Y¸þµ5r'þÚv¶wDÀ¦5‰.=Í_îËw·×ÂÎ^-í옵n‡ÐÏÓ[½I{5/Þz…òwÐÚºëòàAL°fè°zî!æëv1±òÎî¤Z†qŸDÈR&.C”T$.HL¾¨j½J [K1ª4NÅÅæk–és0ygdô û{V£!z…·®-mîlRåKߨ;­¸–š×?¶NíúÑÂA0à³!ɼèìßQ׈p7Pþ€ #ÄŠ®Ö¿m#’JÎ^D¨n•ˆ]Ú4¤¯rêèf„Áfsð÷32fEG[I2ŽÛtÑÕfuõ­sýŒ>ÛºKìÄܧriŸœ«gZ¹÷º‚o‹úTåð:\ôàiFÛvá, åœe‚!¦iÖÌÂÄ`ý#¼Ÿ— B&eÇ· Ö\o #ŸºWßÉî«"Úú«ª NõbœP‹%±5vèÔA[—%°`†FŽÜ“õ6GÈ<;ajÔúKXßhö·ÔG–Ý.n¹¥43pÄãq‘ñ¬=骹7Ò(”VMD½Ö­˜¢ˆ÷í`†l{ÐîJMäîųiÇ#ئˆt±àSšoçKéžúµA+úFœ0TiR¬•GáÓËy½iµ ¿Ry°*(c¥½Ñèo¡‡,üO<¿Apxcã9—Ô[ïÄÇ‹Á®’´êb“f>i¢¯Ãêîc~¿ˆjäí·;õ`aI™Ì´Þµ|¥™gÕƒ!ùµD_“ê×XðymxJñ³Âj2屪æ>"Iª–„0õ3”*q¬"Œ¨èÂÏÜEAm”§¨ÊáÛ÷ަó¹}r[¾}ÈÛò`:ê +À L­œÔGëZ½•cQ”rÄ…RV,`Þ¡¢/aaP56³²jL!1 U/jåZ×P‹Jéàj¡0Œiê¢GMÚÒÿŽÅeU ϱˆîX–ûruÂîA=ÝäÁª&«ˆEÕx%©µÞG‹ñ¡‹ C²’ü¼<鵩§mZs²Ot${»úP1U9‚z°·å)¨_?íL¿®ø6`›»ÝHNoÒÙîBé£ü²dïžç‹,+_Ñzùwo"§fg³d~r£W_´6ÍÅmÜ’íÚs!$°õ½5û¶Ør.zp×ûëö7 ïvøUð`âlM†M®Eµ2´QŸ˜°Á?3·Žï¸þ"¿AëÀ†_ß Yjjª……Emwèf}B‚¸âÈ(::ä^ªå/ËNÜ’&Õ0îÓ+øG»ê¾Âo>NËNá-¿Ö²©/!:tèÐOÛ/:úk«N ײî;8úǼê¾Âo¾yttt›a…Âo½.0ÓÁ€/È_ýnjjzðàÁo½.°–‚_°0æ)º»»»‹‹ X¡¤¤ä;¨Xðpæ%*}ëÚ{øàÉ¿¥=úËæ×, øñ8º6Î<àkìÑÆ,Ï,C¨ìkl´›ÙÈÙôóXÞœO»½ò{¾Â°O{q›úgý"ZÎ4Ò²Áà»âG·0þ¡€…À˼yó&Ož í€`ÀDÙ¥!ÛÓý£Æ3Kv\ý3òÎý×áK„ÜoaÝ 1cÆÀ×€`ÀÿÉý;÷³£â¿™ }ñññ_ÈÂ(»ñ:å¼väO:ˆ’%Ç>7°å{ö1ã`ÕÎ~–V¹óˆFä½ÏVf hø'H“Æt(7dIce[ðÍtÉg÷Ê:ÄØšòQòŒ' MqN3ýGÞI\LE ›¶à\;ZÐù[ÝÚz2‚.ÏsK;öë‡eŽÃê9šbÅ׳÷í.¶rÖ~{ó=ÙÐ(¤c7¼ÜñüÌ-ªŽƒFöbÜÙ4¨»&"¥ÕÊŒjŒK—ª‘1zÃãy²82ãI‰ÏÜ{q¯Ô~MÓ:ø÷v©Ã¯þ¿Ð·–lWCyygÇ1ãÞ{äž<Ÿv†Ÿ“úÿ[8£^FÆ1k‡g$?e51ó‹àÓî[KŸ Ó:®¾z_,sílXÓY”³çUÏ$¨Ÿívyµ{qvä4æ¥`ÝÞ6õuƒ¶uqvDœ-Ýâøí‚ËdÞDÍåÈzǼÉúþÌ«ý)ïÒ¦{ün±¶tÌîÆÛg<É“êè³ÞØ 8D›Kwï”49öÕÝ6sÛËj¥¢jŒËRÏÏC2qÂ#G2‹·‘Éò ¾ÃW­@0às g§ø›—t ù 7¿Ž ú6ãó<Ã0ÔVü}ö„²ìÁS¸mÝ9w®U UãÙ¿ïȬz*›‘[OI²nSM¹siyP>øÐà!iIí]³±òÁψ@b‰˜92W·g+<Ù=΢ܬ0lÿ¬'ed¹ySc©j‰Ë0•—…àXòIÚà°tÓw뤯oCRðÃ[¨bc6YõÓº:('·Õcúš÷_}£•ü<Ï0Ê·;e†÷U£WÕÚ¬¶³ÔGöGý×ßÞ6¼ò FRºsÅ›®Óm5+…îñŸÕ\ªã**ZîÄØ2ÕÕ¼ÔÙOØÍÌ‚‚ù ð#Ch ô"OÖЀ(¾Wý´Cûöuc¨æ‰YpìòûòA¿o ƒéJ%$bîûIiõÓÖu± —ËP=¦÷|pFŒ´?~¶‘qìT1²eÊþÎGšŸ§bZÈÉñå}üë›%–Î|$Ó_«\-èáÛZKUc\uå+?xˆ5vf[¸ê‡9ð’ç¼E ðƒÓ}öï»gz^ê¶ŸÌFé2ªÒ¯ˆ×tA[ÏIÇ´í‚B‡wܺë›\‹ðŸZÎf(uIf3wÞ­ã%Xµ­±­zXžõ2µ@ƒ_jâÆC÷?~Ö(°.{ÆÓ½kÈžÿ-ê4ÍösˆÁš{ãžX:h½\Tˆó#éNŸ«A Ù¾õoô¤eŶ&¥ï~çYC©jŠ«ž4ucç³û§y&†ø‹»%–Áu¿¿‹þa—£å²@9£¢¾bj…ãÒ(ÇŠ¶A lƒ”î¨Åm“¯ó©²²²nÚ´©ŠÿŸþIkÆõë×›5kö)é4jÛDîhÜV_éÕÈ<²‘ª›aGÆUôø.žò?l®âqtÍgRîé^~ª"O32NisXõ·µª¥Tlµ2¨ÜZÍL#•u2Q}¥aj@^¶U³+/UMqÕ‚axD¹»Íwzñƒ`À­]ºtÉÈÈ ÝžžžÕôë×é%å{ðx¼½{÷úøø@» 𣞞NëDQQ‘º§LVãûõë׫F¥h+Ä××—vÞºuK}÷ò¯‡äOª{v³e÷‚À?¥©feeUE-h®]»†Õ4EyìØ±U|Þ½{gaÁL2pnf½¨ÅWU;õá#>N^j8Ç›¦ìAòϳ"l,<…<“tˆ³jƒ2ŠèÊ©göøïoÿ~›?ØÝÛMu+gI" ÿ¤RýÃS ndQΦhÉ’%3gΔH$ÅÅÅ ggç3gÎT O[U„¤S§N>ô÷÷5­'³†¨4yN&íoÕÖ¤¯–zÈ‚…ºM?°òõ¦3ùà{OKáC¼I{uQdÈûŒ—Ö½åOíGÔ“\Å—rø-ê`H*>|“ðu+Ðá³¼8çÉK1bér;·Ôã¢3¿2‡4ú]êúµü:[ àûAßgʉ{ï[æ/êiXJ¡ iÅ›m;xÙ±³_“c1^ó÷î?(8¦ÃîíŠ]·ð­Ÿ¦r)ƒè'¦t÷žqH¥Rï/.åê’{Ó=g®æsßy Õ®T÷]ï//Ìle×tÜ1UȽcþñ«±›ë‹(éαÝãfïÐ+pášmc}ÃãÓ•?<‹ÊÝs!KÐÒâê©nÅkC|—çTN¡EìÑãåřډ.UǺòmçj>ZìGœ™øׯX9´cîܹK—.ÍÎή1˜â†‚€€¡P3eÊ…Ï£7ç«>6íê㨬4íœÄÏulñó<1Ñm¢ÙÁ]o­pM,ïà¾"só¶m¸r™”ìYœAjpõD×2ñÐÚw¯”pZ˜ÿ½"3à‹ÛKŸ:޶9¹ôù;Œ2ÜNÁâ­¨~[cK–øÄc–‡a¡"pÖ¦¹bV—q–l©2µ QfrY£N,}Q Æ;5;yV¬Snÿß~«^2'ïî-ñó«e‚ÑÖÄå)÷†¥ŠÄYé7HìÂê8ÚéËž+2z.;ý‚äk|(A*N»$ÕÂñÈ8ÚóÒ§Í'ÖCå‡`aÀ×·YÖöe—eRرgçæÙOFèyC÷ÆôûŽ-öÍí[&+¤ÝŽmê# ñ»ËçQ}•û )*Ü1ÕŸ’–H¦ˆ¢vCœwèŠ[Ä`Žä>®šMFQÂô£æ¬@”äVB€eÿTÅx9Û‰þQÙ:kK:3ÝK{!i‘YÂxö&õT‹nìrôè†ã‚ÌtØ T+¶ª§ Vl¦Tlí™ú?Ï·Špe} ÀŸÀ9eee5ηP<ÃhÙ²åèÑ£{öìù‘´x¼‚ë…È]×s¬ !.½œÁ2f±Û9²2ƒÐ)F§ç>Gm˜·¡dÙæŒ[¶ä£ÒbQ# ñææ °¿Ë“)»™Ùl¸N‘ƤàHd–ŸÂŒ\÷u¦ñPk}¹÷€¨‹ó{ejq™S;·‹êáÍ”æ¯A¥2ÐV»™I/jÇ–’à`å)Ì^OQ’½·Èc­õ´°²[NÊŒÊÊrÂÇš^ýíimµµáY2B¸¿ûH³óåw [°JIZ HÅÕºýlÚÔûÖ•Á¾'0W­½w­ãa“™4Ømü*$Q,ÍAž8gÒkÚ¸íãÂéƒÛÂûÖíòŒ[Ñ·ä/ÊÝNØkãŽs¶ÿ½1¶†Ÿ¦ïkµîÈˤñŒSúÍY#~°>³ùR*'ùøÍ†ÞÞ®|M.®êî%·$zpµ¨u;ÔvVúë…~3Ò42w#ªÓƒ7b'µTµš…žßÒä\¯¶ëÕ^l-O¡MH¥bÓ¦Oq´ÞõñÂ,aÆ«½ÀŸ Ç‹¯Í¸páÂ' ß—»kŠîfeš›ÚhTLÐÞŸ:Ù”,?&¬ŒZZ¡·g3eM”cMj£x)3ÿO–’È0EçÎÄ-OŒ)'ãþ´¹ÀU¦ÖÜÜ”[1¼Ê¸\•2T|¥¦~JQ’À_ê ™lç¼w]Tñ¶--e. òUCAæ’¨A‰ÄÚú|•…qlösuA¸}^ÚÆ…_5&U¼y·Zþ7¬¾üO¯éC™ƒøƒä›$§ööù¶Dä¤r£–Û™è½céÏú&Ksyrú7*Ž{þ¶ŽþÃwÈôýNÞÞŒoý^;+JÀiÊÆPÛÙGh'}Ok=#vÓ±0¼¾aù¨:Û®ƒ=ý§«;3i¡³À¡«jLAUle©<Éo_'š#d>¯¦&Ôß’úŠ›kËv&|XT±î¥e/süLžÊlaKI70,K]‘ád‡î½¡ìM0ª¤4%>ñ¹ÝZqOÌ|ÞxŒrÆFKwt(!܇ñœÌÏ.y–‹¸Ýǚ׳%ÝÓ(½ð≣.UOù®×Éüü²çïŠ1ß u5Åå©É§<ÐqÏ/eĺL°º§¦€UÊ@ûˆoæì>SâcóxÝÅ©»o(¾%øÎæ—÷ŸËlƒ¬¸ö„*#¯fe;¾h zâÂæ9doQ¬ïdàŠ#‘ÒÛ{‚Éb]¹Ikr:«÷]®u‚_œ÷W¥n;lºö[)pddä' j¨¿›„ij„Mfæ6·paÞ¤bN´·VŸõ‡ñ5‚§*o·÷Ýò‡ÈȤ£E§ò0^c•l{Y3)x¨&KëÊc#­Ë»®ŠÔÉ{ŽVžj6¶Â¿Ù`ë*3õZ™{Ö|Ê¡g‡r·*#-óî•‚™µ7h_ÑírÍÓðï€P‡J/kµbó]É Àne]“ûs¸`yuOm·‰=Ü&þRøÙ½{÷СC¿ÃoßH¯ü@0‰®$Å0£(z΃»è³wÒˆ{Þ½íúQd¯ÝÐîäªû wæù8ÄìN×-tÉ1Ö§EQ‘:é§õ±©d1ùÈmËàà`¸  à{¦îÐ4F|ɽ©™ò‘eYæê ½ÁuØOÜ7v};÷øÉ' ùoûõ¡Oí›mÛsúœK3¼ZùÈBry\yjÏn¬çÌ=Y‰þR¼?Ç-&ØiÃ3~ß`‡„ì2d¡>½Œ”tŽM½3Ï»ôꉦS ØÅ»vÝ iÔqú!B|ñÂóÒÇåY”]¥ ìÁÀ®tE^ç_ÜÛµú,ŒcñY‡k½£áÓ\zú5¯]¹xHDe$º8ï™`„á¹ç­,J®—h»”œ{ÁsÓÈ{ªcødūοXýC5.|_@«ðèMž‡âË¥.Fæd”"\˜óÜcªuúÜžSêî\ò®ûXƒÓûŠÛuÕ‚Ÿðã€5w´Ü-Ÿ6A‰ý:Rß}g¦D(Þ… ùm#’å&O9'–½}Ö¼È9¿’ò·9Ùl aôý<¥|¹Sm 1/ZJ¤Ì§PúÑ}¾¬b¦FE¹›R¤É˜`>q¼êÛž8O^*ŒÉ•é$5CBìE7'¾¶üÕ–¯HW•EEêÝmº„Éwk”sr¬Ì}‰÷Û¶04hÆA\¬¤°¼‘Ø\ŽLõ¨¢Û™éïöÐMPÝ<ŒWz"㘌2 2xo¤CûÙaÅj\}Q×›ƒÊ‘)óžQRJ‚P§.Ä ?ÿ#- øF ÌB/ýñÈ%˜²³ðjze{Ü1[Í£»µº÷Ý'ïìz$*:};“›)óF4m‚ßΔðË_ÒÑh±èà$/~óÈN9*ÒÚ¥.f©¡RÂ;¶¼›<=¢¡6«z” îø¶i¦æ·G>¥ä\×ø³sºæñüã¶kÙ†]˜ù&(öÑî ¾xŠ,xêý_ñµí³¦ ÍF¡žß¼…ña4u­ùÍëJï½e—\Ít\‡ºù@‚4s Òùû-e¯!q-›ôa¦<ÂsrÝG»Þ°uâ.+x†íÞùÙ1¦ðÃÁ~ÊçL(P<ñî>{«âðDòËÐ9;S&þÔ\þf”µüÙ²} c‹8 Þ¨>Ÿ®ù˜}Í+¥ká/æ Yx\Ý×,`y@¹[ñ^¥‰ï¢H_¥|š…z”!᳇ÈÎÌøºVó®ŽÆà*Còj¥òšº¯üκe9»‰j¹‚þTeQÀP1×Ä%|Þ¡ÏÕ–ÿ[ Ãób®üAÛ×Ué©x€ÑhãíÆÌü#šÐ––Ìë íÌ™ÉÓ™F ’¿é[@ù>®¢·ã¶o@ÿÑSØu¦0·v!ÌξAŒì‚Z€`ÓƒÏÙÍÜ8/\ Mñ­[ü3Ø´Á?úgÁSRR† Í€`ß<3fÌ€Fø¢øùù}àl]ç·BØâ£ÓÞ€ïS§NÕ«W¯¶³4, h€ÿ¯…€`€…ü#//ï÷߇&¦ÑÓÓ=z4´ð­æð_ FnnnóæÍ¡‰i®\¹‚ß®`ßIZ~Ù)¦/³»âÉm žæš£ÁW ‚QÒ¬ O &ÅÄ€Xÿs4h ~بQ£ýû÷C³ _rþü…冂Ò-»µ!á± aþÞ‡†Ácë>:²óÌk—Ê•EEó1ëQ/˜?ä¤~5Ñ(¸¼võ3Ïö¼³'î¼6´m10ÌKžvÉΤÄGY…ZÆõúõ ×ÄQÑMõ\ê¤ïÝ|îÞ+BCß¿Gß&ÆÌ2úeY·“æ‹pWß+„¨ùóŒØiùšCccb8pr?~¬~XTTm€`üw°5Ø’GûÝF à`eOöî<“Ë”dñ‚ÅÈŒ n̸¨ù‹wÄÄŒª¹b<¶ìñöFcZ »;—,Új:!Âá…ËœúŒínΑdŸ[¼peLÌPõ\î%/üÛ**&Æ Qâß,±š£•ei¢pܤ‰l í[>ƒ,º›>øú´Ò˜˜¸zæææ™™™ªÃÝ»wC› ÿ!†ØuÍ8Œapñð=Ë€Œ cGºj%e|Jt„4œtå{;6é°oéa„†1½¥ÉÂwï¾zµØi,C÷®Ü—×fbϦpÑ5¢•‚ñ(ã‹3tdU.<,Óðïûý-UþÈá7 h±cÁüùúÖ.#{ØÇR¢f2OnM¼öܨ~«1! iþ\–,˜¯iÜ zÄð«ÛÿXò[˜ Uð¾“ÆØ–4ÿYÎÓõé=Ò†‹·åè~šë–.Ì‘ [vžØÓ® 6£R0€`|yƒ_wè8å{GNŠDƨ½Úîàêà¥tÇ ”ÿa[ÔöŠT9”‹o¤‹oűISߘ¦ÊãÖáÃO®+rÁØþü+'Á3uøiŒƒº¼Ô†¹¹ùŽ; Œ¯Iεô›¹U<9¦.®0ïû%..Î<àkÜñ-v_Æm„n•KMf¦ÆÁ6yÀ.lcoïÏDÅ8À÷ ‚üh‚±'~I·1c ^ÝNH{7q`íû|Q3ÉîƒOXã=°ª/™·é¯—½í,-.ÓÐäU9Ÿs>醖·wôµËÚ œ …}bn ÿ t­{Z-/¡<öÆ/ ;rGüÊÐ>.‰lû»Š6Ý×Jè5içýí}/ëø›?=^âðnûÚÈу–.;0zPý¯¬:ñÎÞÒñÎ|ϼ(›¼¤<…(—Ó"W·’suPä²iÕÎm|`Õô}J¦ep=fµ¨Íg¸£Ç[ÐŽNƒ&0ú’yã]‹ÞoÒÞÚù?ßeS–º¾Ç¸a)KãƒGZ²îʸþ-–-?اmŽÔ¹NfZ¦‰_]XRêk‡LãÑ}±£ç«¼Óïi×é0ݳ›ë·RæOºD+7ß¿`ÐÈ$2#Ÿ‹Ë–/]JÊÄb„Ü›c\YÖ',.†òï_x|öØ „pkm‘®†cFuEdQÑé-I±UgOÅÏF•ÂÛÇwš¹µÖ¤Z¡¿Õ²Á«£Æa¿/Aˆ+÷`¦ ÊÊŠKKžÝ »³‘‹³yÁ݃înÍp¼áÓÔGH¯%ý›uwäˆîÃ9#:…ûèKVϪÿð¹ï¸Š¾>(ˆÏd¿×•ÜÆ–÷Es©õ"K ÎúÑáQñBøæB0вîlÏo=žÖ®Vøè¡×S÷Òwíç®d5v-¶p6/Ëbîšt·lb`ëkUt>Wÿé–C$Õlù²Ô~í󽣑W¶^–R8%Ej)Ö38“)r)<ƒÏ²ŽòBû¯¾ôw1»¶ï¤‰$e£t»~Vâcø¤a«E{×RÈíÌmiwoäÜyߎý½FÒMWÿï5®=áú_ñþdß”›}£F1o[¥÷ß}=*jT‡¤1훘¡, g¿Ñ+žÿÕùìm¢~‹æ/+—’-8ŸU„ÈS\ÍìêÚ֮ƛôúÆîÜOöxû“—u¢ý‰ÈwIã‚të·ÑÆ2_=zºX¨Sj¹,?8¦}±iSKSî³›ÆrµÑ,º4}÷¦u›wzsåÙdbDt èÚðíÂÖÔË}–^³¼:7ª^—’óƒw¦;²¨,'Wëkû7¹Æs0gÕ^M/$ËL®×ГÈ8iåÕôÆÕŽQ~sĶn¬ÒÍZÙ]Þ»®YÌq's6\-Àw"ÝÆŒ¥?µÌÆ÷f#Ç ¥?]e¹çÛº™c<ÔÓ!Ç(ÆÐvòÓ¦ÿjº›#÷qÃiרQÝèOfê]ëˆ@úsÂ0õèO摈e`¯ò¼cœŽŒS¯Où$<}—È.r‡ l¸ü¯›<@ÓNLºŽºe’ -ŸóÁoØKùƒoÕZ—hf×Ð×scAõ:Ú¥m;½]±DÈÁP›ˆ'Iú2÷­£Í$I=†¹ÖnaðiÆô°ý2Çž½'ë™î}¸ØÓ§.?—Ý¥­iE.²§ùH3jÊræú‘½ÍÍ£oYÊhµP EMÙ<Æ#W¨ÅfQOR¢âwÖjÊ8Û#~+í¶oX¶yá‡Åñ¨ç«µQœæ‹»Fµ Ý'cȤb¶F'õìDxfñÿºœÓ»6tWð½ I}[dÿë¯S$Œ}4°`F‘è}oÁQ|A,›Onk¢¼·ÐDO^•ÚØ;^”øHá©ãXV)¢^Íâ¤1«6ýZ00Âè2í})qº"m(?|]Ƭhfð‘ŒÍº)þæ¹÷ÃaŸ<Õ¢ÜÆÍ¿þËËÿÇÞYÀE±ü|öŠ;º»•PIAEÄÀz‚¶`·XOÅçóù0Ÿ…ñìîV JZ:¯÷¿{{we¼¿:ßχeovjg3¿ýÍN4¾¬!ÔTE9Àª€"ùùYÙ±S.8-·ñÁP|Ú(Úð¶.r’¼ü¢äóqƒåM¼K:cvH<¾@ΖÞO›¦\—ÝÄüæÝKLšÙ›j·:0Ó2½Ç,–ŒŠ‚ ´Ôç˜G‚Ìò?y›ø(¾†pÍ^[à?È/¢0NlX•&X)ÊÒcô@Íÿ7:‰1µ¬ßGtI5JN0¨;9·ymÿ©3>ÒædWšê?ç¹ß&cÕh¦Ô ÖšÄìÔÏöM«».Þ¸çÕ'}éŒ<Ô(œX”†ï-J3m¤{к·¯RiÝõuG·6KŒÙFìÂÒ­ãbtÓûÇwõºÞZ„…džk—¬“€bóñÛ4Ð'=zôá½§OμjP ¿¦…ÐbbðüVÂZÔfF}Öí§žvè4À0ãÁë²'÷³ûÛiŸ}X81rB훫©m5PÿÍ1ÛqÓIìì“yšîÈ#¿·µbBüVY3``ÝÐþ—Ý{ô¶"ùaºoX¤Zóü²Ý‘±vJç¶lô Ÿ´S|Wü:À5âàŽ-8Œqá¡2ð® À°™ö‡Ü;Ã%œ#wíR¯>Œ(ØSE{èš›ç¦V#Ÿme°÷z\Òòd½>ǦÚèË *Çâ=QGw÷. ¶¿`ÅJ3q*ˆôHѹ³(Yû¸û8Á©èK†åÆËOÞŽqÈÊ(ìQBá½Z¸M@ë,r\PscÌC)ņaµi}VºH{·0ø•OÏ– &IPp ÜØ/’_ù¿Î%Ñ(BtÑ¢ÄEä­îüõ˜Äµ™*á¿æE¢àrÓî`) ‚w£ ÉMŸ.ì’ÂŽþ~Úïs®öuG_†à$aï3о€ü`¸™ël|42þx޽³œ ÷ †üš CIÁš²w 7|愾ü›6©š¹³oªXÂ<ÀÆÍ› ì 2PþFU_ìí ûᔸ~­œy/` ôùéJzí_µ_¿Ü²ipióa§6²eÃÂÇA¹içà)š»Ç_ÿÖ ³žLþçïMÉ–ëü¿p_.ŠÑt¯¡›F9sI²]Fí馀ü’ ƒøá>S`¦;GFm}s¼ÙvÄg[©õ6ÆŽ&®‘S]‰K&þÓ„þ'Moô»ÅIâäˆ/Þ¼Ê7]ƒ£Ÿ©†àæ!„ ‹€óS€´6)ú[O––²ù=¤åIìs*¾U§ˆaNP !ÐÂøq̼`1´+Xcð®m÷•}½{~i蓳¦ø¬ÞòIoüâÄ÷²!Ò ©ÕP5d›-ó„Öœ68`ÃåÏ©WEIãî²"}‡ÂM!Pa@£Ñ”•áDhÈ7GÒy—NÒ¯Vºñ½¯Ô=?}è¬Vÿ.=GcÃyÒæóV³^ï>ñw’nÿµ={Ëð./ô±:oµà'ç|Ü 2–jÀ²½ÙBŸ¾Ìí8ú€•Q¥8¸ø›Õ©ÙSšµÕ²^œÄG¹ÒÃ–í¿¶Ü§„¥á»ëìÜ`wÕ/âHÉÕ™Ò$¼ìøæÙ†@Ú€@¾§…Á}›Ïr¼±deðòe|%D9€×¢yNë Þ—¤=áUÁeóð¬ç1y:ËŒ¥ñþk÷^ÙÁ¹+‚—ÇŠ‚oÐÏÑ&áß–Is¬Ix§” ¦Nß“wKåA`Ìpp¦ºŒ"áYB!’ÿô†µoQQV%c#<ˆ3éÐ4w-‘m¤í+ŒwïÞ¥¦¦Â"Æxüø1ÜNù[[ fÃ|& ¦êÏ“VN±2'½xû õ…@¦S€+âëÏûgž·‚u”g€;æŸn3γ±^¸ûI3¼¿<¸Ø7öíñé2Æ•¯2JM‡íAkŸ^2G¼¥$¥:%¯ô¶ˆ?sgù 5ôq‡%íqR ¸¾CÀþnaG­lâÅžåD“F±œÜZê]ÆV·”½“LóhÉ?WîXvöÍÖ%¢Ø8Òúø¥;G™¤wUi’Odä—Fª»äЦîQ§º‹Î»¬˜ý`Ö 5yøÚÉĩس0« ñøÝçŸþV ì qU±wlPÿ¦w$¼¯Ð½¢L6Í"c-™m* ä'‡ÐOT ãPû2qË£.1£»´nÕêÍšÆÁC¥š ¬yþ÷ÖgÖ1£º´gÕ†31у?ØG“€´i8éÏK»j6]QòÉ›y§xýߘ)Þ3Äs)-Ý}¢wuHù–·Ì¾0ݧß:|SЧKܺÍZs#ËÌ¥“tuʦéP'W×±Ÿ¦ü‡›ü&WO® ®6‰áåJ‹Ù?™Ã< |€>÷[ó ü ƒËáS¨-UnŒÑÁ-†’í:*¦k+Z€™õ¹é‚%iÛ £c´ìÄýBg{í'×slûtUÄŸ>Jæ—Ε iâ½´_C?õÚc—Ê޽5oÜÊèÖCïáãš~öF­nÆÇg×K)Š2‘dí¢NîÛtyÄ„¦kÏœš1|ÐÚÄ´B¦—c¼ÝV<6}ü%£ðÖ\»™ÑÕQzÏ;Å3U<ªCq›‡.š|íŸk®ÞØOãÓQný6\!ìÌW Õ£f^LS{s_±÷ÐüÁózcx—Xø`ž¯Çø`I\3Ä}Åц؂úB¡€ü ƒ¿jÕšˆY1ø–¢s¶oó“há³¾=«Öl×è`ƨÌ7'ÚóËWPùòeç¾}›¯›#¶0V­Zå¨Má;ós=Í¢ÇÄŒ¾tá`3/_¾Ù·¯seʉíÿ¦u4·Ì{•ÂëàЭ>Uœ®·RÝcq™'·$¥r:u6ÎNK#›ûMÔk“6¬ZOVÕU`åV«ÌЇþ–Uk¸ªúÆ ìÔw…a3b”ÈP¢~$5ÉÇ,]“HÎ{½?éßÌÕ‘-¬M«¯)<˜waóL ˜jÚáË–!*~ƒ½z”Ÿ{l;4”X o#µ¹0r«5ü wÔÀ‡µš¹ÛZ1šÉ«"®!Ò]êÏFœçש › c` òái®'žà9îƒjBC€ÄBí¼*B ^¶Ô]kšî™WȪ:2wÊ­ã4Š ùy- •Œæ>‰Á·ã~w|=­Sà_|½¨[ «^ï(}ûØ=zšÝ·ï§ß›èÞÑ.J˜bûtÕšj”ÜÇÑèÉ»JL[`->¦-ÂgÅÈbŠjЀu«Vs»)H¤ 8$qdS׈A–¸JÃÞÞVÿŽŠÉ?¿ták‚]=¹}óãRžöãmLÃA3†âk\¹§Þ¼óZÌDW(R?J‚X,žl·€{éöêwõÜ>±F‚²Y¨Ý‚ÔìKRŠ…SM»÷QHÏ*5’ÍN¥ .þ„(õÓÝ]ÌrS* ÖÃuƒD^üÇMê” ¾Òàô"VÀ¿zW}Äüi‡§9¬½c½½9-•M("ÎgZë¯Ûež;昑A’Ö*)ck0O0VõÃ>>:øÈü¥AóúbHŠ —žÉšt5÷å‡_ï¥ÎEqlËC™€üÔ]RJÂN¥”,N‡!ºÄy[õÛ/¾,S¢G ?bµ²a·Ùÿ;Ab‘šfeT£@N RÞ¼zgbÞ¡eÿœRì•U -@}Æ%Ừ¹ô¾[©À_[ô̦U|¿h{KÙ½·ÒÁpÁÐ,NYK^CS†@ Pa|U…á¢vl;ØÇVïÖ­·Í7[î8dìñµì¨2¢UftÓoÐÿëôçþ¾}û‚GŒ˜0°óï«W™t6¯È|UB2‰iMaÐ ¨ nûÁ“êܼJ^ù÷ÒЩ«Ö¯Ûž¬Ì+,®W™¥GCô&J¯Z»>ṉ*)õMNÿ°P ¾ rꆧãÚZ®ÊËËwíÚ5cÆŒ¶YhjÚ†Pr íQaDZ1Ä–’ö¢“&Á1&¢Ëd•|Ó;!Âï—T혘V·‹«• (<'‹-ÇX]Gƒ)Ét’ M“ˆ8 Ï£%Q‡‹\| (}G¦Mݦò³{÷î+V<þ<>>>T¤†ª  0vìXX¨0Úõ©û6Ìmz&AÓ‡Ág ùn0™ÌÎ;/_¾üСC°4 Pa´Qf#bÌàSƒü7ÐáËÖn­›2åúàí ñ±©»¢&ŒŽßÑRMàOÿ=uÝd I§}ûöÍ›7ïêÕ«YYYbÇÒkËe\çfݹީ‡Ë'×”y´f‚vôíÿTóÎ. ï5o«\·òË*ŒV¥±M^sä¸QjÿßN%/“U-šíÌ/ß—Na†ÏÇøcý¾ñÓF4kFØÇþÚù¦¸ÆÔÁÇߪ£Ÿ–š§¿÷[4?ãåÙNuM]ÏÄÂL¬Þsí}ÔÚfrèïq³’óëLY¡p"¦æ=8ü&"=ƒõþØyÉNyx˶ç¬-gŒŒŒPvÑ™ «•¬Ö/:÷@680ÛžQnÒÃ…Ì.\8+ö¢¾dõb5þ›%7Кãëø®kb†µ,ÿ[ãÎ<Ï·9ÙKmÂêW;渴jÂâ»;æÙÆÎšWtÖ­] Ãy½ôZ –‡¿ÇNÙútËkø4!¿ª…Ðbb¢±ÿ綬é7e&3ëöÎSO;ô òÒs/µäÕó÷þ¦$m9P¸S£FÙ¹¹€#?aÒvÆ„¤á=õiû¶m.bˆO Øuú\GROF2ƒ·µbBüVY3`ÐPÁøe÷½­H~˜î©&h-oØ0-¬Åª$<Ü}öŽnôæÐ¶ƸðPÞÛ«©m50 §âŸ‘qvЧ7oR“æØý6ÄÉMÊQõí@‡’Ôö9ø¹÷r|¬tÖÑõÑ#Vi• Þ÷š9º#þìŒgíÆ0qÖ9z #Wìè@Ë~÷Þ`Î’#;> Ò@B|~ß´zø°ùå|me©³‹&0½wlŠX·}Â|{,…ê¯\bW€Eµjê¢Ø;È€3!|óŽ rçïø}GZBdw˜NóÚ†rì†Í.ŒÓ*?¸ÔÞß96rÚÚ©çoÃì愘v,éþþ^ÉŽ¸¶£¾XT_¾KÊÖZ±šþq–=}ꔌ㹆´.ƒB¹Že*pk§Î_÷j¿óØ kÛ¥üºw`úôõõlHC'FQ8™ et)J~f2ë¶ c¨¤)ûED«¡ûÞH$C¦;õ µuøûeͨ.ølJGL[džØzì-³÷بnÁfùõ~‹P§°ãOfóò‘éS¦dŸØÈ&ERoívÃßwèT~ó¯ÃÓSûM‚bÔ.È)‚7tÃå æe¼qÔÌÑ[±ÿ‚´) ´€j0]sÿæ «Sz†,èRñb{¤×t÷‹·Ýh€2ßÄ­¿µ8Ú‡âÁ³QU|z)ÝdHWpþXC*Ù@E0‡Jçfcÿ”LðÉÙ4·¥Áá(+K2ÎÐé}÷¿a'æNߊ$òAøA& ݕ̅³É•ñ%2!_^aÜzT=¸'@(øÄic¿H^Ù=‘ ‚’`{bñ.+©IîZëÞ¤cgìÚZðþR†ºŸ£a¶8†š‰‚JÉo’ÁãèÀOãƒFƒÃ§³ÞÝ®Æ4 •›â:":ÔhàïÉ(|s&ÐÍ!k?O¼”Jë2 Q;A_ p°†¼â¾Æ°ås]ñÅCT.ŽJ>P!qëI:¬â´æ^O[¸b¸ÓËÌÇâŸÒÁsÁTÓŒK&…j¨Pn¾ %D̾2{“k õE»Á3¨ëÍboÛî v.Ža!‹ÏjñAÚþ•ßÌŸ²leÐoAu¥Œ-l}D"«*¥,ø#5,ºÙoO#ï©Ù-šèµàÈö±s§L¨S²\¿djµœcä„ö‚eËfnŠ›9¡Œ¢»jÃÀ{×bNâÂ…b³}ûfÉ8w, ­ýÚØ7J¦oZ=±€£8cåruqHþ¶e|”_Wa ŽŽ‘\…IÆØ92_™ ³0Ô»ûDfí›Fìg@ *ôgÒgúŒ>Ä+Ý´H|ÏdÏ.ø×lÁì=a “¦7švK|ñ¶ÄOGum0I|GOû!)Ø < Aa¢y‚&®‘S]Ežñ%Ó‰Ó{¯À W¸wM»AÖzòÙðë¶îhxÖŠ=b½ðÚ‘ššº’}TÔ¤'NKYºMà™HÐb7 Ãî|DX±EøS±ûØâXišË6Š~;¬ ÀÿX#ŽÓvæ[‰$$âDóßÜÛ]ݱH>U5vÃv‘/a<çWÆ.Ÿ½>Jì’j YÙ±SÛ.;ŸÉðëEûY·un§mÛ¶mذáõë×ÕÕÕ?<{Ú¦Ž;–|ÔHš µ* ä»3tèP M›6Mš?Ò>Ɖø ƒ£¢ÊÚ¹fgè¬)ÿot“0êk™ zËÉpnóÚþSg´EÅ_!íšÌÌL''§ßÿNÒ†@~ ƒ‹à_nØ=õHü¶À1v‡2Mü®Ÿ®ë3Pêb¹á«›6mrÒÆx·^ŠÀz #çd±¶Ïí­Bÿ!Ö·X6¶uw >u€};ŽŽ×ioºAˆUuRŽŸ‘Tsõ²þûÓÆ;ý¾åß ÃTÄÁÿ\µvĬÔÊgJLû©e/4ÒQŠN»C¼D`aa!, äçQ¯O왵àÙlæ–ù<6V¨L +yZ•“Ï/P´'àdI£Û 9ð¨Bé^ïÔÿ%ï^v³u”AÀk‰x`c©ŠÐ¨ÕÕÁž{øV555Ø>¼’4Hé—c`èYõnOCpŠºÊÓ;Ùv#‘:fžÎ;BÑiGÀ%!ŸYatô¼fÛ¥™“Ü ¤dƒ"'=;}’ÖÔ I»ò lo§p‡ô•“»ÿg¹¾m²Ø¿Š‘òí–uÕm<>–‚ÈÊâÓ÷¨‚áN¦>‰’FŒšŒ’:ÝtF)t¶½Uç¡’ÑÑÁÊM».üä ƒø¢€e ÓØ¿à(üƒ¤7¾ß„9ö'íhŠÕz`… ˆÄ¿LG—ôï×­ã#^:ªÅ1µ¢ä€ðU«œÚ×j½‚›áƒzIòVýåñ| Ø´uöïß?wîÜ&KB ŸÓÂøApÖ­Ù>c ,ˆöKDDDQQfR >–Æ·ƒ:}&Ôí&“Ùµk×9sælÚ´ –Òþ†ÁÞ½{ac(++ÃBøF¤¦¦vëÖ---íõë×°4 öª0(Ê¢E‹`C¾˜t;wîþýû, –Ò¾ò-`2™C‡ŬŠ8°@ ¨0 ¦¤¦¦:88`&ʼn'`i@ Pa@ - ^"°ªª –Òp‰@* äcÀ%Û<ü…KŽ/žï½uéüç¹Õ}FÍ î©÷…1p^W“ëÎ?—õ²‘ù9.¸SËÁ¹©+¯xõéYv²­yX>cúÖµØIÒ¼ðÁ˶ðX0ÆÂ)xî˜> ‚ŸRJ³bçè‚ô ‘ˆPÓúéjù-ÿé¶Ë Ò¶€K¶ rŽ.˜5ÙæÈˆðM›°V±*íÕ‹ºnÙ–é§L0eÀÙ)Ò®Ón,¯ÜEa w]ïâ1ÎU/.j¢V}±œ“'çì¡Fü¬€W´ä²À]=qæ´‘kÖ#Ì›"ŽÇûòóâ[ŸNXº^‡Æß´`zè°~É”Êä£K÷Þ3t;Ùá½ØÃ³„1/›Ü·:õ´(Ea¨ØàØ?÷Z“,y§–f²”—®œGÌQ1Švž Soæ(x°¨?±,%³pÕâ–›{}ÇŽØÿS Âù}¶Š&Μ<|I„uÔÆ‰fÄ’Øè´ùÇÖ/õ‡ ù&À%Û‰W¥ç i¢Q•ïÜKò*B¦‘{G»©‘o³«Ön2çè–µk^næ¸n që"c\ˆ›â•9û`Ö\ÃC×mÔA³V?$FVÅ= »*­Ó£2£w¦míÜ’eÅœ0ßa·ÿ„¥’ ÅÝEµ‚žÆG vßŵˆý øÿd6T \"°=RGÆV³à=à1dÌÂx~˜Ü%(þ@9øQ‘!Øi–„oEC¢â/ÝÝ5‚m È5ä‰F¯_›,ÔñÐi@H‚ iwà×óð÷wü=4Ä,N±úáÚ:a(”ˆ›‚{ ¯ 6¬¼#pAùu"ú/<Ñf¢x–@V% Yü’{Šíqpòry¨;°0€Š< ‹* äë°ÿþiӦݽ{.ØîèÊÈÄŽ“ã7l]2ãynwø’Aé –¬XmÉhÒH"K‡ò¦MŸ¦m;lÆ0»gºÁ©iÓÝ÷ÇNf£ÖMX#Þ½Åxäì¢wÎÌÆñË#—#ÓfÌèä ²[ÊdŠ ¡œÌê·–LY<#£†6wÕr5§ˆ•SÃí}@'5"˜ÀCcñô¦Â’Õ Ç‘+—-Ÿ™]M^±®¡_Jµ7uõ$Îêm„ÁA–Ó]°r M—ÌÄÍLÙ.?Ýs‡ ò˜5kVvv6\"°ý8{Øé\Ž·®Tø‚µbÇN~3ˆÎÇ›gãVƒ×¯ $\ú.Ü‚‰Þ¸¥É=££ZGuNOüß´å GÅ®þëןL<ôlˆY2Eq¨žákñh¼Ä–^±¥Ñé"ëÝ*YaîÊâ_añÂ󑘶À~nÚ!áµóD3Ñ)ç=óó=w¨0 ßµ÷‰X"põêÕ°4Ú5$E;oÅ¯× ©ØŽRù¹ ˆª7Ùö'|îPa@¾p‰@* älذa÷îÝÏŸ?ÿäÛ¶mƒ³óÚqqqpåPTïÇàÁƒ‰%£££?Ç¿ŸŸ,´6ÔP1C…ù¤¦¦ÚÛÛ?xðàK—<~ü8´0`C3T¿œüƒÉô`[ÁŽIÜ¢ýÈÃU?áíÿHëlž²—!ýÿöÆM8ð4l˜ÝåC»*: ±Âw-/¸¶GÊy´2ù ²C,øüùóêêêÿp7ÐÂh³ Ù•¿\Æ„‘›‹îgŠñW‘vWÿþ³Ï¨qŸô&fóÚV„¿™‡Š*ŒïU;Øä^Ü­î1–ö“ª|yË©k~†òñ¹KŸôÖ„¦¡¸ïø]ÂþSÍù*KB £}X_UÂ?1iNþ;ºMŸGŠ 6ŸæÊgç[þOÉ|³tÿKæ¡…i—I;yvü—”‡è`/S&ey&‹FuWòMÜ$ñvýÏ÷qa$ÀIø'%ÌO£úÕ¹|ÃþNé7.LZ ›ï¯þ]dÐO:û*»[ÒÓ½E†^†ü· G:‘ÿøçÎÈ¡Þûví±ö®õþT…E™,rçI½—eáî#7=]ûrRN‰ýè^{è1:ÀBöбG¡ã}poÝÀÉÔýµvÃC•ß9ŠÚJe]@‡Çf”ËbWî9ø`Ø`«+,/g}eÏG²‘"kҷǺuë¾Ê$mha´å®’Ów^;iVœNWç.Ý ád )Æ·vKÈX YžËþ­Ž¿6Ÿ,Á-q,]5ÈQ%!!)0ØãìÁ£Áa¿ñÐ¥43áÏóCƒ\/:4h|ؽ¿jÌúö±VKÜwè³Ïžë?<¹íà4âðéV¤[D6–>&ÌR!üòR =3¿g¯ v7—ùâ{ÍÓ¥p‹Zªtrv:uIÇ’Ø€ÇÁC6dZϵÂÍ/‘ÈxŸ‚´à$ZOiSÓs@"IøBìZóÖ¼§ ¥)JSÿ4í°Q>̲÷;Žn+ðÖ4Z"ÚÒÝ B³m1C‡­,(8{ãÆ˜!Ý/UÑ¿b1B £-[­Ñº#| Ù©Î/רHf¡V˜w^]Ey9(ö0b ¯[¬J(JT?EaüøÿÛ¯€oV¥=tœ‡¨:¢ÖÐ{dü”kÿT˜ù£©Âé¶X鸅×*;{ŽéC½¿?á›wýA…ñ³b¥X“V\Å~~¡õ@yÅ¥F?òé+ƒü:>)ý2šØÏºwWʬݽœã6†\þü˼Sôî›…üõ]ÜLÁìNš¬Ußöü÷lÜ:‘á"éŸõþòµR'C…Þš¥NÐ]¥îEn)5ã:ÂÍ ¨Zv¯ö^±ô¶¼ýß_"Z)³^†&¶ÇÎ;tèÐé„„oQŒÐÂhËÆ¥'9Že$C§F®ÔHŒ³%dŒ¢é˜ºëTg»ãIwÃÆö”30õñ³LøûRØhç7ž³ r{öïA›ÀP"Ň˜ükjõHÛýo· >ç/äú…’ïÒ6ùà s/Óûå|À)Óîñio¹Ž°'áïA¾2²ôZ2Ò’Ì·nËÚQF-ÿiN§ªŽJëØÂBPÿï“Ô¡…ñ+bí?ŠD¡ƒ¾îÌ%> Û0âÒpGü¨Þ+;ªù ­½Â¬ñÿa£ðµ9ŽÅ]ñ%Ø@ŸQúØÑthÃ9è,wî‘ïÚOÝ1‚¨A\Òo俯§ .Œ &ÎdçÆ©¡¬†uý‰uœÃkÃ…ê‡{_Rî3êѱcîcÇ>{ö,+ë=U£l|=† e©mZncyÖ«ƒÿ“”pI1n"caãq“1,,P;íŽÇá«<¹ Ńø ‚¨ äЉK¡¸cïQ‚Kd¥@d-è$ê¸F—vB°±Š!fáZ‡£ÃFáÐÖÜ¢Ì7OWT³K»ÅpÁÞ}ôñ;Ôò ƒäËaí9pžËP5Âï'k5ÒÒÒ0“Âßÿ{ì³{÷îÏœâ×11‘ì÷:uú÷ß& ãòâÊ‘g9&Ž>‘Ÿ­å€ƯIÖ`thØOs;â%±Vã{¦Û®÷Mz÷îäÏššØ}-ìûÙÿ¤M´0 혻D`»¶0´´´ Ä??2´0 ížŠŠ eee>¿ÑFcŸ¿D ´0ZäÎ;FFF҇‡““lÈ Ð€´ož={fm¯‹ˆˆØ´iøò%¡…Ñ"†††âsLï† - Hûk‘Ç.ÂsôèÑ¿þúëþýû_ºD ´0ZCÜ+ÕÞû£ …3T¿:“&MÚ¾}»øg~~þ¾}ûÌÌÌÚ”>k¿õJýýQЀŠ*Œ_{{û‡6qŒˆˆhS[j·w ƒè•ú ú£ …3T¿.ÊÊÊåå媪ªÚÚÚ§¢¢"33“D"µ©|bÐìÙ³ÛuQkii9r6dha@>QÁT3ÚfÞ‚gÚh(¨hÊJ¸éÐû·õÊ蘱’›Æ’&**êóK[Ë»-Ö´ØSù)¤Ï<ßYò Ö÷/%Üm´0 í v‘ÏøøøönaüL/@ЀT¶Ëç[oMLL ,¨˜¡Â€@ Ÿ´0 Â€ppQ†Ï"cixŸ˜yû-I§§ºs?Fó«ÐÂÃ|8ñð!Ó}Ä'ŸéZ{ßï%ç%Ý“ ž ߢT->$eñ½ 5¤¾ë­A òAÑ&{3‰).D~ÓwÐoOË{·ZÁ3å„üE!xl.™FùNÏù‘õYRÝz¥ø8/Ÿóͼ …F;§æNîéTÅàßð1Nµ÷sO¥à瘭ÐI Óé}Çk¿ßŸu?1êFÏ|Æ&‚T=)+ªèÝÒä"yù7ùM®b”ßÎ?©ßM®,¥ºFQ!xª ûeþ±Û i)ž©&/ùN­£¹DY‘ù¢4—¤®ÔNßj+®G:þX«³MAÚ‹ˆ³6ƲeW¦ü{2ÙÐ~@é“3Õ*!s"›‡Êþ{ð',}kû§WIÝ—†¸~aâ´@esw©ò{2¦ê­zk‰º{¡GoXRÐÂ.6OÿÝgsÙB‹ÖRX41ª·¹&(dtõŒÜr6ªw­†•ކTÖóQçl ej.<¾ïª~÷þÅÏñÍg óa= ?|Ó}JÇm‰›W§vmaprËŽî¬Ð±eæÕ–VPƒãtŸ{0.GÉTVª²NÚˆÒDª­l©‡c3©ÚÒš ü¬TfŸc i Y)Ž,Êè¨A¢uSʹXʱÖ`½­²²£=½TéµÀXÞɾýÕ³`½¬%uÕð"Sý´¬˜ÈKë” U¾ŸR„ä{áoä©I6ÿ~:ß?Ö˜†‡AìƒKr±+ò6Ê—+¸N*VúèÁÓM¯bm¦-Ç3°Ð~j‡eä3UÔ(È«ó‰ÃÇSåÜÉxg¬Û·ô–Á*-ßIa|m ƒ‰i‹  7¥°Û¬»s4>ÎfîL[l¸‰ßøðÙ¢zçÕG6ß,ÜeRÐÈþR$F}HŒöGCnæÿBµZ3p,¾ŸNòRgÀhÙ[‹Í ‰Lùw†ÅÂÎÍ:2÷¯™a±~SKañÐèˆKõ¤/³È„ÌÙ‚¹8óJÊʹؽ`ÚB˜ó9û£\Ê8>²T š‘ô'°öÒUè1ìa„÷––f2ù((üç=Å\Ós¨4æòbc KJ5ò!)5R÷ƒ¿EY§__<_C¢Rà(Œ4ì ,,C닆Æc®¤”ÊGé¼¾dRge?9¼üQîÁØtˆ±œµ2#©¢£‡Êwî’‚ä;a¬!¨lVhD¡Ðšzjñ*‹‰92DÍ›.¼Ëå«agê‰Tt :3ûÐ7+oûë%2RDÖ¥{ ™Û°ag¢GôàMv]s…¡¡IJšáÌ-æ‹Ýþ»t¦Îx+⧉«éóû-{kµ”4 U‘VÀ?ù‘°&Ú‚æŠl¤'S›å¬ÛcŒƒß8eUDsðpÏBÂ?ö ßä1ñ%$Õ¼¿÷³@Ño‘œùHµ6få)JY÷W51Ã7ŠÏÊ@u† wŒ7v¢½|ÚÈÿë—<ÝáÒĹ”‘à6ªÄs”zµÉÉïÄÝ­Zµê«VÜüjæ‚JÞ6Ú¼ùã\µÄoÝMYü;BubÔ¢ØÅø\^kÞ>š"EþÇÊSq]vó—w/1ifoªÝêÀLGÈô³¸ÑË@ ¦Z¾Õûðw¶0HÊrÁqrÜJÖ³SÅrübñ/âÅû\ÍEj©Ô›=bîѭŃËàåÏ?¸(ëÖhha@¾ö’FSXcòŸ±ñ÷IhXSÂg£‚—(v³­,Z¼*…½¸ñëù€!¨^ï™ÀU²~ü~åÊ#e@}-È`·ÉJNŒ™ s©ãÁ81~¸Ë€&+?q²P4倕º‘p32¦Þ¹ó˜âÛ¾¥^É -{k•B,]|»ivÖI@±ùdX´îí«TšEw}ÇÑíÍc6»¨å¼|W¯û·]ßð;ÃÈZ©a­@Q²©Ç\’‘Q†è#÷1nF¤ßf¹Fþ;u!_¾^ ŒqWæë Àù‚Ä8lLÓÊåÿ¦äÇÊ<´0 _º¥8žûð J.ª!aÖú›&/¯dk}äXl¦¶)=ÿ-¯éKUËW¯Ò'â2 ¬åŠŸV“;¨¨KN¸Ó¯]yèƒ|mŽMsÖèhUô:ÙlòiÌÅgˆãÑi.Fž…Î’:MÕ”̦j¦;”ß§Ä}Qc Àù+û6ºß}}ÆÈ¤r;JùcÍž]À ~ËÞFD¶œ­ž‰³Gu0×|÷ä®ý¼+@Šôñ°Cûi¢ç«KÝ4Õ¥³’ïè ?ŒeËo¸ÛÑiκÖÕi+I½B¾±Âؾ}û÷ÔRåÕ‡•j›ËrK당¤*i˜î­%ïOW2¨õê¶tÖÈ¿ª>uQæÉ?jÕ¼ì׬þó¿$1ðNýU¬ÈeÖ«Psãx©«ŸŠ²¸º)W··F/êw»ñv7A*Œ¶ÿˆhÁqD}PÄþº ãˆ\o[¿5"Ó}¦ñG®*8h;Î|Õj'­`‘?·†ÈI’ µ;ó\Ñucˆkãw^â,86W¨U춇Ø5:³!Àáyˆ„£­g«ÞZy‚Æ!+ñÆ·Ç(¡Ã'’@¤GŠÎE¾díãBì‰-ÖE_2,7†X~«g1f̘ï)ã*nºÁnM *){Ö®¤+#ÑU±æ”ôßpN— ŽÚºcu'’Rí&<ï9×øûWîv7”* H[®_Ôvøë¯¿àJ-ßvWÈPa@Ú í\[à)š»aÑoæ;[¿,Ѐ@~M ‘ì¶’„èé‚Zf°ê.Ç7vV0Sö Vü¤÷3KóÌ×ÿ¬L®R°’ÿˆÿ+‹³Ý`'Ïã3»LÒ<$H‹,/å;M‡Ê&­ÛS½W?ÙÛË2Þ &w+ Ô÷´oxЩ[2ͦI¾×"ê­3ùd–>÷³0nÄ8g³°¶ZÞcÉ)MÙO,’Å/N|/b Ýð¨Šj¨ Uë^‘­£!pßy¬ {Ì/[0ЬÃ=œ;IS;õŸ „"=ŸÈÒ§cøÞÆÕK,¤†çÜ›ê÷,„ì­¯RW‘'£¨Çø2™oâ()]ÿl«uÜ éøœBª) Rîá:ŠŸ7¨˜_Ò$?¸¸ªÖ"“­UŸOòõZ tGöê@â¼-*b¹ÌÒó§j”»«;wa¾zÁÎ~ÂtŽ4-++PPÖ¡°¯¾#ʽ¼>»œMÿëi%úɬ?—#K"ÇJz.»Stã>GOÐÕ¦”œ=U£å¢¥ñ¶ðI)0F÷ ‘‡=ª ¥Œ¤¼ätŽé­A–ªNcwƒÇçÜ‘TñïÁÊÎ#õé7s±lò Ú)3-#άÈÇ<{ •þÌ»øï"û`ö‚a+]\ê[ÁR·ïüœÉtõz¶ºÿ AÇgFø­Ù”¼Ô£KþѹæiüéCgµúoÔJõ(Wzزý×–û”°4|cwe}ú2·ãèV?’VòR7ÔùŠøçÝ…}æ­ÕŸtÞ¥“´D+W—4ÇOÚz80õ€s>nPK5`Éê“{Wë“ztG‰<¸¸vÆ=s²Æ†ó¤Í­”ÓçJøòÎ=Z¯©«¦9·šîòÒAË¡³£°tŠ^šºÍÖ£f^LSë«~<÷¼¡ Áÿ³îâ+[hq ©çÝÙ^å; ©®Î8»"Ÿ¡ÆG:«ð^–Ðl4{èW\æ Ç«s*Ù¤þÓõ®®Êg¨òkd伇+tv‘AkESjDRýpMf÷™F·6g—±)±·%.G$c×7f—"tÿͳ9ŠGþïò|º Ÿ­*oZ[މëßä$“£•W¼Nç¼»SÛ3ÒP‘Ú(!Œº4Q-îÊzõ¸Žf§õnGäÝõ²£4¹^]>kA0ha@„¤_©ë NœEgý“ÅE©ÝÔº¡GÔù»5mŠ\£ ÉìúGù5 µÃëù³ f±µeµú¨ÙÛK·–JîßY1ÙV•2U°DƒcéôÊgU²|þÁEø&€âE.=¤EkÑвH‘ KçŽóüêñ‹ÊÄIŸ>±êøRx YÛ Ä—HÜóáõ¥ŸyÿÙ¾ÇW=¥Xb>ŽìsZ™ZwhÏ·Ösúž¢ÄÐôeœÑù·à•Q×fûv\8YÕ“õ$Âj&ªöرTð¤Þ}a’’|+/®h]b>jÉrìAIµgÞS«Žr¶y&â¿„Z¤þÑ4×¥çÑÔs/p Ð}á92ûÁý÷ÊêT]^½0À5 Ïþqm¯N½@Ý5VUO9‰Ô#¾³*%U”~k³Ï(’˜|„NÄ/2ól˜­þ™wñ•- dh˜àmš'?1/3ƒÛ;RŸhû.ê:^÷ß%ùè^QÆÑ>.ógNæó‚náJþÑÃõ2\¾k¨nÚÖL(t5o¡™êhG)OÎï2 ÷ò k`×jBƘÏó»…*’P>*”CÌÂä‡ßw‚nñÑ,¥@5ÀWJ&çïŽÌT:(^|Îó°´õÕ'O\‹ÉJ¤îZ•‘Œ&wg§Ùäv …ù2,ÃŒZ®aÖ8#˜4‹çª²^hi2æ®"¼}× Æ_pìuAÉ^w-b•9ŸXÉ ¬_““0)./Í–ìÅ@këÔœdÀÙò&†ÐB¼«ÿ0[ƒ/J²y|èïèÊREÑ›‘û†œ skyR{¿r¸ ž?r_ÍÂ@–· ˜Oþ•°¨9Dó½9\â=¼deðòe|‰ÂdVÆßß øï¼²ƒsW/Ä«XUR é(3KN¹*0)ÐÒ¤;Å’›Ý‚g×?ôvÍ, Aü‚9ʬç1y:ËŒ¥y¢$›ælåd>\‹æu." “å6[ в%<·~ßåÆûTŽCˆŽ§ç œ,#~ ëÆ~Jæ~@Ãl¼)÷¸Ý’Y¸’ÏLª¤«¥C9<4۵巒T*¾ WC†$,ŒÃ’/t¤ùݵ|;Ѐ|)ÞÀ±ÕÙ=4“ýüÃñÛuýb IdÚÓ59– ¨nýÒ n~ÿÁS=ã\1ÿâ 6jU¶‚¥Š[rR|–ÜC¡Ý4ý ë²Êêìõˆ¦õ¡~æ*{@¡Á¡ÓK½åöÙ¦™qëÆ<º&ÇDPMT˜§·æw1©´”íÙgi4äaÞ•ürÿû´lž±¯®Â“<,KÂJ¤&/ÎùÀàð’ÌÎ#ô»(K¥lÉvq¦KÈ×¢#»øº†Ð¬²‰¿µÔ»Œ­28nÏù”³+¹ºá˜}áèN¯Ÿ¬Ã ^úSõçI+§X™“RÊŒ“×z[ÄŸ¹³|Їú€¸ÃY|•Qj:L´ý2ÍÒ²|áÞ¨«Ê6ŒbÜ Â«ø’7ºò_# ’lïEð¤©c·îì,7éî¿SšqàýåÁž±oOwìXsöbVC 8–ZT´öéá%s€L§çN§{›/OD"Î9vk7ã‚Zÿ<ØhêF”ÑY¸¹Íçÿ»äýÀÙê·r¥z'»r Fª€züg‰O…\öÕtr„ʬúùüQF åÜtÆ(g&¡“[/çŠ+Óe¦Ø[kü;7xÀÚˤÆI'ÇNin÷¼\éa1ûbÇ'KR¡*o当UµéJ}¸5Û2܈ñ©Íí[Ÿ- ÈãùõzÝžü+o¥Ên×NQ<±æÃà™j„è_x%Ýßžé%…z.¯÷<ƒS‹sM•»ôœîá"utCéhå[§j{8q±òre†{¬ñÃÕYãRX ùÅjîÞÇ!‘lB þù³&hDsÿ(Y ¹_Ø"Þn]]ží2×àÆŠœž´J}M™ìRÔDEšôuÊá[[Ï.<ÖïS}!­SÙ•‹ÃæŒ:ºpÙÅóˆýL²“w¯šsÏ´©IãÜV<6}¼ÿÜþçYzyšŠÛj-Ø;ïô’|oÑü±Ìs^”rè:Gÿì’÷^ t_@Í>U¡._%ù/ÀGéÙMÅ3€ÖÖÞÍ¡Û2Ê3åU:)#hUÍÝ÷ '½º»Ù íºgur€ÃdñÁ“µ™Ž³Œ®,Ëq›§Sr³ ¿ân1Ѐ|1]z3i´ôY]å ‡a0RU|ÉÜ–èhYr]ogÆÙ-¹L>LÓÄúþÉÇã2;†`¦C5î•*EA€²ZûºÖÄIIZK¼FÒ0ÌTbÐ_îá÷î §^¬Ê'+ZÄâ'­ÌB¹(0ÑÈÜ››SEõïØ>, +D†]úðž³ÚAÛÖ0l¦ø’e€Á.}t¯»Ý©£™¼*¬Ø::á³ê*žæÚyâ “h±rR•çÖ¼ºÒÑuŒŒî,*g ¹Ñ·TuV ]ìâ¥ãé.õg#ÎóëÔ†…Vkø@î¨!%á8 ¨6WؼBVÕ‘¹Pnè|àmÂØì Ý¡ß~yª¯kaðJkõ•± ž­Iá«}ÙZC ^\8hSû˜AϻñÖn:ÐH$óú/ åÐjUy|ð›*òÉ Eøà×óXuõïø2–*ôú«ù—y¨ª¯ Pâ%àû…kîTÜ(Å6b„Õ(º ß{K¥TI nnEâv<„ä‡ñê>KÏž§fC×5Ó¼¸»¨o˜~“Kª6R7®²‚"U“ð¶ ÁGo¿¢ø-2>¹ªÈì·FSÆÒ¯‹QÝÜR %\º¼[Ò›\ž4;¢`%ò¦;TÿŸ ¥A“¥ MòdGv¿ßŒ°ÊôÑœ"t²ëlý·ÇŠëïZ ×µÊ.)f¯µ ò·¶0Rn¦ô*Us´Ôëºúì–ùžÓŽ5¾T®æÐùê¹W#æO;<-Hün|ã™VàúëGçÅZDšJÆ&ÝÑ1µ€©Ÿ½ Ðç.žƒø7¯?îé¤zîhïµgTK  0ù!Û¥§0Hí½Ûè½èÍi©l’ ¾«Òàô"–qƒ#¿¥\“5éjîË¿ÞcN×ñÙ¼[SÈZßxëé¯ka”:&à×TÞH¥¹öb0¤úùêók®—)65~ù4¡ %ð©=Ye¨¥„Ì‹å ™˜v—]‚šªByô÷0l¥Þ-Uô•­{Rhª‡Þ/Hç gWùÅà½O2– jÒÝõ¹©%Ô¬WL Ò_ð½•òJ(¤$£½½¾f9C ò…uIU±¿`Dl¼-'ÕД$;,¥p놵ú¸Íî‡wò ìy¤Ÿ/>}Ì'F%†!b¶9¢ªLy'¬•J}õƒ[ASñž]QO1Š%æÚL$z  ˆToá8H<•9xÝ3õW^5VÕøzEñMµI=Ä»¿ Õ°ÅŠÕRa¤FFž" úÙ`·’ñøAI ÇçåY†oŠÊ]½/á˜K¸]‚«Ðñ”4¡Y à²…ؾÂgíìØo®Ü–ŸÄ?`às`ú®Ç½­Ûë68 è¾bK|ðÀ®Äçu+¼Üq¦Ö·˯ka r/Ö™+¸öÂùé‹å¡-(˜v"9Œ••^b×MSØÊ/À={ Æ‹KʼX.ÔT ãOV(Y;-b˜.#ö­þºÔK Ÿ#üVÈËÙâÿÈæ:À\§Ó,¼jô‡g£÷lƒ¯[ÎЀügÐËs/øÿ%½´&«Ðüfê´¯ûÿ^£¤˜û§ X{âÿއsnÁ€ Ä0hñΟO¿ö()Ä˪¶„%­ú9†Ê¿”&7ЬíT¨o´0 ÿ½R.4hb|ü§©ˆÇL£öxÿßkL-}øºMŒÿÔ¨P½–\üYe±ÿþ_¹ÐÍÔèŸ+¿¤~2ߢBµA¾t‚$T? Šêô’›Æ°¾9Uʳ0äÔ NÇÁü"Ô´ ?ßóõë׌Zxípé4öáñ°0¿·–ÛÝI¨0¾‘“b`!|7 cڤѰ¸¾)...-ºËH)ÂÉ•_‘v7A* H[Îôn;´fa@¾.Ѐ@¾¹…ùQZ´0 ЀTha@ …- ¨0 Ѐ@ ZPa´¦­­W®\/yd±Xm0«­›”saa!ö †UªŒ;v÷îÝÍØ Z“[–<Ξ=û;ßa*µ—oMIcÆŽ0&&æ#Odâĉ->Gìˆ=eìYO¼ùñܹsX®0MÖüèààœœ¬¥¥UQQ¡¯¯Ÿ““#yTWW¯¬¬TPPh~d³?¶ÑFk-`qqqó„ÄÇôôt+++,KÍXV%3ù×ÔÔ„ ã—è€cÇíÛ··àíú»7¤=!þè-yl_ÀÛïwo* @…@ ¨0 À¯JHÊ óÇG²óÊž­¶òÖ.9˜L¶UþTHôïóy£®þüÌRp·d\õÉ?ÝÇ…‘'។° Væsq ޾Bëœj#÷L¿{ëË[¦CÂd~r§¦whù£sžåtpôéÛUóê_ ò*R2n£ôËï?û„¦l02À“Ä«þgïÁJD9$dªTH¡*»#©JÛ×1|þðY`Ì|Q´,£ïã`WpmIƳÅnZ|ˆ¨0 o] €—)þæ¯î©ì —] À€®xE@¤ª¼,D;7 78×"uå@€´Ó5ªþøŽâAÜìÉs[öÖè —ÍÀRwStÒç2±“W‡Ê•}ô oÖãÕ_¯)>¸šéå‰Åè&ò˜U¢&˜sÒA¤æñ€¬³¨0 ï¾8`ã~"î"~iWe-l|t>6£JUº›“ MÔaU^”„ê@Z›r[öØÌ#k ±ÿ$yYÿPi‰´„ÿË*¢š0KˆE¼I,•$ö%LAÜ“ òÝ䊩TÔZsÙ| …"éRQ Ô•PÔ8«¾%OÑ$ÂÜ%T‹,(©à}¼­¯Îä´æ Ðès Eꊅ¥%ŠT¸¯¸Š"È+æ}¼&¢L¬’¨0 ¶™ªÀ‡l;Ú‡+y—ŸHÏPÅ\î¾àöèBáWÕ–উpš( \©ð¹(  àêú¢±ïì)ôOÚUáó®%óvËÞuIQ¤0õò<‡ßUŸT|Qø ÃòGb3èÒg¼Ý›sdñûà…zŽ= -Ê3’÷#{ô Úš7ɘæêžÛ˜ýª± Ó§ÞÊ⣀¤®ä;Ž|jYF=‡ÔÑ[{ - >#TH±£gר¥ûÝî¿éV:ÁVN”º«wW%®š…è› N =5 =…A‚Ã[õÖ(%)š×,#âÜ$N8‹n ?x^£IÁ¢K€.'CœêŽ5†Ö* @…@ ¨0 Ò~à±ÿ½Àè%ý"!³c¨Ñ«Í¹ÖëêOÝ’i6Ũ‰#¿¤"OFQñY ²jøR² £Ÿžnj!EŧMÏË+³¨ F²ÿéî¸ì«éä>玈G·‡•RA³TƒÂ!Pa@ M ‘«“K ­i]Âp5PV‰¢µµwsè¶ŒòLy•ŽHÕ¥— îÜ[yôêy^ t_@Åߢ¯/Ëî=ÏàÔâ\ïÉxs~yYŽÛ<ýÛ+³zÎ6<¿(Ã=Öøáê,ÇI*w³ÚuÏêäºëá­ðåøB¯pq´¬J|6ÝÕåÙ.s n¬Èq™¨pé9ÝÃEêÊŠœ>³õŽ­þà&•~§ÞЉw»Hšwè=‘â ©râz(T¦°þÇÞ]FômŸÈJÝ -ÒânÅ¥´¸SJÑBq/Î=¤¸»s¸K[¤×rwØáÇ…"EêPÝÍ&_’Ý*¥”ƒ{¿ãîùÝû–Ýd2™d³;óOf§ˆwWì˜#/õù¸OÐßVD`T”÷þZ¤IUûäŸ#Œ÷Šôƒùþû²µÌiÚäu`’9«TPRŒQ¬¬‚MV/È*╞”ʲ-ßg…¡{sk¸°Õõži‰3áÚx~è¹¥âô‡+½ÔÙ6© 3¡¯÷¥G‘Õ;L\<¢EØéÚŽHû-Nɘ8mÜ·­¸Iú‰­X[œ Õ7´úþ#äþ›b.17özZ™lRpÙΕ-â];lëâüÛž«/z-:d¾ÖÃjá…ÆÖbWWÏÐУYr6Šuí°ÝEè¹ýbÄò!kNܱ.^w惡j!ù`Ð/b…‘KÎ}kXëb®wõý:QÑuÚÆ!œš¹º Uãèûøèø‹”îõŒŒŒ¥“@âoiÒ7Uú~}ýP›ùN”Iä{BÌÿŒÊâ5E Gö-Ñva{Ðÿ¹>M¬,Xܽ%ÔÏÔ0)oádg\µ0÷ J‘s…%Ÿ!ʧfÜÇ~øN¾)•œ[L/˜šÿ®Ý€ôZ¸xÍ´F£¢Æß _F•]z>™WfRÎâÚ]UÛ¤‚õLÞï˱™s֤⸀ï³ÂX:pÑòý¡E"ú¶™õëñi5«×cx"þ,ÝûnÿP“{'4žw`ŽØÇõâû,íô{›ü3ϪoJHJèå¡#ïæêÖîÂA)÷²Õè«¡çCÅŠÉ͵éùÐÓ† "áÉï–SÆ¥[¹ˆ•H¸Ç¿†^s®® /\:³yzÁ³x¢ôô+€}ÿÝ ãÁŠÕ}G=|øP|=¢žéâÛÉ~µ'ÝróÛ¯aþ Cĉ>M»¯¼jI‘ƒ]“³.›Ã,]\úÏ·þäkS””Ÿºæ£K&UI¤ßa¸™¾þH ¸êÙŸÂï_EêçǦåùÔÂÂÖÇ#ßKª1‘!|¶œ…xBéêé…¥øàý-õ‡»¸²šT ËÜs&•z„†öëϾnnóÎ…Ú⩜õØkâW{þãï{ òD¨«þllͪë]õ;¿Â'ß±gÌÏO“~5Ë[’§n”Š<ö¤ˆãýÓ×gZ8Û¬¶]ÅoT쌧˜Þ{bâ¦ï£H[7q¾[ý“b)×§mŽ ™™¶´âÔÖ‘Mê»6íèc—¶óðåÀsiVp¸U÷s«‡_”ìgòQq+Ž^ìÛΧùÂ]9ä|ÔÏPg½>äî{iîøŽOŽŸ.ã>ÇpVÄ®eî9oèZÚwª‹ö1O[ФGkŸ‚¡#ËßÐRçø‡·›V$ÇÃ:df„þl’^ü­÷•òún}âl9d“p7:ä@¼cCÇzõÕ?Ï {¡!¬…ª±oKUÞ¾-r×Þ;‹>µ á]"e›üݾ¯ ƒ>›ùd=[(ôü ñßûB¤MDŸÀÅPUt“ß®—þÖÈ6‹ÐÐ@ù߯¡ò[¹‹ÔvÃ*ê7ê˜eÝê¢^¡¡^ú׃ ¿öÔ^CâÍ{É9\Xœ–óE¹–)zôPz£/[ÎúÄŒƒGh ´úº5vôÐ/{rºø7÷œ—Ÿ5ì‡ ¡RȲ-ø޼¿Ã£í/8•ØÎ-{¯¡›)tv^D*<'NõðÑq>Ô>¹œXwhãQi“j&ïC¼wtw¨Q4éþõ$eu‡ÑÇŽ$8¸9Ô­£<¿,<šR·÷µ9&'søcõÓ’CŠÐ©É—_ª¸1¶Õè 9¦L;M³¹¿â©P¿¡é.þÎâÄ« žVõ+"‡”™Åá±Æc\¡“s"Ô6¼ÆÖ¼…—ùÑÙ†×ÍÜ2êÃz‡çOº¥/L¾Çon¼¦½úšeÞ:elÚæŒpŽ9úêÖCm‰Ž…ÊÅYOø>OIü/•ðÎÿú™‚»ýº²¯“ËìO6Ñê<3Ý/–¢)ºŒm«š–§nÓv¬¢^fÿb¾ãX§×{žéJXÑUJZS:cël/Í O1UTöu¶¤ž¢ô‰C‘RÝlþŒ,μ«TZ¡,­åpHjÛ–RáTNµwjXaB™»o—¬Î&óú³””û(gF“|í¥@q|£ß<ÓóL¯-õ‹¤Hå—×+uqCaŠ´MI0¦H|J¦­kß8}stÉwø£œ,M1^Paä]ú3íÄtöëE 1Èôè:Š•8tqbãä‘:AK#;ŒÏÇ †³b‹^«Ëø¦,Ìï­§8󖥓9ùqxúÚBô䮦³ѨÃáZ§ôôw¯puÜ¥©÷ß¼vÈçl”ñÐ<Ï|.-KùÓ×{$½09n]¦Íi;¹ÑéæF{·Ç!¨0òD]ÁáÊ2éäO« ž›õÉdEŠò§.jZ·$óÂ-ÊÛ4¬c˜^Ü&%xUD…äi¾ü¯W<‹!*¯QúÄú5-b’Z8«,-¯¬N¤šþPØTþY&Ä홚`[ÝN:‰Êó{¦†Ñ&Êæ£‹èá•NWW¼ˆlfvüµEZñœs´i!ÿðë_7K{ŸXþËK ëM/̃8åݵ᥆YŠso­2l‰Ó¤oν]/þ×m‡µðo©0¤ÇÅÈßž]>Mºn\=ò²ý2w‹¿O÷&CÅ¿;N­Ì>ƒ{9ä‚ÙêFø\ÿ«‡³~Ôqahãë‡Sè}4~ÂI‘¡l?ÎÊP…È+÷wªœ¶H™QÎúE»É‰ëK9èjèÑä6Ì)óÊmjÙw©ehÝ×T4{ØcbÔq¼4Æ¢zÇ™M†NÒ_KcAäB6L[o–Âø;Ò¤m±Ê2ʤø®+ŒÎ‡ï=½|S—&=÷|²üú^e{6ôÞrvûg)]Å–”QkOzaœ?£—Ȉæ—ÛѲ͜b©¿/?8¹U‹™GªŸ¸óþ·+ú™m ±îÉíÚœèÕ!f;!C~hÚzþÉÃô <· 0üeî•K·+€ÿj„AQžmJ‹!À §öa<²÷4äãn,Û|A|!$?ÓÖ›2®¾>d¸ãБ¦ǃ'6ìÄâÓÌ(1mÚ¬BôÆáCtIÆ~{çT›N>Ö¼7¹H:u¯Þ£{Ï8î=>Ý1GË’¹lÙ§Â?¥Üÿe‹"øGW–Â[±.8ùJ# ƒ–¾)lþgñ8žÚ=kJÚÒeÔ(—‹WöåNNðh×ffYÍžtÜ|\3o¸aÞ»àqÃÖíàFïOåóÕtÛô ±ÝÛÍ„ wÄþÜÞÑmÝ:áÓý·š:u*v—òtÁ>€v…±îÌ^ñïžP)tЙÞuNwHµ0¯æçsXy*Hüì¯;?$˜dºz!0î¶X>uÛw ø§ü´ÕâßFƒÅ?‡CáÓøn* @…¨0þ~R·ÚmAÍÝ=^8cô¥ n?ukeŸ¹I#öŒ­„Ïà_Ra¤w«í1¿ÇŽÃWL=—U¸4ÅïÀ wFã“ddöÙûÏî¿îòKOÿÝuÏ×/H¸—£ö>rj‡[ ü# J¡fÚ.íP€nTôìþÙK=¶Ÿ;ÿ·›Ž?u.éÞO1ÅûTêƒÍg’—î?XÌZÑpaAÂì˜ßdÈ˜Šøðþ=E¤[ä$j¤¿¶¦Œa!œî“}ÏS⎪Œè!àÌ¢iÞj)1sÊ}AøŽ+Œ±I¯þCj›¥ßo™^Öâ~sÎí¬>¹^ë:=3¿Ý:¾ûž[Ñ­'lu{:/÷à;®0\®Ü2ÐðZ?£BÏEÇÓj„¼ŒÃè9w‡!yýŒ‡ì?ŽOà_Ua* @…€ Pa* ø§Zýû.¿¥éTVzáïïoëöïû€¢B‹~«' ÂT€ Pa* @…¨0¾BêõíãFŠÿ2–å:L]«¤HÜõÕ!Ûw3v.í&,SÑäúú< ·ª4°eïÌé-+öoÓ§GŽY;´íü•SyÏNo8EzžÂí¥O+Œ,’ãÃÚâo½·¨dþ2Où#òƒ³ü, +Ÿ–Z$}VÈ̈–?:~ü:w9¦Œ<ùÒ¬qA5ý=T}ÛOß8åÌÂî¥Fì(¨È-åö~­š¯9j¶]J«1•ŒõÛûž \Õ4ï«ÙmñÒ£ÅÝ;-Þ±o4I¾¹?®bG‡ô{ª“ÓÚWž¨ßuBÌÉgfM‹d)U²ï‰äUͬÅW϶ôžtªÚξŸø¨ïÿ´»G·9ªßf'W›xmT›+Žè³Mº13¬Ô¤G?x´Óê‘ã€?~è䵨ã'ü×|­”1ážýùMË ·n)½½—¿Ž£{xÍšÒ`m·Æ|âKAÿÀœ´ôÚ_§³ûKƒ÷sh¾Ìͽtòýõ7í)70Hÿ…Ü7sY§GŸðo“jÛaÖŽ÷&=VÒ8ªÒØS)n>´í`Áæ ëÖ+ñ•…?:;BmÃklÍ[´5:´8‚7Rµóµ9U Vk•šª¬îP8..äÀ{Gw‡Z5g‡Çjq…˜˜¸?îkÿœ\½¶ê·_RÛŒ/,ý…c7=K“˜Ëo/þª-$Oº¸"ÁĬµ·…8ƒŒ½G~#Åu„“>eв(Ïá6Gç>WW² š6nZ0hYŒçëï&ÂhôÃÚ!QÃ:¶³[òÈþJÈÓ]Ý]úãni×ÉÏçuv™¸—!ü^Û)>âow©ŽcˆàÙwWІ–ýÅe½GïZä6àÀû·;¶ÚÙpÚÝò­÷¬ä;6ÞºÖáÞ½¨|ÍiœnºgýE‡r¬ü“¯O½XoºÙºÎ…jáêͽW!òJŒ¼¬Ï´ÆÄ,=ÿø·g¯\\LG õóèÓu—4 M|»?{pE­¡g4/ÎÍ´rµÂZ±FQ—í^Éü!æµ&þ<®ýnçñ­ÒÖhìòcyBÖF—/uø\™Ñ} '~:1ÀÍó5Ͷ‹†}Îç¥^ó/_©™<™*›ï¯ªQ*nc ß£ ýZôÈü8áþ±ßÊŒ"Lé¾]掙3¶ÊXÏË¿ƒÒ\ºmKUÈ59]ÚcE³äFQi²Vfâ$®¼ŸÄJÈò{hbJeû…ü‡V|Ô™^¿ç«Ù{ÕX—ðëý–ô~póî”å=}•èÐÓ¢{÷>¬S³-³:‹)÷onÞ¾eK]¥[çø «ú÷‰_¾zëè1'G©Öõëå·j{ælmª58tØ€¶¢y—œÖ»~­{ÇŽÌJµ]ÕžZ=uôoqÕ÷,p÷êÖßÍA]¥Zóþò²?3•WŒÚäWî>ÿ6áS}¨H7’ó´sÔªRÈ2ͳWÕB)SfÝ¡ª÷lò`âÐ uéRÃGû"À{â AýûžÝ‹;µï .ÓqGƒËÁɵZÛÑûûÄh:vè¼sÿ¦A]ºX53ïE@çl‰ÛàwþÓšùO;|ìqÛ«’Õ;GîVä«Þná&šâ¯/ëöì­M¥Þ-{}|Ö–*aûàÜ¡•ÊÒw_sí¼È®–@X§ž»íÙvŠï¯³»¼k7íqÐë1ûýÏ5QˆKµk¯Û7©µE•‘Í:4þÒrV]øä¢g1ITƒQNú_åS+žsŽ6Í“’ƒ–¾%Æ*:¤HQþT¨¦DCi~ë–$p^¸Ey›†îWW¼ˆlfvüuµA&çÌØ˜„=ãKÐ +§,x^Ü„¨+8üº"<:‘júCa¥Åé Ú4—+2r³ø(+ÍíÈ Ÿ“šŽsËêTè謗­&:œœõÌ¢†5qι?yE;~ëOðo©06_¼þzΞ@ù_éÇrgoéÕŽ›ÒçÒæåC M€zÖד_È0šÖ,½Þ·º¥ø·šßâ‹mk=Ó—µ·/Ûz öïo ’º1­ÏôÅcäº5pçýÜôeÝWVÿêó/µ`wÚâ>[é_L Ú’žç¾‹Æ Ï~›ßPº§(ä쥟~ ð€ÜÞ‰ªo,⎷vLÛü={ôG]öÄÿMªªn¥ô r—¶ò£7-ªéVuHúÏ@Ýûëæ˜^Vu䑪éo†x/”¬$_ñö˜¿UüÛu¶ô#S«Æªs=;Ì8è7PLoT¦_§Yýþb¦éçÌÍø&à ë_zN4L/ÚÍ©hÚ|uq«öã CÇñRÊêU¤ßj©¶1±, ¥°6„$ •pð%ñ+hëæàåfXÜm˜þ:i51ã^;snÒïÕŒ+ä–5í=Ý3R¶šTPHLÌסPe\¸M´ÒºÀ7ÿ$ÿ ½¤ôW¼33r™fô2ï4sk§Ü,[süü34˜-] ÷\°áÛf›ÇÞJyäêWðë3¡m- }‹™˜Ô*-‹))Ç'®å¿ýþ[*ŒíF.;¸ôÒÜ^5ÇoQ|ùâ‚`8U' )U¦Ye: —S§œeî¥ÏgÔÄ‹[æÔÏÜ'ê/ÝÓâ }òR˜^ô«Ë²QR©Fù^eÕÌ­æV¤ô½‘_µiÿFŸ¶ºî#üÇŒ[›zeJDÕéÏýÛWö(ÃW›õh²g¹Ž5.Wû‰|Uÿ ‰ .seô½¡æÖW[ç³—mÛÜïðñùž}wK=¦ö¿êQˆ7[Õ¾tóŠïå|ª÷iAÌ2Väá1+½UÉæåcå4åš×È=£J\‘ä"õÈ*Ó¼ ÑE4÷­í1ø¾OTZ¬„Ø3¿î_Pä2WyÁ”ór·(í‹å+Óó,ÕªŠ>ÿË¥‚Œ~–Äiˆ.òJl¦Wí}Onó¹-¯ºJ§ê¿ë»oÍ_ÓÜ·N»aú®VÚç fnŸ@%Ë¥ª,ðlF x >¬/’˜OWwK¹G™Ãù•Çõ]³"–Ì9||Áþý¿ÉÓÏOX˜^6©: ;* áÜÝ+úüâ×7­më>õèytá€ï Âpî¸xGEÂoÓ~»V¯1©m—J(…Ô%€'©lM¿ |R¨&:dèÒÇúÞPé˪œ] áÒzL½ªbCS5ò¿¸VÚOª}¨^ß+"§y‘Ö3êÍ͇…«K=²Ä#úÊÊvõ¦*§ï•–ÿ=ãrå(³Òu Y`è×%ψ›åŒ&”*õÃ{1Á»K›©ŒW’··Ã ɫ֤uߊÿE\Ýì=éy:»¾»¿ÇI.UÖ-ЗK殮Ûù›¾GYjz×,yo¤Oç3—ÃÒŒu×DÎ'ê~„ CZU²À‘ ßG…ñ$ÈNðŸÆÎ·ÎêÓ³Ÿq µcJô9¡*£¨ '(ÞwIWo§VF©Öë{+­ò´üøº´ úSË~¬ºËôÏÑUö-ó2äãV Ï¨u+~¼Òb}—öÖ§ù¡´¾gÔ°~Ë{È=²Öx‘-4Së)ÓûD¥÷È _;¸{—ĵ»¶µ£7è»Eeɳßò^r„®‰TÔì{W~ࢌWb™‹ˆ«ÖoY¡»äd[~ÒŒ¬G2çY¼·¿¾T5²”Z™©›SæÅZ}²67Ò»fÉÓ =ÍŒÍ+e,šp阦Nú†\žÜȨ¤Ï$ïÛ2ÕqhÀwQa¸ô˜¹?m<ÿö­?é_lY6GÿBþéµÛ½Kßev©¾·Rzm±m[’©ÇTÙzdDÖ|öNxíë+Ħmö­žN2õ¡JO“Þ3*½GÖT©3ñÎèeÈßyä}W…^Ë÷æ4ÍÒ/+sŸ®uâÔvÇÉG®2­ºZî¾U!{žm3—ªÒ«£¾~!úMXµ"­H-¤¾aúLöýØSß5Ë^^0sO³Ìe“ú›¤í(gyÓ„”Ç]inFáЀï¢Âø{K\ ÕªUß÷ éÏnÂgºf}¥.¾gûfÖð¿äæü 2I;}›é`þ¦­ž¼ä?a’ß“ÈkßnBßдµŠs©o·…¹¯KUá›ÆÍà«”²ù—lˆ’5.ãP(* @…¨0 ÂT€  ÂT€ Pa* @…€ Pa* @…¨0 Â@…ߢÂ{¾M€]0 À@€0 À@€0 @€0 @€0` @€0` @€ð¯ 0x"ˆAúK‰¥ŸnøGž›y‚ %åõïhýbâDŠ_0⟠§Óÿ_ÐgEe䜞Af´œŒÊÓd¬E”²âÓ2щyë³ä­£ÒRRTn™KYÉE¢¤—<¥/²>A¿ /o‹˜#-Ÿ¢ð5€ÿD€ñ©Æ´~:­oÄË ä)óå¸@§oÿ¢Š‘“Òúè@lxËiĶ8¡3b“²':JŸ›ÀdMÞòÏXu7$­¹Ÿ¾Ž¢©Ý/ J xCHCŠòÙx@L ÏF^2òª…´Y‚!d’w‹¸ …œJ ðï 0¨´àAÿ–ç9*#œ[ˬ £dœN'5™Š8q"M3†À/_„ÐñË|ž²Ló—ßôrR9_%Ð7û9N.6MqK(C‘Ää<%]|àuœœO8F”~¹†¦él…L -ŽãZ§|x)zóc)‰NNÆÓ<«O)_ß  .`À$ÀàõgÚ‹maÛÔ×nÞÚ²;è]dBµê•{{·³27cÅÖ´NJ(6ºyŠ„¿z»uÇþÛ÷ÿpÊ_°g÷Ë”¦(–0D§Ò:0 )ܶûC¹c¢V·÷lÝ¢qM9xÈÜZÏLÄ6¸V,_wñòMš5’âš"™" J, /]‹'jµ±¥¥yÚ.®u\ °ãBK{X§Ó1Œ>äc©ÑOëx骋†×*TêW‘‘;v¾vãÞˈ^+1 æR Q«X[‹¦ÍuölddD‹A-Å Ò ù¯!xä%è8^Š%˜w1š½ûƒÎ]¼ü.æCŠ–£¥R¡NLH0Q+l¬LjU.Û¹³WQ§|â~¥)-Ï‹Ñ ­ïÿ%õÓB)ø·Ró]l¿K£ÕRÇ,zðà©%Ð÷âù¥ }gFîݶu-5Ës<ÏS¦7Ø´õÏ õäíÃË7£jVwZ8g¨Ø|fy1Uèå#ÆNW™Ú§hu,ÍÜ™¿fõú {wýdžÓn¯\ð Eâ£ã££RcV—šJS ­ty„æùÚ‚|D&6÷5„$ /£®=|µhý~µ‚Xš²ëVÎ/`gÁÒ´"ÆRPb¼!]= ™¨ØSg,ûíÆ#Š5æ+†@j•©@¥êx­À(ŵ$ ôãˆøG›7l NMŠéàÑÈoT…*E´¾Û•Ü!JGq‚N ©%Ë7<Ū­9¯c&„å CF`J•xöÞ¡‹R“ã-ÍÈŠ%³JÉO Z%+]è )_ ø÷†á¼~ЀøŽÓ}бf¥æ…TVÐé4) ¹·%µùéĤD±¥­cˆVl+ 4'¼Õ%+¤ œ”§‘:E¢†¦)*YÙ¨b`@ T¶°Æ°rŠ—‡…³¼Nœ$FZŠâòÙuõêÀ1×ÊH† AsZáMÄ» Š}ϲtJ2Ãé<: îÕÝsXŸb¶:Z`)FÅ-ÐY¼pÍ#§Xó|Z…RMi©äh{ó†nÕëÔ©fgoËqÔï·îŸ:ùþŸáœ FC´J•ÿè±ëAÎŽ; “g#^H!R¨£”Æn3$åƒÐ½Ï˜·ñ©Œ¹MÌûX#†+å\°u3·*.¥Tf©í›Èèë×o>u!úC¬@™² eJrÒ‚¹‹–Λbaa,_·áÂȃUþ†t±BRÍðÏÒÔúuóŸ¾tøDjJj‡B½{t*UÔ‰¢tQHgòyn”o¯F \·nßñ.ÊÈTÑÕ«WC×ZZF¡`¤¾?4_§vå#vì>pû÷J¥²A½Ú;´T+t„äÖªä{-q:^ ŒÚ·©§b¤rI½”(±Q®•z òX =²-¡¯Ü±}ßq-kAæ·(Q4_ó&uyT!|*§â;å÷?#(•µ&5•p‰M×è7H­T<ÏÜ}ødÆMÆÎÈoo- Ãàuò=¬Òî“õu´Ï¶ôðÙøRzÉÔ˜¼¨¶iJ¹3¯Ãàxé¥]Ç »‡—Veš™xel¿_´_V ãÒž?LÒ¸°:‡-ú² ‹5ìÚ§o׳úŠâ4`çfŸÂ ü Œÿžâ äk :1Lhݸv›µ–ÑN ­Fº-+ÏQ Ãë´•ÊZ0s4MI!‡Ž×!U¾BÁÈWB¤{*°2š8´Gäñ R?%­Üê7ɽ$RË›¦uR?+F Å–3O¤¡ ÒÕŠ(å›QIMt^'ÅCbƒßÇ»ÝñSbS9Š·áÖ{-šÔ^'ˆQ†bÕº­„¿¦hÍmJüâ¹Ô«ÂJq/H¡‹[J «ˆVñ¼®ˆ£í…“g¬Ô¨Mß^Þm;´kiee"n§ä¡á:^º±”ÊðÒ q§Š¹ÓtúóC(ò½ßRŠ1)P¥Í°m†&Þ˜×eÄÑ8BÞøŽ*¸¶Ý—.¡íKÔj#þ¯ïdB´¯OÎ8ãL,ysôÇöGznÚØ¯„ ¿ß_€Á‹íqiô/]Ãà…ÄTjÁ²U§Ï]Òi8 cÓ~}½=Ú4e¥ø€“bŠ 8træ­4è¢r…Ò?Žeg%Ÿ¾–.>°bF¿\»¿`ñÊØ÷IœNSºd±±£—.áÄäÚ®æÓ0b"P /E9Ò£)¤žQ¼Ü­ˆ2<‡ClË3º{Ã~??…7’/Xh-ŒI˦nÇ)5'p!!'“5ŒÊLÜ2µÛ±S[Aà èÈmüƒ`¤b»vl?cÑO©œh>‰}ðGx¥òˆ uóîÜ&9)eÕ†,cÃ¥¢4^»íØš­Gh^05V)\ \çfM]Ë”.Æòb´!õ:÷+Ïë(ŠM¿‹îgŸâ÷½ L*tjWàè–WÒ›‡gÿLjcgú×sS84v¨N«Y]FŸˆ'$|kŸ&»7v-Èâçà; 0ä+<-è£Ñ}Æ¼ŠŒ¢”&Mb>ðK–ì‰x7|hg§•ž(GÓ‹–®ß½÷8aMi…‘Ž¡¹ùlȰÉ{·.aäBð‚æPÈ¥i³×•KXž(~ûýÙàQþkW,,[Ì:çF½@ פñZN§üýÞ“z­»²:–âU:1œ ´Òð©3E+y±éOñ:Ã1 -—jÆÒ*†Û¸aAç|bAŠI/^¼¤)–ç¤ðÉÔÒÄÂ܄М|·*:ý†¹†'mgºž@ÉãÍK–(¤åRÆBŒ¦´šÄ×ïÞU"EäÙZ×õíÕ¡GwÏࣧ×n ŒˆŒ#jcÂ( Í w?üíÍ?^„ü¢MM`Y–aIß^]|:·T3DB/éiæÒÃiü;ž‹ÁÇ=¸öÊðÚ±¢ã×_o L«ûÍ÷¼:0(F|¶~ñåV‹ê›ã޾ßW€!MÉÑæ%[²xÁ×ï¢YÁL+è´$19õ]õº•¥Q V~È_»v½ÇËhÂr„UR…‹8Ò&ŠñÍPlåò¥MÔ”†×¤(Ô” `YâhoS¢ˆun Kéiw:ЦŕŠS˜˜$§¤²R©t+u˜2¦UɉÉJµ‘†hÖéÄiI´1WÌ›é_£J)`à54£”žtG#¥¥¸$¥_¦ :…tƒ,-CÓ,•iÂÇ­|y°»V#Z•ªÕšª•‰©©j¥J~È·XD%#wÖR«í=›vhçN(1þa^¾Œ >ròÜ…?ŸG7×: … Ó¥0 +µÚyÊ©]èÙ]/#ânþ~Ke¤¬UÃÅÂXÍðZBçÒ¤îK¼  ¤{ß/”o¢ß0VH¥(𣠆WÐìÎAGÏÐJ#F¡à)z`ÿ^}𰼏BB œP¬´b ðå*£µ¥ÐÑtT\ÜÍ[÷jU©$ði]¬>Uš!¼pñÒ¯))Z1ÚIIþÏÖªd‰"Äp'_üloi´MÄ0Ljȃ9L èÜPgZÌÍjuü¹ ——¬Þñ6ê½øVÃ1Ç{víshÿ&F~J¹`èéõÏõjKφ[òš8ó©+Æ6Îÿí\³Ê´>lœV'|u +ú¯lhË €ã†’nÊH„ØdfÕ¼ ¨YºM Wy¬€þt»ØrÛÞÒyȲÔÜ®áR¡FÕ †GSóâ ¥|§%yœ·4æ›sr4srtÓ?[lûKwnʵ¼tQ‚Ò œñ°TjÙ’öJ)`Ñ7 ¥1åÓ¦ 361>pä4Çs Q­Y½))þå°Ý´Rj¶Ë-A y)Öê»Õ.ThwØËH–5ÒrÔÓïݹÒÒH-µìFn;Käg bÔdˆp¤‚{½eçiøáhŠ©W»‚C>KJÿ4oZ ´Ò…iŒˆt1B¾Åa¤‘Ü´!F¢8%¡š5¨ÓÔ­öïŸ÷6]ÃQœ.%&:ùàÁ£=½½ä§êþéOÁ°*ZÆÑè£Ï‹O~õ ,N~I—ê»|®wE[å7o¸ëbÜ1¼v¬XàSÝ®h#3“<}­L¬Õ4¢ @€ñ¿d ˆ¾….à‰ÔJ×H¦XVîøä%1ÐáY£-{O¨MMöꤿ,1D3b¼£3a™!ºŒ?ÓHe’˜*¼å†Ž˜¾jéTk cTn)¡ô|pi£ä§Ë3ÞD&:AË+šfŸK7|po)º’$)¡Œ%$jN¾Ø¼Y}#ýƒóÄÈIºS¡Xp⎢¥í‹Ë8t4VPÉÉZAÌŒRˆ{MÎéÛÜ£–Q[¥5Éã#“ybúù8 )ïžÇ^›å7ûôQYÀcꪜo«}¶c ÏºG„¸qh¿·‹·ùU7ÿ¦%âY¾î±þµº^߆öŸÈ½@µ¸M- Àø§‚Ø:f¤áÍÒíg…«7žŒ›´ 6!‘ÛÍ\J¹âN+—O·¶PqœFÁŠmUTl⨱ÓoÝ}BIW-[³…³'–/ë,è4â"b_Ë3 —mÜ¢á1À`„”¡ƒzôêÞá³!†T±©/…†V4‘‡Añǰ¬Ø’WRÚYSG± r™V™ò‚bÅšJšîÛÓK!.ÝœIc)æ!|ËuéYþ~“š›juÂýG‘îÍûy4¯Û·oׂVbà#ߢJzFOØGa¯–¯Øôóowi1 ÑfF”¹bÿ¶=VæF/Ý,‹°lr²fòìÅÇN_e•Sço¬ZÁi`ÿ^+–4Q±ÒCÎNên&†b8FQ7î>9~Fd<§¤•*AkemêÙ®µt™Eêl&¯n•Óöõ<Ë.ž_zýpã–»Mü*}æsN¸¶bñmÃÒ•»5rø+—QÎÝ7ª±¡_ßmá$:xt«Ÿ[Ìß>¾¶Å· 2øÈS“ºO¿”"¿±ë¸|j] ðø iè… Ý^IK‰Í„™ ßÄq µ §å”òΟá«Öoè7D ÙAºíªß¤é7îü©6±NNÕ²¬êõ{ÎÉúæ©Fz<¡<¿yg QXÒ´ŠH²P®þiwñÒeÝj–ýdãW›ZA'7÷¥ûÒbÃ\J¾±«ÀÈ“~œ0,ö}¹K·ÆÄHm¾ríŽT-7°OVj¼ë¤gõQ´ü\Ò¤Q­ÃåÖŽö›Ëñbð£8q=èô5"hXZg¢6biEBb²†“®?hµDP1´ŠMíÔ®ÁÈAÝÔ,Ï¥2CQ ÏS‘ÑqáO#AÉG±WïÅýî·45ù=Ëò*¥¸ÃT´@ó:êý‡$bh±¨ÒS %¢Ó$-_¼ÌHzDµ«¤=åïk?6»6Kׄu|à!1‡}›Þòš³Ä·ž]Ž'õùÄ?ƒfŽ^zÉpù¢hßÍ‹šÚüå @]²ÿöãµVô²ÿ ‰=6¶õåÆs¶O®gõA†òòÜš§>Ñéߛ֟ºmzc;¿ßc€!è{F4æ*jú¸ÁCGÌå5J#V©IÕÊoÓ¿wWFÐÉ££)JAûOßcÀèØØ$µR­R“¢"|§ 2¢¥Ò“·)¦ic×jGï>|¡ãSĉI‰ÑmÛ7¯S£l.e:BÉw²¢E-? ;Kø!èÇpHƒ'xµ‚,7iô¸Ù§/\Æ„6]ýS¥¥u¯F¬|CŸ¤AK—øü6¦û¶/ÿð!iÑ¢õÁÇ/PŒ©Ž0:JÁQª¸N~ ·BºFB4´"E!h&Ù®U¥‚•^!…4 ^ÿqŠ+\Èfï¶Å)©º-_—"h4*…ÊX«åu©Œ¦Ðò}nÅHLËqjq‡¦¼/lk6yò¨ê5*)‰ŽãR ­¢hV—Öìk•p®ëùÅ#&yIÂ&´0ÌP˜ZYš°º¤ø˜š¬±Aù^ çõ®ôÕÝš(“ Ã÷­5ßgÌÑzBÛ+î3vú»[*ßWûÇ÷¾ Î<—×$ÄÇÆÄ%é²&Ì×`ôÜñíŠãÊÀ÷`ÐD¥ï±#½ ¤~ê·¯èGMètDêš$† ÈWH'» Ç·Éà cö XZ¾¡déí?-ÔéxéZ‚|W90ø8¦Ðÿ£†rS‚ùXF¡¿½’¸¬‚ÖÉ®fÈϧÒbĘ@ÅR«MÖê¤Çðñòø ­VÇJ«£ôÅ”ž(\'ÆJ•ø^in:Ûô¬i£xŠJIá^¾|ñ&5UËiy+kË¢Eìì,ä‘”\ýý©¬É6Ža‰XÈNžÍ:x4ÕðZ«|ÿ>ùéÓo^¿ÕŠÑE© ( f¨fž×?&\ŠhJ¡däÛ?ÿ‚µw»;t,!\Ü£+gÎ]¾qû΃°×ѱ‘ b‰•&Ö —ªP±rµz Ü*:¨¿ép Ú¼Æø Ãuü»M:û$œŸìÑ¢Þ”³šäü0ïÄ×áOs˜¬¶t,T¬L¥juÜÕ¯ðË€ã‚'‚ôäiéä¾|ƒ%†’Ç_§?|Zv-·ô¥‹úÜŒƒH—hšä'ç1bkŸçõ1‰<šÊ­q-P †¥Òn™«îXeX£‚ÈÚL—çrÑßOJJ$Há‡þú†KÈçì)C@Bôwf’ÏßKËÓQä“=ƒ¤K%?Ï[z¾¶&¤­‘×G)™Ó¼tYƒÒßÊJ.–J^?¥¿­Éœž—ßÊáŠ@ÈO—‹Æ¦ÇKBÚÖ2‚¡Àú€$ûz…L1ÏÈ÷ߥô×qꥅ–FS¬~ÍÒƒ:ôø€ÿj€AS¹  ämIox§÷[¢ä¥h:K@"_³È[Û:£;Rö+4MçPÆô+LÚ:èôQÙÒ¦çJåø|»ô‰LÆæÈ“?y1$-ÎÉe^5¥¿®üŽ¡Ðñþà À0 Àø_K}°´Ë€mËU&TTg¥y¼®[ï MWN®lô™l„„»{7žˆ-Ù©_‹BŠÌÆñÑ!ƒÚÍ s]txv ãgs¯ööí²2̱o—ª´ á’¢Ÿý~6äÊKΪñÌ-“ݬé¯\ËgpÏwôêy¼ÙÖÍ>…_±'³m ¯MŠûì†'“J½çÍîõõOõþb_²-YöÃß{8öUþý;Se›G›—kÒ¬¼åÿ÷ýÀ²€ã_ˆ9>ÄcÖ;¯• *\ZµñÈÕ‰„˜:Õé0|\ïÖ´vúÀÁç Ü»Wº2°óò§U§,nœÑ6×<\ÙµßÞ”æËöMr1ózÿðO?8{#<^'6霪5ë6¸o³â&´ØX?6¨Ýì(¯Å?Zîðßt#¶âŒà•®Üõ½«7¼tïu"OˆÊºxµfÝ÷iè¤Öß*VH ?»yíÎS×E¦ÂX8¹4é6´ó¢Æy|$•¿NkÏz¦™'uë?òé&Ÿ›ýç6=2¿¶X`.æFÀºMA@›¬äæÙg€We«L÷ù¥ˆæå™e+×ß|“B¶ev9¢}Y3y|bq‹8)2y ¥Xß­ázEíGæ×2JÛ“=õmk]Ü uœ¿õ*g,ŠÖjÝÓ·WƒBj*OÛ2l’¸³#ýÐeh«ýíŸZÃT^îÓû_\_L®{ûSårøàÜM3m ý: _§¥1mÍ(qfõ¶Ó÷"5DiW®±ÏÈa%SgÛ‡üÞeÙ $· ÷#óÓŸ»cýö³~î™[øŸ^]Ž[j(Ãò9¥N/Ywô^´Ž˜8Õï1~œ§ÅÕŸ­?|="…¨ ÔìòäÞÕ¬è\Z}¼ší¨0ÁO+ŒŠQŠÍéÈÃ[Ÿø,\¼ËWš¤ ßÞ»û˜n+'WLKÆ8z-˜ê5cæ´Ó.K›êÛw)wWŒÝû.÷Í~btÁ½Ü7°ëŠWõgìÚ6ÚÐüÓ½>èÛ¥ù¢Z³æÖcUbƒ22`}Øž5‡z±R\sl°ÇìçM—¯b¸Œ’ò4dϹc×Û´­fÃä{›¦¯ºaâ5ïÀ;ZŸY`ÿN=[žšuxq}Ó¼l˜ ùšöŽKŽ ¿¼aEÐ+¶ÂˆáÕMÄ­ÜÖ»û†ˆê?îÛ5ÁV_`îÕþ]Ú®ª0îÀÊÖv†&lJèÆëƒ×/ß?BnÁ¿ Öq`ËÃwmêÈïÊeñõ§œutÐlÀδsÕ|æVî‹]}½×¼m0wïîqòsÇ?ü:£«wË]ƒ·¬ñÎë©mÚ®ù”‰Ám¦Y}l@ÕŽŽBnûN¹ËCrÙÛ¹•§U¶.û¶PJ#1ALðÖçûW¬m7Ažwa|‡þ-íÚœm?ð‘‡3oBîA+enGæ'/¾ ©1o""²]r¢h#ë|¦o¶çºº¶TÐ;ŽF÷™¾¶…Ÿ8%áç±mÇnunô¾µK÷“‚ìG«½ûŒ Ù´spÁG¹´æ6-?>*Æ¿]Ù«ŽMÚYa…u!KBžG%è²$±i2kÎE¯±³¦œpYÞ–Nº¹xüÁ˜’#÷ö+®›YOƒ÷ÿ)¦º8ÙÃ-[Þ—÷\{_·šÜÌséÙ¼€~WÒÖÍæ¯Œœ1uxSWñIÁŠÕjÖmÔª½O sýÕ£²Þƒ¼øM#½¾‰NÐi™ÅÅ$ó$OI|ñè¡…¾ÊÇýºzNà«ò#wuÔ@ó(äH8±hÙÓÍ6ýl8[ yÊ+~üýà娖ö†ÈªÆ€6éÝyh{·Î•æß¾yæúk—×¹.Þ,—‚iŸ……‹Ö«Z¤=×Ϭæ”àÐ)_ø¡ \ŠFZ­Š¥ˆ&,·ýÿaen{;·òñ³~pŸø~TïÞÀ>mGЖUÛ–£~¹qæzt׿¹,¤y–ëGÐÂ=Gf6 /=4ËÖ-Ræ«d¡ÈÃêrÜRºl‹Šæ†]ÃZå7#ļAu;Ãe.ÖÜÑœ71I|î­9×ßw€¡°+•Ÿ»wn¾ÕVtÊr²”{såÒBÊV.¥Ÿz:Qfµ'-lÝÙwî”ãÕæÚ®šp,©†ÿBOG¹¡ÅÚµ§È›r®jaóqSJˆ—3`2Í¡-*õXx°GÚ[þým#Û¸?*71pe ËW;{y¯¨9#p‡¿¥¾d|Ì _™wó¾(«²5ëÔI‹EêÔ©[s†÷¸Î­oLß5£5MXËÂV„¼}™,ôŽI\ìóXñ­½ƒÔ«Hž^÷Vl:š ®ûðæ½ ¶sí,l¹/ùé’1V…m¹ÿâM²P!mY>%æm¬FeÏZ•Ç.`ÚçûÆÏýƒØuÓTlÚó¹ïѧ÷¶u.å±g>úàrÂżþÀ“´½'ÖÚNœ•Ë—ê³A^Ì,Ÿ»ME×9u‘â#ó°ºÏni.ûàÅÎ~_{ÐŒ.Ú¶ÅÊ@£¹ƒ&wo¸É¡Z‹†Uœ¬Øä·þzúÌýXRÀcî¡Ñu­ÿBSʨâèÅ>×{Ïéåügš/›ÞÐÊ mÝdÁê°ƒg·kÖ§o›ÊÊO Üx›vóß6½¡MöŒt¯ê¶ð¦e­®ÝšU*dΤDÿyþôcž.ã^ÞBlýÛ”+oIÂoìÜyÊÜÍA÷æöÉ݇¢«Vs$wŸ>}­¬»ÿå;Ä¢ÎÔƒ;Kî>Å£}Ûe;~p±k¹xùã¾ÃýÛõømP¯Æ¥­tooݸñ»’ý~šRCîÏóÒ9èØß>wÚuoZÆZû"tûŠOLÜfN¨mnM庸ÖÔÞŒðãûŽ:Vµwª^«x¦>;´M³Kï÷9½m— ½¼ë;±Q·Žn?xGW{âö9-r,¼ðærpP¤ \Rì‹WÎ^ø#žXÖ¶ñDÇ’ò ”Ü÷¿›öH.{;·ò4gò¶{£÷éu§½Oó²Všð [V ÷ÒÄÚ¦D—e?¸Ëò‘|æ#ˆÿÆ_‰¿yuŸ9h–/î È~T˜â²Œï cç>) tR–i}†OË–Š²h¸*´aÖifî+CCõ/MÛþÚ6óMàî¯ ¸û±.¾xGíêfÍÿðz~÷ÓÁ1Ä¡só-¾vÆÔÿS1ãžisé.!*;³|F…x>96!*QÿÎÌcN³ÑõŒè/Ì;æÄq™Q¤T­Àõ%ìè¯/,wkvàÐóù—¬_ÕØ°Š¨£Ç<çF“2u®-fC‹=¢ÛèsdË+ùµE±eûê¸ÿ½Ÿ@Ö½ô7lÑÿ~ Àøö(¶ìv!5~é>êñè–ï|6¶P2ãg3õÑ­¾}n‡£ÖKÚŽ­¦ü{ƒ AHM”j:×µµžÕfdæã|̳±BM8ðx¼×êVÆÿíOáýëm§R‰"Ë^¶mÕ2´Õ7\‡æ·Y'ÄèÂi@›¹f—».z2z|þK‹Úþï6û[oÑÿ~ Àøû˜U«t¨À´n¶÷Ýss¤Ç /3–¯žê¶è­ÖÌiÖN×úVr³_àí>;dÍÛB¬K¨RTÍ$~¸÷Ë»WZBœJ/YU­š…˜Œµ÷h—•q¤býà•N™.6¼8Úiilúôø3'ZO{GW¬Òñýͽ¯MK–0¶©Vmz_õ_ÚÚ®Naòë#žÂce^K› ÷~g¿Õ%ªØäSiÂ÷"™…ïæ&]œ˜¼m>ÿ<ävào¯nrbnQÖ\ýY©,íY¾iAú£³ï\ؾsƒV¼×`Qľ¤ýþ黇‘<¡,½W4XI™k¤ ¼9tæ‡3RºÆoKªá´‹Ó®þ–™ÚäBdð±öó¢I±Ò-4Ï+ 6©eí`Â=»üøÄ½TÂÚÚØ´[Q&Ïɲ—!§ë yØ(>ùüŒàɧÅ]¨pª”ÏÙ†ÑÅÆßº÷AÜ¥MÜ6ÿXØšÖåuæíó}þD«Éï¨r•º w$:´jœÏQ¥}qõñÁ«I„XõÛÚ¢g[€à«ÑÖ…§·ñ;4géÁÖ×j Vü¾ðœF]³ÎžyÅì 0îÖÜÀ¡!©¬K½ƒKŠdî£é\‡ Œê8?Ƚ¶i^×Ȩ¤‹üí?… Þ¡¥¿¦‘'$> _?õR`!v¥&÷²VþµÒ> ãVv ­”Qk$\»ÔqÔÓU=ÏÚ5id•· [VRBøùLì#Ûƒ«§wïÉZ`îî‚ Á‡SŒÝQÐ<-ÌÞ¿ôï÷Ë©ù—lf»urúäIýãºï¢(AU`Æ‚RR*u£™ ítêØæ“s+yN®šb0 9ë'/í·v=™ÞŒîáâ÷à·.®í}&_P“ÆÖyMö9yÚ(mL‚¢^ÕñõÌë5°µH߇|Ò‘óO]ð«Ø~C;“ÂyÛ‡yü|iV:Ì„{áf»»œ*˜–®kÅnG;.‰ýivXËoÓ/`@M~“–‹»TØw¢ûŠßªüÈvò¥Œ4I‘ûϦ¢pëY([x‹ªe뛾<™qø¾¶v/  o],ï‹$ ØðñdsûÖëmZáT"½a›×Òf:ãïT¦S¹,U†iùuÍžžøyò¡¶QŨ/Îð“µï”t ¿®W~óLQ(ó‚ÓöuüL,ÿ|ʰõ¢úî–iSóû-+ÿ{¯»'GŸ­v i »¬WfœK6/œe«Š8W·xx,>òäŸ\ãZì—%ûºRØÚU)’°uß鱱üGyÄq:1ÖÍË𥟯SQ×ü™ÓQ¦ö*)ðHNIÊë*`ütþZ… ­ˆ 'õkšdý¥äá/äÐîä‰9ÍÊ”ˆÏñGÚp=oŒ¼Ö{fƒÁ%8´øö»3wKöéN}UiúSíLyÆ×nþG \Þ0lìûÝÃ/\›ñ$%xèîàðïf»Uj{墙Êú¸¼:<ƒúòd_³Q|âßÀùw‰ºfm§‹9dRsaøÞo~ѾøÂƒ"¾Ü€àŸÅضccõ¹#)·„GU)–i<±sùîùDBÌœ:WÛŒ‚‘¹üÛ˜ #é¿ÁºÄËÇbÿ†ßxSÏUˬ î¿óRûÖ/2†‹äµ´™„= /5 Óå”Ä»~þ@ˆ2ËRŠ/ÎÐÐÊÍ1J²íÐH}æpÊ…ÏÞU)aŸžUòÛ9O†Ä+›­ðú±òÇ•wkщ5a„©\÷À²œÆs ©—&N¸tÇw¶ýþ)ަé ê§+5¤dÆv%Üýór!Š|-K+2ºå1Ù×lTÉøËÄIꦽœ2EBü•« äèBÈ9Røš£À?øç´ÂØöÛ‹]²ô²§Û/vå T)¬âcã¿%“êÕ~š]¦¨4@›²n\gÀþÃë]ïÒñU›VŽ…uoî>;ú+ëÙÃŽ~É‹¾uÁJò®xÉ{ܳImß¶ZÔvl ×ÒJxNnÇ–tNš±ÛõEõšÖ¶Œ&ìêˇqbCÖqìwW‹¼o>Q:ä/c|ïMÒóQ]ƒ+RX6¨=Õ+ÛÝÙò~ž[Î ZqÅËíŠÊÁ¦¬#ûáÙ»ÇÑb1,:-mæ›Ct!D8;"8…˜8ÏŸó‰»EQªzSµítâðé³~.ž«Ú¤Ý¶¶h¡3v¹FZJÛE§>¹úêÏxBTùGnvw³È´x“}úSÈÃF9ŒãxmvÄáÁ{®º8Uu¤ãž½ýånR‘žÍVûà3/òåÆ3ã^ªÝ©JÇ<ìü¾0þ?) —ßZþ3g¯†!^ŸÍÂÂg“O–IGÊÿ é™1É´^“‹¡y-eYdMh‘\æ[Ôq=êúWJ›åþ§UFæ–2oš:N?á“mÚG·Xe‹vjr²SÞ?ʶYÓóÍ>—JmïwØÇ/-&Iû8,û¬÷÷ÙaŸIFY7kÚ,Ç–÷¢ì[4:Õ"ÇYÍ/¶Îü6/û0Oǧ³/:ü` @€ðÏ“­SÓW&€` €` À€`ü¯Tsv¾êïÿ;ÒíÚµ«víÚEŠÁ®€tÎÎŽØ 0ò‚éÙs(öd0bĈ*Uª`W ÀøZqqq–––Ø0¾ØØX+++ìß@BB®` ÀøâââÌḬ̀`|±±±¸|€àßïÂ… nnn<Ø·o_©R¥ºté’—×OŸ>ݶm›““S¯^½òþÚÞÞ~ðàÁoÞ¼Y·nÝ—¾þ?öÎ.Škkà3³½°»ôÞ{•®" ‚"({‰&j_¢É—ø ººúçŸÖ<ÌãñV­ZE¡P–-[ÖݰT8+V¬þ»|ùòn…—.]J¥RW®\Éçó›ÃOŸ>UmâÛ„/^,MöÓO?ÕÖÖj^·n]YYÙÛo¿mbb¢yxúôé¶¶¶[·nÍËËënx„ ®®®»wïÎÎÎÖ<œœœ|ëÖ­˜˜Ÿî†SSSÓÓÓ#""ØI¸´´tÆŒšLûââb˜íZší†_ælW„_ælW„µ:ÛÛ„CCC¥séÜ–^m49 00´…ô†$ýWz;T( †¥·Þ‡¥·ù‡¥êE·ÂRU¦ÇáfEªga…ÒÖ>}ú´Tgm¯6,U»–*¦=K⇥Êw·Â±rzŽ”ÓeXÃiß¿éXÃl×ÒlïVøMí/2ó5œíjÃ!ràÖ@_²bÅ UEаFí+5Ÿ×¬Y£ªã\Õ00z ¸½4Ö¨}uæóû￲઀ zø¬KÒPøèi£ž½½!¹þ~Òþg #,ÈÒxQé¹ÉNc'0 h^š°èôŽ”2ññþz„>•†¸üÊ?J|'ź0ÐÞ-MÓ¼{( œ«: /QqÚŽCÅnã'tÖâ—5ÄÚõ`À´I¥©N*YyûïÒü£Ûéérè„nϽޙæ=âÞ=‰´}UÀÀè-:¿IêŸ^=s)³ˆ+&±­½ƒÜyçäÚØß@R}ùB™³á\ê• iÂ#[72<ÇN¨P¡ñ†g׎\¾SP'ÆèÆnƒÂØ21DXp|û‘j߉ã½Ù˜\½*<±ýp•Ï„ñ>J½[\ûøÂ…kJ$D–¥Wp¨Ÿ­‚"ªÉ¹vñZvA­!sl<ƒ‚},è²ÒDÕ¯^ÌxXX#@P ÇÜÙ?8ÀŽEPÞ¸+¼GºW]¹ò°R€PÜó&gŸ;ëY­˜È²ñ6ÔË€¤ÔÒë]¸‡»Ç:PJÎl=Té=ÜæÙ¹ŒbÖ)q.”õåKUÎg7ΧßVÉ“ (UÏÊ-0Ø×Š©–&U³DÅw/œm4±Ë8´­«;…Ún¢Ṳ̈UGÁ€Ø‰£©4:©ê¬ êXx:ITµËº§¯f=«æã(UßÎ{Ð O*úªÌçf:÷`À´ïißIß%ÅgþnU—’§fRáµww_®”†¸×ìä?aœsõõŽæ^¯H£ C^Ýw:í%õù7.\UH ¡èZ{ âcAÃzt‰Ú Í…«°.ÀÀèc:yÖ%©½³÷âɳ£™²{%/ÿän.BÁ°æÓ}ÌD|ß?×Y#§)åÊ¢¹…ÕzcGN ÏŽý}4…4>>@¯«–ÔæU™,»ÁV^Û“øwqØÔhe ¯Ï>´ó¬8xòÄ™òöJ®Ÿ½xU2(P/ÿàÎs¢ãg*ôQù•=»·>Œ˜iCÀ0©ÌçYEw •–ðàÀŽûE1“¢ü¤ÕT\ݳïðEÃ)¡¦²;ˆ°8=½ÒlH¤!)%`HÅ£ÚaãføaÎ}p`³úò-j¯$ͱŽ<×X~’4”—54ˆL¢ji2IÕ74 õ‡Q]hƒu( {qvrÝ”Ž‚Hu:DSiH[ØQ]V|Ŭ˜2;Zþ€Zv„  íëQÊŽ3õ>ããgDÊ-AQÚî¿v:Œ™dø ÌgU:ñ`À´ï½ißÙTT­«Iæí&Êò?Û éé>§þÎþ̽Žgl·¤Ñ9j‡X—ßñ´'Šùb¦ý X?&IÖLIõ­Ä=»*FNPy¨''Q+¡Éò=¿¬v ~ø<``ô)K—.í診  áø™Ð•ÊÕÔÍŠü¤´ë2™f ¥:†Q$¤\(ƻΥck­£ÌEÐ17&ß,,ª;ÐZ®íÂÊÜ2\Ç˨Iù"›ø7‘ÝóŸ”#:^æÌ&ȶ2&ß)zV-²Ñ—ýfr(ò<(‰J’VdÂR*ýIDÄEã$Õ™žÐ|Æ[S•ú"ÓRY¢°²ãòƒ&Mµ¹ãDâ±g•<©ˆ ]Cš´.MNEukc×êu( +~ǹº£¿k"NZhÆ—Î ~†Mn éòù¬Vä”áˆøFâŸ7T+ÌË­éoÈzIóùÅ=0í{qÚw!±¦ºä2W?©Ú Ms¯²7¤Ñ£!îtÚ?Ï8tð>Á)8ØÃœC#!|±Ô¤Š…Õ=:‰Ø­„&Ëg¨~ Àº éäQ.‘eÂB2 Ÿó|8re‹_œ•/@(ê’âšÜž $ ñ…ʤnI¥Qy¤îYqƒŸž\Ùו 0= v« ;IßÎIË{Æõ×—?¤•]=r¾ÊaX¸µ!r®%U=-­u»q_àå]ºÑh7ƒƒµ;$­·£ò…µ…Ï*©Nƒ¢<‚åIùGÿJLA&›åü=æƒïõ ×þªÃ$‰távöÃbÁ¶Ù¹Wt92Æ-Î­à›»ûòRÛ`µ¢ ‰»ê¦F£ t™Ø`ÆF Šžóp}ùÃW©BT(PÜIúöFX¾8hrŒ›R’ðk¹8ƒE% —4Ÿ_܃Ó¾ÇÓ>’Ò¦´.ú®"ó'•†É:i­¶§\'Ó^Xpça=Ëwü`7ù§¢²;ÙÕBï¼#ŸD¢¶Uw0Sîüó=Ø``ô%<ÊÅ8¾ã&Ð/œNüã !ëÙù t°"电V0?ǬSG·n¤ÚšnÜÉ}Øtplð¹“)Þ–ÞJYýÝ-™H¾D®¤áѳc]8põaY£„ȲòŽžêc&{*z~iwR¦^䌑Vt§˜Ù†¯œÝ½¹„+BHl+‘Ãeo~³cg›<¾z~Ï–¢Z¡ìMdk÷)3-eÏEšIATvãb‘n`‚™º±Q†K‡å“ už]>º+§TÚ ù‹ßN¡l.\&”•å©–Syëʃ[Wá1qÑö}»§lhÛ…ˆ¢ãf ­GÁœô‚³¢³.“½Ç%è\9“ôç¹ ‘iî>ÀÓž™õT"‘æ¢;Žže’›q!q›ìõq„È0²õ0Гõçó‹{0`Ú÷xÚ_Ýݺ´ÎúÞFæN* “uÖZ‘v§\'Óžd|ödòŸ7„EÏÁ/$(.‚wàø±¿ŽyÅćçœ{Ñ“ˆ¤£n cÀº oél9IÍýÓçòG{™Ñ%5ù7ÒK,†ºê„`6sž"Ãnh‚ÝЦ<ÆC¦ÏS½2O›ÜôC×-,Þ-¬å¨í¼ ù_‚ù°YŠ\–ÎCÚ^Û ƒ¦*“É‹p Žq nà8E;µoݲMô¼–ŸË+~ž—¦³åt0¶×Ø•“͉˜îÓ”E‹­\¹²¸¸¸M¼ÏÑ£GKKKµR+F$“ÿÕwC õªÎ’Á´ÿwò;`]€ÐÇÀ–ÆÚãÈ‘#¾¾¾x»‡¢RvõÖ>»…G¼œÚ¶4ÖÞÞÞ ¸|ùrsÌèÑ£íììÂÂÂ@8Z¢<ðï8 00´x0´ÊéÓ§uttD"Ùw¦ÑÑÑ¥¥¥±hð`Lo00úð`h*•ºråÊÿüç?FFFÇúô)ÈD«€`zƒÐÇ€CÛ,Y²dõêÕ Û¶m355hð`Lo00ú˜wÞy§»Y¾ým› â)ˆNsfÏž-ý7;;[zãihÍÀ&rü /ãîåz ŒªúâÍ[þàVà0F€¶Ñ7Ñyïí»› ¬ 00ú˜­[·v÷-)©ua 70@»§ôÄ{ ŒŠú<©ua0ø Œ mÊÏÛ•só ˜ÖÚ8 00´ÅÌ™3AÀ|ƒ0½ÁÀèczàÁ€Wø`zƒÐÇ€£¯‘ð®-Ø»#±ühÜ1tL‡Wçmw.K€ úúNtóÉA1¾ddÕ5o°ƒw»ðÀ~>bfóK9O¤³§¶ánrÅ£ÇB‘T r4=…AA5ÍûŠ Ì.Þ·³1Ô5Ÿ£CxEåüFžÚ<Z‹…8Ü›”°¨´Pj]°íí²£‚5çßåÁòoÿQ’]‹Ç[õ ÀèoÔôàõ<#ªK›sàÀÄnÅ„…a*ωÅÜss“ö?nŠÇù7ßÛ³íj7ϵaãý S= CšÓ¢!QÎDIIÎæY—îq¥–ƒž[€.CÒPpµ¸Dßa°ªj(¨¹²õaAA‰4R[vö÷k·‰£(¯AŽp“Ó„WÀƒs/¦ VFcf3Uæ ^Ÿ^xèHK|ãÂäd>ÑÕ4:\x+±òi‰„äaO“ ´PXx¡23£¡²GPLÇ–éÁÅ46y’Zùð>¿Aš’B2êÇñ®ÃÆDE*î]—×…ØŽ¬~Ñ3V|m(ŠJDÅç+î\o¨’–† ts†S„¾³ Aµ8AQ]ÖùºgOø\ž, ͘fÀq÷£RÛ¸Äâò›ÕYõeÅ"¡l¹/iJª¹Ÿ®‡?•ªz¶ 5••&õv2 ÂRnÖ¹ZiöºYk0:IÏŽá8„ceŒ¡}w``h ð`ô6(J’Ýð'ð%'§YRšâ¹…[§]ºÇ#õûnìÌ-ï;‰žÜ^9C%;™=`^€àþÕ;gjjYF! ÀƒÑ^#&›¢‡eÇ؃gÛ hš)‚Çe‡¶s…Ù}žu„¹\Åñê+Å)©|•ܘù »!?cMá#.ÁvŽU+T‘w_×yåxIU꺪:„`5Î|ô4¢òÕ¼†Æ›‹œA¨~f£FSI(B”kÐâÅÇX¦#Æš»Œ“%ãÝ->˜øüèÕçˆ;ümãˆPyÞ:îÙ5eç~¨syÇÒÛ´ûjsYeêQÐ £¡ò¼|ÞE·¶p³|ÍFÇR¥g”¤²æÔ/8f>Ú,r™(O%©æ¦ÿQt Ѳ @RôB\X‘²±¦Q&‹ÁæJ @T\}j}Ñ#Äææi&çnÔ«~@qqþ_ù—žà¬Póã)Šì.©ºXrâ÷§—- cfëôú‹XàÁ †¶0Œv0£´üägçdó„aܯÕ×D‡PÇ;‰@`½Âkô ªxxM¢ œÊÑ#7œ‚)R­1kêѤKVÎ@Ó°ÊüWÅ•¨y^‘àþ?RëÑ‹1èElž(æ3רò»²òŒ²Ì¹"®8Æá 5Ï[ªKi|ŽÝô ›ì_T‡noŽ”ä‰Ê Ÿ)±ÛSgèÛúú¤¦ŸªK8õþ?<~>¯QLÕÁ™Û¥Z>¢?Æ2ػŧq˜æ#õÒ-{âjîÀ–+úæú±+ô•æ_Ìkˆ%RËfo\/>y™’0 e%êF½êTšXî3©{À-r'YÉ¡˜n°Ù„à>> 00´Å®]»æÏŸrx!pu{®(X›DòTí/\"ƒ{‹×ï 2Mõ¥±¨ªV6{غm^žAéfR=§Ó©¢y^±¨²F–’cHh3!Q ‘Í@ÊëE•Õ8Ò술Hª³Yiw`Trë¼h‡gC×ЈäÖ' ÚÔ4¼¥ÁHERÞ?Ijó Ë*$lY¢¢ªS«ªp„`H·s§±XYfáu¼î˪;õªP”`1Õvb#?ÿrÍÃy—ªš¤ƒMƒõýBLbŸÚb̘1 ÍÀˆtùÓÚÆç‰TãjŠ–”\Ëé:7ÙÑÖŽ”ÿ ¾àÒ]C`‹C•u¶lë5^ Ú¬·BP+é:/Àf"Å5âšj b¥ª¨Jêr…½–—HÔç Åâª21nÕÊÛ€ó„Õõ²úº¯Ò²eD’¡.R\ŽèÇZó%tÖ2~cú©uYͰ ²SÑûE‚ê“Ý—•æõv>#hë0#ë0•f>zžúwiÊyê€Ìl˜}s``h‹¤¤$ð`hh`Ð|?ñ9;ífáo¾¼äØ?EÔçž~œEuŽðD î⸸³G·(Ûjîÿßg]¿¹äŸ›TO6]\_x«ªÖÞ5Ò=*Í.ÁAÆ/Ì+àÁ@iVT"h,¨}VÃpà(­úÛeiDè2—ôG{Ê÷ßá˜yZÉŸ¯KÄe§ŠÓnKz-/ì– ûlmUÕ¡ÂËóžÊo0$µõW7>¯@!&&¯’A ¹LÖ/ø¥¢"ùÙY¡Ù @2IÑ:‘èÙᢋ7D¨µÁè™òUe‰D]ò¬\RñX ²¥*Œ'þ³êK»j„²o$p~…H‚0 e¥y½ ©¬9ùsE%FqŸiâaÝl¢à!.«†J¤‘úì,ÀÀÐàÁèÎ}ÆÆã£ó­¢fÈÿøF´D‘=~ž¶Fmvk×E§]ÕñÑú7Ù-ðËó ðîó*x0æ13²S+ï¯Í½.½ƒÏ¶gº 3Œž$o«‰ä¦dÇÚ;ÕÝdü§‚¼´Ê¬Ýy÷ë¥Iå« 7ãP~p+W(êÌÕX —³Ì%êZ3¼æZÛZ°¾; 00´x0€×÷ã?nß¾=;;Çq—3gÎt™±ùoii©©©©4¶hÑ¢˜˜˜^iÊ ¹Œ3wim<~EË’³iвSÈ6#LlÚ˜ˆÑ¸F­"H¿ìüz–Wž–jÍò“þ×qGÔ7’Ê[a×^—¶˜e—Ð}Yu$µñdSf¿ Ì~]HÓõ3ó3hO¡¸N³r푬4©·ÃEQNÎK;/Àƒ@ àuáÖ­[+W®LMM­©©Q›ÀÕÕuøðášÕ¬~=}úTñõý)9M !Ê`0ÂÃÿýö[i™ ùî"*­Í¼!Ôdí’)ËÝ›„Èz°.ÀÀècÀƒ¼š”””Œ õÌËÉ …f‰DiiiŸ|òI—)›ñòùüöG¥&—ËM–£ˆÁ0ÌÊÊjúôé|ð M× ™1«_ˆ¡Ï}ŒÖ=âü{«§çøma-NÙXº3þøƒð¨Ï?0Ý(.\wðÇ ÷ÿÛè¤×wÏ1ùçþû~žŠªIà¸Û„¿ïì¢\î o¨¾±õæécÅ…•b#zÛ„¼åä¡X‰V\~úÖþ­OÄbœ¨¯ç>Þo\‚1£ëîHʶ§|ŸÞï‹ß¬éÝi-Î-M^tæluÀÑû½©7?“Ç®=»~äŸþIII166®¬¬ìÈw¡œkbñĉ5)¼Yý*,,ÔHà mmm³³³}}}sssccc‡fÃÕx5ë €>Fë ‚•ë䘿}Ÿ7ðg[LRšxõ‘¯—ÅÙ«—¢†˜¢’²'ÿìEÃ6Ù‰vüäšMqvºØsÉo.8÷æÚ‹S«q34‹ø,(Ä…PºõÐOWmC Šï?ãÕTbŽs‡$Œf“I‰Úx ïá¶Ë‰ûÊÁÀlø²ÀAŽ„çÛS~R­EåÆÒ­æ'…87iú¢ÜÛ+çœ@wŽ 6AjŽüz yú®Ð4/#ÌýùàV;/ýÓƒsóüw?’æî‰Ÿ§Ì+©/àŠ8BUýüSm#uZŽóªÓ>:~Á"hñGL^ÅÙo.¤^PõØžãsÖ‡ï‰ôÓmR¢ ²7.¼ž].¡ê3e+߈êïn¼”|¤J@@q¦~Ðâ ärõÝì@PÒ#B5ÒV•Õ¢‰g¾½Y,AÄ8ÝÓ9þS/'ŠtSÂ݇B¡Ž•Ó#UîwïÞ½sçÎÒÒR===©yÀårU³$''Ïž=»Ë’;Äëàà`aa!5WòóóÉdò¤I“âââ|||G—]Ù±î‚Èæ7^ü±Ÿ`l!éÈ×g«x,`…ÏÕÓ§tPºsÝsÒ$sÃ-Ó¤6;.[E_¬õÖl7Kî‘àöo…•톺kÿ+òi¹X˜µ® 0Äj˜§J;yõ§W—ë̲ °D›»sç·Â’!VÃ} ¨êLl³»¹F3-LøM’6{ð`€ÐǼ„o0Ö󺎿˜|ÛrŠMAâ?ä‘Û<íÏþ¸¦Ð¥QÞ/7*‡…³#p30A%´%>N±j£„æ2g˜÷û²eùWÓ–/»a³;€N@Eõ¤€_GDdžíãŽþe¶XýÍ’c'ƒ™àÊ6¨Í2ÔS-™XWwæ·JÊhÙj¶xEíùÕ:S-ý,Q5mÅl^°¯®=½¶š5ÁÜß‘€×p/­+Çc-ƒqG ”¶Z—r”W§þZ‰…[ B&òxk‹«B-Ã\øçÛårBkUe¢¶‘4n]Z»ùÐjŽ­«3ŸeîeòW?|Ž3^l®J ‚’Éhç“„ª…Ó¬ 00ú˜ÔÔÔ™3gj¹¦Ù¸Å¬o~ÌtrË© óÑLj#}v]H=f••a0a·1Á¹RÕ™AS®Ž‰óï,MÚM\²ÜNŸŒHļewà–€W}>Ù&•þO¤cJu‡a6ûÈX顊{*µ´FŃW8¾js™)ÏRœÆ7®¾}gòP?ƒFÞžûe¶®>æHí¼ÌØoNPÀåÓÏ¢¿y×ë¿ëíÙmIªi¼¨ªçeÿî•Cg¬æF10é!IË&ÆhWO`¥ÇUvN–©oŠ:;ꦚ6t,í¦BÖïý^Ñ·ÊçiËNg‡._Î鮄µ•J(§9fÅŠªŽh~Ä»DN¯6J¶ÅJD1é¤QÓ2Ï=…¢¸„'Æk넦2zjèµ$ 9GŽª¹¿§àüÄ€áÅ¡a¼ÖºÙÁ—Bêp–àõ™5åv‚t¨™¾¦ã|åÑšhUŠ’qR¾„t¸àÀay‰"¼êÏk"M]ÛTê½_[¡Ë`/›É(›áÖ¯òäžÐQ½ªÖ¥äí¡ºù“eù©W,ç6_ä£.³•LÔ5¯WÓ£F; nËÞLÖªÇÑ€[ÔþdCÛìŸ(;UÐöŽ\\°·àªX?êsC™LøMm 00ú˜—P ʱ#ygšõ;û9²«5Å ró¿Ÿgš-ëÑþ]v”lïhôUú wXf&aólݰ‹–ÐüŒ(¼þÕÑ›™uU\šç»#'D¶_UÛø@&É/޶åòªÑåõR%€Æñ};(v˜†æ¢úq#VX]ù6öÐÀM£¢¬aÃV ª¹±%mUjQq•Á(Æ~6¡óFÿ¾ü餇±ÎžŒ_W<Ë+‘ê (Ù@ÏutÀgk-ÚYj_õ@¶c²‘¥õŒd³§ëŽ,›a³pC¿þ߇U|~â“8ÃXÏ'ŽÃèÄ€R}×Ä‘7]Z]ÉÃL×8dUl˜©²ãÅÕ W'mÆ”A*ÚâÍ{;ÈÊ)—ö¥;9&,0¢ ˜´êžJX{ôå>8ÞX\ŸuðyQ7bƒŒ 7JÎeІ½g¤GT\*=‚/ÊôS©Q(+$hÖ:ñºô’Ë%:Á“-ˆàIyêÞrƒw˜ÍÙåS %9J#QnE5nn‚ ëžVâ e¸³õÏTÞ{È pÆï–?Š XdlÚÔ”Õ>K›’Q†Ûøl•Î8s?GÂç?>\#ìO!©mÛûÆÆÊÃõVÝÏaÊ<UÜ{·q‹q42¢þ{ý®ä GÄ»ŸÎ7 ¥Ý“DP„ˆWE&êi¤¦GT‰Á8Uû¸P§Ÿ%Úp¿êa9Þv2SiÞA؉Ê8“ ìÌ0q5ïIjY6‘=Ì­Ýß(Áb¢óLÁ¡Ÿùa ô :$}x``h‹³gÏÚÚÚj¿kØßÓ†©D0B‡ýp^E§^ßò“è÷þ¡–åù“låŸD?Eiœ!_ô‹l¯i·'Ð\熹Îm•¬u--Pü†¬<Ö*†æ;àË4ÕòÙ~ †ú-P«³S-Ö`€ö4š³zšâÉfAìjYù8÷JÖÅg¦Óvyê þz伫ukU‡äè÷ßÔæ{ÝãaïhÔMõ‚R/m)ž«'7i‹>žoýíÙ¶¬îHøeñ²wò¦Ð}bÓ$G”fÆô}‡éÛtîo>Á_9IôƒMã‚•S?ìsF§ ZFFg€ióŽd;ƒ˜¥²€qSvT—ùY‹}޲t†®ü®‡l­½B_Ô ÿ?e$ÃËxŒW›6¨ÍÒªdi±C?iú\ˆBq«Ü#BmÛTž)´Ô‹êê Y¦S¼?°i/Ů䠘öT÷r¿ƒ>àcÅ U›KU&êˆPÔöHwÔ•_:Ñ=â<Õl¢n9!¼iöëÑ\&[»¨ òÄœ¡–†*¯&L’v_ÞY€ -^Ž£WÀZÔqâ_‹Æ«1˜¡CÿªÔ=œù®Úðúò*ìä ¯ÅY€ -^–^/Ûƒ¼ûÜ€3ò3È¡wÏ m¡]?ãÜòOñYЧqqõ{›?Îb~÷ÖPòóîo!áñëD&‹€¾\‰ 2¿›õ,"1ÒWã­dPc­>Ðn.ijìÆÊ1‰Ãû±_´MR±÷𪓮Ÿ­³ga/Uí%ðRFçPyuêúÏ%f–´®°ªæØZ®óûæ¶½òaÚ…_5;•ÊŽ»,¤úšFñN®opŸAÏܦQþµ€u@ó=(ãçxÿïó5‚¡†ÍŠGñ¼ëÿå/2uA¶ûﲏ¤pƒÄ”ïOX.üÃÇ «¹øù±ÄtÖôCÃ-“Û$V{µ–0zóð0{bcúùo–K¦í qa³–íßc¶ì=CФ!sÝÕL×Àñá-ëfrÓNõ=iÊ_ƒ½8ÂÇ?Zw×í“?\Ð}j‹’”n?üÝQ‹…›|¬)YÛ”ðÚ¬Y©¶ÙÃLþj=!ê·ð7²lÙPõ…à8(_GmIeò‰•ÛØ37õwÓëOž[ýž°+Äüø‘¯Ö“ã·d&Êú"iÃ5ÃÉ[† î~z Ñ0üÿ>4èäsQÁƒ¬´æÑþ”ºSiß~‡ÍÜ7ÄäÜÉo×Q'nò5Ež<óã6Ö¼¶Tµ"rïlßH¼ú¨ú*ö4K}ÐÙph ð`hjiTTÛØ`B*Éä×׈p3Ýàx6§Ý‚ wŸŸ¸ÜP]'¡9é Ïf“Þ“ª«‡kËŒ@4lè@–¯×„×ß«¸rœ[Å—è¦CŒRHÒ¹|ùù¥´FȲg°ÅÊ2Õ– ³|þh°òEÝÀÝß6sR¬Q+>ÚQt3G,¡ˆêfŽúÆ…O—ÝÍI¡Q£ Ýíè¿ipazƒÐÇhý •ý%P²¡ïÌÿ­G‘/ýÔ!âúû§¹&ñN–tEØßs=w³õ~Ë(Bvq °%Jµª¥K”[Óˆ# ’Ë—£â÷ÞÝ:+-;Glâ>f²Êº™J÷tp÷è¢C‡Q©ç‰Å5\!¢£¶(J}æ‰:㱎–2÷ Íu²“ñ)6|–6Œäà4P±ÿ·¨«BÔ&qoï¯0˜4ÈE¦a¡œÁž¿;wG0IÚNgÇ~f‚õhä*GOci¢…ÿˆß©4¥t õ¥JE¡ãj¢+í ·®dw ¿–”8'1Q>D¢†ª´;>¶$5"j¬Ò¾‘bî-õ%U%Ðéph ð`hjîc(*’`®¡A¨T°¾àÚ=æ0ŸÖŠ8Ž] †”'XWpõs0±ôРʰEÖºr¹xwþÑrÓQ#)¥:腺ȷRi¼ðcÉmKKŠâ“×èËŽòoü\-3 î©-# ˜PŒùYŒ¡ÒÉq²Iý¯Åµ£-‡8`’òVKôvTRZsï®Ät„¡“ÃDÿ…ƒ Ó €>FëŒ6;d·£›Rñ“å•Ks¢ /%·\À@t§´ÃIOŠ#=ÍšôuÙe ^ÓÖžûäBᨹ[$ü‡?¤l[cðß/M•ëfJê¯,=sÙ/rÙr}b]ù™åge )æDºkãðþGùQ>6äúÛ[²KùÌ®›­è/ªq!j™Þã R·ÜÍ>À•#©8}ûšÀrª79Ö{CB`z'˜¤nfMÝ覇ð>LÜ)âIR/"L]#;*A¾I€R‡¶FwÎM”¤Ø-m³ŸJKrs Q삱¦Ý0Ó›yˆ¿äÐAÔÿm#]YAù.Ú­ ”íï¢,U] ²´F£vÃ@;( ±0ˆù\ñ¤B\~©ìì9BðFÆ”ÑÀÂô éß¿¿Ko¿ük³‚Þ²¢QtÔ÷ÑŠH²ý¸5 åÁc¾G±i;p®ý©d¡9 ]e-TÌÌuéIWyòÃȦXŠÓGã¾iU!#hÓ” EXÇ üÇxår“ê‹"˜Î‰ýA¹qÃ÷‹ñ¾_´UnØj›Ýj‘Ö a7/2ÛA‚Ñ«F+èG…ý/ªMɪ‹ALߊ[Ù©¦¯¶ƒQÃWF)#©NÎS•½ë@Dj©¾•ê°N‡C[€C« ÅÓ4šVþ{^EƒÔ&@ÙžzýG0™D„lÍvÐ/»¶áÙ=¢qžµ#råïæl“0ï²sßæ ©¶ËPöjBõR_BO®.4oh¼ üáS±E0Å.VÏòï'˜Þ``ô1·oßvuu}õÚ%¬ËXs!ùx5_ª¿ÚØDÿ9Ôƒ ƒÕââ¿Ïl=T'jM3ûó wö¿JàÁ蜖å˜h*ûE`$ç¶ÎmŒ ]õ ¨º! uÛZ š÷[ÖÞÍ¿}¬­cÓ˜–w0•Ë@©/¡õž*Ê]ËÖÍ·V®(…ª/ŠNsŸléþ/¾ € €>¦_¿~¯d»H:þEù¤ Ó©Ã>™ r@Àƒ0½ÁÀèszàÁ`Û§¬Ñu‹´´´ÐÐPƒæÐ lÌuºë%x00L¦oèÒaŒ­‚#Hy2‚ €>¦ŒÞ™rë._|ñÅ™3g@Úæ%x0ì ü—/÷Q/ƒZ< 00´Å«ú ôø`zƒÐǼªß`@O€o0¦7} x0€7 ð`Lo00úð`oêUÞÞÞR%,&&ÆÇÇ'99ùÖ­[LMMMOOïn8444$$äìÙ³ŠOù5 _¾|ùøñãýû÷ŒŒìnøæÍ›”ö"66Vó°³³sBBBVVÖž={º¶¶¶ž9sfnnî_ý¥y¸¤¤dÆ ™OŸ>ÝÖÖvëÖ­yyyš‡wïÞ=aÂWWWÍê#ÛÝpÏfBwGÿÅgB'#Ö2rrrþþûoøb háúõë³g϶´´QÚ<À›„†Ïncå´GÊéY8DŽæárzö‘Ó³°ô|oQwÃR¿[a“6Ã!µ:º–Z8=w4Êš„µ=úÚž Jp‡!àåãìì BÞàÙ-``ô1ùùùðÐ xcX¹rå²eË@€ÐgXYY€7†÷ß„¯x}æß¿¥!&#L÷ÖAq Ù‰ë<!ÓÄÚHǸÿ¨P+ ²€×ð`okÖ¬``¼j„D$B$¬‚¨:¯Tj]Ð<§ÌiAz½ûò VZ<ÚÀÌ̬¸¸¸M$ж\*ÈdrZZZó—š@o ÀÀÐ’êk[6œ.G,bMv¡µÜÔ$5ÛÖŸ,kŠÇ³vþr°µñç½VÍ66ÖaÚ„Ç›$5÷’¶~Ì—ZÆö6F4¼®$÷i9ÓËSµ-*î\¼URß 7\?s*›@Ðó ò1"k¦ž×ÝÙþûÑbÄÐÏS|3›`ïfg¦ÊßÎ,â!˜YÈÌI åÊs³m=U/½)ë[Z0Hâ†ò‚ür‚0ÜÆÌŠvbÈ:ØQ_Œñ¢sÛ·_)—g¶2d’$¼šÒgE5R£È ÿÔ©!æ w‹´Ã‡¶~ ­ƒb`emÄ"ðËósJ¤?©ö#¦ñÖ%tR… fðÚ mpéÒ%;;»ŽVï>|¸››XÚ<€Ñç I®8ÜDf,YjÒ,C~NòŸ‡ ÉÎñócí¨Íö‰øù…?7«Ê\ß+$ܵèøÃõ4 ÿ¡áÝô``yÑÏstfø!A;04²øÄ†¿nœÝ²—õn‚××C£õ]L[Œ%¼îö_¿§ÞOÚk1† í¨/âò‹)Rë‚ìšðnŒµŠá#æV ŽPaÑñ ÛoÖlF¿;ÁÙbá ×%ÛøGõ¬¹¡FĎį1àÁÐ666³gÏþóÏ?Û{ú$çVÊéý•"¡{ŒŸ;Òž¦|5šl38:ÆJƒ×»ÚU¯/àÁÐí_”‚—£´ x0C{ $š\QæÕñq¤åµ"Imνç]ç&»Y²sù9· ù–¶-KB ‹¯^}Þû-ϸõÜw¨qËò‹nåð¥z¼µ—)å”JãèîA.*ÖÞøädj~Ç&Ss:^YΣ¼ ‚½Ÿ›AÉ,{/éA‚Üý¿îytïÌí¶ôÌ=˜np³/d×MòÔQ5„•U±¬¬˜D°)€7’ÒÒR‚–hó¢¼õ``hÑÀ`¸F…\ûólÙé ërúyÙè‘ŵ…îä}Z ¥8.éL+GiNãf…íÞr:kÏš,ÇÜBŸ*®+}VVo0Ƚ ÍÞ«:òR~XUg`ck¢ƒ6–=Í)m”ާÕðYcd¶‘õ°vO?¹õ÷O¹Ö.Ö¬±üYNaAД)QÕ›ŽV]Ø›Xíhâ©¶+½úðþK§Ó!tCKS=&ÔWç?o@ªã¨ø@= A0Óáï¼mš²ãð‘ßW!éZX³HbîóüürÙWî‘ÓlŒaNo(l6„ =T_”‚—£^àÁ mB00ké€VQƒ†Éÿ„µDQ–.U›]?`ÊÔ Ôú7É,â½¥/ÖÔàéK£:t`,ø=ÔšºÔKå—‘º¾ d³Á³>Üu#8±ïzÄvž¨CqÀkKMM A«(^”6l¼õX¿~=Ø€Зt׃q¿Iùg[cùSæœ;wnРA+V¬ihŽ¡™Í‚·ft+ËÌ™3An€ñ&¡Ü&B£Ñr˜ðÞ8ô9Ýõ`äT"RëÂ4z9ˆNs怸ºƒ„œ­wsê|}Iv­;k:õ­Eò 'øO’ÖÿY9a¶/óÉž“¦ –Þ[ù‡Öýu5?œˆŠê Þ³†dJûýöã'›ÙtÞrúÜņ²$ÂFžlá[Š1lOt.Û3B»ÿ÷}gÍæEÄDÜ_{ÖfòœA˜ú¢LNý}ÃfÆ¢±²¢DÅ'7\ê°?¢´µçˆ ˜Ü×±ùè—ižÌæÛ– èVÑi¢=CÃÏMÞ´ÿ1O>;Œ‡L› G• ìš´1;×3Ÿ6w‘Qn4$¯ûãPÜL‡ ¶‹\c0><ûϤ ÇanêÁg.ãçÚ›#Ÿü±ç‚ÍÜ!†’Â3‡r¤‘`]¯¯CøàÆšO²ª‰&3÷Ñ…{Àè¿OöÅìåmN  ÀÀÐ:xCÎ…ëuáN, iD”HnºÊSìÆ,ž/{û(QÙÓB¶¿…bÿnŒÂ¤4=ÎR“Qju ˆDÜ´›†DP߀“IhNâú£Äˆ£Ý8D—HÚo—¡®(î]Õ·ÚÍD¤(·¼Ceå´NK¶ð·—$Ÿ¿?8¡Ÿ´ÇÛØw—È œÄu§Í[ƒ«v o)@DÕGÊ¢QV¿±#l:pÃrг”2ßI³ÌdަûØ1OþH‚ê°Ã]G͵hU ·à÷Qg*ÎaQɶ˜íÛÄæóøÅšôbîÙ9II9·ïÆM¦äØøàî½z¾ôRÀf;ðˆ™cgJWI[U–¾=óò¹Ò‚R¡ìB@¥™zYMïÔªÜ賓¾H„ŧ3ïúðA]½Pv±a˜ë;…9ŸbcÆPi©„ÿìøý“ÉOfqÅÒ+!ÍÌÇjÐ4¯^T¬Ë*4¤;]îöh6›|ŧÖÞ¾t©²V(-™ãã;ݬzõ¾µ'„& â>š¤C4\] âÁ4^Ÿ¸ó>Áó‡ñStŸÝp?#£Zö*+a3Ø%ú=WÝ7CÀƒÚ0)ÿùi•òÙ‘¡ç€Ðùè“emºkÂÛ”‹G6ÿZÔ(U›In!£†ºéÈÒx™)eV×òŽa3FÛëËU5zµ9n“æ‘ϦüñSQ½eZDF ˆ…¿·^ʱm/0Ù6!nöèá½{Ø“¢<­ùGÿüåÉi“ª+ÊcBB]râšïùû~tB÷ñC©c/®~|åà¶;OJê„òo0l\}ƒæÍ1këþGé².œ;ºù—b>Š¢ +ÿñóú[ÐPËö‘òÎP†kܨ¿oÛ¯?üXƒ¦=Å)6Q\ÿز‹>üi˜Àë‡@ Ð~%‘N“)°™ß¤pã‡.J¤ÔRqAÖŠ¤ §ˆ×GZ˵^œWuö£ä™*Ù™ ÎNÜ¿úõÛÙµlûE‰AvÔn]tYzñý’v~:zÎ:·© 5þyîŸS/¬ÚsÅùó¸·#¤Wqþ/~ÜÛ€Øx}ø×P+… Ž‹ ¶§~ÿÞÞ}&îÿÙá+»tмê麱çŠØ#6EOwV>Á*O/9ºzûÛÇ.ÍÀIyâ±o~.Ǚ֞i£H&©â•àÃÆ`@ǯ\ß$ù¿=UŸÒ)z’™(µ.é?yYÓ›O4ÝÐOs?ÿêyÒòÇýþpâ`TÑë]î©ÏU”s¿ÔºÀŒgþâmËTF’,ìfî¤nsêvcÍb63ŠÙÒ*cëPÏ+Onñrn6ˆ=X/ö¤&!!Î6ÀÀècZtw gd»Æ,p9€Fp骗jQYUµ,–­ßf9ÝÒA*z¹v]WF›QW‡×UÖÔ „,z¶õØ›+q„`ìàÓÍæeodòêx ££Ó¾ l«·OMmxôôìΛâÎWð›âMÌÂö1„)UæE¥åU²¸ò±ïPÛÄ‚’2¾‡¦¾ŠÞïr ŒçU²/wôuõÚ¸’hzvÈíÌ.²Ó ImÈ`òß=v^«””4þ|8ÕÔзZÐ6(ª|¨Í·SbA W]ŸÍB «ªk*[UU•_÷¨ ÷[•U/ŠcUb%ÕuÒ?ºÂϸø«Ôº [/Hâ¤ò‰‚ðQeŠÆâ ;ÚF-·jŽð²¾KÙðI§ú Zñ‹ÃÌH)*C &%Eö7xŸ=wÞå&AW‡‰ 5 +EÕëÎzÚ·3r̘1pZÆKD—üû~I\Ó"¶8¿*çBâþ,ËIó"-É}ßûßÚò]SNó2ØQ¹=¨8oï¢sé%¨ýÇcÞ•}ªñ’ºŒHz8š$'÷‘ý²wÝ.ÞúiöGß;˯º¢¢Üï^ºWß·3<€Ñ×*½P BIT²ìn†×ÝûgÓúˆé£ÜØxÕ­}Û.ëÆÏƸ½uC-bî¶ðÉÁõ{ŸZŒš5ÖC‡ÿhÿ†:ÞŠ0i¸µëÏKú±3"ìHíý[ŽãQsÃë7ßqŸ=C¶gÿéÁ)¤¸yQ|5å‡S3¶n¹ë0yÆ3bÓËåÂ6ËÙˆ«2vÈ·Øsä]ߺá41tÖ¤@C"ÿɡţç±ÕðÝdIÍÍ¿ÿÌpœ1k >ûã€(zÞ(óº+íkÇ«¯oÙFsóè{\‚2u†¹Eÿ:ÞåÇýkO E â^ôäY~;×®ðànÞ¬m (›íš0øÓÙ6FTEO<–¥š]Yý䇻Î4H•hªY }øÛ¡_M!ñ³îmý¿[×íºiá8ÿO_µ=1?ò§èÚ{{ï¥.ÚŸ—ÛÀ—µ¥›êÙöY|ÐÞVWa5`† #š (8™yòÇ”£ŠU¤P’®³©÷Œ¨¯£ ˜½½RDç]îùhbôþ¿Mñ¼ÿðàÚ̯JS’ ½Æö‹Ý3ÎcÑÞ¿î!(†ôÑU<€Ñwà “7ŸóŸ(å3ÃéyùÄÖßNÈUr± ìZÁ¡Ò›¬I?g6Az¯à3I ýYÒÛ$™cH”ñ$’šìŒbN`´­ü‰Ëi GÚŽëEÔIã†?í1Ý«òè¡bωs,É’êÛíËÏïg–Y¥ïëm"[åŠaÛßG?ëIG –¦ ™úzÈø‘õ̘âûuBi½´ Ž‹ë¹Ü¦%qDBåã9Œí?úÉÆ=i¶o ‘œIÉsŸmE–T娫]úƒhäãeJQˆEM øNNT˜BÐ|v2}ܧmpo½"aÍŠædŸ§­é ;ÅÎ.nµ]\›èå k–·Š »~y>ðÅ.|(ÝÝ)~S|G=aè \1pIÛxª«Ç;û=Z~wДÊòœä9­«f`d‹Ÿ™>§èD\½ÚeŒ°~Z@·GSZ¬¸&»$ç1bÿþè‰M~Ytuþõ‡Ò¿LGgŠÒùcZÿ®ûÕ{ý``ô¥F@wŠ[À¹°uÝúÂIsÂ-ÈÛ%ÐúâÝèéÃí(¿ôæ‰t¾Ÿ9¹‹,¥¹üÍ.^¼üÔm„]j£\¼'rж¢ T1QÙ›÷~X_ÕjŒ|Ë:uå[êÙgoÜ*öbN¬{x1£BôB»g¡(‘Æ`2›_‘¢µ|GˆÒcÆçnJÜUˆ‰}¦Ë÷ùcÙvP;ÚüfT„ù}ЍèÀô|±’Eœg€9t¹×o!#<ûÿ®¦—]ÝÑ-ýôuÉÂʬ’Ùµì¡k#£ûjÕnð`ÆË…lûþª3 žûQÓj®¨ŽgÂûžÊcßèy¨eQWÕõ¦†Cæ)Ö§ô›üA?e$Ûcüâ¦g|tçñï9·º©/?ø­¦°\cÞsiÓän,PÛ¶wB2\ø•Ÿ¦ý°·=𙨇){¡¶öVKôb¬:@^îÍâ|»£FÚ=§‡.¿(˜žÅ¤}Ó&½r‚``/añém;3xæƒâæ%XP_“ï'àsàåÐØØBÞÀƒÀËd6wIÈÔÀf³{­,~ƹåŸâ³’Bœé.hÌÙ™¶~ezb˜[Û½”mOù>½ß¿YÓ{«D¿^@d²Ô/a'̾¾úä9›¼LºÚJB¶ä+†ŠÝX¹ "&qx¿^…PãbÍx‘§=.áÅ«îxçwà¼àßn`ØÚÚgddÀÍYZZ‚€—@MM–JÆ%1ÙÆÈH¦òãÜ´Ó_}Ošò×`/ŽðñχÖÝuûä‡çÿ·yز÷ )’†ÌuW3]LJÓjžüvu↠_SäùÁ3?ncÍÛ¨²K^•rrÕvÎìþŽtnú²Ã‡Ø!Ÿ}nÜ|TãŠHÙËÚGÒ›>Ü’”ï=&·X¬÷þj-aôæáaöÄÆôóß,—LÛbU\Q-0UÔX­¦Á¬ƒ‡¿ZOˆú-<Â,×­qœ@$Õ6ÏÕ€ ¶S&üÔÎEÑRleòñ•ÛØ37õwÓëOž[ýž°+Ô‹ƒTìiÓŒ{ì±Q["‡;o]]õŸÊ;#<ïŸi×6tŸj ¬eY ¨ÍHÇzÖ1NjÀÀ@0 ƒÇ-ô½éÁP%RŒƒíSî¹h?3”F÷tp÷è¢C‡Q©ç‰Å5\!ÉåËQñ{ïn•–#6q3™†‰¹·v—ðkI‰så ´¨¡*íŽm`“§@Ľµ÷¹~ü@¶´ ?$ȿҒ4m›jZ‚ª‹TÛ„ìâ`+ÛƒjiÀåÖ4ª¬«¾ÁÞ1(BrpèBnýä^mó\]§Äué‹¢÷öþ ƒIƒ\ô¤µ¡œÁž¿;wGè5„„¨o† ’§G½ìÆIsµóÒyt=KÔ_]ÛtZ• ùµ‘ISi¿(gÏžµµµ…ó€»Q[[»eË–êêjB ==½ùóç‰ðâ u´æÁ@Q€IøåEB\"I_zæ²_ä²åúĺò3ËÏÊ øµç¾¼P8*dîÖ ÿá)ÛÖü÷Kï“Ôͬ©ÝôÞlj;C•XŸ‘}ƒkã"Pß6Õ„µç>ÑpÈZK@}FS-,É'5`` ÏŸ?—Z~~~0„@3ÅÅÅð–ðèMÅoÈÊcÍF·w˜•â ø´iJ"¤cþc|¸<èôÃÈ&}âôѸo…D _¥Œ¦:9Oý¢­á¢;:bõhE˜é÷Íŵ“>-fõ´îU¢.²Ù€0j*½ºi ÌÌuéIWYhHÄ÷C”íá¨m°J.)$G¿ÿ¦ÊCêš×a§º…J±£#V)³ô£Âþ§Ì…ê·n†*ä~žC\e[X0ƒ}}¢ã¶©–@b…h>ddÔàÁ €>F{ß`ÀË<€ÐÇhë à¦Å?óÆ ÀÀx¥Àë3ÿþ-¥1±`º·NÓ«³’ºÇ玞¾™[%@²]Ü;ãi­6ˆsïl_{´1ùî4Of_ïèÐÓ^À›Ö<üšëÇy.£Œ™˜&ŒÒäEgÎæ‘í|ðg<ÿ/~³ä*—m´^VY¸ßáU']?[gÏêæ'ÃŽ¶šµpÏ›¦E™D97¿}«8bO”wÞùÿ¾ŸÇoIKà¸Û„¿ï,ÿ^™Ÿq®å(Jä8™úÆ÷‹®K•7 ÕQ%zã÷Œ 6UsÉd~7ëYDb¤/»døê–ðR``¼òˆJÎlßw½³ŽY8Ñ•ÞezNYâ†#(Ø-U^R•¾ecZ­K»±Öä>ï¼ù÷~¡â¢‡ßIÏ®"0v˜[;Ä—Ýpwã¥ä#UŠ3õƒ¤b-zvöƅ׳Ë%T}:†‰ºS¸éÐP×ßøîhÚùªZÍ}þÐiã8²K‡„÷pÛåÄ}e Œ``6|Yà G’æ'?J·š/ßÍCy ɽ½rÎ tçÈ`´ýÑÆ—ÿ^þwTˆ9Öþh[Sª¡âì×çS3„t#¶ó0ލy=*!÷æÚ‹S«q34‹ø,h0+·• Yõm„¸´ê‘0ïñÞ¯ogK1N÷tŽÿÔ˾áQ³ ¨;ûĦ¿8;]ì¹ä7Gá–ƒ?ÞõÿòKš¢wóÊâ’†{Ðïÿyiÿ²jªëï6áÿ<íê©´!Øtû\áFI)?]k*ù›ÊjÄÞ¾mN-]ŠÁƒ=CR}mˆÓåˆEì¢É.*Oâ%5ÛÖŸ,kŠWúHNÞ\{æPZfì:éÝ+ÙÒ"¢êœ+ioç”pEJÕ³rõìØªþãÝ?ïËSÜü$y]}AÌG/œâF×Ѓqw‡ŠçÞû{íá"¢ã„÷F1^8{õþÓò ‚YæŽ~CÂü­èÂÏÙûKâù¢%ȃÝ?=@’ÓÄ÷ÆØ(ì œW’™~åÖƒ§ÅÕ|ù¢+†VN>õ³hZI]mÇŽhH:ÔQ/$ w.§ß~˜_Z+%!1 -½ò¶d´zT'®Ë»•~ýîÃü²:i:2ËÌÎ#0x€“¾êÍ½ËæÀ+J~~¾O/J0sšñaîò ¦ ÿò2!ò2ÞK>ìùIŠžl ¤†’mã“·=n†¯òªM°pž»šûíÂÚø!úûS¾O×¼pOÒéB’ç¢B—Ê3.ß ì¯Ç¿±hÿ!×ÈO5ÖmŽ?TöCìXW‚†íÇòרÞ\¡Qëèí‘ýLÔ_ühžnƒLS®^i<ŽÙ./‚ÐmÞ=0Ø‘¦¸ 5^ÿðØÿ‘_ÿ#í¼0ëÚ×Ûš+¡¹Ìæý¾l_?þÕ´åËnØìîß"Ci7$jØPUÌ®¤;7Íâ>wñòÖe)–gâ´Ô‰ëXЖø8™DÄÅjúÁËXœt´ßÈeGdm“ðøSG’Ú\(Š *å%y7ª;¢¦mÚ<€¡UPMv>>¼µÁÜ”EÑÊ…ÐqÞ“Cë÷fñÃ é §›Êcqáóë{7ž.RÉNqHøx©°èø†í7ëižSæ´ ½Pc(²=Ú³>eä̸xOÅú$’ÚÛ»6¤îʼê=õíæöñ-)KûcKz-¹•CR•±ã“E8ÅaÄÔÙ± ½^\“udûŽ_£¦áoMõ×Å:ìïÇnêz!*>µñ¯ëuˆAÐô9cM•a K¯ü½uço'Xýg¾j,k°¸üÒÖ?Ï—#ŸñSß'·;ðÆü´¿wmº„°¦Ï 3%iØ<xE±²²ÒþÕEð–­#pG{ñ”À¨dÅY‡bŠâ®¬’HÇ”µ0ÌfÛÖJá°èõµå ¸ µéÊø´¢–ª£Çhã£À+_µ¹ÜáB8÷Ò­³ÏÆ Q>˜èƒË6ÖP†Å±¢µ8ÿÎÒ¤ÝäÀ%ËíôɈD,ÁUä¥Q„`ýþØï¦Fåó´e§Ž³C—aÒ*ƒFm¶°0‘(‹ÀB‘b9Zi^¡DY®HXWShÔÖ²V“«UɈ]mÛ´ch¤§§ƒ00´|S—B²?À¤ùu#qùÕãRë1žlÚ´ùJ2 ˜P½aû ®v£ã7!Ö“Ýrc9˜§<«ö¬Nb®§ö.~~i¯T}GÌF½5ÖƒÑü‘Àvž…×þv¨àTòm§>,T};š.¦á –†+oò‚†ú¾Hz_%Ùz›;^Tû(§f°±>A\~e¿Ôº@,FOnßä¹AiVCßZ:´ûÍ€W­x0dÏ(œí¸—WFŽZ1|MyÓ¥UÑ•< ÁtCVņy{£ð‚ábu—ªïš8Ú–Ë«F—×ÿ?{çÅÑðÝë…+ôÞ‘.Uª(UE@A,ØÑ$&j š&FË—X»`ì;v{¯€bATzïWw¿½;Êwp ’ùÿüÉîÞô}oÞ¼Ýl$Ne;Åy†ù3¤'IH¶î ûò.¬NI¸YVQ‡ÔTíF;ýtL‹‰‡Z~A«†-2¸±4ì˜ÇæáCÍDÒKÊGS2Õqï´ð ‹¬È3Ž£ºüá_±ð‚!<ª:Û:TƒA€Pl˜“L"ûi,¾ùGô#¦ŽÖÆÖ¸«¾Vú<¾© ÷¯þõHE•fè­LÅ£*j4ÒÆ«¿Wóa¦ƒuôOvZ˜\•ºþ2b)Òì²ËÖ=ØÛÛƒ‡£ûah2¤ÛFPU(Úò–¦Æjµµ+ž©Å€ šî- ™AiiEÀ’É.´ÍtœTóÅß æX»â„ÌåoÊùŽL’ìúÊå\Ûõï•B"¨šÙYê«2h"VA¹ôØBP™W…ý¡ª0忼ÝÙ⽌îò`àµÍ¦3k<£ÙÎô·)7pó~M»O´9—xtÓè½i“ QªÕ´!VÓÚ-¡ªNÀ/:mÅ”ônb¨Nî¿\jþuùeù"®MÜÖ¶’FàMçã/»:Ï9Ö¼’krÃ$|sËД0ݱÿôýi(Qh–VÈÚQ!MçÑ·é³ÛÏÚ¹²bIïw!»Ùe—­{xøð¡••x®00:dª¾åÜ!ÜjŽZ_IM zUUWZÅG!éq3¿<§¼WÞX¶zUé ý|¼ÝZŠ—srf],£>3’ú ŠŠÒ¤³VÖDz.­/,®GõZ|qDoàDBwøˆt—è €£kà”tõ• âš¼{Ϫ,Y€°2ýØž›U’áo»í¤á6ÄôÞá—ïŽíNcŽ÷ÖûõÑú7©»÷¥sz¼n0Ž zWQÆA %.¼ªë¨ÁY›.æ¥lÚÏî¤ÑàyV>=³ëÈ£*œ~p\´}çÖ¨Ä3´˜Ð³R^~v ÏPGòJ}îÍ#‡îrEo ëÊj…*¯â>(}ËåÂ3[@ÂÄßW œwWöìºVˆ*9Ÿ Kì†â‘Îz0HâWUi å:ŸË!’) :§º x000ºZUí€Y³-nŸO½±ågø¢×zÕŒl\}†ÅEãþÙó”'ൻÎ#L³=onqÆ•ÔÉÞ-åDV6´vñ‰™mrfÝîL.íªhoðjžÑáõ‡Oß;³nÅ<ÃÔol„£2^Å56Þ…S˜qóÆ™ÄË’eš SËÈrà„Ù¶:]X§ ¯ê>uŽÉ£Ôó7ö®ºÅ}¢¨nlëîñ…;‘—óHrZúîUO•í£&ë{Nw«Î¹wõzòºseõXÎD†–±Íˆ©1–j ¦Ä‡/ðé¬#È Z¸´[‡Ü¿Ù²e‡Ž‹‹›;w®‰‰‰ü7A²‰è|O Œ®ƒ£¸˜àÖúrØÜø°¦²Yt|¼#ƒ¤n3d´ÍV—Cç涸@Ô ü">°+„•ì&ÆÛA¦ÍuÓ"`¢EÛ×¢aЦO˜M; Ê­¯ÌZÀd ûÀ±öm*GÖvó™{Ks„aèŒýk·¾è|ŒU¤þdgg'%%mÛ¶ ãFEEÅÄÄìÝ»4ËGx000>%øÅ÷¯>**’¤éèi«‚M| €o0º ‡Ã9tèfQ`¦ÅرcgΜ¹H h™x000>%ˆê޾~ €¾†¹¹yo/"Zûlß²¿Ÿ:ω3‘ìZVß[»`þQÌoñ>ªÍ¯!r³¶Äÿ‘=daB¨N7©„ÌÌÌåË—cvEDDD|||Œ¹¡¥ÊóAÚáÎïó6U…,\8Bç£i<”óòðò5÷,?›?Æ’þ ,c<díÂ}µoáò»ßýo¡iãÞ HiêÚM¯ìg~AÙ¹vÍÉ~?‡¼×p›“¾>~2cÅg6-¾ÂFÂá`‘›"113*H$RBBfN$‰Q(A²ùÔÕ>ñB2_ø?û} çÍwøî—hSr//.ð```|hx9Gþ9„„>Òˆ!Üʼçw.ž½Çs7Á[‡Ô¥™'Ñ7‰0üž“V‚‚ [O#& TSàµ)¤üfbâ ÏY1VÔælQ~}D£à;.‰ øÆî¯ íƒ]͵^UÞÓë§Î>S>u¤U‹Ed?HÕ€OŸÞ= «{¼eåyÊÈ_"›¶‚Üc«v— ŠÿÚÑV Z¸dõ~ë%cM¤–›.Iûse}h¸§¡èöþ­§ÞZLûõ FÕ5?$–yLŠõ3c"åÏ/îÚ~6nñ6‹‰õÖ!Ô½º~·„ÏjYaùÝI/}6®çNÒ† ßÉc]Õ ÜWÇ6Ž˜5Ò¸yF÷&e×Urèçcú5LEb`<;éûl¤K¡¡jĪ»¶\S ‹ 4¥CU‡Ï Cg„kfíis1œRu÷ß-l¦Äº°q÷õÑljá3‚˜é;¶Üí;ÙCñßÞtX2c¸ØRðIÑ«=œìË|íÇæÙ NÖΕ'áá?2" ¤;â«Ñé ×$Ù-nÓ4Wr˜>'ÊTô êë}EÎýú¯Cgß9ŒRc«+AOï]¾Æ8ô·u—0p¼D¾ÐÉ8¨º²låŠe[7¬3Rfj~½ÿ—)dhJƒ=Sþ„yøLê¿k’«ëùÊÇ.\ÃÅ Œçû¶ÜÀùÎÿb„±h/mýÉ¿ùLnN&P•”hä–›‚'ÞÆ ŠŸ!1†T£¾¡}³6)Å{Q„¦èÃ1vÒ`#QZZ‚$?x”Q,°5$*(ðU=g|^+£œvl/¾zúýª•Í1"TÞÜøïk븥ުüIÒ¿[S~`V~³~ãûï}”DëÍÆÍ 7k¯xU7­CÇ/gsìlzõz»`Ñ Œ*ä a#•Ooæð8¤³IkÏŠ‡ÚB^Ñíwƒ¼±–ÓópPi1²vsÊÎô®‘h» G;mñ2#¾±×¹Ë0Ì€ ÃÛnÌÉ‚Qˆîw£kWvoIÃ.s뤴V5+#yI¥—«:9h‰œ,tc7GÕÌWòj#RzÚN¶âý(H*:JÂŒj> ‘›æø`c©¢’uvQ!§®^€B¼œãÛ®éO˜"r¡ÀMUCÊŸÝÍg»†ÓE/p3Í=l/í¼ó¦È¬íÅw\ss–Ó¨€§[’ïö›hW–r,¿ÔT}rˆñjã¾KÆÓ½‘‹Çs¬"§ëðÉñ ¼RÒô„£Õ÷6ýy9ìs[~^NŽäšiD¨Æ_ÿl¸µtŽS‡Çµœ÷‡±s˜f9~ù±M!¨É{zqËïËvÜ{šó‚ADFXëÓ«ýüÕ/¿ý»ãûOÜCš>êà>ß¶à÷‡ö_/ýi²x¤Í{pá’³âF$mN®<+ûQqŽT¡ëKZ·WNˆb9áÛÐ_þÜi÷ùÑí…s–8*aZÔ¬°°¼ ?¿ÑˆÑŠþ9 Ä€%…$ÒH8Y7¡—-ÀÀèVËBPSøìÆ©S ^£Í±A>ÙÒÕðê剦t˜[xÿìM®³. *„ï®ß-0¨M¬}7“«3X› U‰tg£ÖcɈ¨¯N såÊÕ—ÁfÔêÌ£ÛÎáBfŒP{zðÀCà SCµœ¼›G¦æsÅ{jàPA=O´…„̤T ¬Ô{òm½u ÕYWï– ”»Zi¢~Є!û“Ön~é<ÐF—E&¡/\¾ô† çHÅ5Y!âªaõ sõêõ×ÖA&4Ìô¹úD`b¤©ÎmsÑ@¤±a†íȡ϶:‘U[î6>TCÜß`j¿ÐÑÙ›ìÎÅ £'j‚NøôèÕ б—ñïëJüƒ4ñ¢O/6<ÑûÛ;U顯áçŸÌßúçÓïý¢óª;›×³¢#ÜõE·vm|Œ· Ð#Ô>ÙüÙâkO r_¿=&"ÌCßÖÂiö¿G#ôj./›¿£ðYÆku]6ÒZ¤(¨AמÞ|œ«n ¿»qøèK*BKž¿­075œâöø¯•¿“'ŽvÕä¿NÝ»û>äçB´±‘9Ä÷(ã5S—Õ"ÁiîÐ_«V3¦FyÑj²ÎmKLW \0Tñ:Ó&õY•4¿pŠW2°0j§œ, ž =ìë)Y V-¼®1bat?± B6‹œ1(cÕ¶=¬Ø1^& AQúÙ]»n1cÍófÈØJIXúðfÑj”qoß.x000>4$ð9s‡Ñ%-ÿI6þMóOŒþÑsú7œ5BD[^Ë0ª7p€¶È}@3 ™=Oüó€)ó@íF„ û˜y Ÿ,ë‘_Z‹b¿uhè¸GÍnØNÂ|ì7æí&å5ý[/É5¦UèV¡­ª…WqŸ6OœEª`8ö€)_hÝxeÇè¹Í³W8†–å HËAMç¬æpLû˜¹ UÀ³lGeÛP/Å…§YŒþ¢M£íæÎÚöÔqŠ« ØQð)Ò»=4»ió†,\¾ê@¿EQ&ª¾ 6ø¶ ƒc{~·Þ³AÚL]½ajãšdœqtEÄ¥õÌùóçoÛ»U:Ú¨†¿Êƒ¾ßÐ$"ÆÿÞâ›lœÚàï7 n 8ô3±ôšÜø«í”?6Li´rŒ~ñ‰•‘ ôGÞ¶“ßÐYÝml‚ÛØFÑmÚ2_’ɸÿmצ¢0}À·Èn¨öÊ)šqBŽd3ùÛáMÄKùtD¨xÇþâ+»<7ûàʃõ¾ßM·ëõ;¸à“†ŸaÛ®»Ýá3¢õ(à{qÀ§Io_EŠlµt¥ýÞeßþâ<ç»Æejå³sçÎ}ûöa•Š4iÒ\1ÿáÛ+(<õëÏÉy4}¯èŸWºi;Êyudù껟­\öI,S <=O³sÐiˆÚC¦}=¤»R½ž t?ŸÂ7tËèÅÊù133sÍš5»ví:tèœ9sƉ·µI3j/Üü>O1 _øgø'SaàÁÀÀø¸ðrŽü½ç©Ô˾†Ž¥{€¿£¹7LKÉZ VXv#Q¼~”EÚ5-Ñ+Ÿ{jý³£ÍÈ]Ëø/póæÍOkYOÉÆ«V­ÂŽ"""Ö‹·F“Ì£¤†àÂ’+[’vCÓcX0„Ö½¾vòìÝ\‡W2vè¨A(¿‘øï+wö›ù%¥>>½¿÷ïß_¶lÙáÇccc,X0K ¸w€¶ÆGåeí]µ¼ñ ¯bêâ3m¼…ØºÈØ½.U{üô/Å+!q_%¯ßR6fª ò)ÖCǸÃÂÒk[“.×Ïã ŠR·ìºc=JëåîMiº¦})^T‰—sdݦ“á³Fû=-èëÂægŸ:úÖrô4̺‘~dŒÖù÷Œb¿ŒPÇC ÿ܆krKŽÇJÂÅ[Žqʼn½ [SžZNèßbëv’—Í*:Ž|õäÖ¿òê±Q4QÍÚgø`kfGö Ízì RZÊÖ?ó¹˜ÍA70z†›6À'Y…ú϶Cª3ÃÄ[ðÂ2ÓgÛŽ‰®>r`õï\2CÍÔ^†ï¾/›ÉFCÇXmJÜM ˜9AR$¥Žs—[A ÏЃŒÌÌÌåË—cvEDDD|||ŒpGï‹Å€ñ‘Þ%C2|&}þm“ÅA7i2¨¥¨nÞ5Bz½)¼º÷Œ9 ±f¾cÌ|Û˜³ˆyñ--éCd=Ï1³<›N[¯gÕ‰0ÚÔ"êÏþ¦éLXùüFdíÈjÚqOfî-ö‘[A ¯ð1=’ï³1£‚D"%$$`æD’p àÁÀÀ|<ð,«ÐÏ>¥¥r¤_Cºîö`4}Ÿ7wî\ð}6 [ D¢h-$&“ n!øø|pFvvvRRÒ† °”£¢¢"""À÷Ù€ð```ˆ000X¸p!¸i¼½½A#>ïïÁàp8»wï^ºt)v¼`Á‚±cÇ‚ï³=ð```@Ó5FfffBBBJJJttôܹs'‹ èq€z˜S§N)òQ‡ÃY·nÝš5k˜LæüùóÁÆ€Þ ð```@3räHy?íÚµëÈ‘#©©©qqq“&Mš+´ 7Ããñ@#``@O’œœÜäÁÈÌÌLLLLJJ‹L&3++ 4 Ð)Ê;ë—×ý}˜œwfåoG¸1㇠0bÁUoî¥ìØ~•ñÓ¶aŒš{dáÒcþ÷µ=;É;¶hé‹Ñ+¾Ò½ö뇡ßÌfL…!¤ä|Ó)¹âúꄃJãLvQE‹.ÿ½ô„æ‹Æš’Åa"~ø:PXŸ¾åÇM‚©Ëf•æ” ,[>¥iË.Øÿã0lDÍ}¹ãçõü)‹'[4nå—§Mâ6¤ìêê_NêÄ-cI)½öϯ‡èqK¦XÔ]þcÑIíßÇØ2ÑòÛïB'ü2CÿÖÒ6)Ìм*;ÙòëkÚÔ1JùNÛ¼¬† ÊŒ‚5‹  å×Å×í¿ù>̘Tý$åB>OµÕâ5¦PšÖ¶Ø³]ÝÑò8ˆD'·±pT5S1ñÎvüðûZÝe_0d'@2 ûnüº–P[4Æ)``À'À®]»0+âáDZ±±3gÎlçûléo0€BöEÁ½GõÆcÍh¢†Q¡édD=/#*Üê)¾{æ)§–²kÉ·»ÄæŸóîÜË‘¦Ö$ñÔ×C—„E¡h³·*8¨Œtqªƒ¾œúäÇ¿Ù, Gmyæ:ûg Šå‘‘8±äî¹—ª~-”p0¤>ðËÕ!‘›àÊÅ×ê“­ÅóîÊCÝüï‹úX) š2“%•ʨc–—IÛ¼ ¨¶Ñj’Ý,UniùzR°˜6A¾Z·Ë®ž°äž¬b;:Ò¤ÛNäC’6"P…`\­¾¿iá¿‚± OdÉõ> ž&ÚñNÀ´~ƒŒköÜ/Œ0ÔCX``@o$33sùò凊ˆˆˆWüûlàÁ: ž®Ff–Ö!Gî7ỈÕK¾ýáAäÄ03U|Í›»Ç·í¼«ó㬪8ºº•]Ê·×#Ôe_½UÄWi]¶|ªá§ê`yü¸ÆÔùcm™0çͥݧ9ƒMÉØpUö³mx5œ–Æ Lw˜úEzÂÚ•/qßyó ZÌŽË-¬Zª9û;vâ±Óx;¥Š[›Û‹Ÿ¼dšµøbJ†ë8[RrçøuÃTstCáÆ“YGs¦Œ¼l*Éi¼Š­“êáK—_{†›Êï¿PÀW—ÝD°š¬bS¥CR­G*-]¿UÖØFt~é‹«û6Ÿ#úÇ;1[{9`†cÜrõcKüøêëŸÇ˜RZþŽò+Å/É]!„~?Ï‘.|*·%ºÒ*„®J¯Hz '113*H$RBBfN$‰él:ÀƒtœŠÇøÁ§ÿÜ÷x@œ=&hù}³Ö¯éG¶±çøÏñgç¯•ÌÆC´~‘‹7DŠý~ú«9N­ù§ì9wµgÃÁ“§7Œi¥Âˆ"ü,ÉÐñë¿Æ@šCý5´!Ù8x¨Úow|~ò×Ä·*y‡åiN‚U¼¾ùÓKrYÕmæn’hÍqj_¬òŸ‚œde×QV^Í”Ý,¿ü3Br¬â2í.ÓZß*ZS 2‹- Q?,៰ÆuË€Ïhú‘b9cõéÀz#5æÜòW˜È2t‹þÁ-º!`«ˆÍ†HÍ£½G9Cæº+ГܿÙ²e‡Ž‹‹›;wî,1ï™æØ±cAÄh8jñÂûÛ–ÿú*ö›ðÖsØ= ïõþß~¿Xk:øþÙ‰‰‰`û< óà˜Ž“qìm¥"E&¬w§wSM#~\ Ú€4Û¶m{ýúõÂ… ±ãE‹aÿ+~¼lÙ2.—O¡P?þꫯØlöªU«ªªª:{§¥¥µnݺ¢¢"űAmNNÎĉ;{¼gÏžgÏž3ÆÊÊJñãÐÐPGGÇ#GŽ>~ܸqüÅ'Å»+ð`ú,K‘``a@_b÷îÝ`ž€O`]ºÀ¡C‡0+"555..nÒ¤IílLñ‘»+ð`ú z0V¯^-=ý|Ò€y"``ú]÷` u¹Ï_׫˜šª“j3’½uÒ½/,(LÛuäyD”»^ñÔøyv/²9@ߣ ",¹±÷pÓØ0K:Ü;Rä_Úy,ßzô¼(½C©†2QQfÓðr‚}øfÉÌÌÄÆî{öìñðð|ŸÑ »+ÐL€¾„‚Œ9sætE´Ê“áVw%5´Fº<Ÿ€¨o-™;Ÿ¸‚r¾»ù-ß!`ž€¾@‡ÖRûúÖÅkéy5B"ËÐÁÓ†sùd¶iD”›Rñìú•"k¥º´S7J±€'“6ÒûGDy°%bªîíí“×½«âhšÖýÜ•pÿÝ™í'+œ¢F;H6 åçžÝ~¢ÜqÌhGvƒ”®zqåÊí§u©oçåë¬Gm#•/o_½ýì]"±ú{z9êÑD© *^ܺz7+·’Ád¶®Å/&¾An—: ³)¿q#«ŒQ4lù;ž¥]~ð¶JH` ðl§Ö°{ZûüÊÔ&ÌŒ\p1éX™C€ÑÛ´»ùLïqá–äJÙécZúí½Ë73Þ–q¦¨X»z9ˆ7jJ Ó1íÔÉ¿¸£E^æPNC›z¶®æ’§ÐªÇö\/ÃŽjîœ<ô|À˜QwÚkh¥÷m ‡³{÷î¥K—b‰-X°`ìØ±+Äôòî 4 /ñÁ<2E«PŽ gÉÒŽÃÉÎRãWλ«É'³ž#ƒm• Âê×w¯ÞÊ|[ÁEaŠª‰ÃÀýµ(hMzò®«ÒåQk9"’/Üä ÒVÊ ßR8ËKPžlo•QÌþ©½Ò’9Ò‘Øœ¸|Ѭ[Û•ó£í lEêåVpø¸‚š©}sïÊ-I™ ²²¡­‡·£ê¨å?`ž€¾@ûSÂHÕ£C{n¼c¦„(‰Fúœ7çöÔ@d\³ÎÀ)ÙŒŒBî½Ã6¡Áƒ!º\“[¡1l¬ vÈ{{zGÊqâèH•Ž S•S®9:t¼hû aÙí}väb&ec µÏŽíJzÅDM—‡Wp'õê-d «Ê›£»ÒîQ‘“$jOPrcßž¤¬ÀñÁFx†ÊÞp BF[úb)<=¼óì!AèØ¡ÑÎX6¥·ö˜<)3*&‹ù„º+ÐL€>Æð`´#Z rd8¿£(²'œÝ´Ô½¾”|æ­–ßÈi^J˜P­{~lçÅZÇÑ‘±Áâ)z^Þ¥=ÿî2剕G ]é\Ún²©låÕ$œñ˜lßÕIÙÞRb‹’Ì*x‘ϦIò Še'B«SHÎ+×?=²U¡úB‚Â"E5+T2æ¬DeT<8°owé° zí´üÇÌÐh¸&¨xW±µ78¢h[^vœ¬’ž½Á Á‘éD¨„/D;ŽÅ06d4ÄÂ3t5I÷sóª„fÔæÇ_–]„2ì4m’Ö€-‘jzóªbØé*5Z>–&éQÞÛ ‘ªèœ®Î&‹ãÀD ËH‹)I;%@Bž¤pHEú•WTÇц”3II¿!E~™üô5=ÇŽ7ʸwöÀé·e¬‰Ô-]}<´Z¦¦My‰Ûœa¯Þ¸Ù–•éQ¡Ì[#;X{¥mÙ\!|òܹ#‹~ý]•?vDÿyÓãX"ECü»+ÐL€>Ƈò`È­*ÐŒ"O8C|ѺU÷l½AÌþ¡ƒL„jéË"Þ;°åžt29Ù•nêÊíäÒpk)Hå(/)áÌÓyÙÞR;´™–k!ù ê²QPÎ+^_ i:~ñÝcG3ðæ^^¶ºl*Ә͡ŠþH€y"``úíO ˜ZLènn1Ç‘-ÓÜüÌ7<ˆ,sþJé„'â —ß©)(@Rï@U¿Í¯sVk5au^§¢Çjñ,UM4 K9ok¨Š§sE·N^.7ó÷34Q‡Òš¯C‚ò×ù<‚¦¡r'%Nε{õ&A¶ì¶ZËW^úüªÜ·eóCm½ÄAyoRþ=pŠ &·J­ƒºKµ¹ z—WÌAUÅ3[˜Îåµ ík§´ØÉ¹ë·NlNþþMæÄ‰gM ó÷¶8)ÜBt‘ªGŸtw…Àr:€¾Å‡ò`t(ZÛÊp9QäÊ1yÂ9 ŸèW¦ãèÈ캧)û“þ5ãk@!ªšjàÞ=cB­FÈ·ª¥3)x‘«SÚn */iQßyÙ>.ܬzD^"¡Z ÉyÅë«8üÂGYµL§Ñƒ¬ÅÅŠ=Ãl@Zgµy7所è ´?\ñF¡]¹p`ÓEDR1qö03 ½,j9.Æ1ÌœûežOIÚH1>ÖOS~rDíAa^içŽoyˆIR¦ž­›¾ôK3A!fޕ÷²ŠêÓÀ!d¼£ŽhHP|mOrºJpì0šyèõ¬©{¶Ô "ËÀÖ#8@ô>++lŠÖ‹[—÷%æUñE/ºÚøŒ›¤/ò¢kAѽ«yÊ®Ñ:²æîaº¥Üô‰êŒ·×Sv¿,Ä $~EÖÜ7ÊŨîÖž–©µW÷Vmî0*šqãbò–´:„ ¤kãÞßT)ó5‚(¬Ui Êê¯\½ríÒ©ki£â¿™æïájÛø >ïu_ê®XNз(**R$X»Ý^¾håË‘áíHc¹r –'œùµÍÙXŸlðêܾ“´|#ÍGLÖʾ{åÀ6Ñ7®aÜßÝ£?³uy"ír6ÈR»¢X ˜ò¶õ–íftXP#÷N[ë"Cv"xH!9¯x}‡¨7$Ü+õÜ‘-÷øYÅÌÙÇ3ûãtW ™ºV/J—£>Àƒø所è Íôqðóó»páB;„B!@?~üÕ«WAsu¹»._¾téîCúE)ðrÔGx0ÿAÀ<00} ™º•ŠŠ ›¼¼÷ᦂgU°f¤á`[¬¤þFS“ †%``ÀTAÖ\Ë=~šhŒœ¢$5G…ÖÞÌ=v²ùzý½Ü#G¸+í?þƒe¯ ¢­vX$Uôòù¹WÊÒïÖ•U£Œc+Yø+ë¶ÈÉÝöúrç’háþœ=û!H_#|ªEÐaÜæ"ÕgW¥_©Î}Í«ˆ”?Y¬ÝŸeíIg’BÔ?È=’ÌÅ[j‡…B¯N•eepë°d¢†=Û9€Á ò®”>¹#Î ‡gõcÚ‡°u˜ð°»öÍį{~4ýÒÉ7/^Ôqˆ¬¥fl<ÎP“Ò2̑ǎ¿}ñ²žÉ6ºÎ£l}}XšM–ÝÜž~=­ð]!_´¿6…ªm§ï9ÑÞÓž"=vâç½;·îÑ륕\f0ûùY Ÿ¦×åÔ+YMêÔää—xëÿŠ!¿<¼ñéã'µ\±XA¶¡SM´iÌ©»wp÷S‚Ý#‡ÞݾþUnÑiÍè‰Náç_H?sèuÖÓêZQkâ躪æC,ÆéÐ¥Zá¾=“qîÈë¬Ìšz!öðPu N°ó°£à:̢nj†.\X“™Võö·ºNÔEp4¢Š ½Ÿ7Û@×|‹;×òe5¬˜–£)øï)œ…Â’û™wk‹òâþS5)ºÎʶ(ýÉÛ‘“ö×^ü «¬7ÑÐË´Ïzu ˜*è à©"Y/È*:]Ç4ÅȽqrˆ÷¢èØö>D²™a¨+å(Zq#ÿø)®Tlœn¬I4Ÿ{wuîó¼ñT7X÷`ÇqÅÊ¥ üÔºòjo0JwÄ‚Dc uõ÷7柼Qœu† aˆ  ŸæŸfjEèZŽã<Î?z 8åV1¤Âò‹Ó ôÇ­®I]]”öGµåL}mø¿Ö]{¶3 ¶\¶¹Ò±˜±.bºŠ¨õ‘Ê‚cŸ]š)¶`¶* æn>þ¿mUÛhÂÆ‘qÚø«÷Εs¦@÷¿Â£ˆ Ü7á›?¯Ü_ÙÍûw°d¼Ž Þm?õûûjÙ|³ÓI¡¼ÌEÉÎó »¹G‡Šƒ¡œòÔoNï|jŠãi"ƒJ˜ñmò®ïGL]g=^2R*ÎÞ2þÊò}7,~ ¤áÏG QEÏiú¯Çk"y| ÄCË_¯‹¸œ%`m™hA€žŸ² _§¬Ø~Åø»ˆÙ#è8)9pú×5%¨’Þ˜u#&I‚!e篭þ|ÿ~œÚÈA>z8yYô(à ¾ù÷͵W(ÓW7h4¹ñ#åW Îþóúº¾zèÖ‘ײeµâBXž¦@ßC8 sKo¬¬[onƒÁ ȯ8¿>ïðIBc0œÎxãÈ‚²“ë*jIÀƒL|"À’)0"Õc<[¥i%à==Ž©+H-BÛ¶QîC0ÌöÐRöæì-a{)*WÀËØ‹)6H%T×ÃŽÐ4œiTÇieÿ+*¹[”î"Ö1’ߨl¯ *©1ÅŒ© ÕCëhõÆùq˜A3Õ… rE¹BT›ÿǺkOj&avú̺€Ô'¬wµVnÕ°´ÂvNkºã¯ž$bÖ¤µÕËY½ùŽÓ øêÇÒŸ—ßøõ±6ªîXà ¾µúˆÑ·¢¾¦Fˆ ÙÍÜpÓÍœ‚·ùz†8Á«ô˜u©_egØè4€)ʾ¿”D¥\)í\jz¬$èÆLJorDàÔÇýøòÇïóŸýóä­«!¹ùJÞê!:yÅWm`ápxÑïUON½sÐ5ÔV‚Åϊߺq~Ímþx=f]@jãvúº¨4µ9NÅoà·ÂšŸ'/|a¿Éœ““EO<¢;%î?ÕOkòlˆúby 㔽tÆx}q­ –­)šúz—„3^W5l‘ªäW„+äÔ!B‚HTS=èÎ;An–ÀN›øüB K€S}‰*ýˆPP^%w±”q-Çè0M{<ÛÕXŠÇ Ê*E!ÙêøV–L&°èPI­ ¬…šd| mÓ`wà(-'—%Ã$ý/vמìÌü‚’2ì‹¥B•?š),)…QÖd´¾ã]¶T\SXZ΃:60PÁÛ¤Ó+·–¡^ÓËÌÑžÅb“DÓ»œjŽäwIvE墱K•Ö2;"M_‚J;—ZP¶¢·ª A™A‡ò«Ë*«°!©Óù²ûѤ„YqçÇ×=ºëéæðË¥ÓÕ°–Žßl· o%bS›C%;Ãvì”YÊwE\s6Uv=Š››[· È>!éãõÆGÕsß\¯ÌÚ•s­¼±ä0AÛKÕÙ—®Dx_qÝ9!ÜJS4Ñ%á,È+?¿±«^fbCe2q$‘‚6ô0,¦ z¥f’=FáU!ÇÅãYJP~¥°² ¤õ RÍÿ`q U6”_*,/¢-¼ (‡_Q+ ¡ª –8éDwíIÍDÔÕPƒr +Ëò*QcŠÔmC>A ˜HÁµÔU ¼âʲ‚*Ô„ÒâŽ×ç”×`5UUx‰{÷ê_ظœføY²·¹Ô÷ üçeÇ¥»¢*‹ å–WT–ÕCÆÒp«Ÿ¿ëtj] <³VN—®¯ B´¥¤š2›ø¡ò…iýŒ‡.4Úü q2ÿw|ÃÉçí.úÓ„®£¡ åAjc“ƒÝÔ>­Ç)55ÕØØ È`*Ùpˆ†á©>û¼øÔŽÂã—)îßêQÞC\÷ æÖßLĬ œA¬§‰”u"àUœr ˜*èµ*É€B…xõïªÞVÒÍØ ÖFíâKW <‚dË Úó}u%ó±uúˆ'ÆaÑùüK‘O²ŽV~ûwyù±Üëd]÷þ ¯ÿ"Uµ·6—BÃ[ËV è®=Ù™ñV“§e/Û\¶?ö"´ÎÛÓX4ZAªŠNÏ=s: eEÿ0Wdl3ujβ-eû¦\¡lè¤ÙpÇ+.]_¹¬‚˜¿Ùëbãñû˜ºª2ô¦°®43[ÐÏF<,B¸Ù»Ó¶ìçÓˆØS\†@†8¢™M¸Ç³ÄëÅÛçÜWþÛÁD©á³_]¸SÝéÔºÐ&µ'Ïý£4k¼ªä{næ£õ¿aöÿÊV !ï›/RràÔ’5¥8s»/VÚ™°à&‹ŽÇµ EJÂAxC›éŸ¿ýíï’Ýã.p×zê×ð‰‹ ?gÿ—i7 `ÓïF~.úT£âããó!e•çÖ”–áÈ6“´l ñÍ·˜Šo1J|?q݃B˜@PfBoKÒ<1EbÜpßV\Û]É}ïrKÔàqbçOPÍÀ7``ÀTAO‚×U ýŽþìTYÆßÙwx¢7yY¦J–þê!±Ð‘mµŠ M¯ŠË€b£5ú{^Î¥²Ì=9µXPñ²$:#ÍJŽ&Õð%Ñß;.NCyè"6'§:ýJÁ±£¼zžH“д)z¾:ᎠXó¶“ݵg5^+vÄ꘺¬ä‡góHW2U^9‹w=8*°Çfâe)¯VbüC-Ð$‘‡í·Ï{WPž:î\!»–ãûka`0¦ ϤZ¦>;X[ŧ“ëª.ü]Á£; ­¬¹¶® Ó÷T¯>ýWÎOÏß›Dàpîþ_î«ïçL@ ËNnä8~«£KòŸü[lè£Ú(kkÓV—#ô<¬ðü×%§þåX|¡kA”U¢š’UÕ—Ö–‘Gˆ–DK«.o¬`Œ×·ã=NôùLUŒÖg•Ý}Fv®DëêŠO´‡‰ÔFŒâpt†Ót%ƒcoÎï$…ŽëxµL¡ž^W­;Y×N漨È*Fé VSf€æ]‰!þó‚ÖU7G/¯<½º ?DÇ×›LÄt™¬6÷Õª½øO9;J×ÑW{¿àôYüÀ¯4´Ð†2ÈŒ2Ø'2¡ºúb7ß‹îÁ€ñlg«`׌—+yƒÉµGÎ,ÛÆš´ÙÍZ­8—¶â4z··Ö±¿mÄ O 0#Ô?¸µü›² ]AHþ¦£+øåOÑàIýpÙŒ¢ðd¿ÆÏMÑšKÿN÷ï ;6ÿÅšcë[/ØdEË/­àiKT¤œ[ºŽµÁÓI*>zqå6挎œ„Cût‡ÌÿBŒÔ¥¯»•nå:Ú¯«‰"¼z!D!“Úô[œ’’ñP—9ƒöEÞ`2j†rÇ»pû‰ÿ¥èÍÞìhH®ÏÜþ´€CW°š2¨5‰Ÿ9¿u•‡á›£—î;±x=~èZ¿@kìÊjsÝKç–ogOÙ8 ­ææüÇX>?þ¤6”Af”[%锉•)g»÷^È¥‡<0Ý^ň‡TU¬jQ!öhâªVd0}3Ššµÿ ãþ’û^Zy^l!èqDr€¢çëB¼(<¶½^m¤ž·—Ypü$Á÷K5å²÷’óHYcF\Êe V͙եø½Á1åRwýÏ"á(/3Aƒå;NÝc¢üº¶ã#F¡7þn-Äœõá¶ÖÑ ½¹¾µÀÔ¬o)iÛG·¶âT[õgݺ‚¶S•žom];/+<$³2*ØñC^!¯¹š )‘áíÜ;^w§×KÀÀô$陵äÝ¿¯÷H4‰ jËö›ËT&¡5wªJ•Y5ËaÝÚ¾ìÜ Ö¯)ÖH¢ÎM!Yá^>äò í÷u˜J±DM¿˜—r†Q„#D«j!¨yº ­}RYÈEˆ'Þ>!> å×8vc4ƒ‡Wfì{wùQ£[eS[‹bX4mÓbáBE!¸U0Tønÿ»[BÕ¡?©Sqòj|&À -кg5ÕjLSQXŠ»ŸZMžBÕ”@¥9Ѭm•[nK ™9‘‰r'›ÐÚôÊ6Ë͵Œ’“ö('ÉŒ¸"âJ’2ZÓÅ{Ñ –-[6þün×LhÝ›uAÛ:¶ºšÓ¤ ŸG¨Õוªh)2ì`ö þ.ÿœN{ăµ~[OSQO¦Z™Ø1žßÉä{h´on´þVþ.S¾nÕ=Ñò7Û&\Ì ý=¾½ŽÍÀD’œ‚Úô³Õšýôiâ6ˆ1×<Ÿ«P5å20ˆ–m«üHººX×7÷°$É-$Ö’û‹U#=ÌXX ÷?¢ÝÅ—ë:d7¦,¬îê½x‚ƒƒ{d@F`‘ÄÒ¯,¶uGF7ŠINQ]Ö¹âGÅŒ /TZ¸¨ˆdSkÑ©6™JšYŠöu ªÈ<¯£½(:€Íb*C–r ånæ@eI&ª0М*´ÝEÈåŠñúô B,ŠÚFÀ²Ì‚¶­—/iÛª?kÅjgE'B]« üæjUÈvïÂwx0€|(Í„ÃéMlë“…é6,Õ‹å/•D³&å5O¢z£¨$ˆ 87¹Ú¾dB]ýó'ˆZ Y$7©D2TSZêjÁ¼Üê×e “úêî¤Ý¥ú¡¡‚GJ¯^>ËåóÅKÝC(+ÎË–¥™ZÎ¥ëÜq¹/NTòÝÈõ7 n0¼bô\ðïUÉ©ý%js4[lND¡:xâÎî-bU3ÑÁ +8¯N=#°ü­ñ0ÚbþZ/Ê@éâ»ck¸CDsW­¤7ZŸ_›y´ø%A90–NB:ŒÃ´~túùª¹ {}¸.£<«UR¨šò4é´úfÁõVUž©Ô]2^j ËhsÉ]+{’¥äb«\t&rÿRS»± 0SþmjH¹«÷¢3Ì™3çch&˜f0«íA%‡Ñj§? p·b#¥Þæéw B9ÿñ“ËOuƒ¬µwŸÝ«Qµulš6=WRÆÓ×%ðrŽg—ð¤:6R{#þâuçàù U Õ%^<–ÉÂp0Êår…˜rWrˆÖ:µ•9~ƒ«µ ÄÉÊ:°‹çmY—¶àjîpŸiIx„›õÇñm«Õ~þE[º1©.΃Y)[—¨LkfÀ–=~‘¼0“ì £ÙRT6˜|ˆ‘2åÐâ'ó¿Ô ·¨ Üúw©Oö®xN˜2ìso2r·C…E³ò¡Ÿ8ôüÍPG#RíÃÄg…\%…ª‰— ÙQ•¶àJ«*ãßÔJ‹ªY Éhs¼è®¥l}”îën˪»—pòaà ºeÀ±åߦ†”ñ]¼‚äääY³fõì€ )­<÷O9i°¦‹+•N‚IJx* Æá;÷f ü^r¾åB„ªßc6¡…gÖ#m…Q†€-U™,C`jµ”´-Íð¶êÛ²‚X혪7ÚªNí²'J^sÁ0¿¾;Àƒ àƒh&2uà#ÙRÅðûÑ8’axÏ#%¢}´lÜų&tšûw~&#৆À$CÕE¯9{ØâUÏèŽÐ0xPõÒ÷’Ó‡üÔ ž`&cðFc‘Èý"Äï èj6†d¢/£ŒÊ~úcüNð*TËÃÆí2ZÕ fÖ3XV­a˜ª£ä4SÉIvDY™†òðŸ^8¡õ×ïßðÆ ­£jÊ Ð\H†»Œ*k6µ’2+øÇæÙFXv›7ß5ºæH»Ve¥EÊ]½`õêÕÝîÁ ;{/;-»c+\>¢¡Ï¨òÛPQÇ.Â*fßßÛJÔ±•<.9Ûš2ô÷†Š›Î_=[|8!t…xÇÏÍã<%?2ÔüVF6tEïÀß½»ÝЀeCías‹ñ ¢ƒ?†5v%²ù·£~•Qz•á;Æ oìØjNÖÓ5Γ¶ªIyèŽqCeÕ&Sõ]¾ t‘Qxí©aLmè1N £Ž;ª¦œÍ³âLUÖnj%ÕÈ‘R’Gf›\Ñp×”œãܪ 2£´H¹«÷â0r¤Bëvuë€ §Ê ü©Yzàèdã‘ â[­QPS›å®é"v¬©²@ÒÁÞKÎ7§I•¡\°‡­Y¾áˆŸ[(®¼Z‰q¢,!†õNYV»­À¤¶´MÅFjeª?BÛ Ȩ]K.³‚rÔ±L]Ü¢¹Z&.ûÞutw€˜*|Ú|$Ð;è  K€ôÞ©é© k| Fg;¶F£SøÐô¨¿¾:,ð_œ*è`ÃO¢ í,†ë„‡¹õWÏËkŽg’ ¼Ôœ\ÉD^‹Ÿ,²–-ËÖG‰-yûMD åᮄæ·jQ¤èL^Úu>É€ å!Ž’eLzº=ߟO׃ÑÁµŸJÐúŠ{‰÷ÏŸÎÏ+B8’†³±ß,×~ò¾±nÊQ¿Fá¬;\å¶¹05…G¾¼˜šCq_9tð£ÓÍèS Ïx08O‹Ï_Ä»NVQ©«y|²âõk>AQ§Zˆ3VÊdÑÚ'¥7ÎÔ”sEßmk{k¸zñ¥§6Õ8AÏï¡6q:æ Á«EŸ …¨”~!ê6&Rº¤´âôÆ:cbA:·¶R€ê({E²Ø¤ìzñõÔz Ï´bj¼.+ô2ð·Ãw¢‚­¾’¯ÞxÖ´oó§þöŸÙe^zâºËþ¼¾Y>ß™wÿ¥¡ài8HÐVÙ¿*¿u¢ª¤Âá ZƒÔ]HD¿mõáÞ×#z¡£3ý™[yuÑñ«·«ªJŽŸûD:¼[3)ÛmÛ0_=q~t}É~ôokFsÇ+H:¶ê–±¯Z~Æ[Ne®ß4ïè,"¿æþßWž*¯GQœºNàž>–øâíÇWÝ6r>»)ìÿõZKVî‹ýK¦ç#¥õ·ˆüÞΜ-õ˜ì<ñÇ Ó ½¼‡ÏjË ƒIƒ'F²‰u¥©¿^9u‡GQaõ­ùr}¾ß¾`ge©ñü¥‹‹E"wû}÷YcßÖ??ùö9Ó¨Ÿ&Ô>ÞxíÈÉrF•T=¿ò r•5j’Qx"„e½äò©»|šËŸ-@冄›íggßyV‚PT•doSp²¶]?p°¨ëéÌwØ(ÈiÛ,p/–Ï}ƒ–Ÿy{©TuØL:™Wwy})q¬~øøÙ…Ôñk…¢ü`¨kBOÏ?£àä_\ßÏU”¥ÆMò–Õ†ø2·­<­1(ï×.Õ ¨¦)%üJ¼o1¦?hVóã(GP'lZ±£­ª"ñîœ=Õˆq„‹ j*Ã?c3ð2Ä8¾m‘DêOtµîiÙÍÓ5<,œ²³š›/µ{M²><,Ц Po£ä ‹fB¾9›¬:Q=ÿ¯‚'¦zvšPÉ™¢|+­aýZŠI†ÑAÛoHC¬3aci3_5Ñ™[eeÁC}g%ÇâœõFÁâáJå“Ljvº¹5•­Ô ü›Öî€q¢dqVj¾ž06|ºþÝí't/¨ðÜZÐwš,¼H—Ü\Õ¹eÅê¢y_‘U£Yèù[`.¿uH ÅÜ…púA]½‹Þ&"Õ`’§qcSà‰ýb´jÿʯ¡ïÅ®:µ¾Å’œœÇyÇÎ’ý¿4ëc$Ï›”í`»ê¶Õï…|Úß` õx‡B°v¯/Ø>*eWBĬø¼_¿yh¾ÝQGX|dQ~ÿå¡RÖ…øÆŠÆíD—¿‚†b¬¾‹õ¯æ¨©¨–Sýæˆûó­K çß3ÚãÊ àxe8ÏÄÈpÑ€B˜“üè^½NøO–vÊLr›þL‚58»oüãŃI×ïûúÀ?ž¾ê6ì×_ÙXV܇×~á·Z¶™ÿúp>~°¿šTÿÀSû0• “î~uä„mð‚ã*¢üë ¶>²}IøÐ¶­€oSøÝvÅóN_0lÉol‚hç‹ÛK¶É ¹Ç­iA¼žÅ´5KgWEîlEGж’œ{_:fü½¤<µy[#ý1ÜùtÛféÍôZY}ë&¾ÿ—tÑZedÚ x½ÒÇ•7·×¾æÖ!xU¦?›!3¦bBl©f›úööCf€3¡CÉ%,l-çeÊÃáÃÈü‡ùçnÓ¿Ó÷Iî½5ﯡïª ôÁæ’¹¤`ßÛËÏÄk¦ÉvÓµ-TEK;µUUh‡ÀÊÀËHÌ{c¢ãçGÁì™ÅêÚ¦H‰¡ÑTá£üç)þ³î{sâ fX$µ×4u @_ wOÀ¸&á,™âa( Š®;±«Lk$t+‡áG!t`¡ˆ,^FAÊQx@œ†‘2 ¡¢yFZ8µqsf¼žZèO$,¹V”š†÷š«¡ÞÒt!J¦OaÑl*In¶)dè6<žAEªÊT¿Á€ryeÕ0C¹qÂUjN-¯ºðwy= 's^ ­­{rC LoØÉ«}FûmŠý#4í‹ÓŽ6 ÛV_³÷ À>m„oÞ§›­Ì@Ÿ©7ŽlúGgzýåð!ߨÊìÏhsF±ûÇ}|Éõë…&ª$"Mû^àéTJƒ o8'âwÉ -+¾4ÿü–ï¦ ©±?‹ …ŠÇž–F·,Ã'@2¥#üùÞØ o]\“ÍôäŸûùƒœý힊æ¹]TÖÖ0(Vøä¶…—^Ó"¢ ]”ó(þ°Ìj*ÜÓa­ñq¢ëL9!:°jÛ,Z½ØÐè ¤^ÀÃãibéæäæ@êvÊn ž1¤°ìÄŸyœ¹º&¤® =Ž®ó*ûBˆû/‚6ôE¾’#çq.2å!Äk¹K‚| E4`é …+ÙB8­1†¢uʸu©+Kùâô¹Çd¨*´ævÁÙkDéFÖ´öÄ8RR/£H²”Ü›ÝvÀƒ @ß 7¿…pÂGÅgqjªªµj`8U4i¢îcûöt"Þy®‹ {\ÁÃb=Å¢XªŽ¤Ò¸™jÑí oŸ0šž*†ý ;òi-ÞÑFëê3—d½"˜à§’MÂTÔ±aG{««ÃTG-Ÿò‹K+Q:mÃd·}ç›Hq™gPpµäìõåUJÀ«X±ìçjÊrÀÊL¿oˆ·×¾IqÖ òl1]‡£“´ÙöóŒ™â=]ríjÅÍrJë°jìþ*nAJtž¬ê÷>fΜù©j&lÔL`î.N¹ó¤º¢žê0{ØØ¢þl>ßÏi܉µlן׳eöggqÊýôêòjÿχŸҹP?Å7ÿˆ~ÄÔÑ2ÃØwuÃ×ôq[Îîÿ¿½û€kânã~wÙö"SA†QŽnqkÝÖªU먭ÖÖ½wÕj­Z[ëÞƒ:¨³î-*"²7Ù÷&a…|]Øß÷}?öHîþ+—Üóä.ÿ»µ}ÁÝÇÉ´:Uà»»Eް|à Jò K™~lÊvZ`eêßA¬½»W ‚FMæʸ¶éÌüCññi*‚ɵkèÞò‹Àf6š´&`qöúó?´I•PebòCû°Z¬¤Ûzµ°]º–jü—ÂQs›Öûîä”0ÏB\£¥SýöçXs‚pôboVE² ®º=¼M~h›œ£þ(ቆ6hßT(«ì°|d¿þúë¸qãªt@Æ0Øq3Ÿ<2,ƒ¬[7ä~ÊQ&² $ð9ødL”…Ië¯5ßrÕ)§¥çÜ»A¸ô·q+ëÚi’Zú„꾟x~ƒüŠþôwrÒþ·¦Î´$ŸW³§CM½¢ Íò^4 9“sÿ’ܪ‹C 'Cö$åh ÛþԷk †uc+ëÆ#ýR3—syu¿,˜_¾áT—²S„7ßpƒ`rüÆå¯SÔ…¢iLH®«IÈ(“’ëêþ§ççŸ.ÿ*©OöÈDY÷oÿCõ‚ODÉý95úöe•ë‹_8U¡#|–a  €·<2Q”f‡4:`¸à}K.÷Ùw~C;ñ aÆÇÀÃ{²ßj«÷tƒÃD&>ÒᣤWÅ„ À;ûªÀZTïvø@ê•÷ä;?ƒÑ¼:Ñûö[„Ë$Yé]ÿçuªüžöžÎ`„×޽>ôw’0 øá«¨Bªîo0ÞÂçð „%H0à?oc¨B>¿ß`”ãóø Â$€¯ >]8ƒÿ)8ƒK à«€÷ g0à?g0a Á|Uð~á ü§à  ,$€¯ Þ¯ÈÈH™à¿cõêÕ“'OF@K Àûbmm#üwT$»ÀnH0  Á@‚H0>*L§€àAvH˜` @ H0ªV@¦Ê¼¹gǪQ¯Ž^²øaeê¥]»¯ ›÷oãÄ&äñ'·íOôîÒµŽ)ãcõ¡"í,ǧÐ@ H0½²¸cÛŽªšõnnÏþ`u²lÃúyåÐ*š¤HìRŸl € ªdYwï—Õ©ënÎÌ|tþÔõTÛ°Èpîß¿LèÞÅODiV‘¿<¶õ@š·.þbÕë³Û÷>`˜:û5nèeÁÌ|xêÏÓ/m[ôŒp`JÒRå*#©D"¥Ø¦2îèÖ2 ¡*ÙDEY•:r Î`tnÎ9½ë"+´W[w¾&M sìÛvZ^?²£7!z×þ»,FjÙqóâ®þû‰°A·6ÞÆ”"áìö¿sM¬ªø9™˜˜›r%üz*Û=4ÔÛšOg¿ºý÷ÙûÜàÈ6ê㣷.{ág›0 do…ãÞº•æSؼ^+fêÖÃÿÜHiXþ&\çÆ¡5-5›ˆ]|]cbŸÅe*-ØE —ËÑ<¥|Ç5\iÁ“¤q͈†={ê©C+‘ûèäÙ×zx«^>vWéÙ®{ckͦ&5Â:óò¶;~Ϲc ®&aX5Ѝk]pb Œ9DüÓ{÷*g‡êÁÝ<TPf!Bœöø´f$ï' £Ø|Ideä©ίÙ)¹Ï–[üÍ;ÅБ ÿ¦  U*ºDٌ⫉Þ_—YHåÛYn¥”Qˆà‡¿ž>ûܶ‘âÔ™ëОžêà_AjVV榧¥–.nÐ¥ƒË#ó›Æä0‹KcÛ6î=¤±fI%I}yïÌ d^í#ók4\|b 3 €÷q«·èöן{6>wñ÷q1ç©rSâîßxĬ޴s°Uñ§nîã“Çy ê¹›QÏxN97«eeöÌ”ˆ½s'Þ½¾=GãÌù%Á{SkHu¬N(Sž½L䙈LÅl±c… ©h;߈z5môð·“{ÿTæØ…÷tÓ^+Å´ ÷Œ;púœ 4ÈÃ’§Ì|q3úÜ#^Ãnmj¥òé‹;½´®àl¡8!—A(YÚ,Ü“2\|˜„ ÀÇÈXu:®Sü·³kÚ¡%VÐüB:¬èO¡_ë(¿üEÏC< åÛú·ìî_¸eÕ¸¯îª™–Á}†ç/ <;m¥)®ÌB*ÛNf9•êþÈ›z¶è©W:Ǯ𬄶Q5Bº×1Ü‚ãÞ¯øcã:íª6«ÌBà%ÌH0UMwïÞÕ{Ç+>ùâêêzôèQŒÕM˜` «Šú÷ï?f̽%IþBDD„zÙf@‚€€ *dôèÑ«W¯.}CÍÊÊêúõë/^Ä(!a$È ¢ÎŸ?oaa¡P(ô¯[·nXXXµjÕ0DH˜ 2¨(±X¼`Á½ ¥"""233LJñA H0Aåè](…‹£0 dðѽP G!a$ÈàÿRt¡.ŽB H0Á;0zôèM›6=zôÉ“' $Ì€Y ^÷ï>©y#ÄÊ•0hA-‚¨uðéLâ)£¢x,£'-*»"a$2ø4‘$ã$ÌH0Þ1d€„ 2$Ì€Ù'@òïË?÷H [óvƒù”áGÞmù¬#€„` @ H0}htÆ…„c‡óÁ±äš“²DIj&Ml¯¶µœ(R³ vþÕñ£%Apmù–– J*O~(ÉVoc.j2ÐÌŠ_±ªTÊ{âÎÝTC;qEBR•#OŠ•ÉÔÅÖ²jÑQÀÍ?] R<Ýs_E 7žX@çÅç%$2\É·)­¼öT¬¢Šu_v;~ÏN agâ®Èˆ]ÜXŒ,ÉÓ‹9™*‚WÛÊW‘üO,Û%€oÄP$]ψK&K“–CMDUä‹„` «Pv‘¼ïùñËJf ëNÝøì¢¸:/÷üš¤Ø¿¹=¬<̉¤½ÏO\SRÕ,Û÷òtboéý„¿¶gœZ¨hü¥•-·ùEŽœò4­çɶ«ÁáEÿ´âñÚç—n¼>ãèQ—Iªø/bîÓê&µÓm’BvsE\åK+¯9«ˆ®`÷ÉüÚ^æŠ&8ç¯"ò¬ŸytarÚ•×;:uíÄÈßÚ£¡èášçWÒ.ß7¯É¨û3² @‚€€¬d’û74gì¹lÝ`œÇo0Ö©0ŽÎ{p[³Ž}ŸW2`çTÙssŸIrÇ©l]ßücʈki©¸s<éÐï2‰JÿYE.M)“Æ>¡5MªW²IL¶KûöYåJ+¯ï«H*©\÷-…V‚âuHƒ¥ù/Û>ÿ\PAÓ)·bD H0 jd¤6¼U©Þ¼¦&.멊ԤR<ÞøüÒ ‚éjÑrš‘ ø‹{Uܦؿc‹Ë*£"šVV¾4m‚tî§W/d:p…a,-+XQe»OÎÈ*¾?#»$È*€Íu÷a<¿¬Œ;•“ëlTÊ% 3 Ád€„ 2$Ì€f@‚ï< S¦fß<˜+—©hšÁ4q7öo-¶ÐÜ@šÎø7Kêjl)xë¢åwWŽ qlêóæ;¾©’Ó¯Îõ™`ëÀ{—cõ¦bÿï>ª‹HË8²"Ûc¬]5á‡ÝhUâÑø³äÜ›í¸ïí€ú† 3 Áø¤½Ë€Lš{~u «‡C‡ÞÓ¡ªrå9JšV*o‹¿üXIñ3l[Ùø‘é1G³Ó¤šù‘l[Ö â°HB•’~dmnµVÂmiN†‚¶5 î*3U©’ΟÎSð˜ÆÕ"¥á˜5çVÊÅ’ê¤ tî½Ô˜#Ùé2‚$(“Úæ¡<.UFu,Bò$ퟙÉyÅ`Z7²¨]—Í24·“Í;ñ“wõѶ¡CZª(FJúáu¹ŽÄëtÍ¡¶î¦DÞô˜ƒ™É™4)ây´µ¨Y­ á¹7“Ž]ÈMÏRñÜMu‰X†ú˜j¸ êTA=hÎäÉØ c/cËØÔ×ÁŽMk1ÊëšRþp[üµÇJ—Á¤ ;µDã]é uíNÁ¬ÄûÒÌd•(ØÂ]™y÷ž,+6 ·iP—E•~]©gÛJ Ñû¸ç² @‚aˆìÑÚÞQ[_Æ‹~›^çÝ|‡¥JúkH§Ÿ7YüçìÚÜ”ƒÃ:Ì}ÒhÁ_ß×ã¿qÃrWVU¦¨²jÈzxr×®ƒgþ¹›¢¹Ç-[ìèU'¤mdd3ãª5c»î óñ~„*ã]d~£Iö)73b¶æ¾Ž•æªf5k61X®]ÍŸý”j5ÀÞÛ‚TJLCkšk¢KiÞß þup¬ã@’I*T”—yhRïÞ[wé– ˜|}ü?â++±ú^.½º$ÝP­$×U¿À€Â3 ’¯œà6åd¢9D¨^ï|~àw«ö]y Õ 1_ï;Æi:º`åW;žJ¶iÝŠSúŒ‰ÖÞ6Õé£äf|é¢Z‘”\IÕ¶ïØœÔ¶-~ÿ)n³/œ5½SÑR MÓÚûÜÑ4ÓÓ¼Y¶äUqÿÜ6õg”îcm¡.¨×”\uü2¿ùWV"Fþ}B47Ï3Øžâ®1Xn=­s–½ÊlëÐØ•R7¬ô µmZ¢ñtšºvš]Ë"´‘úÃ/íÐê4é8Û°B™zhSÊëZÖ6¯K!ª 3Àg’`¨ÒOO¶5µÁ×3xKf›à³kekÆÿ_,eÑn}t»‚*>™¾¦žÕgêÉLë–3ÍýùkNáᆖÆ™;²õœën«¶Œòæ}*ÍUª(UÁA¨:Þa@¦Ê’¼|FXÔ2 ô3)xäuê¥ñ’qv.…ŸÐÒ; ûþ"ë µt6!Õ‘´ŠÖ¹½4I²ò¿T'5÷í.uGjºè6Þ´\)•h6$ÕoÊØ×ûË*0pcj’,«:Ív$“¢ V l"Ë{G—ÛZÒPQtš„ (—,^IU´­ÈQlŠ­-™]T2¥i˜zÐ ÷Ñ`hퟥ 2]+cÐtŸ_;³`A½BþrÑð–÷BW•„à³H0äO7˜~ßfùÌ–¾Tµ»7/¾Ìí×±5¹ê£Pâ¾]æß÷ÿæ÷EÍL Â\éÝÅ‘C~§;­Þ1®&W•rrj¯+½» ïZÏ^({yþ׿ßf†Ìùuvˆ ¡{£DȤšYú¥5/n1­˜:¹y%hãiàp$×Ï&,óõÙ¹Oå\†ÈÝØB@äG©$‹Á-\Ÿv¹š%êÈk_ðÕ×Ǧ ;-fųT©:öeXY·n¨ù¡`—ä¨Wæ¥Ç¬|–’«^ƒù˜6 +~laôñU¸mxcEéýî@ݶÖìÔ‹ËbS²iRÈõhoéma8Þgê#¿“áS¥<ë´×§æfЦ¸¦±˜_8îšÁAc¥Ë*µ3l³°¿…αßÇYjœÁ$%ôŒs3‡n|á4è—ñ¾šC£çˆec®w_2jJÍÝ Ôá±eëy³Ïvž>gƱ€%ÍÍ(ÍÙõÅ_ýžì4ä—‘š„ ÌÂæÓ)¯^]»¤öÎl9“Ô¨ƒE™ñ@y[Y~øÓÂVK7v·ÓžJ jÚ°Ú€ÈeóæžkøSâ$ éÀ¸¿¾ª7ç¹A—uÕ hæ3¢çÒ/æ×Ü3Í«×ÛÜÇ—â¹±¯É1ê’¿TGê~3÷. ç7æ[/$Äm@•ãg×Ù;¯†æ1¥I·¥ËZši‹²èÁ?ûeää³yñl}ï°õºÏ\ž=|ƒË/ƒ«³Ä¡3çGtûý7G–µä_ûqòþÌZS6örÒ~§ˆÿsBŸWÞ‡õhìa-æ³)Éë%QþIé nŲr_¨ÅÙˆHB™‘š§sµ•2+!S}hQ%?¹_çkuÏñ+WR¦˜À½q#öȹ„n‘öå½vŠô¸t‚ژ랙gÛÄÓ”¤‚6P§8QÑ^ 9#OPå Z…ÚL™9ˆ ûÎóûzôתœ¸›1Ç6x!æQ:Áòê¿lÑ€šò]µ¹2 ƒRŸ®‚Æ“ N–p\ÌÚNG ðŸL0èì˜ï†®5ë¸jÇxï’_õˬì9pËðY5vÛÐXPû«]¯ ™7{/)ZsT2^Ë‚«‹äÏüzUfÜbù¢±¾Úè¼{¦]‘„J¡*3ǨèVò˜­'êµËÿ5ˆ*)ú·4áÖ²®™Î¹–S뮞›_9ütB»®ö×.HŸü±ô·$ßžî5 ¼\=Vüô¼ï—+z´ùgÄÂYÝk/É{ºÞ¸ù'Sªظ&ÊS­mg×í+Žo<5xQQwŸíÛô/ÁªÓ=Øì§ØË´7µY¢÷*åÞÛ½bûÓšCǵò ëªþÿPíW݇ü<ÿ@‹ÝìtöÿÕæ7UÄÀ› a$åPÄíýå‰ϱ›ÆèešPÕ}ت)wºÌJÃí»oŒî^æÓ”E«ågZ'Ný¶E÷3°š‘wäìÍ‘%lóÝžÂÌbht—‚%³Vk£[Up+‚è¼)º³v!`y³±úuê¥-Í«í¸…mÇU¦÷”À%,jzXÔÖûv›²¼ÛѸ(lEtXÉÇŒB—GG—ȤÊ´rÛl dJèÖzô­G—ñB•œEêÿisyñf‰ž‰7µ2MÜÝο•s-áÈ1FÃ1–ÖtqÉ…m°1½ðª°å‘AÈŸ$îÿl޽V¿ÒÚ¤Îg¤¸ùtíTªì4¥‚Å KEè%p4 ,tÜ÷üÄ6v»(aÑ¥•ì¦Ê8¼,• ·oÚX=’++^¥…:„×fÒê\¢ÔãMœJ¤,«t­”*òàé‚÷@áÃú¯]°ƒH3ðêÒ‰íg…Œ03çÐyR¯Üç´òßÿäãÈ. ÀGöa2:çNfЉ¨~uÍÝH‘ †oêñ‹yõG8Û5€Ã*ç rÇÕÍT¯Àa™ÑÏ2iÚN§Ø[¯¥*Ö¸?hÿVÐiç%>%Š%y\F¼Û§â IZ%QÒ™9t΋Œd±(ЙA’„0À¦s€¶¼<_ êZÕ¹÷÷?üù?»¥.}íøâKWZ«;ÏàI[¦1[ÄÌNx¡t7cê%­’Ó$“Ô=E`¨ÁÁS—Å­Q‡­9æq9Î^Ôã¥òÚLÍŸ¥w*5þ· õWUFEyí¼,C¯ÓߪEëŒ;;㢟ÈTæÏ–bÞ¹µÎ` €ìÃd¤ ¦ÈìTÚÇBÍ·àiÙ·þ¥í;«#ò,í#*_AˤÚb½EVgÒŒ:ÛÕvcRé£ò@“é›{5áì^Ó‘–¦ UÊù×ÑǤr9¡mOê­ºTÞÍÄ£‡ˆú£­lŠKÖA1«u·x¾òõÅ;Ê솶AÖÉ7P©nv!š´«´zïj ®1ƒEÑYY4­×QšÎ{•s÷¯¤ÇL“ˆ~Ý9½ 5˜ÖÄý É©M(‡™›÷ð–ÊD@¦3*)2 ŸjT°lbÔxrþ²Þü­…!ý¦…„M/˜.‰46j2¥ X‚ÃqëdYºX~»nu Š0 ¶éœ¿\ÜA-«Žµ ‹JÖƒ•B&êÜÍÂp¥ÅXÕ,:~Sø‡‰ pBµÂ•y §8Æí$ÏV0LPªû¬JV—Ë­Y_{ZFÀ¯ÿUA™š(ßÀãEX´`¨¿†GÆÀ 8xíÊšó×&¢°#lóv“>Ë„`|ÂäOÖõrsÔŸKƒ…š¯¼6öòïÈ?8þ5ôRxkåï”ýÖ/ïb+»¿sÎŒMWr,ê6­&§ Å‹=¦/¿”¬˜Ù0Èÿ;pW¦\Øðý’?o$I–u"'Ní Hþ{í÷Ë>ÊcP„гݘÉQõL œã–¿:¹â»•‡fÓ*†E`ßiSºyjæR¥sõ\ÎÊð‘ $ÌŸa‚aÉâ2¤©Œv›ödi~bwxüð?ê¬ß÷½ +ÿvÔ› ¦C§yó_÷õìËm? *P${{Ü#Î#¾·çèõtÚ±1Ý7ø®ÝzPS¾J’‘¥L9:¦Ç:ïÕÛö»iÎÙç^™Ñ¥×ì9{f”h†i½ BÇjnêûÏ×&¯®¹c‚7;õH©—¹2&C@@RâŒJG ðŸM0(Rsë í¢J–#+œñ”!0ÌêHë^¸K+JºòµÐ’ Víˆú¶C§ Hu©òÂR¹ii%¡{m­º”ÓtÆ™IÝæ³'¬›ÑÌ–Mª” šV•Ù`ÍÊÝ ­ U% kë7áù?‹’£]0tð¾ÙÚ[!a$o‰åÜ嫮׿ôîþ³•™eÍÆÕ*ý»ãQfÍ,IœñU˰lEµí|M˜´²²Á9eÚ _gÃO‘&Mïà®Ó«ù­9eæ9izTË%;Œ×ÏíÛæ~.E’&~Ý~ØÞ£ÐûÍ iä۵÷?ŠÜhn[»ÇfAÔw'جXÜÛ@ƒi£Úe¬ì ðQLšT¹«ãkô°¯0nðy$ÌŸm‚AP¢€¡Ë÷ -ú;ÿÆ]>ÖUg¡O¿»‹oæÐKû¯Éˆ]‡ßÕZX'8ƒH0 ¼ÆB—ƒ»¯f\¾°o !EÈŸmu¨áòõƒkpÒ.nÝ+±Ön«¢\³b¾*7!AiakÄ0ð\ÎÅÉ]Øý¸y¤7_•|~ÕÂs^#;ÇOd ÆJV Ÿ4œÁ€Ï ² @‚Q.’$8®Ûz 5“Ã*^Ÿ?ö©S[¾:¬7 ìÙÑéÄ…7æéWwl=óZQü{æÄë3V|ÙØL/ËÎÞ8~×–o¢¦\z,wé1º»"fsek€*gìØ± kÖ¬±´´>|xþ²±±ñ¸qãÒÓÓ—,YRñe‰DòÃ?p8uÆRÙeBûÝsQ€XñåI“&q¹ÜyóæI¥ÒÊ.3F,/Z´(33³âË«V­JLL:t¨µµuÅ—CCCCBBvìØqÿþýnݺyyyU|¹]»vþþþ{÷î½~ýze—#""‚‚‚>Sñå3gΜ>}:¿Í•]¾páÂÑ£G[´hQñe??¿öíÛ_»ví¯¿þªì²‡‡GddäÝ»wwîܙ߼¯ Á0²ÓÇï$È‚]™Ùwö})³*Ê1 N0­C¬×îùënË!Þìij›v?“Ú½©XJÐsT€Þƒã¿6¸®üùî)ß>l=gîÏ“XªÌË úÏXæ>¯Ò5@•£Ž¶ÕApÑ÷¾ºËê`ºRËê¢Þz™(ùÝse—uOÂTvYUjY†½õ²:~ëåöZo·ÜB«âË!Zo·¤õvËþZo·¬ÎÇpú`èdmÖœh“¿,ôµ#z”v±Ä4µ,—ÛO Ì_¶ Ÿ¹7|¦vQôަ©e9v]°®°9Æu&îÙ¯ýÜ7P#A°ÝÞÝܸH0  @‚H0`ÀG3åæ¼¤XŒÃÇebã;'…ưTl±tð€¡æFNH0uvaÓ÷âø˜Ä<âî®Yº¨³ óFO02UEr´KRö3$ðyB‚H0  Á@‚H0JS¾Ú5¨û²3.¥R‘ÆÕu:¸µ‡ú?‹U¥_ÿméÊ=W^Ë ¥Š_=|À„¡M¹¤þjyWgöÚÐ`Ãòòýt/óôØáW‡l_ƒ[ð€üɺ¨ÉY_o)|$ïÚì^˽V¬íjÃ(£mƒÖ/knª?(ŠÄ‹'_y4õ5)o´ o®Œß=¤ûÉÀ­?÷wfU¾[ò¤ gÌüUþÅ®5í,ÔåJŸ\4w˵tZ!çzu2¥»§ Ô€ªRÿY?gñágRZ%ôë?kR{gvöííßýxè…’$ÄÃfŒ6g¼UÉð¹’^9;ãk:ê¾öP’“ugÃÉ',Gîrá„$õè¨ÃÇ ·®ãkÖrçQ™éw÷\Þ±%'`aËε9ªØ›?|ì>»i›B6¡Ì¸vkÃÄ»¢™4*ŽJ”O+Ó¯ÞÚøÕ]á´ƒ›p+|´Q%nÝÿSŒïÌåNüª6¼’œ“ó“¢ë:öV!»±üeBcÇfŒJnåÒk«’X=ì¼- 7¢Õÿ#È÷vĦ³²ÿ^.êmW˦dJùÝUq/C›ú«TÉé‡WçúL°uàé=AKsi–€¢Þ]ƒË¬«Œ¼±&!³‰}ÚŒO<Ê©Jg0(ó¦ßoûÆ?ÿÜ]Ú·ûþ['¸&ü9wÎî§4[•CyõŸ=ÎëÄð/_MØú•—P½ÞûÅð˽µ¹½bý¥,§²o;qR'7^Á‹"¹ùCÏï„s7¯íÁ)x•s“RUê=]•½böÚK9\–’pj7é«NvE±ï†yëtв¿7§÷R£0Ï´çOéÔÕöÑ¥Gϼ²´à릢%6±…É­oû,‡»%>Oz›í=vþè@qå¤ÜËÓÛï5®žž˜žôR0zΰz¼g¿Ïš¾#ÎÈÎÎÙ!S©ýŒ-QïxßksFþpVáq¾ß´É¡¯·”h¿«¿y‰Ïë{+ÇÿQwÍzÎ܉‹ü·|åË˽4µç–ðÍKÃDdîåi½~nòó²àÔ?¾¾=–giãîMþs»Éêe-Í z¥’Jû =¾²°@ŽS«É«[©ŸÉº½yìÌßïµZ[ ÿNS0\ºÎÝ6„Cª»;£×Ü£u¿Î™þ}ÚÄÛ<9„*áaÃm讨|ÉðŸA«dyJ‚ËakÂGùÝ™GNX…Ξc[ð-ž‰I­Í¼^þnøIû-Eb[~Öåí·D9Nž~6¾ãOø–W8É×öjQïÎ/Ѳ&ùé“ßþÄêµ¥Q-±üÑ’}«nÖ˜²ÎËœA§í?þÃVñ€µuÜøÙ1“ì5RMÛ4EÎÕ9‡÷*üÇÌp1eÑÙ6÷P¨S‘c£Öù;Rç¦ÙcÜw_‹~èøÜUÜîkØIZ¸ÙxȶzÕ¸w¬5!ò²T*ܾic6S"¹²âUZ¨Ccãä}ûY!#ÌÌ9tÞƒÔ+÷9­…|…"5ƒ¶RAZƑũŒ0ÛÐÆIЙY§—§rÚÚÕ÷aÒ)™ÑkÓz;˜æž]œÌêdäÅÇ&Þ"ñiçaJæoËncZ—¥xôzßÖ<óŽöý˜²» û2CG››±tò™uÉdÇüìBÝÎ#«²ì¢ìjÙ“’Gé’hu `°jM¨)—Ü8“gÁcçä\\•˜ÛÌ!ÌŸI§fœÐ&öªœÒms'3,Na4³oÒP=¹–&*;;»RåT“ü{WÐtîͤãGéZ-Ť*)íðêl{uSíÈŒK¯OÈ5êâ¤É…XœZ-¢—¼¼nâàoûI§Uö)®½¿]Îö¸\UuJ`n!NÌb°¹É'—®mñûô¹‘_Œ_qkÓX³3~uþzÚíI£ö2]l¸4ÁT=Ü>g•ûšñ>Ú÷¢*+ö‘Ìa€§8…á[˜«÷©GkÇ­d|³y«;[½31`¶Ã¦®šýôñ†“Jµ¸)“âºv›ØÆBv{Aÿ%²¡«fÛ(ï/ðÓ©„Ðöz ™Ìd’L‡N“FYQ’óú¬8Ó³n{ËJeIQ<¯¾ß´³ Ô 5÷Üœj«wÙ|óË÷"÷Ÿ)çiöQý™: Åo/_Om«ØÔ§dû¿ä/Ôß¼øÃ9óÜì‰1-–mªáL~ßqàðg~ù¡®~‹d6MûÝvæö9nl"'fÊß7u“zŠ#äÃü›§LŠÏRÖè}u@±EælUÖ­­ß|{Ñ{ê–UµØ÷åðEÚ=•Z %g2oU2ü7’‹´ç›û\PŒk÷Ó$^þQ–¤ZIëß™š¦iR}\%H‡¾ûú<&—¼:wwÿÜë¯[µž<ÂT÷Ü=û|Uó­ùå±-Ìú7ÿ¦­©:„`ùx5­{óÐè}H’È‘(•Ùrœξ¾+ɬk«Hý¨Qý‘õ5g0Ù¿ç¾ Sòš†Nší`¤iÉ/½y^Γ“ÙÖ]ÝøIˆ‚Fz½öRS­2ûúŽi&k÷ÀÝ»óS•Ü´Ó7ü«Õc½÷1%5'h½ÑÓŒka8É­Q‡­9Rs9Î^Ôã¥D”U‹ÖwvÆE?‘©Ìž-Å<½ˆ‡Év Ðdê¢rne¼–ªXâþ<ß/:í¼¤VW®G#ÞíSñ‡N$­’(éÌ‚0ÕnËâT¯ÁR—Çsx,¥«'S] ˔͑Édªâ”)9/%ÜÚŽTÁëw?;Ëܸº­æO®«ØÍ<;ž Ví®é‘OcG½®ßÇqüºTîÏ, šIž¡¶ 5 sõckZÃa™ÑÏ25;]‰< Ô@É4ÉÌÅŸž*¹ÂàVöBmSääXˆ\ÕMUïµÍ÷Dfl¢Q +"óZJ~S ÷8UN6ÍQ¸DêÝ`Øtݰ§ð=εŸ¼#\»l5ø—ßò­Þcù±ù‹­omU¸eÝoþü5‰ïÙmŒg‰(Þ1rõ¡ÈÂR¼"îÍÿkæžzùš„~·'4ÿ‘õ¿¥Šš²3ÿ*nñ;Öh—Øî_ü²^³PºaSv­.x§úLÚ¹¦ü³\lù«°iƵmܧùÄnõ&¾buFk4sOæ¹……i×Lüóa¸Þ›·–1ž¥7/ïköw(~“šE,Þ¡YÚ½1Çqºó„f?O2†Á`«×0®îcgùÈš¯—Oskõš²hµl_Áëb>w¯öÌK<°ãYÿ‰AFEi_ÄÜíz#ñó¶üE—>ëwV¸døÏàÔn<ïˆÎßl“–¿ôjYü´8|uÏâcƒXì3 ©Ï€‚¿,"[ýY|ÀºUïõ{õ7”_¼º Áú^ ò—ÌÃv /JsÚFÌo›¿,¬ý]·Úš‡ùùßÕ«?£ ´26Ññ§a´ö¨Þ ê'®¦h¯õ"Å-›Í+ì×Ý£÷Ì—´…;t+ìÔçÙÓ©d@Å­Y_{:BÀ¯ÿ•öJ0¦èXÎv1o7© »aÓó/`µ˜&*.ÝØ¨É”Â8€Ãqëd©Y°³ëV§0 ¶é\Ô”âm)sq«iâ‚e+Ó6SJ6ZdT70ýÌ¡\‡î|IP–&­¿1)ƒ|,;øX滪 q«YŪ{TÐ#‚,ª®ŽÁ¶étŠbyŒ¨æa º+=PE]àÕï\°šiÛ馴6‡0ö3­ö·$]PHï'ß’‰Bý˜H0 ŒCo }ãZ¼€ü<çB‰½Ãó?q(û®kwV¾žß¨‰xýtȳ®,þ{ïÑt©:‘pvn³¡‰·ƒòy‘i„cË»IÇ×H£LÍ9U¨åtö” G³ÒeÉf;5³käA´*ùx|L¶IËQ.õ©w  %²¸£+æÿr9• Ty¹ÌêíÆOéã'ú˜\¡©¥*4ƒSå«54[Tq{r/;âHëUSøoØä½+§û…Oñnδ5pùaâ &ã9z½«ÀX…eïþrô/_-œ\æ¬ü£õš!•jÏ{Ý¿>Ê«˨ÎÄ–uªÆpº§>A\/‹Ö^Un H¡¯y3_ó’QæÍì[—•‘Ðô'5ìUhšÚý³–>m·öç¶¶:W*õ§{²½5Moš£ù¦Kû.ðoe†Íþ¶ÿÊšÙ«.¤)e„C»ÉÓº[Ý.9+”›òÜè.[[n_Õ²0¨Ë»ömŸ¢ÍÛs.êT7:œVeý»iÊ·âÓ…¡“ç}QÏ(¥D{ÆÝÿaTÁ NS;9•¼LR]r™3P™¥êõ˵ôtOšé\KNiUøµÇ“«“»Ïóc<ýýë’›”.WNÚEÝéáE^žZzû”ÕNó Ý6ŒŒ¸3{½Î4YßwM^<º û_\ûÉðÜVZHsó´¡æÙÝ›SjÞ-e~ïÜoOíPÖ Ý0Êïæšß‹:.ßÿݼÕWsm¸®X”>ÕXZ©m4öÏy%&³U=ÝSr¾¬ùÖ+ûí­JMVæëkÉ(kÖ¡¥±Lý«ÁIº>IUè7Öíï¤Ì~ñïéË—c¢àøÅ²‰Óõ¦{ÚØ©TÈ`¤}ÿ%ãmòGk¢–(§oÞâÁÖâ×êͪä¾f|ðÒÃÁen¾6J·º³ŸQÎÃz?Ñ’R%í5÷üwÕW—hÏ÷[çÏट]ä—\Æ T/2¦•ì—Õ·N«JN÷$¼~Œ^ã…jSØ”ËÎÕµÆøñ†1ú›l˜ WìçÕ:¢‘KT¢Ž“K´!–#ew+ž&ë\Ï%XurT>`xn«NÖ7oäçE6èOÞõsýy·j_ÕöΜº^Ö =2g]ÔtÝŽ³lÛŒíwôFtÔÜqµõOzÈnšfp-šÐ›Œ+¨×?úóeéì-y^zÒ°²fkÒÝŽa¸Ëz/ô©Ã›¦¦6[jx’.$ÿUú™©}×9ÌZ1Ì?ÔÁ7¤eˆý¨ ÑO„]]¥ëJL÷ÄåèMs¤ =Y\í¢W!´tÖ}ÄÈœ‘í‚‘©*¸& “ÿI5 |4_ï‡AøÔŒÿb` @‚€` @‚€` $€` $€` Á$€` Á$PÅý@‡ñ$Ä6oIEND®B`‚ros-robot-model-1.11.8/robot_model/package.xml000066400000000000000000000022061257532150500212550ustar00rootroot00000000000000 robot_model 1.11.8 robot_model contains packages for modeling various aspects of robot information, specified in the Xml Robot Description Format (URDF). The core package of this stack is urdf, which parses URDF files, and constructs an object model (C++) of the robot. Ioan Sucan Ioan Sucan BSD http://ros.org/wiki/robot_model https://github.com/ros/robot_model https://github.com/ros/robot_model/issues catkin collada_parser collada_urdf kdl_parser resource_retriever urdf urdf_parser_plugin joint_state_publisher ros-robot-model-1.11.8/urdf/000077500000000000000000000000001257532150500155735ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf/CHANGELOG.rst000066400000000000000000000027561257532150500176260ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package urdf ^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.11.8 (2015-09-11) ------------------- * Removed pcre hack for newer released collada-dom. * Fixed link order of libpcrecpp. * Contributors: Kei Okada 1.11.7 (2015-04-22) ------------------- * Removed the exporting of Boost and pcre as they are not used in the headers, and added TinyXML because it is. * Fixed a bug with pcrecpp on Ubuntu > 13.04. * Contributors: Kei Okada, William Woodall 1.11.6 (2014-11-30) ------------------- * Add install for static libs needed for Android cross-compilation * Contributors: Gary Servin 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 * Contributors: Tully Foote 1.11.3 (2014-06-24) ------------------- * fix urdfdom_headers find_package re `ros/rosdistro#4633 `_ * Contributors: Tully Foote 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- * fix urdf files for test * fix test at urdf * Contributors: YoheiKakiuchi 1.10.18 (2013-12-04) -------------------- * add DEPENDS for kdl_parser * Contributors: Ioan Sucan 1.10.16 (2013-11-18) -------------------- * check for CATKIN_ENABLE_TESTING * fix for using collada_parser_plugin 1.10.15 (2013-08-17) -------------------- * fix `#30 `_ ros-robot-model-1.11.8/urdf/CMakeLists.txt000066400000000000000000000033671257532150500203440ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(urdf) find_package(Boost REQUIRED thread) find_package(urdfdom REQUIRED) find_package(urdfdom_headers REQUIRED) find_package(catkin REQUIRED COMPONENTS urdf_parser_plugin pluginlib rosconsole_bridge roscpp cmake_modules) find_package(TinyXML REQUIRED) find_package(PkgConfig) pkg_check_modules(libpcrecpp libpcrecpp) catkin_package( LIBRARIES ${PROJECT_NAME} INCLUDE_DIRS include ${TinyXML_INLCLUDE_DIRS} CATKIN_DEPENDS rosconsole_bridge roscpp DEPENDS urdfdom_headers urdfdom Boost pcrecpp ) include_directories(SYSTEM ${Boost_INCLUDE_DIR}) link_directories(${Boost_LIBRARY_DIRS}) include_directories( include ${catkin_INCLUDE_DIRS} ${urdfdom_INCLUDE_DIRS} ${urdfdom_headers_INCLUDE_DIRS} ${TinyXML_INCLUDE_DIRS} ) link_directories(${catkin_LIBRARY_DIRS}) add_library(${PROJECT_NAME} src/model.cpp src/rosconsole_bridge.cpp) target_link_libraries(${PROJECT_NAME} ${TinyXML_LIBRARIES} ${catkin_LIBRARIES} ${urdfdom_LIBRARIES}) if(APPLE) set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "-undefined dynamic_lookup") endif(APPLE) if(CATKIN_ENABLE_TESTING) find_package(catkin REQUIRED COMPONENTS rostest) add_rostest_gtest(test_urdf_parser test/test_robot_model_parser.launch test/test_robot_model_parser.cpp) target_link_libraries(test_urdf_parser ${PROJECT_NAME}) endif() # no idea how CATKIN does this # rosbuild_add_rostest(${PROJECT_SOURCE_DIR}/test/test_robot_model_parser.launch) install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) ros-robot-model-1.11.8/urdf/include/000077500000000000000000000000001257532150500172165ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf/include/urdf/000077500000000000000000000000001257532150500201565ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf/include/urdf/model.h000066400000000000000000000046371257532150500214410ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #ifndef URDF_MODEL_H #define URDF_MODEL_H #include #include #include #include namespace urdf{ class Model: public ModelInterface { public: /// \brief Load Model from TiXMLElement bool initXml(TiXmlElement *xml); /// \brief Load Model from TiXMLDocument bool initXml(TiXmlDocument *xml); /// \brief Load Model given a filename bool initFile(const std::string& filename); /// \brief Load Model given the name of a parameter on the parameter server bool initParam(const std::string& param); /// \brief Load Model from a XML-string bool initString(const std::string& xmlstring); }; } #endif ros-robot-model-1.11.8/urdf/mainpage.dox000066400000000000000000000077741257532150500201070ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html urdf::Model is a class containing robot model data structure. Every Robot Description File (URDF) can be described as a list of Links (urdf::Model::links_) and Joints (urdf::Model::joints_). The connection between links(nodes) and joints(edges) should define a tree (i.e. 1 parent link, 0+ children links). \li Here is an example Robot Description Describing a Parent Link 'P', a Child Link 'C', and a Joint 'J' @verbatim @endverbatim \section codeapi Code API The URDF parser API contains the following methods: \li Parse and build tree from XML: urdf::Model::initXml \li Parse and build tree from File: urdf::Model::initFile \li Parse and build tree from String: urdf::Model::initString \li Get Root Link: urdf::Model::getRoot \li Get Link by name urdf::Model::getLink \li Get all Link's urdf::Model::getLinks \li Get Joint by name urdf::Model::getJoint */ ros-robot-model-1.11.8/urdf/package.xml000066400000000000000000000025421257532150500177130ustar00rootroot00000000000000 urdf 1.11.8 This package contains a C++ parser for the Unified Robot Description Format (URDF), which is an XML format for representing a robot model. The code API of the parser has been through our review process and will remain backwards compatible in future releases. Ioan Sucan Ioan Sucan BSD http://ros.org/wiki/urdf https://github.com/ros/robot_model https://github.com/ros/robot_model/issues catkin liburdfdom-dev liburdfdom-headers-dev rosconsole_bridge roscpp urdf_parser_plugin pluginlib cmake_modules rostest liburdfdom-dev liburdfdom-headers-dev rosconsole_bridge roscpp urdf_parser_plugin pluginlib ros-robot-model-1.11.8/urdf/src/000077500000000000000000000000001257532150500163625ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf/src/model.cpp000066400000000000000000000130531257532150500201700ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #include "urdf/model.h" #include /* we include the default parser for plain URDF files; other parsers are loaded via plugins (if available) */ #include #include #include #include #include #include #include #include #include namespace urdf{ static bool IsColladaData(const std::string& data) { return data.find(" model; // necessary for COLLADA compatibility if( IsColladaData(xml_string) ) { ROS_DEBUG("Parsing robot collada xml string"); static boost::mutex PARSER_PLUGIN_LOCK; static boost::scoped_ptr > PARSER_PLUGIN_LOADER; boost::mutex::scoped_lock _(PARSER_PLUGIN_LOCK); try { if (!PARSER_PLUGIN_LOADER) PARSER_PLUGIN_LOADER.reset(new pluginlib::ClassLoader("urdf_parser_plugin", "urdf::URDFParser")); const std::vector &classes = PARSER_PLUGIN_LOADER->getDeclaredClasses(); bool found = false; for (std::size_t i = 0 ; i < classes.size() ; ++i) if (classes[i].find("urdf/ColladaURDFParser") != std::string::npos) { boost::shared_ptr instance = PARSER_PLUGIN_LOADER->createInstance(classes[i]); if (instance) model = instance->parse(xml_string); found = true; break; } if (!found) ROS_ERROR_STREAM("No URDF parser plugin found for Collada files. Did you install the corresponding package?"); } catch(pluginlib::PluginlibException& ex) { ROS_ERROR_STREAM("Exception while creating planning plugin loader " << ex.what() << ". Will not parse Collada file."); } } else { ROS_DEBUG("Parsing robot urdf xml string"); model = parseURDF(xml_string); } // copy data from model into this object if (model){ this->links_ = model->links_; this->joints_ = model->joints_; this->materials_ = model->materials_; this->name_ = model->name_; this->root_link_ = model->root_link_; return true; } else return false; } }// namespace ros-robot-model-1.11.8/urdf/src/rosconsole_bridge.cpp000066400000000000000000000034601257532150500225730ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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 REGISTER_ROSCONSOLE_BRIDGE; ros-robot-model-1.11.8/urdf/test/000077500000000000000000000000001257532150500165525ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_bracket.urdf000066400000000000000000000013741257532150500236300ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_double.urdf000066400000000000000000000027051257532150500234660ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_double_joint.urdf000066400000000000000000000027211257532150500246670ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_loop.urdf000066400000000000000000000026671257532150500231740ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_no_filename_in_mesh.urdf000066400000000000000000004250031257532150500261720ustar00rootroot00000000000000 true 1000.0 true 1000.0 true 1.0 5 -10.0 1.0 10.0 1200000.0 diagnostic battery_state self_test true 1000.0 -75.0676691729 fl_caster_l_wheel_link_geom 100.0 true 100.0 fl_caster_l_wheel_bumper 75.0676691729 fl_caster_r_wheel_link_geom 100.0 true 100.0 fl_caster_r_wheel_bumper -75.0676691729 -75.0676691729 fr_caster_l_wheel_link_geom 100.0 true 100.0 fr_caster_l_wheel_bumper 75.0676691729 fr_caster_r_wheel_link_geom 100.0 true 100.0 fr_caster_r_wheel_bumper -75.0676691729 -75.0676691729 bl_caster_l_wheel_link_geom 100.0 true 100.0 bl_caster_l_wheel_bumper 75.0676691729 bl_caster_r_wheel_link_geom 100.0 true 100.0 bl_caster_r_wheel_bumper -75.0676691729 -75.0676691729 br_caster_l_wheel_link_geom 100.0 true 100.0 br_caster_l_wheel_bumper 75.0676691729 br_caster_r_wheel_link_geom 100.0 true 100.0 br_caster_r_wheel_bumper -75.0676691729 base_link_geom 100.0 true 100.0 base_bumper base_link true 100.0 base_link base_pose_ground_truth 0.01 map 25.7 25.7 0 0 0 0 true 100.0 plug_holder plug_holder_pose_ground_truth 0.01 map 0 0 0 0 0 0 640 640 1 0.0 0.0 0.0 false -135 135 0.05 10.0 0.01 20.0 0.005 true 20.0 base_scan base_laser_link torso_lift_link_geom 100.0 true 100.0 torso_lift_bumper true 100.0 torso_lift_link imu_data 0.01 map 0 0 0 0 0 0 -52143.33 6.0 6.0 R8G8B8 2448 2050 45 0.1 100 20.0 true 20.0 prosilica/cam_info prosilica/image prosilica/image_rect prosilica/cam_info_service prosilica/poll hight_def_optical_frame 1224.5 1224.5 1025.5 2955 0 0 0 0 0 640 480 L8 90 0.1 100 20.0 true 20.0 wide_stereo/left_image wide_stereo_l_stereo_camera_frame 640 480 L8 90 0.1 100 20.0 true 20.0 wide_stereo/right_image wide_stereo_r_stereo_camera_frame true 20.0 wide_stereo_l_sensor wide_stereo_r_sensor wide_stereo/raw_stereo wide_stereo_optical_frame 320 320 240 320 0 0 0 0 0 -0.09 640 480 L8 45 0.1 100 20.0 true 20.0 narrow_stereo/left_image narrow_stereo_l_stereo_camera_frame 640 480 L8 45 0.1 100 20.0 true 20.0 narrow_stereo/right_image narrow_stereo_r_stereo_camera_frame true 20.0 narrow_stereo_l_sensor narrow_stereo_r_sensor narrow_stereo/raw_stereo narrow_stereo_optical_frame 320 320 240 772.55 0 0 0 0 0 -0.09 640 640 1 0.0 0.0 0.0 false -80 80 0.05 10.0 0.01 40.0 0.005 true 40.0 tilt_scan laser_tilt_link 6.0 r_shoulder_pan_link_geom 100.0 true 100.0 r_shoulder_pan_bumper true r_shoulder_lift_link_geom 100.0 true 100.0 r_r_shoulder_lift_bumper true true r_upper_arm_link_geom 100.0 true 100.0 r_upper_arm_bumper true r_elbow_flex_link_geom 100.0 true 100.0 r_elbow_flex_bumper true true true r_forearm_link_geom 100.0 true 100.0 r_forearm_bumper true r_wrist_flex_link_geom 100.0 true 100.0 r_wrist_flex_bumper true r_wrist_roll_link_geom 100.0 true 100.0 r_wrist_roll_bumper 63.16 61.89 32.65 -36.17 90.5142857143 true r_gripper_l_finger_link_geom 100.0 true 100.0 r_gripper_l_finger_bumper true r_gripper_r_finger_link_geom 100.0 true 100.0 r_gripper_r_finger_bumper true r_gripper_l_finger_tip_link_geom 100.0 true 100.0 r_gripper_l_finger_tip_bumper true r_gripper_r_finger_tip_link_geom 100.0 true 100.0 r_gripper_r_finger_tip_bumper true 100.0 r_gripper_l_finger_link r_gripper_l_finger_pose_ground_truth 0.0 map true 100.0 r_gripper_l_finger_link r_gripper_l_finger_force_ground_truth r_gripper_l_finger_link true r_gripper_palm_link_geom 100.0 true 100.0 r_gripper_palm_bumper true r_gripper_l_finger_tip_link r_gripper_float_link r_gripper_l_finger_tip_link 0 1 0 0 0 0 r_gripper_r_finger_tip_link r_gripper_float_link r_gripper_r_finger_tip_link 0 1 0 0 0 0 true 100.0 r_gripper_palm_link r_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map true 100.0 r_gripper_tool_frame r_gripper_tool_frame_pose_ground_truth 0 0 0 0 0 0 0.0 /map true l_shoulder_pan_link_geom 100.0 true 100.0 l_shoulder_pan_bumper true l_shoulder_lift_link_geom 100.0 true 100.0 l_r_shoulder_lift_bumper true true l_upper_arm_link_geom 100.0 true 100.0 l_upper_arm_bumper true l_elbow_flex_link_geom 100.0 true 100.0 l_elbow_flex_bumper true true true l_forearm_link_geom 100.0 true 100.0 l_forearm_bumper true l_wrist_flex_link_geom 100.0 true 100.0 l_wrist_flex_bumper true l_wrist_roll_link_geom 100.0 true 100.0 l_wrist_roll_bumper 63.16 61.89 32.65 -36.17 90.5142857143 true l_gripper_l_finger_link_geom 100.0 true 100.0 l_gripper_l_finger_bumper true l_gripper_r_finger_link_geom 100.0 true 100.0 l_gripper_r_finger_bumper true l_gripper_l_finger_tip_link_geom 100.0 true 100.0 l_gripper_l_finger_tip_bumper true l_gripper_r_finger_tip_link_geom 100.0 true 100.0 l_gripper_r_finger_tip_bumper true 100.0 l_gripper_l_finger_link l_gripper_l_finger_pose_ground_truth 0.0 map true 100.0 l_gripper_l_finger_link l_gripper_l_finger_force_ground_truth l_gripper_l_finger_link true l_gripper_palm_link_geom 100.0 true 100.0 l_gripper_palm_bumper true l_gripper_l_finger_tip_link l_gripper_float_link l_gripper_l_finger_tip_link 0 1 0 0 0 0 l_gripper_r_finger_tip_link l_gripper_float_link l_gripper_r_finger_tip_link 0 1 0 0 0 0 true 100.0 l_gripper_palm_link l_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map true 100.0 l_gripper_tool_frame l_gripper_tool_frame_pose_ground_truth 0 0 0 0 0 0 0.0 /map true 640 480 L8 90 0.1 100 20.0 true 20.0 l_forearm_cam/image l_forearm_cam_frame true PR2/Blue true 640 480 L8 90 0.1 100 20.0 true 20.0 r_forearm_cam/image r_forearm_cam_frame true PR2/Blue true ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_no_joint2.urdf000066400000000000000000000013351257532150500241130ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_parent_itself.urdf000066400000000000000000000013361257532150500250520ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_pr2_desc_two_trees.urdf000066400000000000000000000026771257532150500242370ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/fail_three_links_one_joint.urdf000066400000000000000000000011451257532150500250030ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/no_visual.urdf000066400000000000000000000004601257532150500214330ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/one_link.urdf000066400000000000000000000006121257532150500212310ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/pr2_desc.urdf000066400000000000000000003656721257532150500211600ustar00rootroot00000000000000 true 1000.0 true 1.0 5 power_state 10.0 87.78 -474 525 15.52 16.41 640 640 1 0.0 0.0 0.0 false -129.998394137 129.998394137 0.08 10.0 0.01 20 0.005 true 20 base_scan base_laser_link -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 -79.2380952381 79.2380952381 -79.2380952381 true base_link_geom 100.0 true 100.0 base_bumper true 100.0 base_link base_pose_ground_truth 0.01 map 25.7 25.7 0 0 0 0 base_footprint torso_lift_link_geom 100.0 true 100.0 torso_lift_bumper -52143.33 true 100.0 imu_link torso_lift_imu/data 2.89e-08 0 0 0 0 0 0 6.0 6.0 R8G8B8 2448 2050 45 0.1 100 20.0 true 20.0 /prosilica/image_raw /prosilica/camera_info /prosilica/request_image high_def_frame 1224.5 1224.5 1025.5 2955 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 640 480 BAYER_BGGR8 90 0.1 100 25.0 true 25.0 wide_stereo/left/image_raw wide_stereo/left/camera_info wide_stereo_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 BAYER_BGGR8 90 0.1 100 25.0 true 25.0 wide_stereo/right/image_raw wide_stereo/right/camera_info wide_stereo_optical_frame 0.09 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 45 0.1 100 25.0 true 25.0 narrow_stereo/left/image_raw narrow_stereo/left/camera_info narrow_stereo_optical_frame 0 320.5 320.5 240.5 772.55 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 45 0.1 100 25.0 true 25.0 narrow_stereo/right/image_raw narrow_stereo/right/camera_info narrow_stereo_optical_frame 0.09 320.5 320.5 240.5 772.55 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue true 15.0 stereo_projection_pattern_high_res_red.png projector_wg6802418_child_frame stereo_projection_pattern_filter.png projector_wg6802418_controller/image projector_wg6802418_controller/projector 0.785398163397 0.4 10 640 640 1 0.0 0.0 0.0 false -79.9999999086 79.9999999086 0.08 10.0 0.01 40 0.005 true 40 tilt_scan laser_tilt_link -6.05 true 32.6525111499 true true 63.1552452977 61.8948225713 true true -90.5142857143 -1.0 true -36.167452007 true true true true r_gripper_l_finger_link_geom 100.0 true 100.0 r_gripper_l_finger_link r_gripper_l_finger_bumper true r_gripper_r_finger_link_geom 100.0 true r_gripper_r_finger_link 100.0 r_gripper_r_finger_bumper true false r_gripper_l_finger_tip_link_geom 100.0 true r_gripper_l_finger_tip_link 100.0 r_gripper_l_finger_tip_bumper true false r_gripper_r_finger_tip_link_geom 100.0 true r_gripper_r_finger_tip_link 100.0 r_gripper_r_finger_tip_bumper true 100.0 r_gripper_l_finger_link r_gripper_l_finger_pose_ground_truth 0.0 base_link true 100.0 r_gripper_l_finger_link r_gripper_l_finger_force_ground_truth r_gripper_l_finger_link true 0.17126 7.7562e-05 1.49095e-06 -9.83385e-06 0.000197083 -3.06125e-06 0.000181054 0.03598 0.0173 -0.00164 0.82991 -0.157 0.790675 0 -0 0 true false true 0.17389 7.73841e-05 -2.09309e-06 -8.36228e-06 0.000198474 2.4611e-06 0.00018107 0.03576 -0.01736 -0.00095 0.82991 -0.219 0.790675 0 -0 0 true false r_gripper_r_parallel_link r_gripper_palm_link r_gripper_palm_link 0 0 -1 0.2 0.05891 -0.031 0 r_gripper_l_parallel_link r_gripper_palm_link r_gripper_palm_link 0 0 1 0.2 0.05891 0.031 0 r_gripper_r_parallel_link r_gripper_r_finger_tip_link r_gripper_r_finger_tip_link 0 0 1 -0.018 -0.021 0 r_gripper_l_parallel_link r_gripper_l_finger_tip_link r_gripper_l_finger_tip_link 0 0 1 -0.018 0.021 0 r_gripper_l_finger_tip_link r_gripper_r_finger_tip_link r_gripper_r_finger_tip_link 0 1 0 true true true r_gripper_palm_link_geom 100.0 true 100.0 r_gripper_palm_link r_gripper_palm_bumper true 100.0 r_gripper_palm_link r_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map true 32.6525111499 true true 63.1552452977 61.8948225713 true true -90.5142857143 -1.0 true -36.167452007 true true true true l_gripper_l_finger_link_geom 100.0 true 100.0 l_gripper_l_finger_link l_gripper_l_finger_bumper true l_gripper_r_finger_link_geom 100.0 true l_gripper_r_finger_link 100.0 l_gripper_r_finger_bumper true false l_gripper_l_finger_tip_link_geom 100.0 true l_gripper_l_finger_tip_link 100.0 l_gripper_l_finger_tip_bumper true false l_gripper_r_finger_tip_link_geom 100.0 true l_gripper_r_finger_tip_link 100.0 l_gripper_r_finger_tip_bumper true 100.0 l_gripper_l_finger_link l_gripper_l_finger_pose_ground_truth 0.0 base_link true 100.0 l_gripper_l_finger_link l_gripper_l_finger_force_ground_truth l_gripper_l_finger_link true 0.17126 7.7562e-05 1.49095e-06 -9.83385e-06 0.000197083 -3.06125e-06 0.000181054 0.03598 0.0173 -0.00164 0.82991 0.219 0.790675 0 -0 0 true false true 0.17389 7.73841e-05 -2.09309e-06 -8.36228e-06 0.000198474 2.4611e-06 0.00018107 0.03576 -0.01736 -0.00095 0.82991 0.157 0.790675 0 -0 0 true false l_gripper_r_parallel_link l_gripper_palm_link l_gripper_palm_link 0 0 -1 0.2 0.05891 -0.031 0 l_gripper_l_parallel_link l_gripper_palm_link l_gripper_palm_link 0 0 1 0.2 0.05891 0.031 0 l_gripper_r_parallel_link l_gripper_r_finger_tip_link l_gripper_r_finger_tip_link 0 0 1 -0.018 -0.021 0 l_gripper_l_parallel_link l_gripper_l_finger_tip_link l_gripper_l_finger_tip_link 0 0 1 -0.018 0.021 0 l_gripper_l_finger_tip_link l_gripper_r_finger_tip_link l_gripper_r_finger_tip_link 0 1 0 true true true l_gripper_palm_link_geom 100.0 true 100.0 l_gripper_palm_link l_gripper_palm_bumper true 100.0 l_gripper_palm_link l_gripper_palm_pose_ground_truth 0 0 0 0 0 0 0.0 map 640 480 L8 90 0.1 100 25.0 true 25.0 l_forearm_cam/image_raw l_forearm_cam/camera_info l_forearm_cam_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue 640 480 L8 90 0.1 100 25.0 true 25.0 r_forearm_cam/image_raw r_forearm_cam/camera_info r_forearm_cam_optical_frame 0 320.5 320.5 240.5 320 0.00000001 0.00000001 0.00000001 0.00000001 0.00000001 true PR2/Blue ros-robot-model-1.11.8/urdf/test/pr2_desc_no_joint.urdf000066400000000000000000000005411257532150500230340ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/singularity.urdf000066400000000000000000000015571257532150500220160ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf/test/test_robot_model_parser.cpp000066400000000000000000000103631257532150500242010ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Wim Meeussen */ #include #include #include "urdf/model.h" // Including ros, just to be able to call ros::init(), to remove unwanted // args from command-line. #include using namespace urdf; int g_argc; char** g_argv; class TestParser : public testing::Test { public: Model robot; bool checkModel() { // get root link boost::shared_ptr root_link=this->robot.getRoot(); if (!root_link) { ROS_ERROR("no root link %s",this->robot.getName().c_str()); return false; } // go through entire tree return this->traverse_tree(root_link); }; protected: /// constructor TestParser() { } /// Destructor ~TestParser() { } bool traverse_tree(boost::shared_ptr link,int level = 0) { level+=2; for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) { if (*child) { // check rpy double roll,pitch,yaw; (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(roll,pitch,yaw); if (isnan(roll) || isnan(pitch) || isnan(yaw)) { ROS_ERROR("getRPY() returned nan!"); return false; } // recurse down the tree return this->traverse_tree(*child,level); } else { ROS_ERROR("root link: %s has a null child!",link->name.c_str()); return false; } } // no children return true; }; }; TEST_F(TestParser, test) { std::string folder = std::string(g_argv[1]) + "/test/"; ROS_INFO("Folder %s",folder.c_str()); for (int i=2; i ros-robot-model-1.11.8/urdf/test/two_links_one_joint.urdf000066400000000000000000000007161257532150500235150ustar00rootroot00000000000000 ros-robot-model-1.11.8/urdf_parser_plugin/000077500000000000000000000000001257532150500205255ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf_parser_plugin/CHANGELOG.rst000066400000000000000000000015761257532150500225570ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package urdf_parser_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.11.8 (2015-09-11) ------------------- 1.11.7 (2015-04-22) ------------------- 1.11.6 (2014-11-30) ------------------- 1.11.5 (2014-07-24) ------------------- 1.11.4 (2014-07-07) ------------------- * moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 * Contributors: Tully Foote 1.11.3 (2014-06-24) ------------------- * update usage of urdfdom_headers for indigo/trusty * Contributors: William Woodall 1.11.2 (2014-03-22) ------------------- 1.11.1 (2014-03-20) ------------------- 1.11.0 (2014-02-21) ------------------- 1.10.18 (2013-12-04) -------------------- * add DEPENDS for kdl_parser * Contributors: Ioan Sucan 1.10.16 (2013-11-18) -------------------- 1.10.15 (2013-08-17) -------------------- ros-robot-model-1.11.8/urdf_parser_plugin/CMakeLists.txt000066400000000000000000000004561257532150500232720ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(urdf_parser_plugin) find_package(catkin REQUIRED) find_package(urdfdom_headers REQUIRED) catkin_package( INCLUDE_DIRS include DEPENDS urdfdom_headers ) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) ros-robot-model-1.11.8/urdf_parser_plugin/include/000077500000000000000000000000001257532150500221505ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf_parser_plugin/include/urdf_parser_plugin/000077500000000000000000000000001257532150500260425ustar00rootroot00000000000000ros-robot-model-1.11.8/urdf_parser_plugin/include/urdf_parser_plugin/parser.h000066400000000000000000000041711257532150500275120ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2013, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER 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. *********************************************************************/ /* Author: Ioan Sucan */ #ifndef URDF_PARSER_PLUGIN_H #define URDF_PARSER_PLUGIN_H #include namespace urdf { /** \brief Base class for URDF parsers */ class URDFParser { public: URDFParser() { } virtual ~URDFParser() { } /// \brief Load Model from string virtual boost::shared_ptr parse(const std::string &xml_string) = 0; }; } #endif ros-robot-model-1.11.8/urdf_parser_plugin/package.xml000066400000000000000000000012331257532150500226410ustar00rootroot00000000000000 urdf_parser_plugin 1.11.8 This package contains a C++ base class for URDF parsers. Ioan Sucan Ioan Sucan BSD http://ros.org/wiki/urdf https://github.com/ros/robot_model https://github.com/ros/robot_model/issues catkin liburdfdom-headers-dev liburdfdom-headers-dev