From cc89516b9248bea4a07302c1f247303e500039a4 Mon Sep 17 00:00:00 2001 From: Silvio Date: Thu, 6 Oct 2022 19:18:32 +0200 Subject: [PATCH 001/267] ffmpeg_grabber: Fix linking errors on Windows --- doc/release/yarp_3_7/fixffmpegwin.md | 4 ++++ src/devices/ffmpeg/CMakeLists.txt | 6 ++++-- src/portmonitors/image_compression_ffmpeg/CMakeLists.txt | 4 +++- 3 files changed, 11 insertions(+), 3 deletions(-) create mode 100644 doc/release/yarp_3_7/fixffmpegwin.md diff --git a/doc/release/yarp_3_7/fixffmpegwin.md b/doc/release/yarp_3_7/fixffmpegwin.md new file mode 100644 index 00000000000..98df078c62f --- /dev/null +++ b/doc/release/yarp_3_7/fixffmpegwin.md @@ -0,0 +1,4 @@ +fixffmpegwin {#yarp_3_7} +----------- + +* ffmpeg_grabber: Fix linking problems on Windows. diff --git a/src/devices/ffmpeg/CMakeLists.txt b/src/devices/ffmpeg/CMakeLists.txt index 7003a0dc256..a0b090d50c7 100644 --- a/src/devices/ffmpeg/CMakeLists.txt +++ b/src/devices/ffmpeg/CMakeLists.txt @@ -8,14 +8,14 @@ yarp_prepare_plugin(ffmpeg_grabber INCLUDE FfmpegGrabber.h EXTRA_CONFIG WRAPPER=grabberDual - DEPENDS "YARP_HAS_FFMPEG;FFMPEG_avformat_FOUND;FFMPEG_avdevice_FOUND;FFMPEG_swscale_FOUND" + DEPENDS "YARP_HAS_FFMPEG;FFMPEG_avcodec_FOUND;FFMPEG_avformat_FOUND;FFMPEG_avdevice_FOUND;FFMPEG_avutil_FOUND;FFMPEG_swscale_FOUND" ) yarp_prepare_plugin(ffmpeg_writer CATEGORY device TYPE FfmpegWriter INCLUDE FfmpegWriter.h - DEPENDS "YARP_HAS_FFMPEG;FFMPEG_avformat_FOUND;FFMPEG_avdevice_FOUND;FFMPEG_swscale_FOUND" + DEPENDS "YARP_HAS_FFMPEG;FFMPEG_avcodec_FOUND;FFMPEG_avformat_FOUND;FFMPEG_avdevice_FOUND;FFMPEG_avutil_FOUND;FFMPEG_swscale_FOUND" ) if(NOT SKIP_ffmpeg_grabber OR NOT SKIP_ffmpeg_writer) @@ -48,6 +48,7 @@ if(NOT SKIP_ffmpeg_grabber OR NOT SKIP_ffmpeg_writer) ${FFMPEG_avcodec_INCLUDE_DIRS} ${FFMPEG_avformat_INCLUDE_DIRS} ${FFMPEG_avdevice_INCLUDE_DIRS} + ${FFMPEG_avutil_INCLUDE_DIRS} ${FFMPEG_swscale_INCLUDE_DIRS} ) target_link_libraries(yarp_ffmpeg @@ -55,6 +56,7 @@ if(NOT SKIP_ffmpeg_grabber OR NOT SKIP_ffmpeg_writer) ${FFMPEG_avcodec_LIBRARIES} ${FFMPEG_avformat_LIBRARIES} ${FFMPEG_avdevice_LIBRARIES} + ${FFMPEG_avutil_LIBRARIES} ${FFMPEG_swscale_LIBRARIES} ) # list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS FFMPEG) # Not using targets diff --git a/src/portmonitors/image_compression_ffmpeg/CMakeLists.txt b/src/portmonitors/image_compression_ffmpeg/CMakeLists.txt index 42a3f0e3314..b1a294b167b 100644 --- a/src/portmonitors/image_compression_ffmpeg/CMakeLists.txt +++ b/src/portmonitors/image_compression_ffmpeg/CMakeLists.txt @@ -5,7 +5,7 @@ yarp_prepare_plugin(image_compression_ffmpeg TYPE FfmpegMonitorObject INCLUDE ffmpegPortmonitor.h CATEGORY portmonitor - DEPENDS "ENABLE_yarpcar_portmonitor;YARP_HAS_FFMPEG;FFMPEG_swscale_FOUND" + DEPENDS "ENABLE_yarpcar_portmonitor;YARP_HAS_FFMPEG;FFMPEG_avcodec_FOUND;FFMPEG_avutil_FOUND;FFMPEG_swscale_FOUND" ) if(SKIP_image_compression_ffmpeg) @@ -33,11 +33,13 @@ list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS target_include_directories(yarp_pm_image_compression_ffmpeg SYSTEM PRIVATE ${FFMPEG_avcodec_INCLUDE_DIRS} + ${FFMPEG_avutil_INCLUDE_DIRS} ${FFMPEG_swscale_INCLUDE_DIRS} ) target_link_libraries(yarp_pm_image_compression_ffmpeg PRIVATE ${FFMPEG_avcodec_LIBRARIES} + ${FFMPEG_avutil_LIBRARIES} ${FFMPEG_swscale_LIBRARIES} ) # list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS FFMPEG) # Not using targets From 2a907e93f3e2c683256380ac526f04a3e2d67a90 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 8 Nov 2022 15:57:00 +0100 Subject: [PATCH 002/267] `yarprobotinterface`: is now able to parse `enabled_by` and `disabled_by` xml attributes. See attached yarprobotinterface Doxygen documentation. --- .../cmd_yarprobotinterface.dox | 10 +- .../yarp_robotinterface_xml_config_files.dox | 69 +++++++++- .../master/yarprobotinterface_enable_tags.md | 7 + .../robotinterface/impl/XMLReaderFileV3.cpp | 125 ++++++++++++++---- 4 files changed, 179 insertions(+), 32 deletions(-) create mode 100644 doc/release/master/yarprobotinterface_enable_tags.md diff --git a/doc/module_executables/cmd_yarprobotinterface.dox b/doc/module_executables/cmd_yarprobotinterface.dox index cb10f85f4bf..8ab51acac50 100644 --- a/doc/module_executables/cmd_yarprobotinterface.dox +++ b/doc/module_executables/cmd_yarprobotinterface.dox @@ -8,12 +8,12 @@ \section yarprobotinterface_intro Description -The yarprobotinterface is a command line tool that is useful to launch multiple YARP device at once. +The yarprobotinterface is a command line tool that is useful to launch multiple YARP devices at once. Its name derives from the fact that the first and main use of the yarprobotinterface was used as the main program to provide a network "interface", via YARP Network Server Wrappers (NWS) devices, to a robot. -However, the yarprobotinterface can be used to launch YARP devices of any kind. In a sense, is an extension of the +However, the yarprobotinterface can be used to launch YARP devices of any kind. In a sense, it is an extension of the yarpdev command, that instead can be used only to launch one or two devices, while yarprobotinterface can launch an arbitrary number of YARP devices. @@ -36,6 +36,12 @@ The details of the xml format of the files loaded by yarprobotinterface are docu - If this option is specified, then xml file is only loaded without actually opening devices. This option is useful to validate if xml files are well formed. +`--enable_tags (xxx yyy ... zzz)` +- This options can be used to enable optional devices which have been marked with the in `enabled_by` attribute in the xml file. See \ref yarp_robotinterface_xml_config_files + +`--disable_tags (xxx yyy ... zzz)` +- This options can be used to disable included devices which have been marked with the in `disabled_by` attribute in the xml file. See \ref yarp_robotinterface_xml_config_files + \section yarprobotinterface_conf_file Configuration Files yarprobotinterface loads the xml file from the location specified in the `--config` option. diff --git a/doc/module_yarprobotinterface/yarp_robotinterface_xml_config_files.dox b/doc/module_yarprobotinterface/yarp_robotinterface_xml_config_files.dox index f69b6062c10..56909525b47 100644 --- a/doc/module_yarprobotinterface/yarp_robotinterface_xml_config_files.dox +++ b/doc/module_yarprobotinterface/yarp_robotinterface_xml_config_files.dox @@ -17,10 +17,10 @@ Here is a minimal config file, let's call it "config.xml": - + - 3 - + 3 + @@ -86,5 +86,66 @@ in the `portprefix` attribute of the `robot` element. This element still needs to be documented. +\section yarp_robotinterface_xml_config_files_advanced Inclusion of multiple XML files -*/ +Here is an example of .xml config file which includes other xml files, using the `xi:include` tag: + +\code + + + + + + + + + + + + + + + +\endcode + +Contents of the file "wrappers/odometry/odometry_nws_yarp.xml". + +\code + + + + + /cer/odometry + /cer/odometer + /cer/velocity + + + cer_odometry + + + +\endcode + +It must be noticed that the included file contains just a single `device` section, that will be incorporated inside the +`devices` block in the parent file. In this way, it is possible to better organize the xml file and eventually add/remove/replace + individual devices. +Additionally each device included through a xi:include can be enabled/disabled by the the use of `enabled_by` and `disabled_by` attributes. +By default, if no attribute is added, than the file is automatically included. +If a `enabled_by` attribute is found, then the include line is not enabled by default and it is enabled only if yarprobotinterface +has been executed with the option `--enable_tags (xxx)` (xxx should match the contents of the `enabled_by` attribute) +If a `disabled_by` attribute is found, then the include line (either enabled by default or by an `enable_by` attribute ) can +be disabled if yarprobotinterface has been executed with the specific option `--disable_tags (yyy)` (yyy should match the contetes of the `disabled_by` attribute) + +Examples: +- `yarprobotinterface` starts yarprobotinterface including the following devices: odometry_nws_yarp.xml odometry.xml body.xml body_nws_yarp.xml +- `yarprobotinterface --disable_tags (disable_odometry)` starts yarprobotinterface including the following devices: body.xml body_nws_yarp.xml +- `yarprobotinterface --enable_tags (enable_ros) --disable_tags (disable_body)` starts yarprobotinterface including the following devices: odometry_nws_yarp.xml odometry.xml odometry_nws_ros.xml +- `yarprobotinterface --enable_tags (enable_ros enable_ros2) --disable_tags (disable_body)` starts yarprobotinterface including the following devices: odometry_nws_yarp.xml odometry.xml odometry_nws_ros.xml odometry_nws_ros2.xml +- `yarprobotinterface --enable_tags (enable_all)` starts yarprobotinterface including the following devices: odometry_nws_yarp.xml odometry.xml odometry_nws_ros.xml odometry_nws_ros2.xml body.xml body_nws_yarp.xml +- `yarprobotinterface --enable_tags (enable_all) --disable_tags (disable_body)` starts yarprobotinterface including the following devices: odometry_nws_yarp.xml odometry.xml odometry_nws_ros.xml odometry_nws_ros2.xml + +The latter two examples show the use of the special `enable_all` tag, which can be used to enable all optional devices (i.e. marked by a `enabled_by` attribute) + +N.B. The `disable_tags` is always processed after the `enable_tags` and can be used to remove previously enabled devices. +The enabled_by/disabled_by attributes are parsed by the yarprobotinterface pre-processor, hence they can be used only in combination with a xi:include tag. +*/ \ No newline at end of file diff --git a/doc/release/master/yarprobotinterface_enable_tags.md b/doc/release/master/yarprobotinterface_enable_tags.md new file mode 100644 index 00000000000..d4ee006d315 --- /dev/null +++ b/doc/release/master/yarprobotinterface_enable_tags.md @@ -0,0 +1,7 @@ +yarprobotinterface_enable_tags {#master} +----------- + +### `yarprobotinterface` + +* `yarprobotinterface`: is now able to parse `enabled_by` and `disabled_by` xml attributes. +See attached yarprobotinterface Doxygen documentation. diff --git a/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp b/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp index 1b0d08bbda9..bc140781484 100644 --- a/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp +++ b/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp @@ -56,6 +56,7 @@ class yarp::robotinterface::impl::XMLReaderFileV3::Private yarp::robotinterface::Action readActionTag(TiXmlElement* actionElem, yarp::robotinterface::XMLReaderResult& result); yarp::robotinterface::ActionList readActionsTag(TiXmlElement* actionsElem, yarp::robotinterface::XMLReaderResult& result); + bool Check_include_section_is_enabled(const std::string& href_enable_tags, const std::string& href_disable_tags); bool PerformInclusions(TiXmlNode* pParent, const std::string& parent_fileName, const std::string& current_path); void ReplaceAllStrings(std::string& str, const std::string& from, const std::string& to); XMLReaderFileV3* const parent; @@ -69,6 +70,8 @@ class yarp::robotinterface::impl::XMLReaderFileV3::Private std::string curr_filename; unsigned int minorVersion; unsigned int majorVersion; + yarp::os::Bottle b_enabled_options; + yarp::os::Bottle b_disabled_options; }; @@ -128,16 +131,25 @@ yarp::robotinterface::XMLReaderResult yarp::robotinterface::impl::XMLReaderFileV current_filename = fileName.substr(fileName.find_last_of("\\/") + 1); log_filename = current_filename.substr(0, current_filename.find(".xml")); log_filename += "_preprocessor_log.xml"; + + yarp::os::Bottle* enable_tags = config.find("enable_tags").asList(); + yarp::os::Bottle* disable_tags = config.find("disable_tags").asList(); + if (enable_tags) b_enabled_options = *enable_tags; + if (disable_tags) b_disabled_options = *disable_tags; + double start_time = yarp::os::Time::now(); PerformInclusions(doc->RootElement(), current_filename, current_path); double end_time = yarp::os::Time::now(); + std::string full_log_withpath = current_path + std::string("\\") + log_filename; std::replace(full_log_withpath.begin(), full_log_withpath.end(), '\\', '/'); yDebug() << "Preprocessor complete in: " << end_time - start_time << "s"; - if (verbose_output) { + if (verbose_output) + { yDebug() << "Preprocessor output stored in: " << full_log_withpath; doc->SaveFile(full_log_withpath); } + yarp::robotinterface::XMLReaderResult result = readRobotTag(doc->RootElement()); delete doc; @@ -166,6 +178,44 @@ yarp::robotinterface::XMLReaderResult yarp::robotinterface::impl::XMLReaderFileV return result; } +bool yarp::robotinterface::impl::XMLReaderFileV3::Private::Check_include_section_is_enabled(const std::string& href_enable_tags, const std::string& href_disable_tags) +{ + yarp::os::Bottle b_included_enable_options; + b_included_enable_options.fromString(href_enable_tags); + yarp::os::Bottle b_included_disable_options; + b_included_disable_options.fromString(href_disable_tags); + //yDebug() << "included enable tag size:" << b_included_enable_options.size() << " contents:" << b_included_enable_options.toString(); + //yDebug() << "included disable tag size:" << b_included_disable_options.size() << " contents:" << b_included_disable_options.toString(); + + //if no `enabled_by` attribute are found in the xi::include line, then the include is enabled by default. + bool enabled = true; + if (b_included_enable_options.size() != 0) + { + //.otherwise, if a `enabled_by` attribute is found, then the include line is not enabled by default and it + // is enabled only if yarprobotinterface has been executed with the specific option --enable_tags + enabled = false; + for (size_t i = 0; i < b_included_enable_options.size(); i++) + { + std::string s = b_included_enable_options.get(i).asString(); + if (b_enabled_options.check(s) || b_enabled_options.check("enable_all")) + { + enabled = true; + } + } + } + // if a `disabled_by` attribute is found, then the include line (either enabled by default or by an `enable_by` tag ) can + // be disabled if yarprobotinterface has been executed with the specific option --disable_tags + for (size_t i = 0; i < b_included_disable_options.size(); i++) + { + std::string s = b_included_disable_options.get(i).asString(); + if (b_disabled_options.check(s)) + { + enabled = false; + } + } + return enabled; +} + bool yarp::robotinterface::impl::XMLReaderFileV3::Private::PerformInclusions(TiXmlNode* pParent, const std::string& parent_fileName, const std::string& current_path) { loop_start: //goto label @@ -182,36 +232,59 @@ bool yarp::robotinterface::impl::XMLReaderFileV3::Private::PerformInclusions(TiX return false; } - if (elemString == "xi:include") { + if (elemString == "xi:include") + { std::string href_filename; - std::string included_filename; - std::string included_path; - if (childElem->QueryStringAttribute("href", &href_filename) == TIXML_SUCCESS) { - included_path = std::string(current_path).append("\\").append(href_filename.substr(0, href_filename.find_last_of("\\/"))); - included_filename = href_filename.substr(href_filename.find_last_of("\\/") + 1); - std::string full_path_file = std::string(included_path).append("\\").append(included_filename); - TiXmlDocument included_file; - - std::replace(full_path_file.begin(), full_path_file.end(), '\\', '/'); - if (included_file.LoadFile(full_path_file)) { - PerformInclusions(included_file.RootElement(), included_filename, included_path); - //included_file.RootElement()->SetAttribute("xml:base", href_filename); //not yet implemented - included_file.RootElement()->RemoveAttribute("xmlns:xi"); - if (pParent->ReplaceChild(childElem, *included_file.FirstChildElement())) { - //the replace operation invalidates the iterator, hence we need to restart the parsing of this level - goto loop_start; - } else { + if (childElem->QueryStringAttribute("href", &href_filename) == TIXML_SUCCESS) + { + std::string href_enable_tags, href_disable_tags; + childElem->QueryStringAttribute("enabled_by", &href_enable_tags); + childElem->QueryStringAttribute("disabled_by", &href_disable_tags); + if (Check_include_section_is_enabled(href_enable_tags, href_disable_tags)) + { + std::string included_path = std::string(current_path).append("\\").append(href_filename.substr(0, href_filename.find_last_of("\\/"))); + std::string included_filename = href_filename.substr(href_filename.find_last_of("\\/") + 1); + std::string full_path_file = std::string(included_path).append("\\").append(included_filename); + TiXmlDocument included_file; + + std::replace(full_path_file.begin(), full_path_file.end(), '\\', '/'); + if (included_file.LoadFile(full_path_file)) + { + PerformInclusions(included_file.RootElement(), included_filename, included_path); + //included_file.RootElement()->SetAttribute("xml:base", href_filename); //not yet implemented + included_file.RootElement()->RemoveAttribute("xmlns:xi"); + if (pParent->ReplaceChild(childElem, *included_file.FirstChildElement())) + { + //the replace operation invalidates the iterator, hence we need to restart the parsing of this level + goto loop_start; + } + else + { + //fatal error + yFatal() << "Failed to include: " << included_filename << " in: " << parent_fileName; + return false; + } + } + else + { //fatal error - yFatal() << "Failed to include: " << included_filename << " in: " << parent_fileName; + yError() << included_file.ErrorDesc() << " file" << full_path_file << "included by " << parent_fileName << "at line" << childElem->Row(); + yFatal() << "In file:" << included_filename << " included by: " << parent_fileName << " at line: " << childElem->Row(); return false; } - } else { - //fatal error - yError() << included_file.ErrorDesc() << " file" << full_path_file << "included by " << parent_fileName << "at line" << childElem->Row(); - yFatal() << "In file:" << included_filename << " included by: " << parent_fileName << " at line: " << childElem->Row(); - return false; } - } else { + else + { + yDebug() << "Skipping include section `" << href_filename << "` because is not enabled"; + if (pParent->RemoveChild(childElem)) + { + //the remove operation invalidates the iterator, hence we need to restart the parsing of this level + goto loop_start; + } + } + } + else + { //fatal error yFatal() << "Syntax error in: " << parent_fileName << " while searching for href attribute"; return false; From d5d7f5edee1e8fc27e89920e6ce83841ba124af6 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 11 Nov 2022 17:20:14 +0100 Subject: [PATCH 003/267] added extra prints to show a list of enable/disable tags during yarprobotinterface startup --- .../robotinterface/impl/XMLReaderFileV3.cpp | 85 ++++++++++++++----- 1 file changed, 65 insertions(+), 20 deletions(-) diff --git a/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp b/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp index bc140781484..6938f326338 100644 --- a/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp +++ b/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #define SYNTAX_ERROR(line) yError() << "Syntax error while loading" << curr_filename << "at line" << line << "." #define SYNTAX_WARNING(line) yWarning() << "Invalid syntax while loading" << curr_filename << "at line" << line << "." @@ -56,7 +57,7 @@ class yarp::robotinterface::impl::XMLReaderFileV3::Private yarp::robotinterface::Action readActionTag(TiXmlElement* actionElem, yarp::robotinterface::XMLReaderResult& result); yarp::robotinterface::ActionList readActionsTag(TiXmlElement* actionsElem, yarp::robotinterface::XMLReaderResult& result); - bool Check_include_section_is_enabled(const std::string& href_enable_tags, const std::string& href_disable_tags); + bool CheckIfIncludeSectionIsEnabled(const std::string& href_enable_tags, const std::string& href_disable_tags); bool PerformInclusions(TiXmlNode* pParent, const std::string& parent_fileName, const std::string& current_path); void ReplaceAllStrings(std::string& str, const std::string& from, const std::string& to); XMLReaderFileV3* const parent; @@ -70,8 +71,10 @@ class yarp::robotinterface::impl::XMLReaderFileV3::Private std::string curr_filename; unsigned int minorVersion; unsigned int majorVersion; - yarp::os::Bottle b_enabled_options; - yarp::os::Bottle b_disabled_options; + std::set m_enabled_options_from_command_line; + std::set m_disabled_options_from_command_line; + std::set m_enable_set_found_in_all_xml; + std::set m_disable_set_found_in_all_xml; }; @@ -132,15 +135,51 @@ yarp::robotinterface::XMLReaderResult yarp::robotinterface::impl::XMLReaderFileV log_filename = current_filename.substr(0, current_filename.find(".xml")); log_filename += "_preprocessor_log.xml"; - yarp::os::Bottle* enable_tags = config.find("enable_tags").asList(); - yarp::os::Bottle* disable_tags = config.find("disable_tags").asList(); - if (enable_tags) b_enabled_options = *enable_tags; - if (disable_tags) b_disabled_options = *disable_tags; + std::string enable_tags_string; + yarp::os::Bottle* be = config.find("enable_tags").asList(); + if (be) { enable_tags_string = be->toString();} + + std::string disable_tags_string; + yarp::os::Bottle* bd = config.find("disable_tags").asList(); + if (bd) { disable_tags_string = bd->toString();} + + { + char* all_string = strdup(enable_tags_string.c_str()); + char* token = strtok(all_string, " "); + while (token) { + m_enabled_options_from_command_line.insert(token); + token = strtok(NULL, " "); + } + } + { + char* all_string = strdup(disable_tags_string.c_str()); + char* token = strtok(all_string, " "); + while (token) { + m_disabled_options_from_command_line.insert(token); + token = strtok(NULL, " "); + } + } + yInfo() << "Yarprobotinterface was started using the following enable_tags:"<< enable_tags_string; + yInfo() << "Yarprobotinterface was started using the following disable_tags:" << disable_tags_string; double start_time = yarp::os::Time::now(); PerformInclusions(doc->RootElement(), current_filename, current_path); double end_time = yarp::os::Time::now(); + std::string all_enable_att_string = "List of all enable attributes found in the include tags: "; + for (auto it = m_enable_set_found_in_all_xml.begin(); it != m_enable_set_found_in_all_xml.end(); it++) + { + all_enable_att_string += (" " + *it); + } + yDebug() << all_enable_att_string; + + std::string all_disable_att_string = "List of all disable attributes found in the include tags: "; + for (auto it = m_disable_set_found_in_all_xml.begin(); it != m_disable_set_found_in_all_xml.end(); it++) + { + all_disable_att_string += (" " + *it); + } + yDebug() << all_disable_att_string; + std::string full_log_withpath = current_path + std::string("\\") + log_filename; std::replace(full_log_withpath.begin(), full_log_withpath.end(), '\\', '/'); yDebug() << "Preprocessor complete in: " << end_time - start_time << "s"; @@ -178,26 +217,29 @@ yarp::robotinterface::XMLReaderResult yarp::robotinterface::impl::XMLReaderFileV return result; } -bool yarp::robotinterface::impl::XMLReaderFileV3::Private::Check_include_section_is_enabled(const std::string& href_enable_tags, const std::string& href_disable_tags) +bool yarp::robotinterface::impl::XMLReaderFileV3::Private::CheckIfIncludeSectionIsEnabled(const std::string& hrefxml_enable_tags_s, const std::string& hrefxml_disable_tags_s) { - yarp::os::Bottle b_included_enable_options; - b_included_enable_options.fromString(href_enable_tags); - yarp::os::Bottle b_included_disable_options; - b_included_disable_options.fromString(href_disable_tags); + yarp::os::Bottle hrefxml_enable_tags_b; + hrefxml_enable_tags_b.fromString(hrefxml_enable_tags_s); + yarp::os::Bottle hrefxml_disable_tags_b; + hrefxml_disable_tags_b.fromString(hrefxml_disable_tags_s); //yDebug() << "included enable tag size:" << b_included_enable_options.size() << " contents:" << b_included_enable_options.toString(); //yDebug() << "included disable tag size:" << b_included_disable_options.size() << " contents:" << b_included_disable_options.toString(); //if no `enabled_by` attribute are found in the xi::include line, then the include is enabled by default. bool enabled = true; - if (b_included_enable_options.size() != 0) + size_t hrefxml_enable_tags_b_size = hrefxml_enable_tags_b.size(); + if (hrefxml_enable_tags_b_size != 0) { //.otherwise, if a `enabled_by` attribute is found, then the include line is not enabled by default and it // is enabled only if yarprobotinterface has been executed with the specific option --enable_tags enabled = false; - for (size_t i = 0; i < b_included_enable_options.size(); i++) + for (size_t i = 0; i < hrefxml_enable_tags_b_size; i++) { - std::string s = b_included_enable_options.get(i).asString(); - if (b_enabled_options.check(s) || b_enabled_options.check("enable_all")) + std::string s = hrefxml_enable_tags_b.get(i).asString(); + m_enable_set_found_in_all_xml.insert(s); + if (m_enabled_options_from_command_line.find(s) != m_enabled_options_from_command_line.end() || + m_enabled_options_from_command_line.find("enable_all") != m_enabled_options_from_command_line.end()) { enabled = true; } @@ -205,14 +247,17 @@ bool yarp::robotinterface::impl::XMLReaderFileV3::Private::Check_include_section } // if a `disabled_by` attribute is found, then the include line (either enabled by default or by an `enable_by` tag ) can // be disabled if yarprobotinterface has been executed with the specific option --disable_tags - for (size_t i = 0; i < b_included_disable_options.size(); i++) + size_t hrefxml_disable_tags_b_size = hrefxml_disable_tags_b.size(); + for (size_t i = 0; i < hrefxml_disable_tags_b_size; i++) { - std::string s = b_included_disable_options.get(i).asString(); - if (b_disabled_options.check(s)) + std::string s = hrefxml_disable_tags_b.get(i).asString(); + m_disable_set_found_in_all_xml.insert(s); + if (m_disabled_options_from_command_line.find(s) != m_disabled_options_from_command_line.end()) { enabled = false; } } + return enabled; } @@ -240,7 +285,7 @@ bool yarp::robotinterface::impl::XMLReaderFileV3::Private::PerformInclusions(TiX std::string href_enable_tags, href_disable_tags; childElem->QueryStringAttribute("enabled_by", &href_enable_tags); childElem->QueryStringAttribute("disabled_by", &href_disable_tags); - if (Check_include_section_is_enabled(href_enable_tags, href_disable_tags)) + if (CheckIfIncludeSectionIsEnabled(href_enable_tags, href_disable_tags)) { std::string included_path = std::string(current_path).append("\\").append(href_filename.substr(0, href_filename.find_last_of("\\/"))); std::string included_filename = href_filename.substr(href_filename.find_last_of("\\/") + 1); From 4da405c7fb077b4604029fd87e4e51a633e2d7eb Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 16:02:48 +0100 Subject: [PATCH 004/267] Removed deprecated RGBDSensorWrapper in favor of RGBDSensor_nws_yarp/RGBDSensor_nws_ros --- src/devices/CMakeLists.txt | 1 - src/devices/README.md | 1 - src/devices/RGBDSensorWrapper/CMakeLists.txt | 56 -- .../RGBDSensorWrapper/RGBDSensorWrapper.cpp | 879 ------------------ .../RGBDSensorWrapper/RGBDSensorWrapper.h | 250 ----- 5 files changed, 1187 deletions(-) delete mode 100644 src/devices/RGBDSensorWrapper/CMakeLists.txt delete mode 100644 src/devices/RGBDSensorWrapper/RGBDSensorWrapper.cpp delete mode 100644 src/devices/RGBDSensorWrapper/RGBDSensorWrapper.h diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index 0683dc683d4..0697dd4a569 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -94,7 +94,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(RGBDRosConversionUtils) add_subdirectory(RGBDSensorClient) add_subdirectory(ServerInertial) - add_subdirectory(RGBDSensorWrapper) add_subdirectory(RGBDSensor_nws_yarp) add_subdirectory(RGBDSensor_nws_ros) add_subdirectory(RGBDToPointCloudSensorWrapper) diff --git a/src/devices/README.md b/src/devices/README.md index a18eaacd387..e365c26a7f1 100644 --- a/src/devices/README.md +++ b/src/devices/README.md @@ -78,7 +78,6 @@ The tables shown hereunder report all the information needed to understand the f * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **RGBDSensorFromRosTopic** * RGBDSensorWrapper - * ![#cc6600](https://via.placeholder.com/15/cc6600/000000?text=+) *RGBDSensorWrapper* * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) rgbdSensor_nws_ros * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) rgbdSensor_nws_yarp diff --git a/src/devices/RGBDSensorWrapper/CMakeLists.txt b/src/devices/RGBDSensorWrapper/CMakeLists.txt deleted file mode 100644 index c8c7f6aa93d..00000000000 --- a/src/devices/RGBDSensorWrapper/CMakeLists.txt +++ /dev/null @@ -1,56 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(RGBDSensorWrapper - CATEGORY device - TYPE RGBDSensorWrapper - INCLUDE RGBDSensorWrapper.h - EXTRA_CONFIG - WRAPPER=RGBDSensorWrapper - DEFAULT ON -) - -if(NOT SKIP_RGBDSensorWrapper) - yarp_add_plugin(yarp_RGBDSensorWrapper) - - target_sources(yarp_RGBDSensorWrapper - PRIVATE - RGBDSensorWrapper.cpp - RGBDSensorWrapper.h - ) - - target_sources(yarp_RGBDSensorWrapper PRIVATE $) - target_include_directories(yarp_RGBDSensorWrapper PRIVATE $) - - target_sources(yarp_RGBDSensorWrapper PRIVATE $) - target_include_directories(yarp_RGBDSensorWrapper PRIVATE $) - - target_link_libraries(yarp_RGBDSensorWrapper - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_RGBDSensorWrapper - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_RGBDSensorWrapper PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/RGBDSensorWrapper/RGBDSensorWrapper.cpp b/src/devices/RGBDSensorWrapper/RGBDSensorWrapper.cpp deleted file mode 100644 index 79153ebad1f..00000000000 --- a/src/devices/RGBDSensorWrapper/RGBDSensorWrapper.cpp +++ /dev/null @@ -1,879 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "RGBDSensorWrapper.h" -#include -#include -#include -#include -#include -#include -#include "rosPixelCode.h" -#include -#include - -using namespace RGBDImpl; -using namespace yarp::sig; -using namespace yarp::dev; -using namespace yarp::os; - - -#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1 -#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0 - -YARP_LOG_COMPONENT(RGBDSENSORWRAPPER, "yarp.devices.RGBDSensorWrapper") - - -RGBDSensorParser::RGBDSensorParser() : - iRGBDSensor(nullptr) -{ -} - -bool RGBDSensorParser::configure(IRGBDSensor *interface) -{ - bool ret; - iRGBDSensor = interface; - ret = rgbParser.configure(interface); - ret &= depthParser.configure(interface); - return ret; -} - -bool RGBDSensorParser::configure(IRgbVisualParams *rgbInterface, IDepthVisualParams* depthInterface) -{ - bool ret = rgbParser.configure(rgbInterface); - ret &= depthParser.configure(depthInterface); - return ret; -} - -bool RGBDSensorParser::configure(IFrameGrabberControls *_fgCtrl) -{ - return fgCtrlParsers.configure(_fgCtrl); -} - -bool RGBDSensorParser::respond(const Bottle& cmd, Bottle& response) -{ - bool ret = false; - int interfaceType = cmd.get(0).asVocab32(); - - response.clear(); - switch(interfaceType) - { - case VOCAB_RGB_VISUAL_PARAMS: - { - // forwarding to the proper parser. - ret = rgbParser.respond(cmd, response); - } - break; - - case VOCAB_DEPTH_VISUAL_PARAMS: - { - // forwarding to the proper parser. - ret = depthParser.respond(cmd, response); - } - break; - - case VOCAB_FRAMEGRABBER_CONTROL: - { - // forwarding to the proper parser. - ret = fgCtrlParsers.respond(cmd, response); - } - break; - - case VOCAB_RGBD_SENSOR: - { - switch (cmd.get(1).asVocab32()) - { - case VOCAB_GET: - { - switch(cmd.get(2).asVocab32()) - { - case VOCAB_EXTRINSIC_PARAM: - { - yarp::sig::Matrix params; - ret = iRGBDSensor->getExtrinsicParam(params); - if(ret) - { - yarp::os::Bottle params_b; - response.addVocab32(VOCAB_RGBD_SENSOR); - response.addVocab32(VOCAB_EXTRINSIC_PARAM); - response.addVocab32(VOCAB_IS); - ret &= Property::copyPortable(params, params_b); // will it really work?? - response.append(params_b); - } else { - response.addVocab32(VOCAB_FAILED); - } - } - break; - - case VOCAB_ERROR_MSG: - { - response.addVocab32(VOCAB_RGBD_SENSOR); - response.addVocab32(VOCAB_ERROR_MSG); - response.addVocab32(VOCAB_IS); - response.addString(iRGBDSensor->getLastErrorMsg()); - ret = true; - } - break; - - case VOCAB_RGBD_PROTOCOL_VERSION: - { - response.addVocab32(VOCAB_RGBD_SENSOR); - response.addVocab32(VOCAB_RGBD_PROTOCOL_VERSION); - response.addVocab32(VOCAB_IS); - response.addInt32(RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR); - response.addInt32(RGBD_INTERFACE_PROTOCOL_VERSION_MINOR); - } - break; - - case VOCAB_STATUS: - { - response.addVocab32(VOCAB_RGBD_SENSOR); - response.addVocab32(VOCAB_STATUS); - response.addVocab32(VOCAB_IS); - response.addInt32(iRGBDSensor->getSensorStatus()); - } - break; - - default: - { - yCError(RGBDSENSORWRAPPER) << "Interface parser received an unknown GET command. Command is " << cmd.toString(); - response.addVocab32(VOCAB_FAILED); - } - break; - } - } - break; - - case VOCAB_SET: - { - yCError(RGBDSENSORWRAPPER) << "Interface parser received an unknown SET command. Command is " << cmd.toString(); - response.addVocab32(VOCAB_FAILED); - } - break; - } - } - break; - - default: - { - yCError(RGBDSENSORWRAPPER) << "Received a command for a wrong interface " << yarp::os::Vocab32::decode(interfaceType); - return DeviceResponder::respond(cmd,response); - } - break; - } - return ret; -} - - -RGBDSensorWrapper::RGBDSensorWrapper() : - PeriodicThread(DEFAULT_THREAD_PERIOD), - rosNode(nullptr), - nodeSeq(0), - period(DEFAULT_THREAD_PERIOD), - sensor_p(nullptr), - fgCtrl(nullptr), - sensorStatus(IRGBDSensor::RGBD_SENSOR_NOT_READY), - verbose(4), - use_YARP(true), - use_ROS(false), - forceInfoSync(true), - isSubdeviceOwned(false), - subDeviceOwned(nullptr) -{} - -RGBDSensorWrapper::~RGBDSensorWrapper() -{ - close(); - sensor_p = nullptr; - fgCtrl = nullptr; -} - -/** Device driver interface */ - -bool RGBDSensorWrapper::open(yarp::os::Searchable &config) -{ - yCWarning(RGBDSENSORWRAPPER) << "The 'RGBDSensorWrapper' device is deprecated in favour of 'rgbdSensor_nws_yarp'."; - yCWarning(RGBDSENSORWRAPPER) << "The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4."; - yCWarning(RGBDSENSORWRAPPER) << "Please update your scripts."; - -// DeviceResponder::makeUsage(); -// addUsage("[set] [bri] $fBrightness", "set brightness"); -// addUsage("[set] [expo] $fExposure", "set exposure"); -// - m_conf.fromString(config.toString()); - if (verbose >= 5) { - yCTrace(RGBDSENSORWRAPPER) << "\nParameters are: \n" - << config.toString(); - } - - if(!fromConfig(config)) - { - yCError(RGBDSENSORWRAPPER) << "Failed to open, check previous log for error messages."; - return false; - } - - if(use_YARP && !initialize_YARP(config)) - { - yCError(RGBDSENSORWRAPPER) << sensorId << "Error initializing YARP ports"; - return false; - } - - if(use_ROS && !initialize_ROS(config)) - { - yCError(RGBDSENSORWRAPPER) << sensorId << "Error initializing ROS topic"; - return false; - } - - // check if we need to create subdevice or if they are - // passed later on through attachAll() - if(isSubdeviceOwned) - { - if(! openAndAttachSubDevice(config)) - { - yCError(RGBDSENSORWRAPPER, "Error while opening subdevice"); - return false; - } - } - else - { - if (!openDeferredAttach(config)) { - return false; - } - } - - return true; -} - -bool RGBDSensorWrapper::fromConfig(yarp::os::Searchable &config) -{ - if (!config.check("period", "refresh period of the broadcasted values in ms")) - { - if (verbose >= 3) { - yCInfo(RGBDSENSORWRAPPER) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s"; - } - } else { - period = config.find("period").asInt32() / 1000.0; - } - - Bottle &rosGroup = config.findGroup("ROS"); - if(rosGroup.isNull()) - { - if (verbose >= 3) { - yCInfo(RGBDSENSORWRAPPER) << "ROS configuration parameters are not set, skipping ROS topic initialization."; - } - use_ROS = false; - use_YARP = true; - } - else - { - //if(verbose >= 2) - // yCWarning(RGBDSENSORWRAPPER) << "RGBDSensorWrapper: ROS topic support is not yet implemented"; - - std::string confUseRos; - - if (!rosGroup.check("use_ROS")) - { - yCError(RGBDSENSORWRAPPER)<<"Missing use_ROS parameter"; - return false; - } - - confUseRos = rosGroup.find("use_ROS").asString(); - - if (confUseRos == "true" || confUseRos == "only") - { - use_ROS = true; - use_YARP = confUseRos == "true" ? true : false; - } - else - { - use_ROS = false; - if (verbose >= 3 && confUseRos != "false") - { - yCInfo(RGBDSENSORWRAPPER, "'use_ROS' value not understood.. skipping ROS topic initialization"); - } - } - } - - if (use_ROS) - { - //check if param exist and assign it to corresponding variable.. if it doesn't, initialize the variable with default value. - unsigned int i; - std::vector > rosStringParam; - param* prm; - - rosStringParam.emplace_back(nodeName, nodeName_param ); - rosStringParam.emplace_back(rosFrameId, frameId_param ); - rosStringParam.emplace_back(colorTopicName, colorTopicName_param ); - rosStringParam.emplace_back(depthTopicName, depthTopicName_param ); - rosStringParam.emplace_back(cInfoTopicName, colorInfoTopicName_param); - rosStringParam.emplace_back(dInfoTopicName, depthInfoTopicName_param); - - for (i = 0; i < rosStringParam.size(); i++) - { - prm = &rosStringParam[i]; - if (!rosGroup.check(prm->parname)) - { - if(verbose >= 3) - { - yCError(RGBDSENSORWRAPPER) << "Missing " << prm->parname << "check your configuration file, not using ROS"; - } - use_ROS = false; - return false; - } - *(prm->var) = rosGroup.find(prm->parname).asString(); - } - - if (rosGroup.check("forceInfoSync")) - { - forceInfoSync = rosGroup.find("forceInfoSync").asBool(); - } - } - - if(use_YARP) - { - std::string rootName; - rootName = config.check("name",Value("/"), "starting '/' if needed.").asString(); - - if (!config.check("name", "Prefix name of the ports opened by the RGBD wrapper.")) { - yCError(RGBDSENSORWRAPPER) << "Missing 'name' parameter. Check you configuration file; it must be like:"; - yCError(RGBDSENSORWRAPPER) << " name: Prefix name of the ports opened by the RGBD wrapper, e.g. /robotName/RGBD"; - return false; - } - - rootName = config.find("name").asString(); - rpcPort_Name = rootName + "/rpc:i"; - colorFrame_StreamingPort_Name = rootName + "/rgbImage:o"; - depthFrame_StreamingPort_Name = rootName + "/depthImage:o"; - } - - if(config.check("subdevice")) { - isSubdeviceOwned=true; - } else { - isSubdeviceOwned=false; - } - - return true; -} - -bool RGBDSensorWrapper::openDeferredAttach(Searchable& prop) -{ - // I dunno what to do here now... - isSubdeviceOwned = false; - return true; -} - -bool RGBDSensorWrapper::openAndAttachSubDevice(Searchable& prop) -{ - Property p; - subDeviceOwned = new PolyDriver; - p.fromString(prop.toString()); - - p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring - p.unput("device"); - p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before - - // if errors occurred during open, quit here. - yCDebug(RGBDSENSORWRAPPER, "Opening IRGBDSensor subdevice"); - subDeviceOwned->open(p); - - if (!subDeviceOwned->isValid()) - { - yCError(RGBDSENSORWRAPPER, "Opening IRGBDSensor subdevice... FAILED"); - return false; - } - isSubdeviceOwned = true; - if(!attach(subDeviceOwned)) { - return false; - } - - return true; -} - -bool RGBDSensorWrapper::close() -{ - yCTrace(RGBDSENSORWRAPPER, "Close"); - detachAll(); - - // close subdevice if it was created inside the open (--subdevice option) - if(isSubdeviceOwned) - { - if(subDeviceOwned) - { - delete subDeviceOwned; - subDeviceOwned=nullptr; - } - sensor_p = nullptr; - fgCtrl = nullptr; - isSubdeviceOwned = false; - } - - // Closing port - if(use_YARP) - { - rpcPort.interrupt(); - colorFrame_StreamingPort.interrupt(); - depthFrame_StreamingPort.interrupt(); - - rpcPort.close(); - colorFrame_StreamingPort.close(); - depthFrame_StreamingPort.close(); - } - - if(rosNode!=nullptr) - { - rosNode->interrupt(); - delete rosNode; - rosNode = nullptr; - } - - // Closing ROS topic - if(use_ROS) - { - // bla bla bla - } - // - return true; -} - -/* Helper functions */ - -bool RGBDSensorWrapper::initialize_YARP(yarp::os::Searchable ¶ms) -{ - // Open ports - bool bRet; - bRet = true; - if(!rpcPort.open(rpcPort_Name)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to open rpc Port" << rpcPort_Name.c_str(); - bRet = false; - } - rpcPort.setReader(rgbdParser); - - if(!colorFrame_StreamingPort.open(colorFrame_StreamingPort_Name)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to open color streaming Port" << colorFrame_StreamingPort_Name.c_str(); - bRet = false; - } - if(!depthFrame_StreamingPort.open(depthFrame_StreamingPort_Name)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to open depth streaming Port" << depthFrame_StreamingPort_Name.c_str(); - bRet = false; - } - - return bRet; -} - -bool RGBDSensorWrapper::initialize_ROS(yarp::os::Searchable ¶ms) -{ - // open topics here if needed - rosNode = new yarp::os::Node(nodeName); - nodeSeq = 0; - if (!rosPublisherPort_color.topic(colorTopicName)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << colorTopicName.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - if (!rosPublisherPort_depth.topic(depthTopicName)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << depthTopicName.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - if (!rosPublisherPort_colorCaminfo.topic(cInfoTopicName)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << cInfoTopicName.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - if (!rosPublisherPort_depthCaminfo.topic(dInfoTopicName)) - { - yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << dInfoTopicName.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - return true; -} - -/** - * IWrapper and IMultipleWrapper interfaces - */ -bool RGBDSensorWrapper::attachAll(const PolyDriverList &device2attach) -{ - // First implementation only accepts devices with both the interfaces Framegrabber and IDepthSensor, - // on a second version maybe two different devices could be accepted, one for each interface. - // Yet to be defined which and how parameters shall be used in this case ... using the name of the - // interface to view could be a good initial guess. - if (device2attach.size() != 1) - { - yCError(RGBDSENSORWRAPPER, "Cannot attach more than one device"); - return false; - } - - yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly; - if(device2attach[0]->key == "IRGBDSensor") - { - yCInfo(RGBDSENSORWRAPPER) << "Good name!"; - } - else - { - yCInfo(RGBDSENSORWRAPPER) << "Bad name!"; - } - - if (!Idevice2attach->isValid()) - { - yCError(RGBDSENSORWRAPPER) << "Device " << device2attach[0]->key << " to attach to is not valid ... cannot proceed"; - return false; - } - - Idevice2attach->view(sensor_p); - Idevice2attach->view(fgCtrl); - if (!attach(sensor_p)) { - return false; - } - - PeriodicThread::setPeriod(period); - return PeriodicThread::start(); -} - -bool RGBDSensorWrapper::detachAll() -{ - if (yarp::os::PeriodicThread::isRunning()) { - yarp::os::PeriodicThread::stop(); - } - - //check if we already instantiated a subdevice previously - if (isSubdeviceOwned) { - return false; - } - - sensor_p = nullptr; - return true; -} - -bool RGBDSensorWrapper::attach(yarp::dev::IRGBDSensor *s) -{ - if(s == nullptr) - { - yCError(RGBDSENSORWRAPPER) << "Attached device has no valid IRGBDSensor interface."; - return false; - } - sensor_p = s; - if(!rgbdParser.configure(sensor_p)) - { - yCError(RGBDSENSORWRAPPER) << "Error configuring interfaces for parsers"; - return false; - } - if (fgCtrl) - { - if(!rgbdParser.configure(fgCtrl)) - { - yCError(RGBDSENSORWRAPPER) << "Error configuring interfaces for parsers"; - return false; - } - } - - PeriodicThread::setPeriod(period); - return PeriodicThread::start(); -} - -bool RGBDSensorWrapper::attach(PolyDriver* poly) -{ - if(poly) - { - poly->view(sensor_p); - poly->view(fgCtrl); - } - - if(sensor_p == nullptr) - { - yCError(RGBDSENSORWRAPPER) << "Attached device has no valid IRGBDSensor interface."; - return false; - } - - if(!rgbdParser.configure(sensor_p)) - { - yCError(RGBDSENSORWRAPPER) << "Error configuring IRGBD interface"; - return false; - } - - if (!rgbdParser.configure(fgCtrl)) - { - yCWarning(RGBDSENSORWRAPPER) <<"Interface IFrameGrabberControl not implemented by the device"; - } - - PeriodicThread::setPeriod(period); - return PeriodicThread::start(); -} - -bool RGBDSensorWrapper::detach() -{ - sensor_p = nullptr; - return true; -} - -/* IRateThread interface */ - -bool RGBDSensorWrapper::threadInit() -{ - // Get interface from attached device if any. - return true; -} - -void RGBDSensorWrapper::threadRelease() -{ - // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here! -} - -bool RGBDSensorWrapper::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, const std::string& frame_id, const UInt& seq, const SensorType& sensorType) -{ - double phyF = 0.0; - double fx = 0.0; - double fy = 0.0; - double cx = 0.0; - double cy = 0.0; - double k1 = 0.0; - double k2 = 0.0; - double t1 = 0.0; - double t2 = 0.0; - double k3 = 0.0; - double stamp = 0.0; - - std::string distModel; - std::string currentSensor; - UInt i; - Property camData; - std::vector > parVector; - param* par; - bool ok; - - currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth"; - ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData); - - if (!ok) - { - yCError(RGBDSENSORWRAPPER) << "Unable to get intrinsic param from" << currentSensor << "sensor!"; - return false; - } - - if(!camData.check("distortionModel")) - { - yCWarning(RGBDSENSORWRAPPER) << "Missing distortion model"; - return false; - } - - distModel = camData.find("distortionModel").asString(); - if (distModel != "plumb_bob") - { - yCError(RGBDSENSORWRAPPER) << "Distortion model not supported"; - return false; - } - - //std::vector > rosStringParam; - //rosStringParam.push_back(param(nodeName, "asd")); - - parVector.emplace_back(phyF,"physFocalLength"); - parVector.emplace_back(fx,"focalLengthX"); - parVector.emplace_back(fy,"focalLengthY"); - parVector.emplace_back(cx,"principalPointX"); - parVector.emplace_back(cy,"principalPointY"); - parVector.emplace_back(k1,"k1"); - parVector.emplace_back(k2,"k2"); - parVector.emplace_back(t1,"t1"); - parVector.emplace_back(t2,"t2"); - parVector.emplace_back(k3,"k3"); - parVector.emplace_back(stamp,"stamp"); - for(i = 0; i < parVector.size(); i++) - { - par = &parVector[i]; - - if(!camData.check(par->parname)) - { - yCWarning(RGBDSENSORWRAPPER) << "Driver has not the param:" << par->parname; - return false; - } - *par->var = camData.find(par->parname).asFloat64(); - } - - cameraInfo.header.frame_id = frame_id; - cameraInfo.header.seq = seq; - cameraInfo.header.stamp = stamp; - cameraInfo.width = sensorType == COLOR_SENSOR ? sensor_p->getRgbWidth() : sensor_p->getDepthWidth(); - cameraInfo.height = sensorType == COLOR_SENSOR ? sensor_p->getRgbHeight() : sensor_p->getDepthHeight(); - cameraInfo.distortion_model = distModel; - - cameraInfo.D.resize(5); - cameraInfo.D[0] = k1; - cameraInfo.D[1] = k2; - cameraInfo.D[2] = t1; - cameraInfo.D[3] = t2; - cameraInfo.D[4] = k3; - - cameraInfo.K.resize(9); - cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx; - cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy; - cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1; - - /* - * ROS documentation on cameraInfo message: - * "Rectification matrix (stereo cameras only) - * A rotation matrix aligning the camera coordinate system to the ideal - * stereo image plane so that epipolar lines in both stereo images are - * parallel." - * useless in our case, it will be an identity matrix - */ - - cameraInfo.R.assign(9, 0); - cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1; - - cameraInfo.P.resize(12); - cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0; - cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0; - cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0; - - cameraInfo.binning_x = cameraInfo.binning_y = 0; - cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0; - cameraInfo.roi.do_rectify = false; - return true; -} - -bool RGBDSensorWrapper::writeData() -{ - //colorImage.setPixelCode(VOCAB_PIXEL_RGB); - // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT); - - // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does? - // depthImage.resize(hDim, vDim); - if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp)) - { - return false; - } - - static Stamp oldColorStamp = Stamp(0, 0); - static Stamp oldDepthStamp = Stamp(0, 0); - bool rgb_data_ok = true; - bool depth_data_ok = true; - - if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false) - { - rgb_data_ok=false; - //return true; - } - else { oldColorStamp = colorStamp; } - - if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false) - { - depth_data_ok=false; - //return true; - } - else { oldDepthStamp = depthStamp; } - - - if (use_YARP) - { - // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves. - if (rgb_data_ok) - { - FlexImage& yColorImage = colorFrame_StreamingPort.prepare(); - yarp::dev::RGBDRosConversionUtils::shallowCopyImages(colorImage, yColorImage); - colorFrame_StreamingPort.setEnvelope(colorStamp); - colorFrame_StreamingPort.write(); - } - if (depth_data_ok) - { - ImageOf& yDepthImage = depthFrame_StreamingPort.prepare(); - yarp::dev::RGBDRosConversionUtils::shallowCopyImages(depthImage, yDepthImage); - depthFrame_StreamingPort.setEnvelope(depthStamp); - depthFrame_StreamingPort.write(); - } - } - if (use_ROS) - { - // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves. - if (rgb_data_ok) - { - yarp::rosmsg::sensor_msgs::Image& rColorImage = rosPublisherPort_color.prepare(); - yarp::rosmsg::sensor_msgs::CameraInfo& camInfoC = rosPublisherPort_colorCaminfo.prepare(); - yarp::rosmsg::TickTime cRosStamp = colorStamp.getTime(); - yarp::dev::RGBDRosConversionUtils::deepCopyImages(colorImage, rColorImage, rosFrameId, cRosStamp, nodeSeq); - rosPublisherPort_color.setEnvelope(colorStamp); - rosPublisherPort_color.write(); - if (setCamInfo(camInfoC, rosFrameId, nodeSeq, COLOR_SENSOR)) - { - if(forceInfoSync) - {camInfoC.header.stamp = rColorImage.header.stamp;} - rosPublisherPort_colorCaminfo.setEnvelope(colorStamp); - rosPublisherPort_colorCaminfo.write(); - } - else - { - yCWarning(RGBDSENSORWRAPPER, "Missing color camera parameters... camera info messages will be not sent"); - } - } - if (depth_data_ok) - { - yarp::rosmsg::sensor_msgs::Image& rDepthImage = rosPublisherPort_depth.prepare(); - yarp::rosmsg::sensor_msgs::CameraInfo& camInfoD = rosPublisherPort_depthCaminfo.prepare(); - yarp::rosmsg::TickTime dRosStamp = depthStamp.getTime(); - yarp::dev::RGBDRosConversionUtils::deepCopyImages(depthImage, rDepthImage, rosFrameId, dRosStamp, nodeSeq); - rosPublisherPort_depth.setEnvelope(depthStamp); - rosPublisherPort_depth.write(); - if (setCamInfo(camInfoD, rosFrameId, nodeSeq, DEPTH_SENSOR)) - { - if(forceInfoSync) - {camInfoD.header.stamp = rDepthImage.header.stamp;} - rosPublisherPort_depthCaminfo.setEnvelope(depthStamp); - rosPublisherPort_depthCaminfo.write(); - } - else - { - yCWarning(RGBDSENSORWRAPPER, "Missing depth camera parameters... camera info messages will be not sent"); - } - } - - nodeSeq++; - } - return true; -} - -void RGBDSensorWrapper::run() -{ - if (sensor_p!=nullptr) - { - static int i = 0; - sensorStatus = sensor_p->getSensorStatus(); - switch (sensorStatus) - { - case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) : - { - if (!writeData()) { - yCError(RGBDSENSORWRAPPER, "Image not captured.. check hardware configuration"); - } - i = 0; - } - break; - case(IRGBDSensor::RGBD_SENSOR_NOT_READY): - { - if(i < 1000) { - if((i % 30) == 0) { - yCInfo(RGBDSENSORWRAPPER) << "Device not ready, waiting..."; - } - } else { - yCWarning(RGBDSENSORWRAPPER) << "Device is taking too long to start.."; - } - i++; - } - break; - default: - { - if (verbose >= 1) { // better not to print it every cycle anyway, too noisy - yCError(RGBDSENSORWRAPPER, "%s: Sensor returned error", sensorId.c_str()); - } - } - } - } - else - { - if(verbose >= 6) { - yCError(RGBDSENSORWRAPPER, "%s: Sensor interface is not valid", sensorId.c_str()); - } - } -} diff --git a/src/devices/RGBDSensorWrapper/RGBDSensorWrapper.h b/src/devices/RGBDSensorWrapper/RGBDSensorWrapper.h deleted file mode 100644 index 7c1145e57f2..00000000000 --- a/src/devices/RGBDSensorWrapper/RGBDSensorWrapper.h +++ /dev/null @@ -1,250 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_RGBDSENSORWRAPPER_RGBDSENSORWRAPPER_H -#define YARP_DEV_RGBDSENSORWRAPPER_RGBDSENSORWRAPPER_H - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - - -#include - -#include -#include -#include -#include - -#include -#include -#include - -// ROS stuff -#include -#include -#include -#include -#include -#include - - -namespace RGBDImpl -{ - const std::string frameId_param = "ROS_frame_Id"; - const std::string nodeName_param = "ROS_nodeName"; - const std::string colorTopicName_param = "ROS_colorTopicName"; - const std::string depthTopicName_param = "ROS_depthTopicName"; - const std::string depthInfoTopicName_param = "ROS_depthInfoTopicName"; - const std::string colorInfoTopicName_param = "ROS_colorInfoTopicName"; - class RGBDSensorParser; -} - -#define DEFAULT_THREAD_PERIOD 0.03 // s - -// Following three definitions would fit better in a header file -// shared between client and server ... where to place it? -constexpr yarp::conf::vocab32_t VOCAB_PROTOCOL_VERSION = yarp::os::createVocab32('p', 'r', 'o', 't'); -#define RGBD_WRAPPER_PROTOCOL_VERSION_MAJOR 1 -#define RGBD_WRAPPER_PROTOCOL_VERSION_MINOR 0 - - - -class RGBDImpl::RGBDSensorParser : - public yarp::dev::DeviceResponder -{ -private: - yarp::dev::IRGBDSensor *iRGBDSensor; - yarp::proto::framegrabber::RgbVisualParams_Responder rgbParser; - yarp::proto::framegrabber::DepthVisualParams_Responder depthParser; - yarp::proto::framegrabber::FrameGrabberControls_Responder fgCtrlParsers; - -public: - RGBDSensorParser(); - ~RGBDSensorParser() override = default; - bool configure(yarp::dev::IRGBDSensor *interface); - bool configure(yarp::dev::IRgbVisualParams *rgbInterface, yarp::dev::IDepthVisualParams *depthInterface); - bool configure(yarp::dev::IFrameGrabberControls *_fgCtrl); - bool respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& response) override; -}; - - -/** - * @ingroup dev_impl_wrapper dev_impl_deprecated - * - * \section RGBDSensorWrapper_device_parameters Description of input parameters - * - * \brief `RGBDSensorWrapper` *deprecated*: A Network grabber for kinect-like devices. - * - * This device will produce two streams of data through different ports, one for the color frame and the other one - * for depth image following Framegrabber and IDepthSensor interfaces specification respectively. - * See they documentation for more details about each interface. - * - * This device is paired with its client called RGBDSensorWrapper to receive the data streams and perform remote operations. - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:-----------------------------: |:---------------------------------------------------------------------------------------------------:|:-----:| - * | period | - | int | ms | 20 | No | refresh period of the broadcasted values in ms | default 20ms | - * | name | - | string | - | - | Yes, unless useROS='only' | Prefix name of the ports opened by the RGBD wrapper, e.g. /robotName/RGBD | Required suffix like '/rpc' will be added by the device | - * | subdevice | - | string | - | - | alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | - * | ROS | - | group | - | - | No | Group containing parameter for ROS topic initialization | if missing, it is assumed to not use ROS topics | - * | - | use_ROS | string | true/false/only| - | if ROS group is present | set 'true' to have both yarp ports and ROS topic, set 'only' to have only ROS topic and no yarp port| - | - * | - | forceInfoSync | string | bool | - | no | set 'true' to force the timestamp on the camera_info message to match the image one | - | - * | - | ROS_colorTopicName | string | - | - | if ROS group is present | set the name for ROS image topic | must start with a leading '/' | - * | - | ROS_depthTopicName | string | - | - | if ROS group is present | set the name for ROS depth topic | must start with a leading '/' | - * | - | ROS_colorInfoTopicName | string | - | - | if ROS group is present | set the name for ROS imageInfo topic | must start with a leading '/' | - * | - | ROS_depthInfoTopicName | string | - | - | if ROS group is present | set the name for ROS depthInfo topic | must start with a leading '/' | - * | - | ROS_frame_Id | string | - | | if ROS group is present | set the name of the reference frame | | - * | - | ROS_nodeName | string | - | - | if ROS group is present | set the name for ROS node | must start with a leading '/' | - * - * ROS message type used is sensor_msgs/Image.msg ( http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) - * Some example of configuration files: - * - * Example of configuration file using .ini format. - * - * \code{.unparsed} - * device RGBDSensorWrapper - * subdevice - * period 30 - * name //RGBDSensor - * \endcode - */ - -class RGBDSensorWrapper : - public yarp::dev::DeviceDriver, - public yarp::dev::IWrapper, - public yarp::dev::IMultipleWrapper, - public yarp::os::PeriodicThread -{ -private: - typedef yarp::sig::ImageOf DepthImage; - typedef yarp::os::BufferedPort DepthPortType; - typedef yarp::os::BufferedPort ImagePortType; - typedef yarp::os::Publisher ImageTopicType; - typedef yarp::os::Publisher DepthTopicType; - typedef unsigned int UInt; - - enum SensorType{COLOR_SENSOR, DEPTH_SENSOR}; - - template - struct param - { - param(T& inVar, std::string inName) - { - var = &inVar; - parname = inName; - } - T* var; - std::string parname; - }; - - std::string colorFrame_StreamingPort_Name; - std::string depthFrame_StreamingPort_Name; - ImagePortType colorFrame_StreamingPort; - DepthPortType depthFrame_StreamingPort; - - // One RPC port should be enough for the wrapper in all cases - yarp::os::Port rpcPort; - std::string rpcPort_Name; - ImageTopicType rosPublisherPort_color; - ImageTopicType rosPublisherPort_depth; - DepthTopicType rosPublisherPort_colorCaminfo; - DepthTopicType rosPublisherPort_depthCaminfo; - yarp::os::Node* rosNode; - std::string nodeName; - std::string depthTopicName; - std::string colorTopicName; - std::string dInfoTopicName; - std::string cInfoTopicName; - std::string rosFrameId; - yarp::sig::FlexImage colorImage; - DepthImage depthImage; - UInt nodeSeq; - - // It should be possible to attach this guy to more than one port, try to see what - // will happen when receiving 2 calls at the same time (receive one calls while serving - // another one, it will result in concurrent thread most probably) and buffering issues. -// sensor::depth::RGBDSensor_RPCMgsParser RPC_parser; - - //Helper class for RPCs - RGBDImpl::RGBDSensorParser rgbdParser; - - // Image data specs - // int hDim, vDim; - double period; - std::string sensorId; - yarp::dev::IRGBDSensor* sensor_p; - yarp::dev::IFrameGrabberControls* fgCtrl; - yarp::dev::IRGBDSensor::RGBDSensor_status sensorStatus; - int verbose; - bool use_YARP; - bool use_ROS; - bool forceInfoSync; - bool initialize_YARP(yarp::os::Searchable& config); - bool initialize_ROS(yarp::os::Searchable& config); - bool read(yarp::os::ConnectionReader& connection); - - // Open the wrapper only, the attach method needs to be called before using it - // Typical usage: yarprobotinterface - bool openDeferredAttach(yarp::os::Searchable& prop); - - // If a subdevice parameter is given, the wrapper will open it and attach to immediately. - // Typical usage: simulator or command line - bool isSubdeviceOwned; - yarp::dev::PolyDriver* subDeviceOwned; - bool openAndAttachSubDevice(yarp::os::Searchable& prop); - - // Synch - yarp::os::Stamp colorStamp; - yarp::os::Stamp depthStamp; - yarp::os::Property m_conf; - - bool writeData(); - bool setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, - const std::string& frame_id, - const UInt& seq, - const SensorType& sensorType); - - static std::string yarp2RosPixelCode(int code); - -public: - RGBDSensorWrapper(); - RGBDSensorWrapper(const RGBDSensorWrapper&) = delete; - RGBDSensorWrapper(RGBDSensorWrapper&&) = delete; - RGBDSensorWrapper& operator=(const RGBDSensorWrapper&) = delete; - RGBDSensorWrapper& operator=(RGBDSensorWrapper&&) = delete; - ~RGBDSensorWrapper() override; - - bool open(yarp::os::Searchable ¶ms) override; - bool fromConfig(yarp::os::Searchable ¶ms); - bool close() override; - - /** - * Specify which sensor this thread has to read from. - */ - bool attachAll(const yarp::dev::PolyDriverList &p) override; - bool detachAll() override; - - bool attach(yarp::dev::PolyDriver *poly) override; - bool attach(yarp::dev::IRGBDSensor *s); - bool detach() override; - - bool threadInit() override; - void threadRelease() override; - void run() override; -}; - -#endif // YARP_DEV_RGBDSENSORWRAPPER_RGBDSENSORWRAPPER_H From f0d75954843bc651481cea77f8b9e1667f14ac88 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 20:08:33 +0100 Subject: [PATCH 005/267] most of ros-related devices moved to devices/ROS subfolder. They will moved away from the yarp repo soon. --- src/devices/CMakeLists.txt | 13 +-- src/devices/README.md | 6 -- .../ControlBoard_nws_ros/CMakeLists.txt | 0 .../ControlBoard_nws_ros.cpp | 0 .../ControlBoard_nws_ros.h | 0 .../ROS/FrameGrabber_nws_ros/CMakeLists.txt | 52 +++++++++ .../FrameGrabber_nws_ros.cpp | 0 .../FrameGrabber_nws_ros.h | 0 .../RGBDRosConversionUtils/CMakeLists.txt | 0 .../RGBDRosConversionUtils.cpp | 0 .../RGBDRosConversionUtils.h | 0 .../RGBDRosConversionUtils/rosPixelCode.cpp | 0 .../RGBDRosConversionUtils/rosPixelCode.h | 0 .../RGBDSensorFromRosTopic/CMakeLists.txt | 0 .../RGBDSensorFromRosTopic.cpp | 0 .../RGBDSensorFromRosTopic.h | 0 .../RGBDSensor_nws_ros/CMakeLists.txt | 0 .../RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp | 0 .../RGBDSensor_nws_ros/RgbdSensor_nws_ros.h | 0 .../CMakeLists.txt | 0 .../RGBDToPointCloudSensor_nws_ros.cpp | 0 .../RGBDToPointCloudSensor_nws_ros.h | 0 .../Rangefinder2D_nws_ros/CMakeLists.txt | 0 .../Rangefinder2D_nws_ros.cpp | 0 .../Rangefinder2D_nws_ros.h | 0 .../laserFromRosTopic/CMakeLists.txt | 0 .../laserFromRosTopic/LaserFromRosTopic.cpp | 0 .../laserFromRosTopic/LaserFromRosTopic.h | 0 .../localization2D_nws_ros/CMakeLists.txt | 0 .../Localization2D_nws_ros.cpp | 0 .../Localization2D_nws_ros.h | 0 .../{ => ROS}/map2D_nws_ros/CMakeLists.txt | 0 .../{ => ROS}/map2D_nws_ros/Map2D_nws_ros.cpp | 0 .../{ => ROS}/map2D_nws_ros/Map2D_nws_ros.h | 0 .../CMakeLists.txt | 0 .../MobileBaseVelocityControl_nws_ros.cpp | 0 .../MobileBaseVelocityControl_nws_ros.h | 0 .../CMakeLists.txt | 0 .../GenericSensorRosPublisher.h | 0 .../IMURosPublisher.cpp | 0 .../IMURosPublisher.h | 0 .../MagneticFieldRosPublisher.cpp | 0 .../MagneticFieldRosPublisher.h | 0 .../PoseStampedRosPublisher.cpp | 0 .../PoseStampedRosPublisher.h | 0 .../TemperatureRosPublisher.cpp | 0 .../TemperatureRosPublisher.h | 0 .../WrenchStampedRosPublisher.cpp | 0 .../WrenchStampedRosPublisher.h | 0 .../odometry2D_nws_ros/CMakeLists.txt | 0 .../odometry2D_nws_ros/Odometry2D_nws_ros.cpp | 0 .../odometry2D_nws_ros/Odometry2D_nws_ros.h | 0 .../ServerFrameGrabberDual/CMakeLists.txt | 100 ------------------ .../frameGrabber_nws_yarp/CMakeLists.txt | 49 +++++++++ .../FrameGrabber_nws_yarp.cpp | 0 .../FrameGrabber_nws_yarp.h | 0 56 files changed, 102 insertions(+), 118 deletions(-) rename src/devices/{ => ROS}/ControlBoard_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp (100%) rename src/devices/{ => ROS}/ControlBoard_nws_ros/ControlBoard_nws_ros.h (100%) create mode 100644 src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt rename src/devices/{ServerFrameGrabberDual => ROS/FrameGrabber_nws_ros}/FrameGrabber_nws_ros.cpp (100%) rename src/devices/{ServerFrameGrabberDual => ROS/FrameGrabber_nws_ros}/FrameGrabber_nws_ros.h (100%) rename src/devices/{ => ROS}/RGBDRosConversionUtils/CMakeLists.txt (100%) rename src/devices/{ => ROS}/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp (100%) rename src/devices/{ => ROS}/RGBDRosConversionUtils/RGBDRosConversionUtils.h (100%) rename src/devices/{ => ROS}/RGBDRosConversionUtils/rosPixelCode.cpp (100%) rename src/devices/{ => ROS}/RGBDRosConversionUtils/rosPixelCode.h (100%) rename src/devices/{ => ROS}/RGBDSensorFromRosTopic/CMakeLists.txt (100%) rename src/devices/{ => ROS}/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp (100%) rename src/devices/{ => ROS}/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h (100%) rename src/devices/{ => ROS}/RGBDSensor_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp (100%) rename src/devices/{ => ROS}/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h (100%) rename src/devices/{RGBDToPointCloudSensorWrapper => ROS/RGBDToPointCloudSensor_nws_ros}/CMakeLists.txt (100%) rename src/devices/{RGBDToPointCloudSensorWrapper => ROS/RGBDToPointCloudSensor_nws_ros}/RGBDToPointCloudSensor_nws_ros.cpp (100%) rename src/devices/{RGBDToPointCloudSensorWrapper => ROS/RGBDToPointCloudSensor_nws_ros}/RGBDToPointCloudSensor_nws_ros.h (100%) rename src/devices/{ => ROS}/Rangefinder2D_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp (100%) rename src/devices/{ => ROS}/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h (100%) rename src/devices/{ => ROS}/laserFromRosTopic/CMakeLists.txt (100%) rename src/devices/{ => ROS}/laserFromRosTopic/LaserFromRosTopic.cpp (100%) rename src/devices/{ => ROS}/laserFromRosTopic/LaserFromRosTopic.h (100%) rename src/devices/{ => ROS}/localization2D_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/localization2D_nws_ros/Localization2D_nws_ros.cpp (100%) rename src/devices/{ => ROS}/localization2D_nws_ros/Localization2D_nws_ros.h (100%) rename src/devices/{ => ROS}/map2D_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/map2D_nws_ros/Map2D_nws_ros.cpp (100%) rename src/devices/{ => ROS}/map2D_nws_ros/Map2D_nws_ros.h (100%) rename src/devices/{ => ROS}/mobileBaseVelocityControl_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp (100%) rename src/devices/{ => ROS}/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/CMakeLists.txt (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/IMURosPublisher.h (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp (100%) rename src/devices/{ => ROS}/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h (100%) rename src/devices/{ => ROS}/odometry2D_nws_ros/CMakeLists.txt (100%) rename src/devices/{ => ROS}/odometry2D_nws_ros/Odometry2D_nws_ros.cpp (100%) rename src/devices/{ => ROS}/odometry2D_nws_ros/Odometry2D_nws_ros.h (100%) create mode 100644 src/devices/frameGrabber_nws_yarp/CMakeLists.txt rename src/devices/{ServerFrameGrabberDual => frameGrabber_nws_yarp}/FrameGrabber_nws_yarp.cpp (100%) rename src/devices/{ServerFrameGrabberDual => frameGrabber_nws_yarp}/FrameGrabber_nws_yarp.h (100%) diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index 0697dd4a569..fbc9b257c24 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -30,6 +30,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(frameTransformStorageMsgs) add_subdirectory(frameTransformStorage) add_subdirectory(frameTransformUtils) + add_subdirectory(FrameGrabber_nws_yarp) add_subdirectory(transformClient) add_subdirectory(transformServer) add_subdirectory(SerialServoBoard) @@ -50,7 +51,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(laserFromDepth) add_subdirectory(laserFromPointCloud) add_subdirectory(laserFromExternalPort) - add_subdirectory(laserFromRosTopic) add_subdirectory(laserHokuyo) add_subdirectory(fakeFrameGrabber) add_subdirectory(SDLJoypad) @@ -58,27 +58,21 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(batteryWrapper) add_subdirectory(upowerBattery) add_subdirectory(Rangefinder2D_nws_yarp) - add_subdirectory(Rangefinder2D_nws_ros) add_subdirectory(mobileBaseVelocityControl_nwc_yarp) add_subdirectory(mobileBaseVelocityControl_nws_yarp) - add_subdirectory(mobileBaseVelocityControl_nws_ros) add_subdirectory(mobileBaseVelocityControlMsgs) add_subdirectory(multipleAnalogSensorsMsgs) add_subdirectory(multipleanalogsensorsserver) add_subdirectory(multipleanalogsensorsclient) add_subdirectory(multipleanalogsensorsremapper) - add_subdirectory(multipleAnalogSensorsRosPublishers) add_subdirectory(localization2D_nwc_yarp) add_subdirectory(localization2D_nws_yarp) - add_subdirectory(localization2D_nws_ros) add_subdirectory(map2D_nwc_yarp) add_subdirectory(map2D_nws_yarp) - add_subdirectory(map2D_nws_ros) add_subdirectory(map2DStorage) add_subdirectory(navigation2D_nwc_yarp) add_subdirectory(navigation2D_nws_yarp) add_subdirectory(odometry2D_nws_yarp) - add_subdirectory(odometry2D_nws_ros) add_subdirectory(Rangefinder2DClient) add_subdirectory(usbCamera) add_subdirectory(fakeLocalizerDevice) @@ -91,15 +85,10 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(AnalogSensorClient) add_subdirectory(AnalogWrapper) add_subdirectory(VirtualAnalogWrapper) - add_subdirectory(RGBDRosConversionUtils) add_subdirectory(RGBDSensorClient) add_subdirectory(ServerInertial) add_subdirectory(RGBDSensor_nws_yarp) - add_subdirectory(RGBDSensor_nws_ros) - add_subdirectory(RGBDToPointCloudSensorWrapper) - add_subdirectory(RGBDSensorFromRosTopic) add_subdirectory(ControlBoardWrapper) - add_subdirectory(ControlBoard_nws_ros) add_subdirectory(ControlBoardRemapper) add_subdirectory(RobotDescriptionClient) add_subdirectory(RobotDescriptionServer) diff --git a/src/devices/README.md b/src/devices/README.md index e365c26a7f1..5d5870bdc46 100644 --- a/src/devices/README.md +++ b/src/devices/README.md @@ -74,16 +74,10 @@ The tables shown hereunder report all the information needed to understand the f * RGBDSensorClient * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **RGBDSensorClient** -* RGBDSensorFromRosTopic - * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **RGBDSensorFromRosTopic** - * RGBDSensorWrapper * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) rgbdSensor_nws_ros * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) rgbdSensor_nws_yarp -* RGBDToPointCloudSensorWrapper - * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) RGBDToPointCloudSensor_nws_ros - * Rangefinder2DClient * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **Rangefinder2DClient** diff --git a/src/devices/ControlBoard_nws_ros/CMakeLists.txt b/src/devices/ROS/ControlBoard_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/ControlBoard_nws_ros/CMakeLists.txt rename to src/devices/ROS/ControlBoard_nws_ros/CMakeLists.txt diff --git a/src/devices/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp b/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp similarity index 100% rename from src/devices/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp rename to src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp diff --git a/src/devices/ControlBoard_nws_ros/ControlBoard_nws_ros.h b/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.h similarity index 100% rename from src/devices/ControlBoard_nws_ros/ControlBoard_nws_ros.h rename to src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.h diff --git a/src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt b/src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt new file mode 100644 index 00000000000..9329963d1b2 --- /dev/null +++ b/src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt @@ -0,0 +1,52 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + + +yarp_prepare_plugin(frameGrabber_nws_ros + CATEGORY device + TYPE FrameGrabber_nws_ros + INCLUDE FrameGrabber_nws_ros.h + EXTRA_CONFIG + WRAPPER=frameGrabber_nws_ros + DEFAULT ON +) + +if(NOT SKIP_frameGrabber_nws_ros) + yarp_add_plugin(yarp_frameGrabber_nws_ros) + + target_sources(yarp_frameGrabber_nws_ros + PRIVATE + FrameGrabber_nws_ros.cpp + FrameGrabber_nws_ros.h + ) + + target_sources(yarp_frameGrabber_nws_ros PRIVATE $) + target_include_directories(yarp_frameGrabber_nws_ros PRIVATE $) + + target_link_libraries(yarp_frameGrabber_nws_ros + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_rosmsg + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + YARP_rosmsg + ) + + yarp_install( + TARGETS yarp_frameGrabber_nws_ros + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameGrabber_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") +endif() diff --git a/src/devices/ServerFrameGrabberDual/FrameGrabber_nws_ros.cpp b/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.cpp similarity index 100% rename from src/devices/ServerFrameGrabberDual/FrameGrabber_nws_ros.cpp rename to src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.cpp diff --git a/src/devices/ServerFrameGrabberDual/FrameGrabber_nws_ros.h b/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.h similarity index 100% rename from src/devices/ServerFrameGrabberDual/FrameGrabber_nws_ros.h rename to src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.h diff --git a/src/devices/RGBDRosConversionUtils/CMakeLists.txt b/src/devices/ROS/RGBDRosConversionUtils/CMakeLists.txt similarity index 100% rename from src/devices/RGBDRosConversionUtils/CMakeLists.txt rename to src/devices/ROS/RGBDRosConversionUtils/CMakeLists.txt diff --git a/src/devices/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp b/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp similarity index 100% rename from src/devices/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp rename to src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp diff --git a/src/devices/RGBDRosConversionUtils/RGBDRosConversionUtils.h b/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.h similarity index 100% rename from src/devices/RGBDRosConversionUtils/RGBDRosConversionUtils.h rename to src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.h diff --git a/src/devices/RGBDRosConversionUtils/rosPixelCode.cpp b/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.cpp similarity index 100% rename from src/devices/RGBDRosConversionUtils/rosPixelCode.cpp rename to src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.cpp diff --git a/src/devices/RGBDRosConversionUtils/rosPixelCode.h b/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.h similarity index 100% rename from src/devices/RGBDRosConversionUtils/rosPixelCode.h rename to src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.h diff --git a/src/devices/RGBDSensorFromRosTopic/CMakeLists.txt b/src/devices/ROS/RGBDSensorFromRosTopic/CMakeLists.txt similarity index 100% rename from src/devices/RGBDSensorFromRosTopic/CMakeLists.txt rename to src/devices/ROS/RGBDSensorFromRosTopic/CMakeLists.txt diff --git a/src/devices/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp b/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp similarity index 100% rename from src/devices/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp rename to src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp diff --git a/src/devices/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h b/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h similarity index 100% rename from src/devices/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h rename to src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h diff --git a/src/devices/RGBDSensor_nws_ros/CMakeLists.txt b/src/devices/ROS/RGBDSensor_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/RGBDSensor_nws_ros/CMakeLists.txt rename to src/devices/ROS/RGBDSensor_nws_ros/CMakeLists.txt diff --git a/src/devices/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp b/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp similarity index 100% rename from src/devices/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp rename to src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp diff --git a/src/devices/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h b/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h similarity index 100% rename from src/devices/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h rename to src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h diff --git a/src/devices/RGBDToPointCloudSensorWrapper/CMakeLists.txt b/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/RGBDToPointCloudSensorWrapper/CMakeLists.txt rename to src/devices/ROS/RGBDToPointCloudSensor_nws_ros/CMakeLists.txt diff --git a/src/devices/RGBDToPointCloudSensorWrapper/RGBDToPointCloudSensor_nws_ros.cpp b/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.cpp similarity index 100% rename from src/devices/RGBDToPointCloudSensorWrapper/RGBDToPointCloudSensor_nws_ros.cpp rename to src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.cpp diff --git a/src/devices/RGBDToPointCloudSensorWrapper/RGBDToPointCloudSensor_nws_ros.h b/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h similarity index 100% rename from src/devices/RGBDToPointCloudSensorWrapper/RGBDToPointCloudSensor_nws_ros.h rename to src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h diff --git a/src/devices/Rangefinder2D_nws_ros/CMakeLists.txt b/src/devices/ROS/Rangefinder2D_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/Rangefinder2D_nws_ros/CMakeLists.txt rename to src/devices/ROS/Rangefinder2D_nws_ros/CMakeLists.txt diff --git a/src/devices/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp b/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp similarity index 100% rename from src/devices/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp rename to src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp diff --git a/src/devices/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h b/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h similarity index 100% rename from src/devices/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h rename to src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h diff --git a/src/devices/laserFromRosTopic/CMakeLists.txt b/src/devices/ROS/laserFromRosTopic/CMakeLists.txt similarity index 100% rename from src/devices/laserFromRosTopic/CMakeLists.txt rename to src/devices/ROS/laserFromRosTopic/CMakeLists.txt diff --git a/src/devices/laserFromRosTopic/LaserFromRosTopic.cpp b/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.cpp similarity index 100% rename from src/devices/laserFromRosTopic/LaserFromRosTopic.cpp rename to src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.cpp diff --git a/src/devices/laserFromRosTopic/LaserFromRosTopic.h b/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.h similarity index 100% rename from src/devices/laserFromRosTopic/LaserFromRosTopic.h rename to src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.h diff --git a/src/devices/localization2D_nws_ros/CMakeLists.txt b/src/devices/ROS/localization2D_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/localization2D_nws_ros/CMakeLists.txt rename to src/devices/ROS/localization2D_nws_ros/CMakeLists.txt diff --git a/src/devices/localization2D_nws_ros/Localization2D_nws_ros.cpp b/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.cpp similarity index 100% rename from src/devices/localization2D_nws_ros/Localization2D_nws_ros.cpp rename to src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.cpp diff --git a/src/devices/localization2D_nws_ros/Localization2D_nws_ros.h b/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.h similarity index 100% rename from src/devices/localization2D_nws_ros/Localization2D_nws_ros.h rename to src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.h diff --git a/src/devices/map2D_nws_ros/CMakeLists.txt b/src/devices/ROS/map2D_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/map2D_nws_ros/CMakeLists.txt rename to src/devices/ROS/map2D_nws_ros/CMakeLists.txt diff --git a/src/devices/map2D_nws_ros/Map2D_nws_ros.cpp b/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.cpp similarity index 100% rename from src/devices/map2D_nws_ros/Map2D_nws_ros.cpp rename to src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.cpp diff --git a/src/devices/map2D_nws_ros/Map2D_nws_ros.h b/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h similarity index 100% rename from src/devices/map2D_nws_ros/Map2D_nws_ros.h rename to src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h diff --git a/src/devices/mobileBaseVelocityControl_nws_ros/CMakeLists.txt b/src/devices/ROS/mobileBaseVelocityControl_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/mobileBaseVelocityControl_nws_ros/CMakeLists.txt rename to src/devices/ROS/mobileBaseVelocityControl_nws_ros/CMakeLists.txt diff --git a/src/devices/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp b/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp similarity index 100% rename from src/devices/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp rename to src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp diff --git a/src/devices/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h b/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h similarity index 100% rename from src/devices/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h rename to src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h diff --git a/src/devices/multipleAnalogSensorsRosPublishers/CMakeLists.txt b/src/devices/ROS/multipleAnalogSensorsRosPublishers/CMakeLists.txt similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/CMakeLists.txt rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/CMakeLists.txt diff --git a/src/devices/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h diff --git a/src/devices/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp diff --git a/src/devices/multipleAnalogSensorsRosPublishers/IMURosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.h similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/IMURosPublisher.h rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.h diff --git a/src/devices/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp diff --git a/src/devices/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h diff --git a/src/devices/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp diff --git a/src/devices/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h diff --git a/src/devices/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp diff --git a/src/devices/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h diff --git a/src/devices/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp diff --git a/src/devices/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h similarity index 100% rename from src/devices/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h rename to src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h diff --git a/src/devices/odometry2D_nws_ros/CMakeLists.txt b/src/devices/ROS/odometry2D_nws_ros/CMakeLists.txt similarity index 100% rename from src/devices/odometry2D_nws_ros/CMakeLists.txt rename to src/devices/ROS/odometry2D_nws_ros/CMakeLists.txt diff --git a/src/devices/odometry2D_nws_ros/Odometry2D_nws_ros.cpp b/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.cpp similarity index 100% rename from src/devices/odometry2D_nws_ros/Odometry2D_nws_ros.cpp rename to src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.cpp diff --git a/src/devices/odometry2D_nws_ros/Odometry2D_nws_ros.h b/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.h similarity index 100% rename from src/devices/odometry2D_nws_ros/Odometry2D_nws_ros.h rename to src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.h diff --git a/src/devices/ServerFrameGrabberDual/CMakeLists.txt b/src/devices/ServerFrameGrabberDual/CMakeLists.txt index 2617ca1b9f0..273bcc2018d 100644 --- a/src/devices/ServerFrameGrabberDual/CMakeLists.txt +++ b/src/devices/ServerFrameGrabberDual/CMakeLists.txt @@ -48,103 +48,3 @@ if(NOT SKIP_grabberDual) set_property(TARGET yarp_grabberDual PROPERTY FOLDER "Plugins/Device") endif() - - - -yarp_prepare_plugin(frameGrabber_nws_yarp - CATEGORY device - TYPE FrameGrabber_nws_yarp - INCLUDE FrameGrabber_nws_yarp.h - EXTRA_CONFIG - WRAPPER=frameGrabber_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameGrabber_nws_yarp) - yarp_add_plugin(yarp_frameGrabber_nws_yarp) - - target_sources(yarp_frameGrabber_nws_yarp - PRIVATE - FrameGrabber_nws_yarp.cpp - FrameGrabber_nws_yarp.h - ) - - target_sources(yarp_frameGrabber_nws_yarp PRIVATE $) - target_include_directories(yarp_frameGrabber_nws_yarp PRIVATE $) - - target_link_libraries(yarp_frameGrabber_nws_yarp - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_frameGrabber_nws_yarp - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameGrabber_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") -endif() - - - -yarp_prepare_plugin(frameGrabber_nws_ros - CATEGORY device - TYPE FrameGrabber_nws_ros - INCLUDE FrameGrabber_nws_ros.h - EXTRA_CONFIG - WRAPPER=frameGrabber_nws_ros - DEFAULT ON -) - -if(NOT SKIP_frameGrabber_nws_ros) - yarp_add_plugin(yarp_frameGrabber_nws_ros) - - target_sources(yarp_frameGrabber_nws_ros - PRIVATE - FrameGrabber_nws_ros.cpp - FrameGrabber_nws_ros.h - ) - - target_sources(yarp_frameGrabber_nws_ros PRIVATE $) - target_include_directories(yarp_frameGrabber_nws_ros PRIVATE $) - - target_link_libraries(yarp_frameGrabber_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_frameGrabber_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameGrabber_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/frameGrabber_nws_yarp/CMakeLists.txt b/src/devices/frameGrabber_nws_yarp/CMakeLists.txt new file mode 100644 index 00000000000..d797b3dd7d0 --- /dev/null +++ b/src/devices/frameGrabber_nws_yarp/CMakeLists.txt @@ -0,0 +1,49 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +yarp_prepare_plugin(frameGrabber_nws_yarp + CATEGORY device + TYPE FrameGrabber_nws_yarp + INCLUDE FrameGrabber_nws_yarp.h + EXTRA_CONFIG + WRAPPER=frameGrabber_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_frameGrabber_nws_yarp) + yarp_add_plugin(yarp_frameGrabber_nws_yarp) + + target_sources(yarp_frameGrabber_nws_yarp + PRIVATE + FrameGrabber_nws_yarp.cpp + FrameGrabber_nws_yarp.h + ) + + target_sources(yarp_frameGrabber_nws_yarp PRIVATE $) + target_include_directories(yarp_frameGrabber_nws_yarp PRIVATE $) + + target_link_libraries(yarp_frameGrabber_nws_yarp + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + ) + + yarp_install( + TARGETS yarp_frameGrabber_nws_yarp + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameGrabber_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") +endif() diff --git a/src/devices/ServerFrameGrabberDual/FrameGrabber_nws_yarp.cpp b/src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.cpp similarity index 100% rename from src/devices/ServerFrameGrabberDual/FrameGrabber_nws_yarp.cpp rename to src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.cpp diff --git a/src/devices/ServerFrameGrabberDual/FrameGrabber_nws_yarp.h b/src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.h similarity index 100% rename from src/devices/ServerFrameGrabberDual/FrameGrabber_nws_yarp.h rename to src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.h From 68407ba27598fac567968ff010992ef5296c2bb6 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 20:23:34 +0100 Subject: [PATCH 006/267] removed deprecated device ServerInertial. multipleanalogsensorsserver should be used instead. --- src/devices/CMakeLists.txt | 1 - src/devices/README.md | 3 - src/devices/ServerInertial/CMakeLists.txt | 49 -- src/devices/ServerInertial/ServerInertial.cpp | 569 ------------------ src/devices/ServerInertial/ServerInertial.h | 200 ------ 5 files changed, 822 deletions(-) delete mode 100644 src/devices/ServerInertial/CMakeLists.txt delete mode 100644 src/devices/ServerInertial/ServerInertial.cpp delete mode 100644 src/devices/ServerInertial/ServerInertial.h diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index fbc9b257c24..b70a7fbdf16 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -86,7 +86,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(AnalogWrapper) add_subdirectory(VirtualAnalogWrapper) add_subdirectory(RGBDSensorClient) - add_subdirectory(ServerInertial) add_subdirectory(RGBDSensor_nws_yarp) add_subdirectory(ControlBoardWrapper) add_subdirectory(ControlBoardRemapper) diff --git a/src/devices/README.md b/src/devices/README.md index 5d5870bdc46..0789a30a9c7 100644 --- a/src/devices/README.md +++ b/src/devices/README.md @@ -113,9 +113,6 @@ The tables shown hereunder report all the information needed to understand the f * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nws_yarp * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nws_ros -* ServerInertial - * ![#cc6600](https://via.placeholder.com/15/cc6600/000000?text=+) *inertial* - * ServerSerial * ![#ffff00](https://via.placeholder.com/15/ffff00/000000?text=+) serial diff --git a/src/devices/ServerInertial/CMakeLists.txt b/src/devices/ServerInertial/CMakeLists.txt deleted file mode 100644 index 2f114f74186..00000000000 --- a/src/devices/ServerInertial/CMakeLists.txt +++ /dev/null @@ -1,49 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(inertial - CATEGORY device - TYPE ServerInertial - INCLUDE ServerInertial.h - EXTRA_CONFIG - WRAPPER=inertial - DEFAULT ON -) - -if(NOT SKIP_inertial) - yarp_add_plugin(yarp_inertial) - - target_sources(yarp_inertial - PRIVATE - ServerInertial.cpp - ServerInertial.h - ) - - target_link_libraries(yarp_inertial - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_inertial - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_inertial PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/ServerInertial/ServerInertial.cpp b/src/devices/ServerInertial/ServerInertial.cpp deleted file mode 100644 index 3d366a61116..00000000000 --- a/src/devices/ServerInertial/ServerInertial.cpp +++ /dev/null @@ -1,569 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "ServerInertial.h" -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -using namespace yarp::dev; -using namespace yarp::os; - -YARP_LOG_COMPONENT(SERVERINERTIAL, "yarp.devices.ServerInertial") - - -/** - * Constructor. - */ -ServerInertial::ServerInertial() : - IMU_polydriver(nullptr), - ownDevices(false), - subDeviceOwned(nullptr) -{ - IMU = nullptr; - spoke = false; - iTimed=nullptr; - period = 0.005; - prev_timestamp_counter=0; - curr_timestamp_counter=0; - trap = 0; - strict = false; - partName = "Server Inertial"; - - // init ROS data - frame_id = ""; - rosNodeName = ""; - rosTopicName = ""; - rosNode = nullptr; - rosMsgCounter = 0; - useROS = ROS_disabled; - - // init a fake covariance matrix - covariance.resize(9); - covariance.assign(9, 0); - -// rosData.angular_velocity.x = 0; -// rosData.angular_velocity.y = 0; -// rosData.angular_velocity.z = 0; -// rosData.angular_velocity_covariance = covariance; - -// rosData.linear_acceleration.x = 0; -// rosData.linear_acceleration.y = 0; -// rosData.linear_acceleration.z = 0; -// rosData.linear_acceleration_covariance = covariance; - -// rosData.orientation.x = 0; -// rosData.orientation.y = 0; -// rosData.orientation.z = 0; -// rosData.orientation.w = 0; -// rosData.orientation_covariance = covariance; - -// yCDebug(SERVERINERTIAL) << "covariance size is " << covariance.size(); -} - -ServerInertial::~ServerInertial() -{ - if (IMU != nullptr) { - close(); - } -} - - -bool ServerInertial::checkROSParams(yarp::os::Searchable &config) -{ - // check for ROS parameter group - if(!config.check("ROS") ) - { - useROS = ROS_disabled; - yCInfo(SERVERINERTIAL) << "No ROS group found in config file ... skipping ROS initialization."; - return true; - } - - yCInfo(SERVERINERTIAL) << "ROS group was FOUND in config file."; - - Bottle &rosGroup = config.findGroup("ROS"); - if(rosGroup.isNull()) - { - yCError(SERVERINERTIAL) << partName << "ROS group params is not a valid group or empty"; - useROS = ROS_config_error; - return false; - } - - // check for useROS parameter - if(!rosGroup.check("useROS")) - { - yCError(SERVERINERTIAL) << partName << " cannot find useROS parameter, mandatory when using ROS message. \n \ - Allowed values are true, false, ROS_only"; - useROS = ROS_config_error; - return false; - } - std::string ros_use_type = rosGroup.find("useROS").asString(); - if(ros_use_type == "false") - { - yCInfo(SERVERINERTIAL) << partName << "useROS topic if set to 'false'"; - useROS = ROS_disabled; - return true; - } - else if(ros_use_type == "true") - { - yCInfo(SERVERINERTIAL) << partName << "useROS topic if set to 'true'"; - useROS = ROS_enabled; - } - else if(ros_use_type == "only") - { - yCInfo(SERVERINERTIAL) << partName << "useROS topic if set to 'only"; - useROS = ROS_only; - } - else - { - yCInfo(SERVERINERTIAL) << partName << "useROS parameter is seet to unvalid value ('" << ros_use_type << "'), supported values are 'true', 'false', 'only'"; - useROS = ROS_config_error; - return false; - } - - // check for ROS_nodeName parameter - if(!rosGroup.check("ROS_nodeName")) - { - yCError(SERVERINERTIAL) << partName << " cannot find ROS_nodeName parameter, mandatory when using ROS message"; - useROS = ROS_config_error; - return false; - } - rosNodeName = rosGroup.find("ROS_nodeName").asString(); // TODO: check name is correct - yCInfo(SERVERINERTIAL) << partName << "rosNodeName is " << rosNodeName; - - // check for ROS_topicName parameter - if(!rosGroup.check("ROS_topicName")) - { - yCError(SERVERINERTIAL) << partName << " cannot find ROS_topicName parameter, mandatory when using ROS message"; - useROS = ROS_config_error; - return false; - } - rosTopicName = rosGroup.find("ROS_topicName").asString(); - yCInfo(SERVERINERTIAL) << partName << "ROS_topicName is " << rosTopicName; - - // check for frame_id parameter - if(!rosGroup.check("frame_id")) - { - yCError(SERVERINERTIAL) << partName << " cannot find frame_id parameter, mandatory when using ROS message"; - useROS = ROS_config_error; - return false; - } - frame_id = rosGroup.find("frame_id").asString(); - yCInfo(SERVERINERTIAL) << partName << "frame_id is " << frame_id; - - return true; -} - -bool ServerInertial::initialize_ROS() -{ - bool success = false; - switch(useROS) - { - case ROS_enabled: - case ROS_only: - { - rosNode = new yarp::os::Node(rosNodeName); // add a ROS node - - if(rosNode == nullptr) - { - yCError(SERVERINERTIAL) << " opening " << rosNodeName << " Node, check your yarp-ROS network configuration"; - success = false; - break; - } - - if (!rosPublisherPort.topic(rosTopicName) ) - { - yCError(SERVERINERTIAL) << " opening " << rosTopicName << " Topic, check your yarp-ROS network configuration"; - success = false; - break; - } - success = true; - } break; - - case ROS_disabled: - { - yCInfo(SERVERINERTIAL) << partName << ": no ROS initialization required"; - success = true; - } break; - - case ROS_config_error: - { - yCError(SERVERINERTIAL) << partName << " ROS parameter are not correct, check your configuration file"; - success = false; - } break; - - default: - { - yCError(SERVERINERTIAL) << partName << " something went wrong with ROS configuration, we should never be here!!!"; - success = false; - } break; - } - return success; -} - -bool ServerInertial::openDeferredAttach(yarp::os::Property& prop) -{ - return true; -} - -// If a subdevice parameter is given to the wrapper, it will open it as well -// and attach to it immediately. -bool ServerInertial::openAndAttachSubDevice(yarp::os::Property& prop) -{ - yarp::os::Value &subdevice = prop.find("subdevice"); - IMU_polydriver = new yarp::dev::PolyDriver; - - yCDebug(SERVERINERTIAL, "Subdevice %s", subdevice.toString().c_str()); - if (subdevice.isString()) - { - // maybe user isn't doing nested configuration - yarp::os::Property p; - p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring - p.fromString(prop.toString()); - p.put("device",subdevice.toString()); - IMU_polydriver->open(p); - } else { - IMU_polydriver->open(subdevice); - } - - if (!IMU_polydriver->isValid()) - { - yCError(SERVERINERTIAL, "cannot create device <%s>", subdevice.toString().c_str()); - return false; - } - - // if we are here, poly is valid - IMU_polydriver->view(IMU); // attach to subdevice - if(IMU == nullptr) - { - yCError(SERVERINERTIAL, "Error, subdevice <%s> has no valid IMU interface", subdevice.toString().c_str()); - IMU_polydriver->close(); - return false; - } - - // iTimed interface - IMU_polydriver->view(iTimed); // not mandatory - return true; -} - -/** - * Configure with a set of options. These are: - * - * - * - *
subdevice Common name of device to wrap (e.g. "fakeFrameGrabber").
name Port name to assign to this server (default /grabber).
- * - * @param config The options to use - * @return true iff the object could be configured. - */ -bool ServerInertial::open(yarp::os::Searchable& config) -{ - yCWarning(SERVERINERTIAL) << "The 'inertial' device is deprecated in favour of 'multipleanalogsensorsremapper' + 'multipleanalogsensorsserver' + 'IMURosPublisher'."; - yCWarning(SERVERINERTIAL) << "The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4."; - yCWarning(SERVERINERTIAL) << "Please update your scripts."; - - Property prop; - prop.fromString(config.toString()); - - p.setReader(*this); - - period = config.check("period",yarp::os::Value(0.005),"maximum period").asFloat64(); - strict = config.check("strict",yarp::os::Value(false),"strict write").asBool(); - - //Look for the device name (serial Port). Usually /dev/ttyUSB0 - // check if we need to create subdevice or if they are - // passed later on thorugh attachAll() - if(prop.check("subdevice")) - { - ownDevices=true; - if(! openAndAttachSubDevice(prop)) - { - yCError(SERVERINERTIAL, "error while opening subdevice"); - return false; - } - } - else - { - ownDevices=false; - if (!openDeferredAttach(prop)) { - return false; - } - } - - - checkROSParams(config); - - - - //Look for the portname to register (--name option), defaulting to /inertial if missing - std::string portName; - if(useROS != ROS_only) - { - if (config.check("name")) { - portName = config.find("name").asString(); - } else { - yCInfo(SERVERINERTIAL) << "Using default values for port name, you can change it by using '--name /myPortName' parameter"; - portName = "/inertial"; - } - - if(!p.open(portName)) - { - yCError(SERVERINERTIAL) << "ServerInertial, cannot open port " << portName; - return false; - } - writer.attach(p); - } - - // call ROS node/topic initialization, if needed - if(!initialize_ROS() ) - { - return false; - } - - if( (ownDevices) && (IMU!=nullptr) ) - { - start(); - } - - return true; -} - -bool ServerInertial::close() -{ - yCInfo(SERVERINERTIAL, "Closing Server Inertial..."); - stop(); - - if(rosNode!=nullptr) { - rosNode->interrupt(); - delete rosNode; - rosNode = nullptr; - } - - if( (ownDevices) && (IMU_polydriver != nullptr) ) - { - IMU_polydriver->close(); - IMU = nullptr; - } - return true; -} - - -bool ServerInertial::getInertial(yarp::os::Bottle &bot) -{ - if (IMU==nullptr) - { - return false; - } - else - { - int nchannels; - IMU->getChannels (&nchannels); - - yarp::sig::Vector indata(nchannels); - bool worked(false); - - worked=IMU->read(indata); - if (worked) - { - bot.clear(); - - // Euler+accel+gyro+magn orientation values - for (int i = 0; i < nchannels; i++) { - bot.addFloat64(indata[i]); - } - } - else - { - bot.clear(); //dummy info. - } - - return(worked); - } -} - -void ServerInertial::run() -{ - double before, now; - yCInfo(SERVERINERTIAL, "Starting server Inertial thread"); - while (!isStopping()) - { - before = yarp::os::Time::now(); - if (IMU!=nullptr) - { - Bottle imuData; - bool res = getInertial(imuData); - - // publish data on YARP port if required - if(useROS != ROS_only) - { - yarp::os::Bottle& bot = writer.get(); - bot = imuData; - if (res) - { - static yarp::os::Stamp ts; - if (iTimed) { - ts=iTimed->getLastInputStamp(); - } else { - ts.update(); - } - - - curr_timestamp_counter = ts.getCount(); - - if (curr_timestamp_counter!=prev_timestamp_counter) - { - if (!spoke) - { - yCDebug(SERVERINERTIAL, "Writing an Inertial measurement."); - spoke = true; - } - p.setEnvelope(ts); - writer.write(strict); - } - else - { - trap++; - } - - prev_timestamp_counter = curr_timestamp_counter; - } - } - - // publish ROS topic if required - if(useROS != ROS_disabled) - { - double euler_xyz[3], quaternion[4]; - - euler_xyz[0] = imuData.get(0).asFloat64(); - euler_xyz[1] = imuData.get(1).asFloat64(); - euler_xyz[2] = imuData.get(2).asFloat64(); - - convertEulerAngleYXZdegrees_to_quaternion(euler_xyz, quaternion); - - yarp::rosmsg::sensor_msgs::Imu &rosData = rosPublisherPort.prepare(); - - rosData.header.seq = rosMsgCounter++; - rosData.header.stamp = yarp::os::Time::now(); - rosData.header.frame_id = frame_id; - - rosData.orientation.x = quaternion[0]; - rosData.orientation.y = quaternion[1]; - rosData.orientation.z = quaternion[2]; - rosData.orientation.w = quaternion[3]; - rosData.orientation_covariance = covariance; - - rosData.linear_acceleration.x = imuData.get(3).asFloat64(); // [m/s^2] - rosData.linear_acceleration.y = imuData.get(4).asFloat64(); // [m/s^2] - rosData.linear_acceleration.z = imuData.get(5).asFloat64(); // [m/s^2] - rosData.linear_acceleration_covariance = covariance; - - rosData.angular_velocity.x = imuData.get(6).asFloat64(); // to be converted into rad/s (?) - verify with users - rosData.angular_velocity.y = imuData.get(7).asFloat64(); // to be converted into rad/s (?) - verify with users - rosData.angular_velocity.z = imuData.get(8).asFloat64(); // to be converted into rad/s (?) - verify with users - rosData.angular_velocity_covariance = covariance; - - rosPublisherPort.write(); - } - } - - /// wait 5 ms. - now = yarp::os::Time::now(); - if ((now - before) < period) { - double k = period-(now-before); - yarp::os::Time::delay(k); - } - } - yCInfo(SERVERINERTIAL, "Server Intertial thread finished"); -} - -bool ServerInertial::read(ConnectionReader& connection) -{ - yarp::os::Bottle cmd, response; - cmd.read(connection); - yCTrace(SERVERINERTIAL, "command received: %s", cmd.toString().c_str()); - - // We receive a command but don't do anything with it. - return true; -} - -bool ServerInertial::read(yarp::sig::Vector &out) -{ - if (IMU == nullptr) { return false; } - return IMU->read (out); -} - -bool ServerInertial::getChannels(int *nc) -{ - if (IMU == nullptr) { return false; } - return IMU->getChannels (nc); -} - -bool ServerInertial::calibrate(int ch, double v) -{ - if (IMU==nullptr) {return false;} - return IMU->calibrate(ch, v); -} - - -bool ServerInertial::attach(PolyDriver* poly) -{ - yCTrace(SERVERINERTIAL); - if(!poly) - { - yCError(SERVERINERTIAL, "ServerInertial: device to attach to is not valid!"); - return false; - } - IMU_polydriver = poly; - IMU_polydriver->view(IMU); - - // iTimed interface - IMU_polydriver->view(iTimed); // not mandatory - - if(IMU != nullptr) - { - if (!Thread::isRunning()) { - start(); - } - } - else - { - yCError(SERVERINERTIAL, "attach to subdevice failed"); - } - return true; -} - -bool ServerInertial::detach() -{ - return true; -} - -bool ServerInertial::attachAll(const PolyDriverList &imuToAttachTo) -{ - if (imuToAttachTo.size() != 1) - { - yCError(SERVERINERTIAL, "ServerInertial: cannot attach more than one device"); - return false; - } - - return attach(imuToAttachTo[0]->poly); -} - -bool ServerInertial::detachAll() -{ - IMU = nullptr; - return true; -} diff --git a/src/devices/ServerInertial/ServerInertial.h b/src/devices/ServerInertial/ServerInertial.h deleted file mode 100644 index e61a76f1645..00000000000 --- a/src/devices/ServerInertial/ServerInertial.h +++ /dev/null @@ -1,200 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_SERVERINERTIAL_SERVERINERTIAL_H -#define YARP_DEV_SERVERINERTIAL_SERVERINERTIAL_H - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// ROS state publisher -#include -#include -#include -#include - - -/** - * @ingroup dev_impl_wrapper dev_impl_deprecated - * - * \brief `inertial` *deprecated*: Export an inertial sensor. - * The network interface is a single Port. - * We will stream bottles with 12 floats: - * \code{.unparsed} - * 0 1 2 = Euler orientation data (X, Y, Z) global frame representation. - * 3 4 5 = Calibrated 3-axis (X, Y, Z) acceleration data - * 6 7 8 = Calibrated 3-axis (X, Y, Z) gyroscope data - * 9 10 11 = Calibrated 3-axis (X, Y, Z) magnetometer data - * \endcode - * - * It reads the data from an Inertial measurement unit sensor and sends them through yarp port. - * - * \section inertial_device_parameters Description of input parameters - * - * Parameters accepted in the config argument of the open method: - * | Parameter name | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:------: |:--------------:|:-------------:|:--------: |:-------------:|:-----:| - * | name | string | - | - | Yes | full name of the port opened by the device, like /robotName/deviceId/sensorType:o | must start with a '/' character | - * | period | double | s | 0.005 | No | refresh period of the broadcasted values in ms (optional, default 5ms) | - | - * | subdevice | string | - | - | alternative to attach action| name of the yarp IMU device driver to be instantiated | if using yarprobotinterface or custom program the 'attach' action can be used instead | - * | ROS | group | - | - | No | Group containing parameter for ROS topic initialization | if missing, it is assumed to not use ROS topics | - * | useROS | string | true/false/only| - | if ROS group is present | set 'true' to have both yarp ports and ROS topic, set 'only' to have only ROS topic and no yarp port| - | - * | ROS_TopicName | string | - | - | if ROS group is present | set the name for ROS topic | must start with a leading '/' | - * | ROS_nodeName | string | - | - | if ROS group is present | set the name for ROS node | must start with a leading '/' | - * | ROS_msgType | string | enum | - | if ROS group is present | choose the message to be sent through ROS topic | supported value now is ONLY geometry_msgs/WrenchedStamped | - * | frame_id | string | - | - | if ROS group is present | name of reference frame the measures are referred to | - | - * - * ROS message type used is sensor_msgs/Imu.msg (http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html) - * - * Some example of configuration files: - * - * Configuration file using .ini format - * - * \code{.unparsed} - * name /inertial - * period 0.02 - * [ROS] - * useROS true - * ROS_topicName /ROSinertial - * ROS_nodeName /IMUPublisher - * frame_id r_shoulder - * \endcode - * - * Configuration file using .xml format. - * - * \code{.unparsed} - * - * /inertial - * 0.02 - * - * true // use 'only' if you want only ROS topic and NOT yarp ports - * /ROSinertial - * /IMUPublisher - * r_shoulder - * - * - * - * - * - * - * left_upper_arm_mc - * - * - * - * - * - * \endcode - * - * ROS message type used is sensor_msgs/Imu.msg - */ - -class ServerInertial : - public yarp::dev::DeviceDriver, - public yarp::dev::IWrapper, - public yarp::dev::IMultipleWrapper, - private yarp::os::Thread, - public yarp::os::PortReader, - public yarp::dev::IGenericSensor -{ -private: - bool spoke; - std::string partName; - yarp::dev::PolyDriver *IMU_polydriver; - yarp::dev::IGenericSensor *IMU; //The inertial device - yarp::dev::IPreciselyTimed *iTimed; - double period; - yarp::os::Port p; - yarp::os::PortWriterBuffer writer; - int prev_timestamp_counter; - int curr_timestamp_counter; - int trap; - bool strict; - - // ROS data - ROSTopicUsageType useROS; // decide if open ROS topic or not - std::string frame_id; // name of the frame measures are referred to - std::string rosNodeName; // name of the rosNode - std::string rosTopicName; // name of the rosTopic - yarp::os::Node *rosNode; // add a ROS node - yarp::os::NetUint32 rosMsgCounter; // incremental counter in the ROS message - yarp::os::Publisher rosPublisherPort; // Dedicated ROS topic publisher - std::vector covariance; // empty matrix to store covariance data needed by ROS msg - - bool checkROSParams(yarp::os::Searchable &config); - bool initialize_ROS(); - bool initialize_YARP(yarp::os::Searchable &prop); - -public: - ServerInertial(); - ServerInertial(const ServerInertial&) = delete; - ServerInertial(ServerInertial&&) = delete; - ServerInertial& operator=(const ServerInertial&) = delete; - ServerInertial& operator=(ServerInertial&&) = delete; - ~ServerInertial() override; - - /** - * Open the device driver. - * @param config The options to use - * @return true iff the object could be configured. - */ - bool open(yarp::os::Searchable& config) override; - - bool close() override; - - virtual bool getInertial(yarp::os::Bottle &bot); - - void run() override; - - bool read(yarp::os::ConnectionReader& connection) override; - - bool read(yarp::sig::Vector &out) override; - - bool getChannels(int *nc) override; - - bool calibrate(int ch, double v) override; - - /** IWrapper interface - * Attach to another object. - * @param poly the polydriver that you want to attach to. - * @return true/false on success failure. - */ - bool attach(yarp::dev::PolyDriver *poly) override; - bool detach() override; - - /** IMultipleWrapper interface - * Attach to a list of objects. - * @param p the polydriver list that you want to attach to. - * @return true/false on success failure. - */ - bool attachAll(const yarp::dev::PolyDriverList &p) override; - bool detachAll() override; - -private: - - bool ownDevices; - yarp::dev::PolyDriver *subDeviceOwned; - - // Open the wrapper only, the attach method needs to be called before using it - bool openDeferredAttach(yarp::os::Property& prop); - - // If a subdevice parameter is given to the wrapper, it will open it as well - // and attach to it immediately. - bool openAndAttachSubDevice(yarp::os::Property& prop); -}; - - -#endif // YARP_DEV_SERVERINERTIAL_SERVERINERTIAL_H From a40065134182d833f3d7a8e598906467611c2fd7 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 20:47:03 +0100 Subject: [PATCH 007/267] Removed deprecated stuff and general cleanup related to "Generic Sensor Interface". --- .../audioFromFileDevice/audioFromFileDevice.h | 1 - src/devices/fakeMicrophone/fakeMicrophone.h | 1 - src/devices/fakeSpeaker/fakeSpeaker.h | 1 - .../src/yarp/dev/GenericSensorInterfaces.h | 14 -------------- src/libYARP_dev/src/yarp/dev/all.h | 1 - 5 files changed, 18 deletions(-) delete mode 100644 src/libYARP_dev/src/yarp/dev/GenericSensorInterfaces.h diff --git a/src/devices/audioFromFileDevice/audioFromFileDevice.h b/src/devices/audioFromFileDevice/audioFromFileDevice.h index c2d3bf31ece..d468c10fa71 100644 --- a/src/devices/audioFromFileDevice/audioFromFileDevice.h +++ b/src/devices/audioFromFileDevice/audioFromFileDevice.h @@ -5,7 +5,6 @@ #include #include -#include #include #include #include diff --git a/src/devices/fakeMicrophone/fakeMicrophone.h b/src/devices/fakeMicrophone/fakeMicrophone.h index c2fc176a016..7967da15a69 100644 --- a/src/devices/fakeMicrophone/fakeMicrophone.h +++ b/src/devices/fakeMicrophone/fakeMicrophone.h @@ -5,7 +5,6 @@ #include #include -#include #include #include #include diff --git a/src/devices/fakeSpeaker/fakeSpeaker.h b/src/devices/fakeSpeaker/fakeSpeaker.h index 58033640d40..1a407eb5867 100644 --- a/src/devices/fakeSpeaker/fakeSpeaker.h +++ b/src/devices/fakeSpeaker/fakeSpeaker.h @@ -6,7 +6,6 @@ #include #include #include -#include #include #include #include diff --git a/src/libYARP_dev/src/yarp/dev/GenericSensorInterfaces.h b/src/libYARP_dev/src/yarp/dev/GenericSensorInterfaces.h deleted file mode 100644 index 985466fc5dd..00000000000 --- a/src/libYARP_dev/src/yarp/dev/GenericSensorInterfaces.h +++ /dev/null @@ -1,14 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_GENERICSENSORINTERFACES_H -#define YARP_DEV_GENERICSENSORINTERFACES_H - -#include - -YARP_COMPILER_WARNING(" file is deprecated. Use instead") -#include - -#endif // YARP_DEV_GENERICSENSORINTERFACES_H diff --git a/src/libYARP_dev/src/yarp/dev/all.h b/src/libYARP_dev/src/yarp/dev/all.h index 80e421b09b5..6ac95fece2c 100644 --- a/src/libYARP_dev/src/yarp/dev/all.h +++ b/src/libYARP_dev/src/yarp/dev/all.h @@ -26,7 +26,6 @@ #include #include #include -#include #include #include #include From 350b7deb6b4513545ab6a82d811776c2f94be922 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 20:55:00 +0100 Subject: [PATCH 008/267] fakeImu device cleanup --- .../VirtualAnalogWrapper.cpp | 2 - src/devices/fakeIMU/fakeIMU.cpp | 48 ------------------- src/devices/fakeIMU/fakeIMU.h | 7 --- 3 files changed, 57 deletions(-) diff --git a/src/devices/VirtualAnalogWrapper/VirtualAnalogWrapper.cpp b/src/devices/VirtualAnalogWrapper/VirtualAnalogWrapper.cpp index f21438d4ca1..5f2844b8c82 100644 --- a/src/devices/VirtualAnalogWrapper/VirtualAnalogWrapper.cpp +++ b/src/devices/VirtualAnalogWrapper/VirtualAnalogWrapper.cpp @@ -411,8 +411,6 @@ void VirtualAnalogWrapper::run() mSubdevices[d].flushTorques(); } - // Virtual Sensor status is not handled now because server DO NOT implement IVirtual AnalogSensor Interface. - // status=IAnalogSensor::AS_TIMEOUT; yCError(VIRTUALANALOGSERVER) << "Timeout!! No new value received for more than " << timeNow - lastRecv << " secs."; sendLastValueBeforeTimeout = true; } diff --git a/src/devices/fakeIMU/fakeIMU.cpp b/src/devices/fakeIMU/fakeIMU.cpp index d1564868c2c..277d7aae19c 100644 --- a/src/devices/fakeIMU/fakeIMU.cpp +++ b/src/devices/fakeIMU/fakeIMU.cpp @@ -75,60 +75,12 @@ bool fakeIMU::close() return true; } -bool fakeIMU::read(Vector &out) -{ - if (out.size() != nchannels) { - out.resize(nchannels); - } - - out.zero(); - - // Euler angle - for(unsigned int i=0; i<3; i++) - { - out[i] = dummy_value; - } - - // accelerations - for(unsigned int i=0; i<3; i++) - { - out[3+i] = accels[i]; - } - - // gyro - for(unsigned int i=0; i<3; i++) - { - out[6+i] = dummy_value; - } - - // magnetometer - for(unsigned int i=0; i<3; i++) - { - out[9+i] = dummy_value; - } - - return true; -} - -bool fakeIMU::getChannels(int *nc) -{ - *nc=nchannels; - return true; -} - -bool fakeIMU::calibrate(int ch, double v) -{ - yCWarning(FAKEIMU, "Not implemented yet"); - return false; -} - bool fakeIMU::threadInit() { lastStamp.update(); return true; } - void fakeIMU::run() { static double count=10; diff --git a/src/devices/fakeIMU/fakeIMU.h b/src/devices/fakeIMU/fakeIMU.h index c369967e592..2d8c73f4cae 100644 --- a/src/devices/fakeIMU/fakeIMU.h +++ b/src/devices/fakeIMU/fakeIMU.h @@ -6,7 +6,6 @@ #include #include #include -#include #include #include #include @@ -29,7 +28,6 @@ */ class fakeIMU : public yarp::dev::DeviceDriver, - public yarp::dev::IGenericSensor, public yarp::os::PeriodicThread, public yarp::dev::IThreeAxisGyroscopes, public yarp::dev::IThreeAxisLinearAccelerometers, @@ -49,11 +47,6 @@ class fakeIMU : bool open(yarp::os::Searchable &config) override; bool close() override; - // IGenericSensor interface. - bool read(yarp::sig::Vector &out) override; - bool getChannels(int *nc) override; - bool calibrate(int ch, double v) override; - /* IThreeAxisGyroscopes methods */ size_t getNrOfThreeAxisGyroscopes() const override; yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override; From 3c9f6f887b6a05b4e30b97f5f0567aa27b7215c6 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 21:13:56 +0100 Subject: [PATCH 009/267] Other deprecated include files removed --- src/libYARP_dev/src/CMakeLists.txt | 7 +- src/libYARP_dev/src/yarp/dev/DataSource.h | 205 ------------------ src/libYARP_dev/src/yarp/dev/PreciselyTimed.h | 14 -- .../src/yarp/dev/SerialInterfaces.h | 14 -- src/libYARP_dev/src/yarp/dev/Wrapper.h | 23 -- 5 files changed, 2 insertions(+), 261 deletions(-) delete mode 100644 src/libYARP_dev/src/yarp/dev/DataSource.h delete mode 100644 src/libYARP_dev/src/yarp/dev/PreciselyTimed.h delete mode 100644 src/libYARP_dev/src/yarp/dev/SerialInterfaces.h delete mode 100644 src/libYARP_dev/src/yarp/dev/Wrapper.h diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index 225afb360e6..e6319d223dc 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -135,11 +135,8 @@ endif() if(NOT YARP_NO_DEPRECATED) list(APPEND YARP_dev_HDRS - yarp/dev/DataSource.h # DEPRECATED Since YARP 3.3.0 - yarp/dev/GenericSensorInterfaces.h # DEPRECATED Since YARP 3.3.0 - yarp/dev/PreciselyTimed.h # DEPRECATED Since YARP 3.3.0 - yarp/dev/SerialInterfaces.h # DEPRECATED Since YARP 3.3.0 - yarp/dev/Wrapper.h # DEPRECATED Since YARP 3.3.0 + + yarp/dev/FrameGrabberInterfaces.h # DEPRECATED Since YARP 3.5.0 yarp/dev/IFrameGrabber.h # DEPRECATED Since YARP 3.5.0 yarp/dev/IFrameGrabberRgb.h # DEPRECATED Since YARP 3.5.0 diff --git a/src/libYARP_dev/src/yarp/dev/DataSource.h b/src/libYARP_dev/src/yarp/dev/DataSource.h deleted file mode 100644 index f1410ab0dc2..00000000000 --- a/src/libYARP_dev/src/yarp/dev/DataSource.h +++ /dev/null @@ -1,205 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_DATASOURCE_H -#define YARP_DEV_DATASOURCE_H - -#include - -#if !defined(YARP_INCLUDING_DEPRECATED_HEADER_YARP_DEV_DATASOURCE_H_ON_PURPOSE) -YARP_COMPILER_WARNING(" file is deprecated") -#endif - -#ifndef YARP_NO_DEPRECATED // Since YARP 3.3 - -YARP_WARNING_PUSH -YARP_DISABLE_DEPRECATED_WARNING - -#include -#include -#include -#include -#include - -#include - -// These classes are part of the YARP library implementation, -// rather than its user interface -#ifndef DOXYGEN_SHOULD_SKIP_THIS - -const int REPORT_TIME=5; //seconds - -namespace yarp::dev { -template -class DataSource; -template -class DataWriter; -template -class DataSource2; -template -class DataWriter2; -} - -template -class YARP_DEPRECATED yarp::dev::DataSource { -public: - virtual ~DataSource() {} - virtual bool getDatum(T& datum) = 0; -}; - -template -class YARP_DEPRECATED yarp::dev::DataWriter : public yarp::os::Runnable { -private: - yarp::os::Port& port; - yarp::os::PortWriterBuffer writer; - DataSource& dater; - yarp::os::Stamp stamp; - IPreciselyTimed *pPrecTime; - bool canDrop; - bool addStamp; - int counter; - double timePrevious; - double cumulativeT; - double minT; - double maxT; - double lastSpoke; -public: - DataWriter(yarp::os::Port& port, DataSource& dater, - bool canDrop=true, - bool addStamp=false, - IPreciselyTimed *pt=NULL) : - port(port), - dater(dater), - pPrecTime(pt), - canDrop(canDrop), - addStamp(addStamp), - counter(0), - timePrevious(0.0), - cumulativeT(0.0), - minT(1e10), - maxT(0.0), - lastSpoke(yarp::os::Time::now()) - { - writer.attach(port); - } - - void run() override { - - ///////////// execution statistics for logging - double now=yarp::os::Time::now(); - double deltaT=0.0; - - if (counter==0) - { - lastSpoke=now; - timePrevious=now; - cumulativeT=0.0; - } - else - { - deltaT=now-timePrevious; - cumulativeT+=deltaT; - if (deltaT > maxT) { - maxT = deltaT; - } - if (deltaT < minT) { - minT = deltaT; - } - timePrevious=now; - } - - counter++; - - // print report - if (now-lastSpoke>REPORT_TIME) - { - yInfo("Read [%d] frames in %d[s], average period %.2lf[ms], min %.2lf[ms], max %.2lf[ms]\n", - counter, - REPORT_TIME, - (cumulativeT/counter)*1000, - minT*1000, maxT*1000); - cumulativeT=0; - counter=0; - minT=1e10; - maxT=0.0; - lastSpoke=now; - } - ////////////// - - T& datum = writer.get(); - - dater.getDatum(datum); - if (addStamp) { - if (pPrecTime) - { - stamp=pPrecTime->getLastInputStamp(); - } - else - { - stamp.update(); - } - port.setEnvelope(stamp); - } - writer.write(!canDrop); - } -}; - - - -template -class YARP_DEPRECATED yarp::dev::DataSource2 { -public: - virtual ~DataSource2() {} - virtual bool getDatum(T1& datum1, T2& datum2) = 0; -}; - - -template -class YARP_DEPRECATED yarp::dev::DataWriter2 : public yarp::os::Runnable { -private: - yarp::os::Port& port1; - yarp::os::Port& port2; - yarp::os::PortWriterBuffer writer1; - yarp::os::PortWriterBuffer writer2; - DataSource2& dater; - bool canDrop; - bool addStamp; - yarp::os::Stamp stamp; -public: - DataWriter2(yarp::os::Port& port1, - yarp::os::Port& port2, - DataSource2& dater, - bool canDrop=true, - bool addStamp=false) : - port1(port1), port2(port2), dater(dater), canDrop(canDrop), - addStamp(addStamp) - { - writer1.attach(port1); - writer2.attach(port2); - } - - void run() override { - T1& datum1 = writer1.get(); - T2& datum2 = writer2.get(); - dater.getDatum(datum1,datum2); - if (addStamp) { - stamp.update(); - port1.setEnvelope(stamp); - port2.setEnvelope(stamp); - } - writer1.write(!canDrop); - writer2.write(!canDrop); - } -}; - - -#endif // DOXYGEN_SHOULD_SKIP_THIS - -YARP_WARNING_POP - -#endif // YARP_NO_DEPRECATED - -#endif // YARP_DEV_DATASOURCE_H diff --git a/src/libYARP_dev/src/yarp/dev/PreciselyTimed.h b/src/libYARP_dev/src/yarp/dev/PreciselyTimed.h deleted file mode 100644 index 769377ea316..00000000000 --- a/src/libYARP_dev/src/yarp/dev/PreciselyTimed.h +++ /dev/null @@ -1,14 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_PRECISELYTIMED_H -#define YARP_DEV_PRECISELYTIMED_H - -#include - -YARP_COMPILER_WARNING(" file is deprecated. Use instead") -#include - -#endif // YARP_DEV_PRECISELYTIMED_H diff --git a/src/libYARP_dev/src/yarp/dev/SerialInterfaces.h b/src/libYARP_dev/src/yarp/dev/SerialInterfaces.h deleted file mode 100644 index b400c91c711..00000000000 --- a/src/libYARP_dev/src/yarp/dev/SerialInterfaces.h +++ /dev/null @@ -1,14 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_SERIALINTERFACES_H -#define YARP_DEV_SERIALINTERFACES_H - -#include - -YARP_COMPILER_WARNING(" file is deprecated. Use instead") -#include - -#endif // YARP_DEV_SERIALINTERFACES_H diff --git a/src/libYARP_dev/src/yarp/dev/Wrapper.h b/src/libYARP_dev/src/yarp/dev/Wrapper.h deleted file mode 100644 index a99a694384c..00000000000 --- a/src/libYARP_dev/src/yarp/dev/Wrapper.h +++ /dev/null @@ -1,23 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_WRAPPER_H -#define YARP_DEV_WRAPPER_H - -#include - -#include -#if !defined(YARP_INCLUDING_DEPRECATED_HEADER_YARP_DEV_IWRAPPER_H_ON_PURPOSE) -YARP_COMPILER_WARNING(" file is deprecated. Use and instead") -#endif - - -#ifndef YARP_NO_DEPRECATED // Since YARP 3.3.0 -#include -#include -#endif // YARP_NO_DEPRECATED - -#endif // YARP_DEV_WRAPPER_H From 124316cee9d28ba997c2f39457ed77e074a769c1 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 21:16:35 +0100 Subject: [PATCH 010/267] fixed math bug in IMURosPublisher --- .../IMURosPublisher.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp index ea8f0fe1bc3..f4e1e684fa9 100644 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp +++ b/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp @@ -4,6 +4,8 @@ */ #include "IMURosPublisher.h" +#include "Yarp/math/Quaternion.h" +#include "Yarp/math/Math.h" #ifndef M_PI #define M_PI (3.14159265358979323846) @@ -61,9 +63,16 @@ void IMURosPublisher::run() imu_ros_data.linear_acceleration.x = vecacc[0]; imu_ros_data.linear_acceleration.y = vecacc[1]; imu_ros_data.linear_acceleration.z = vecacc[2]; - imu_ros_data.orientation.x = vecrpy[0] * M_PI / 180.0; - imu_ros_data.orientation.y = vecrpy[1] * M_PI / 180.0; - imu_ros_data.orientation.z = vecrpy[2] * M_PI / 180.0; + vecrpy[0] = vecrpy[0] * M_PI / 180.0; + vecrpy[1] = vecrpy[1] * M_PI / 180.0; + vecrpy[2] = vecrpy[2] * M_PI / 180.0; + yarp::sig::Matrix matrix = yarp::math::rpy2dcm(vecrpy); + yarp::math::Quaternion q; q.fromRotationMatrix(matrix); + imu_ros_data.orientation.x = q.x(); + imu_ros_data.orientation.y = q.y(); + imu_ros_data.orientation.z = q.z(); + imu_ros_data.orientation.w = q.w(); + //imu_ros_data.orientation_covariance = 0; m_publisher.write(); } From a83d06b9c1e166d030c696c1e189da6aad7a959c Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 21:26:37 +0100 Subject: [PATCH 011/267] fixed capitalization in CMakeLists --- src/devices/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index b70a7fbdf16..8ef769f2f79 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -30,7 +30,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(frameTransformStorageMsgs) add_subdirectory(frameTransformStorage) add_subdirectory(frameTransformUtils) - add_subdirectory(FrameGrabber_nws_yarp) + add_subdirectory(frameGrabber_nws_yarp) add_subdirectory(transformClient) add_subdirectory(transformServer) add_subdirectory(SerialServoBoard) From 637804401cd024cb8a43b466833b7b957e2d3c93 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 21:49:23 +0100 Subject: [PATCH 012/267] moved FrameTransformGet_nwc_ros, FrameTransformSet_nwc_ros --- .../frameTransformGet_nwc_ros/CMakeLists.txt | 100 ++++++++++++++++++ .../FrameTransformGet_nwc_ros.cpp | 0 .../FrameTransformGet_nwc_ros.h | 0 .../frameTransformSet_nwc_ros/CMakeLists.txt | 100 ++++++++++++++++++ .../FrameTransformSet_nwc_ros.cpp | 0 .../FrameTransformSet_nwc_ros.h | 0 src/devices/frameTransformGet/CMakeLists.txt | 53 ---------- src/devices/frameTransformSet/CMakeLists.txt | 54 ---------- 8 files changed, 200 insertions(+), 107 deletions(-) create mode 100644 src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt rename src/devices/{frameTransformGet => ROS/frameTransformGet_nwc_ros}/FrameTransformGet_nwc_ros.cpp (100%) rename src/devices/{frameTransformGet => ROS/frameTransformGet_nwc_ros}/FrameTransformGet_nwc_ros.h (100%) create mode 100644 src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt rename src/devices/{frameTransformSet => ROS/frameTransformSet_nwc_ros}/FrameTransformSet_nwc_ros.cpp (100%) rename src/devices/{frameTransformSet => ROS/frameTransformSet_nwc_ros}/FrameTransformSet_nwc_ros.h (100%) diff --git a/src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt b/src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt new file mode 100644 index 00000000000..08ca3c746e8 --- /dev/null +++ b/src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt @@ -0,0 +1,100 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + + +yarp_prepare_plugin(frameTransformGet_nwc_ros + CATEGORY device + TYPE FrameTransformGet_nwc_ros + INCLUDE FrameTransformGet_nwc_ros.h + DEPENDS "TARGET YARP::YARP_math" + EXTRA_CONFIG + WRAPPER=frameTransformGet_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_frameTransformGet_nwc_ros) + yarp_add_plugin(yarp_frameTransformGet_nwc_ros) + + target_sources(yarp_frameTransformGet_nwc_ros + PRIVATE + FrameTransformGet_nwc_ros.cpp + FrameTransformGet_nwc_ros.h + ) + + target_sources(yarp_frameTransformGet_nwc_ros PRIVATE $) + target_include_directories(yarp_frameTransformGet_nwc_ros PRIVATE $) + + target_link_libraries(yarp_frameTransformGet_nwc_ros + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_math + YARP::YARP_rosmsg + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + YARP_math + YARP_rosmsg + ) + + yarp_install( + TARGETS yarp_frameTransformGet_nwc_ros + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameTransformGet_nwc_ros PROPERTY FOLDER "Plugins/Device/NWC") +endif() + + + +yarp_prepare_plugin(frameTransformGetMultiplexer + CATEGORY device + TYPE FrameTransformGetMultiplexer + INCLUDE FrameTransformGetMultiplexer.h + DEPENDS "TARGET YARP::YARP_math" + EXTRA_CONFIG + WRAPPER=frameTransformGet_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_frameTransformGetMultiplexer) + yarp_add_plugin(yarp_frameTransformGetMultiplexer) + + target_sources(yarp_frameTransformGetMultiplexer + PRIVATE + FrameTransformGetMultiplexer.cpp + FrameTransformGetMultiplexer.h + ) + + target_link_libraries(yarp_frameTransformGetMultiplexer + PRIVATE + YARP::YARP_os + YARP::YARP_dev + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_dev + ) + + yarp_install( + TARGETS yarp_frameTransformGetMultiplexer + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameTransformGetMultiplexer PROPERTY FOLDER "Plugins/Device") +endif() diff --git a/src/devices/frameTransformGet/FrameTransformGet_nwc_ros.cpp b/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.cpp similarity index 100% rename from src/devices/frameTransformGet/FrameTransformGet_nwc_ros.cpp rename to src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.cpp diff --git a/src/devices/frameTransformGet/FrameTransformGet_nwc_ros.h b/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.h similarity index 100% rename from src/devices/frameTransformGet/FrameTransformGet_nwc_ros.h rename to src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.h diff --git a/src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt b/src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt new file mode 100644 index 00000000000..72209907721 --- /dev/null +++ b/src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt @@ -0,0 +1,100 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + + +yarp_prepare_plugin(frameTransformSet_nwc_ros + CATEGORY device + TYPE FrameTransformSet_nwc_ros + INCLUDE FrameTransformSet_nwc_ros.h + DEPENDS "TARGET YARP::YARP_math" + EXTRA_CONFIG + WRAPPER=frameTransformSet_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_frameTransformSet_nwc_ros) + yarp_add_plugin(yarp_frameTransformSet_nwc_ros) + + target_sources(yarp_frameTransformSet_nwc_ros + PRIVATE + FrameTransformSet_nwc_ros.cpp + FrameTransformSet_nwc_ros.h + ) + + target_sources(yarp_frameTransformSet_nwc_ros PRIVATE $) + target_include_directories(yarp_frameTransformSet_nwc_ros PRIVATE $) + + target_link_libraries(yarp_frameTransformSet_nwc_ros + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_math + YARP::YARP_rosmsg + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + YARP_math + YARP_rosmsg + ) + + yarp_install( + TARGETS yarp_frameTransformSet_nwc_ros + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameTransformSet_nwc_ros PROPERTY FOLDER "Plugins/Device/NWC") +endif() + + + +yarp_prepare_plugin(frameTransformSetMultiplexer + CATEGORY device + TYPE FrameTransformSetMultiplexer + INCLUDE FrameTransformSetMultiplexer.h + DEPENDS "TARGET YARP::YARP_math" + EXTRA_CONFIG + WRAPPER=frameTransformSet_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_frameTransformSetMultiplexer) + yarp_add_plugin(yarp_frameTransformSetMultiplexer) + + target_sources(yarp_frameTransformSetMultiplexer + PRIVATE + FrameTransformSetMultiplexer.cpp + FrameTransformSetMultiplexer.h + ) + + target_link_libraries(yarp_frameTransformSetMultiplexer + PRIVATE + YARP::YARP_os + YARP::YARP_dev + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_dev + ) + + yarp_install( + TARGETS yarp_frameTransformSetMultiplexer + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameTransformSetMultiplexer PROPERTY FOLDER "Plugins/Device") +endif() diff --git a/src/devices/frameTransformSet/FrameTransformSet_nwc_ros.cpp b/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.cpp similarity index 100% rename from src/devices/frameTransformSet/FrameTransformSet_nwc_ros.cpp rename to src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.cpp diff --git a/src/devices/frameTransformSet/FrameTransformSet_nwc_ros.h b/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.h similarity index 100% rename from src/devices/frameTransformSet/FrameTransformSet_nwc_ros.h rename to src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.h diff --git a/src/devices/frameTransformGet/CMakeLists.txt b/src/devices/frameTransformGet/CMakeLists.txt index a4d03384dbd..f8c0a07ad1d 100644 --- a/src/devices/frameTransformGet/CMakeLists.txt +++ b/src/devices/frameTransformGet/CMakeLists.txt @@ -98,59 +98,6 @@ endif() -yarp_prepare_plugin(frameTransformGet_nwc_ros - CATEGORY device - TYPE FrameTransformGet_nwc_ros - INCLUDE FrameTransformGet_nwc_ros.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=frameTransformGet_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameTransformGet_nwc_ros) - yarp_add_plugin(yarp_frameTransformGet_nwc_ros) - - target_sources(yarp_frameTransformGet_nwc_ros - PRIVATE - FrameTransformGet_nwc_ros.cpp - FrameTransformGet_nwc_ros.h - ) - - target_sources(yarp_frameTransformGet_nwc_ros PRIVATE $) - target_include_directories(yarp_frameTransformGet_nwc_ros PRIVATE $) - - target_link_libraries(yarp_frameTransformGet_nwc_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_frameTransformGet_nwc_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameTransformGet_nwc_ros PROPERTY FOLDER "Plugins/Device/NWC") -endif() - - yarp_prepare_plugin(frameTransformGetMultiplexer CATEGORY device diff --git a/src/devices/frameTransformSet/CMakeLists.txt b/src/devices/frameTransformSet/CMakeLists.txt index 3e10a79e082..b4812c26b2e 100644 --- a/src/devices/frameTransformSet/CMakeLists.txt +++ b/src/devices/frameTransformSet/CMakeLists.txt @@ -102,60 +102,6 @@ endif() -yarp_prepare_plugin(frameTransformSet_nwc_ros - CATEGORY device - TYPE FrameTransformSet_nwc_ros - INCLUDE FrameTransformSet_nwc_ros.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=frameTransformSet_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameTransformSet_nwc_ros) - yarp_add_plugin(yarp_frameTransformSet_nwc_ros) - - target_sources(yarp_frameTransformSet_nwc_ros - PRIVATE - FrameTransformSet_nwc_ros.cpp - FrameTransformSet_nwc_ros.h - ) - - target_sources(yarp_frameTransformSet_nwc_ros PRIVATE $) - target_include_directories(yarp_frameTransformSet_nwc_ros PRIVATE $) - - target_link_libraries(yarp_frameTransformSet_nwc_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_frameTransformSet_nwc_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameTransformSet_nwc_ros PROPERTY FOLDER "Plugins/Device/NWC") -endif() - - - yarp_prepare_plugin(frameTransformSetMultiplexer CATEGORY device TYPE FrameTransformSetMultiplexer From a24a247c350858c5691667098842593b1ffcfeaf Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 22:16:50 +0100 Subject: [PATCH 013/267] cleanup --- src/devices/fakeLocalizerDevice/fakeLocalizerDev.h | 1 - src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h | 2 -- 2 files changed, 3 deletions(-) diff --git a/src/devices/fakeLocalizerDevice/fakeLocalizerDev.h b/src/devices/fakeLocalizerDevice/fakeLocalizerDev.h index b23fdf06323..24bc7a7ae7b 100644 --- a/src/devices/fakeLocalizerDevice/fakeLocalizerDev.h +++ b/src/devices/fakeLocalizerDevice/fakeLocalizerDev.h @@ -8,7 +8,6 @@ #include #include #include -#include #include #include #include diff --git a/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h b/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h index 8bd3daabeea..dfb235ef299 100644 --- a/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h +++ b/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h @@ -12,8 +12,6 @@ #include #include #include -#include -#include #include #include #include From 3c691ad17b0944ca4b5f134437ca4d8d4a43018f Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 22:24:25 +0100 Subject: [PATCH 014/267] cleanup --- .../ControlBoard_nws_ros.cpp | 345 ------------------ .../ControlBoard_nws_ros.h | 109 ------ 2 files changed, 454 deletions(-) delete mode 100644 src/devices/ControlBoardWrapper/ControlBoard_nws_ros.cpp delete mode 100644 src/devices/ControlBoardWrapper/ControlBoard_nws_ros.h diff --git a/src/devices/ControlBoardWrapper/ControlBoard_nws_ros.cpp b/src/devices/ControlBoardWrapper/ControlBoard_nws_ros.cpp deleted file mode 100644 index db617b8f0bf..00000000000 --- a/src/devices/ControlBoardWrapper/ControlBoard_nws_ros.cpp +++ /dev/null @@ -1,345 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "ControlBoard_nws_ros.h" - -#include -#include - -#include - -#include - -#include "ControlBoardLogComponent.h" - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - -ControlBoard_nws_ros::ControlBoard_nws_ros() : - yarp::os::PeriodicThread(default_period) -{ -} - - -void ControlBoard_nws_ros::closePorts() -{ - publisherPort.interrupt(); - publisherPort.close(); - - delete node; - node = nullptr; -} - -bool ControlBoard_nws_ros::close() -{ - // Ensure that the device is not running - if (isRunning()) { - stop(); - } - - closeDevice(); - closePorts(); - - return true; -} - - -bool ControlBoard_nws_ros::open(Searchable& config) -{ - Property prop; - prop.fromString(config.toString()); - - // Check parameter, so if both are present we use the correct one - if (prop.check("period")) { - if (!prop.find("period").isFloat64()) { - yCError(CONTROLBOARD) << "'period' parameter is not a double value"; - return false; - } - period = prop.find("period").asFloat64(); - if (period <= 0) { - yCError(CONTROLBOARD) << "'period' parameter is not valid, read value is" << period; - return false; - } - } else { - yCDebug(CONTROLBOARD) << "'period' parameter missing, using default thread period = 0.02s"; - period = default_period; - } - - // Check if we need to create subdevice or if they are - // passed later on through attachAll() - if (prop.check("subdevice")) { - prop.setMonitor(config.getMonitor()); - if (!openAndAttachSubDevice(prop)) { - yCError(CONTROLBOARD, "Error while opening subdevice"); - return false; - } - subdevice_ready = true; - } - - // check for node_name parameter - if (!config.check("node_name")) { - yCError(CONTROLBOARD) << nodeName << " cannot find node_name parameter"; - return false; - } - nodeName = config.find("node_name").asString(); - if(nodeName[0] != '/'){ - yCError(CONTROLBOARD) << "node_name must begin with an initial /"; - return false; - } - - // check for topic_name parameter - if (!config.check("topic_name")) { - yCError(CONTROLBOARD) << nodeName << " cannot find topic_name parameter"; - return false; - } - topicName = config.find("topic_name").asString(); - if(topicName[0] != '/'){ - yCError(CONTROLBOARD) << "topic_name must begin with an initial /"; - return false; - } - yCInfo(CONTROLBOARD) << "topic_name is " << topicName; - // call ROS node/topic initialization - node = new yarp::os::Node(nodeName); - if (!publisherPort.topic(topicName)) { - yCError(CONTROLBOARD) << " opening " << topicName << " Topic, check your configuration"; - return false; - } - - // In case attach is not deferred and the controlboard already owns a valid device - // we can start the thread. Otherwise this will happen when attachAll is called - if (subdevice_ready) { - setPeriod(period); - if (!start()) { - yCError(CONTROLBOARD) << "Error starting thread"; - return false; - } - } - - return true; -} - - - -// For the simulator, if a subdevice parameter is given to the wrapper, it will -// open it and attach to immediately. -bool ControlBoard_nws_ros::openAndAttachSubDevice(Property& prop) -{ - Property p; - auto* subDeviceOwned = new PolyDriver; - p.fromString(prop.toString()); - - std::string subdevice = prop.find("subdevice").asString(); - p.setMonitor(prop.getMonitor(), subdevice.c_str()); // pass on any monitoring - p.unput("device"); - p.put("device", subdevice); // subdevice was already checked before - - // if errors occurred during open, quit here. - yCDebug(CONTROLBOARD, "opening subdevice"); - subDeviceOwned->open(p); - - if (!subDeviceOwned->isValid()) { - yCError(CONTROLBOARD, "opening subdevice... FAILED"); - return false; - } - - return setDevice(subDeviceOwned, true); -} - - -bool ControlBoard_nws_ros::setDevice(yarp::dev::DeviceDriver* driver, bool owned) -{ - yCAssert(CONTROLBOARD, driver); - - // Save the pointer and subDeviceOwned - subdevice_ptr = driver; - subdevice_owned = owned; - - subdevice_ptr->view(iPositionControl); - if (!iPositionControl) { - yCError(CONTROLBOARD, "<%s - %s>: IPositionControl interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str()); - return false; - } - - subdevice_ptr->view(iEncodersTimed); - if (!iEncodersTimed) { - yCError(CONTROLBOARD, "<%s - %s>: IEncodersTimed interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str()); - return false; - } - - subdevice_ptr->view(iTorqueControl); - if (!iTorqueControl) { - yCWarning(CONTROLBOARD, "<%s - %s>: ITorqueControl interface was not found in subdevice.", nodeName.c_str(), topicName.c_str()); - } - - subdevice_ptr->view(iAxisInfo); - if (!iAxisInfo) { - yCError(CONTROLBOARD, "<%s - %s>: IAxisInfo interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str()); - return false; - } - - // Get the number of controlled joints - int tmp_axes; - if (!iPositionControl->getAxes(&tmp_axes)) { - yCError(CONTROLBOARD, "<%s - %s>: Failed to get axes number for subdevice ", nodeName.c_str(), topicName.c_str()); - return false; - } - if (tmp_axes <= 0) { - yCError(CONTROLBOARD, "<%s - %s>: attached device has an invalid number of joints (%d)", nodeName.c_str(), topicName.c_str(), tmp_axes); - return false; - } - subdevice_joints = static_cast(tmp_axes); - times.resize(subdevice_joints); - ros_struct.name.resize(subdevice_joints); - ros_struct.position.resize(subdevice_joints); - ros_struct.velocity.resize(subdevice_joints); - ros_struct.effort.resize(subdevice_joints); - - if (!updateAxisName()) { - return false; - } - - return true; -} - - -void ControlBoard_nws_ros::closeDevice() -{ - // If the subdevice is owned, close and delete the device - if (subdevice_owned) { - yCAssert(CONTROLBOARD, subdevice_ptr); - subdevice_ptr->close(); - delete subdevice_ptr; - } - subdevice_ptr = nullptr; - subdevice_owned = false; - subdevice_joints = 0; - subdevice_ready = false; - - times.clear(); - - // Clear all interfaces - iPositionControl = nullptr; - iEncodersTimed = nullptr; - iTorqueControl = nullptr; - iAxisInfo = nullptr; -} - -bool ControlBoard_nws_ros::attach(yarp::dev::PolyDriver* poly) -{ - // Check if we already instantiated a subdevice previously - if (subdevice_ready) { - return false; - } - - if (!setDevice(poly, false)) { - return false; - } - - setPeriod(period); - if (!start()) { - yCError(CONTROLBOARD) << "Error starting thread"; - return false; - } - - return true; -} - -bool ControlBoard_nws_ros::detach() -{ - //check if we already instantiated a subdevice previously - if (subdevice_owned) { - return false; - } - - // Ensure that the device is not running - if (isRunning()) { - stop(); - } - - closeDevice(); - - return true; -} - - -bool ControlBoard_nws_ros::updateAxisName() -{ - // IMPORTANT!! This function has to be called BEFORE the thread starts, - // the name has to be correct right from the first message!! - - yCAssert(CONTROLBOARD, iAxisInfo); - - std::vector tmpVect; - for (size_t i = 0; i < subdevice_joints; i++) { - std::string tmp; - bool ret = iAxisInfo->getAxisName(i, tmp); - if (!ret) { - yCError(CONTROLBOARD, "Joint name for axis %zu not found!", i); - return false; - } - tmpVect.emplace_back(tmp); - } - - yCAssert(CONTROLBOARD, tmpVect.size() == subdevice_joints); - - jointNames = tmpVect; - - return true; -} - - -void ControlBoard_nws_ros::run() -{ - yCAssert(CONTROLBOARD, iEncodersTimed); - yCAssert(CONTROLBOARD, iAxisInfo); - - bool positionsOk = iEncodersTimed->getEncodersTimed(ros_struct.position.data(), times.data()); - YARP_UNUSED(positionsOk); - - bool speedsOk = iEncodersTimed->getEncoderSpeeds(ros_struct.velocity.data()); - YARP_UNUSED(speedsOk); - - if (iTorqueControl) { - bool torqueOk = iTorqueControl->getTorques(ros_struct.effort.data()); - YARP_UNUSED(torqueOk); - } - - // Check if the encoders timestamps are consistent. - double tt = *times.data(); - for (auto it = times.begin(); it != times.end(); it++) - { - if (fabs(tt - *it) > 1.0) - { - yCError(CONTROLBOARD, "Encoder Timestamps are not consistent! Data will not be published."); - return; - } - } - - // Update the port envelope time by averaging all timestamps - time.update(std::accumulate(times.begin(), times.end(), 0.0) / subdevice_joints); - yarp::os::Stamp averageTime = time; - - // Data from HW have been gathered few lines before - JointTypeEnum jType; - for (size_t i = 0; i < subdevice_joints; i++) { - iAxisInfo->getJointType(i, jType); - if (jType == VOCAB_JOINTTYPE_REVOLUTE) { - ros_struct.position[i] = convertDegreesToRadians(ros_struct.position[i]); - ros_struct.velocity[i] = convertDegreesToRadians(ros_struct.velocity[i]); - } - } - - ros_struct.name = jointNames; - - ros_struct.header.seq = counter++; - ros_struct.header.stamp = averageTime.getTime(); - - publisherPort.write(ros_struct); -} diff --git a/src/devices/ControlBoardWrapper/ControlBoard_nws_ros.h b/src/devices/ControlBoardWrapper/ControlBoard_nws_ros.h deleted file mode 100644 index bfb7e99a76b..00000000000 --- a/src/devices/ControlBoardWrapper/ControlBoard_nws_ros.h +++ /dev/null @@ -1,109 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_CONTROLBOARD_NWS_ROS_H -#define YARP_DEV_CONTROLBOARD_NWS_ROS_H - -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -#include -#include - -#include -#include -#include - - -/** - * @ingroup dev_impl_nws_ros - * - * \brief `controlBoard_nws_ros`: A controlBoard network wrapper server for ROS. - * - * \section controlBoard_nws_ros_device_parameters Description of input parameters - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:---------------:|:--------------:|:-------:|:--------------:|:-------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | node_name | - | string | - | - | Yes | set the name for ROS node | must start with a leading '/' | - * | topic_name | - | string | - | - | Yes | set the name for ROS topic | must start with a leading '/', recommended value is /joint_states | - * | period | - | double | s | 0.02 | No | refresh period of the broadcasted values in s | optional, default 20ms | - * | subdevice | - | string | - | - | No | name of the subdevice to instantiate | when used, parameters for the subdevice must be provided as well | - * - * ROS message type used is sensor_msgs/JointState.msg (http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html) - */ - -class ControlBoard_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::os::PeriodicThread, - public yarp::dev::WrapperSingle -{ -private: - yarp::rosmsg::sensor_msgs::JointState ros_struct; - - yarp::sig::Vector times; // time for each joint - - std::vector jointNames; // name of the joints - std::string nodeName; // name of the rosNode - std::string topicName; // name of the rosTopic - - yarp::os::Node* node; // ROS node - std::uint32_t counter {0}; // incremental counter in the ROS message - - yarp::os::PortWriterBuffer outputState_buffer; // Buffer associated to the ROS topic - yarp::os::Publisher publisherPort; // Dedicated ROS topic publisher - - static constexpr double default_period = 0.02; // s - double period {default_period}; - - yarp::os::Stamp time; // envelope to attach to the state port - - yarp::dev::DeviceDriver* subdevice_ptr{nullptr}; - bool subdevice_owned {true}; - size_t subdevice_joints {0}; - bool subdevice_ready = false; - - yarp::dev::IPositionControl* iPositionControl{nullptr}; - yarp::dev::IEncodersTimed* iEncodersTimed{nullptr}; - yarp::dev::ITorqueControl* iTorqueControl{nullptr}; - yarp::dev::IAxisInfo* iAxisInfo{nullptr}; - - bool setDevice(yarp::dev::DeviceDriver* device, bool owned); - bool openAndAttachSubDevice(yarp::os::Property& prop); - - void closeDevice(); - void closePorts(); - bool updateAxisName(); - -public: - ControlBoard_nws_ros(); - ControlBoard_nws_ros(const ControlBoard_nws_ros&) = delete; - ControlBoard_nws_ros(ControlBoard_nws_ros&&) = delete; - ControlBoard_nws_ros& operator=(const ControlBoard_nws_ros&) = delete; - ControlBoard_nws_ros& operator=(ControlBoard_nws_ros&&) = delete; - ~ControlBoard_nws_ros() override = default; - - // yarp::dev::DeviceDriver - bool close() override; - bool open(yarp::os::Searchable& prop) override; - - // yarp::dev::WrapperSingle - bool attach(yarp::dev::PolyDriver* poly) override; - bool detach() override; - - // yarp::os::PeriodicThread - void run() override; -}; - -#endif // YARP_DEV_CONTROLBOARD_NWS_ROS_H From d4425e12cf22ce79fb238aef2c2d1f629061ab0d Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 14 Nov 2022 22:44:23 +0100 Subject: [PATCH 015/267] audioFromFileDevice fix and cleanup --- src/devices/audioFromFileDevice/audioFromFileDevice.cpp | 1 - src/devices/audioFromFileDevice/audioFromFileDevice.h | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/devices/audioFromFileDevice/audioFromFileDevice.cpp b/src/devices/audioFromFileDevice/audioFromFileDevice.cpp index 967b1af573d..c4759e04f11 100644 --- a/src/devices/audioFromFileDevice/audioFromFileDevice.cpp +++ b/src/devices/audioFromFileDevice/audioFromFileDevice.cpp @@ -7,7 +7,6 @@ #include #include -#include #include #include #include diff --git a/src/devices/audioFromFileDevice/audioFromFileDevice.h b/src/devices/audioFromFileDevice/audioFromFileDevice.h index d468c10fa71..15ddfed9170 100644 --- a/src/devices/audioFromFileDevice/audioFromFileDevice.h +++ b/src/devices/audioFromFileDevice/audioFromFileDevice.h @@ -11,6 +11,8 @@ #include #include +#include +#include /** * @ingroup dev_impl_media From a5c6771a95e9e032a7de45e0946c639c1e6427be Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 15 Nov 2022 12:31:50 +0100 Subject: [PATCH 016/267] removed option --subdevice from serveral tests. Attach operation is now performed externally. --- tests/libYARP_dev/ControlBoardNwsTest.cpp | 37 +++++++++++++++-------- tests/libYARP_dev/Navigation2DnwcTest.cpp | 25 +++++++++++++-- tests/libYARP_dev/TorqueControlTest.cpp | 37 +++++++++++++---------- 3 files changed, 67 insertions(+), 32 deletions(-) diff --git a/tests/libYARP_dev/ControlBoardNwsTest.cpp b/tests/libYARP_dev/ControlBoardNwsTest.cpp index b9efc1bf163..2148d0987b0 100644 --- a/tests/libYARP_dev/ControlBoardNwsTest.cpp +++ b/tests/libYARP_dev/ControlBoardNwsTest.cpp @@ -9,6 +9,7 @@ #include #include #include +#include #include @@ -29,21 +30,30 @@ TEST_CASE("dev::controlBoard_nws_yarp", "[yarp::dev]") SECTION("test the controlBoard_nws_yarp device") { - PolyDriver dd; - Property p; - p.put("device","controlBoard_nws_yarp"); - p.put("subdevice","fakeMotionControl"); - p.put("name","/motor"); - auto& pg = p.addGroup("GENERAL"); + PolyDriver dd_nws; + Property p_nws; + p_nws.put("device", "controlBoard_nws_yarp"); + p_nws.put("name", "/motor"); + bool result_nws = dd_nws.open(p_nws); + REQUIRE(result_nws); + + PolyDriver dd_dev; + Property p_dev; + p_dev.put("device", "fakeMotionControl"); + auto& pg = p_dev.addGroup("GENERAL"); pg.put("Joints", 16); - bool result; - result = dd.open(p); - REQUIRE(result); // controlBoard_nws_yarp open reported successful + bool result_dev = dd_dev.open(p_dev); + REQUIRE(result_dev); + + yarp::dev::WrapperSingle* ww_nws; + dd_nws.view(ww_nws); + bool result_att = ww_nws->attach(&dd_dev); + REQUIRE(result_att); // Check if IMultipleWrapper interface is correctly found yarp::dev::IMultipleWrapper * i_mwrapper=nullptr; - result = dd.view(i_mwrapper); - REQUIRE(result); // IMultipleWrapper view reported successful + bool result_imw = dd_nws.view(i_mwrapper); + REQUIRE(result_imw); // IMultipleWrapper view reported successful REQUIRE(i_mwrapper != nullptr); // IMultipleWrapper pointer not null PolyDriver dd2; @@ -53,7 +63,7 @@ TEST_CASE("dev::controlBoard_nws_yarp", "[yarp::dev]") p2.put("local","/motor/client"); p2.put("carrier","tcp"); p2.put("ignoreProtocolCheck","true"); - result = dd2.open(p2); + bool result = dd2.open(p2); REQUIRE(result); // remote_controlboard open reported successful IPositionControl *pos = nullptr; @@ -62,7 +72,8 @@ TEST_CASE("dev::controlBoard_nws_yarp", "[yarp::dev]") int axes = 0; pos->getAxes(&axes); CHECK(axes == 16); // interface seems functional - CHECK(dd.close()); // close dd reported successful + CHECK(dd_nws.close()); // close dd reported successful + CHECK(dd_dev.close()); // close dd reported successful CHECK(dd2.close()); // close dd2 reported successful } } diff --git a/tests/libYARP_dev/Navigation2DnwcTest.cpp b/tests/libYARP_dev/Navigation2DnwcTest.cpp index 2421297a2f7..6d6f581092e 100644 --- a/tests/libYARP_dev/Navigation2DnwcTest.cpp +++ b/tests/libYARP_dev/Navigation2DnwcTest.cpp @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -38,9 +39,12 @@ TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") { PolyDriver ddnavserver; PolyDriver ddmapserver; + PolyDriver ddmapstorage; PolyDriver ddmapclient; PolyDriver ddlocserver; PolyDriver ddnavclient; + PolyDriver ddfakeLocalizer; + PolyDriver ddfakeNavigation; INavigation2D* inav = nullptr; IMap2D* imap = nullptr; @@ -48,8 +52,12 @@ TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") { Property pmapserver_cfg; pmapserver_cfg.put("device", "map2D_nws_yarp"); - pmapserver_cfg.put("subdevice", "map2DStorage"); REQUIRE(ddmapserver.open(pmapserver_cfg)); + Property pmapstorage_cfg; + pmapstorage_cfg.put("device", "map2DStorage"); + REQUIRE(ddmapstorage.open(pmapstorage_cfg)); + {yarp::dev::WrapperSingle* ww_nws; ddmapserver.view(ww_nws); + bool result_att = ww_nws->attach(&ddmapstorage);} Property pmapclient_cfg; pmapclient_cfg.put("device", "map2D_nwc_yarp"); @@ -60,13 +68,21 @@ TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") Property plocserver_cfg; plocserver_cfg.put("device", "localization2D_nws_yarp"); - plocserver_cfg.put("subdevice", "fakeLocalizer"); REQUIRE(ddlocserver.open(plocserver_cfg)); + Property pfakeLocalizer_cfg; + pfakeLocalizer_cfg.put("device", "fakeLocalizer"); + REQUIRE(ddfakeLocalizer.open(pfakeLocalizer_cfg)); + {yarp::dev::WrapperSingle* ww_nws; ddlocserver.view(ww_nws); + bool result_att = ww_nws->attach(&ddfakeLocalizer); } Property pnavserver_cfg; pnavserver_cfg.put("device", "navigation2D_nws_yarp"); - pnavserver_cfg.put("subdevice", "fakeNavigation"); REQUIRE(ddnavserver.open(pnavserver_cfg)); + Property pfakeNavigation; + pfakeNavigation.put("device", "fakeNavigation"); + REQUIRE(ddfakeNavigation.open(pfakeNavigation)); + {yarp::dev::WrapperSingle* ww_nws; ddnavserver.view(ww_nws); + bool result_att = ww_nws->attach(&ddfakeNavigation); } Property pnavclient_cfg; pnavclient_cfg.put("device", "navigation2D_nwc_yarp"); @@ -89,6 +105,9 @@ TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") CHECK(ddlocserver.close()); CHECK(ddmapclient.close()); CHECK(ddmapserver.close()); + CHECK(ddmapstorage.close()); + CHECK(ddfakeLocalizer.close()); + CHECK(ddfakeNavigation.close()); } } diff --git a/tests/libYARP_dev/TorqueControlTest.cpp b/tests/libYARP_dev/TorqueControlTest.cpp index 970d4519c08..1fb01cf8372 100644 --- a/tests/libYARP_dev/TorqueControlTest.cpp +++ b/tests/libYARP_dev/TorqueControlTest.cpp @@ -14,6 +14,7 @@ #include #include +#include using namespace yarp::os; using namespace yarp::dev; @@ -29,22 +30,25 @@ TEST_CASE("dev::TorqueControl", "[yarp::dev]") SECTION("test the controlBoard_nws_yarp device") { - PolyDriver dd; - Property p; - p.put("device","controlBoard_nws_yarp"); - p.put("subdevice","fakeMotionControl"); - p.put("name","/motor"); - auto& pg = p.addGroup("GENERAL"); + PolyDriver dd_nws; + Property p_nws; + p_nws.put("device","controlBoard_nws_yarp"); + p_nws.put("name", "/motor"); + bool result_nws = dd_nws.open(p_nws); + REQUIRE(result_nws); + + PolyDriver dd_dev; + Property p_dev; + p_dev.put("device", "fakeMotionControl"); + auto& pg = p_dev.addGroup("GENERAL"); pg.put("Joints", 1); - bool result; - result = dd.open(p); - REQUIRE(result); // controlboard_nws_yarp open reported successful + bool result_dev = dd_dev.open(p_dev); + REQUIRE(result_dev); - // Check if IMultipleWrapper interface is correctly found - yarp::dev::IMultipleWrapper * i_mwrapper=nullptr; - result = dd.view(i_mwrapper); - REQUIRE(result); // IMultipleWrapper view reported successful - REQUIRE(i_mwrapper != nullptr); // IMultipleWrapper pointer not null + yarp::dev::WrapperSingle* ww_nws; + dd_nws.view(ww_nws); + bool result_att = ww_nws->attach(&dd_dev); + REQUIRE(result_att); // controlboard_nws_yarp open reported successful PolyDriver dd2; Property p2; @@ -53,7 +57,7 @@ TEST_CASE("dev::TorqueControl", "[yarp::dev]") p2.put("local","/motor/client"); p2.put("carrier","tcp"); p2.put("ignoreProtocolCheck","true"); - result = dd2.open(p2); + bool result = dd2.open(p2); REQUIRE(result); // remote_controlboard open reported successful ITorqueControl *trq = nullptr; @@ -83,7 +87,8 @@ TEST_CASE("dev::TorqueControl", "[yarp::dev]") CHECK(res.viscousNeg == 0.6); // interface seems functional CHECK(res.coulombPos == 0.7); // interface seems functional CHECK(res.coulombNeg == 0.8); // interface seems functional - CHECK(dd.close()); // close dd reported successful + CHECK(dd_nws.close()); // close dd_nws reported successful + CHECK(dd_dev.close()); // close dd_dev reported successful CHECK(dd2.close()); // close dd2 reported successful } } From 48a7dd0d493732b296055c37bb8dcb00dc112261 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 15 Nov 2022 18:14:15 +0100 Subject: [PATCH 017/267] All devices inside the ROS folder have been moved to the new repo: https://github.com/robotology/yarp-devices-ros-nwx --- .../ROS/ControlBoard_nws_ros/CMakeLists.txt | 54 -- .../ControlBoard_nws_ros.cpp | 335 ----------- .../ControlBoard_nws_ros.h | 109 ---- .../ROS/FrameGrabber_nws_ros/CMakeLists.txt | 52 -- .../FrameGrabber_nws_ros.cpp | 366 ------------ .../FrameGrabber_nws_ros.h | 102 ---- .../ROS/RGBDRosConversionUtils/CMakeLists.txt | 28 - .../RGBDRosConversionUtils.cpp | 240 -------- .../RGBDRosConversionUtils.h | 82 --- .../RGBDRosConversionUtils/rosPixelCode.cpp | 84 --- .../ROS/RGBDRosConversionUtils/rosPixelCode.h | 68 --- .../ROS/RGBDSensorFromRosTopic/CMakeLists.txt | 52 -- .../RGBDSensorFromRosTopic.cpp | 418 -------------- .../RGBDSensorFromRosTopic.h | 263 --------- .../ROS/RGBDSensor_nws_ros/CMakeLists.txt | 56 -- .../RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp | 536 ------------------ .../RGBDSensor_nws_ros/RgbdSensor_nws_ros.h | 178 ------ .../CMakeLists.txt | 53 -- .../RGBDToPointCloudSensor_nws_ros.cpp | 345 ----------- .../RGBDToPointCloudSensor_nws_ros.h | 166 ------ .../ROS/Rangefinder2D_nws_ros/CMakeLists.txt | 48 -- .../Rangefinder2D_nws_ros.cpp | 290 ---------- .../Rangefinder2D_nws_ros.h | 124 ---- .../frameTransformGet_nwc_ros/CMakeLists.txt | 100 ---- .../FrameTransformGet_nwc_ros.cpp | 192 ------- .../FrameTransformGet_nwc_ros.h | 105 ---- .../frameTransformSet_nwc_ros/CMakeLists.txt | 100 ---- .../FrameTransformSet_nwc_ros.cpp | 234 -------- .../FrameTransformSet_nwc_ros.h | 110 ---- .../ROS/laserFromRosTopic/CMakeLists.txt | 48 -- .../laserFromRosTopic/LaserFromRosTopic.cpp | 491 ---------------- .../ROS/laserFromRosTopic/LaserFromRosTopic.h | 121 ---- .../ROS/localization2D_nws_ros/CMakeLists.txt | 50 -- .../Localization2D_nws_ros.cpp | 404 ------------- .../Localization2D_nws_ros.h | 107 ---- src/devices/ROS/map2D_nws_ros/CMakeLists.txt | 51 -- .../ROS/map2D_nws_ros/Map2D_nws_ros.cpp | 422 -------------- src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h | 103 ---- .../CMakeLists.txt | 49 -- .../MobileBaseVelocityControl_nws_ros.cpp | 147 ----- .../MobileBaseVelocityControl_nws_ros.h | 80 --- .../CMakeLists.txt | 258 --------- .../GenericSensorRosPublisher.h | 251 -------- .../IMURosPublisher.cpp | 79 --- .../IMURosPublisher.h | 54 -- .../MagneticFieldRosPublisher.cpp | 41 -- .../MagneticFieldRosPublisher.h | 51 -- .../PoseStampedRosPublisher.cpp | 62 -- .../PoseStampedRosPublisher.h | 51 -- .../TemperatureRosPublisher.cpp | 40 -- .../TemperatureRosPublisher.h | 49 -- .../WrenchStampedRosPublisher.cpp | 42 -- .../WrenchStampedRosPublisher.h | 49 -- .../ROS/odometry2D_nws_ros/CMakeLists.txt | 50 -- .../odometry2D_nws_ros/Odometry2D_nws_ros.cpp | 260 --------- .../odometry2D_nws_ros/Odometry2D_nws_ros.h | 140 ----- 56 files changed, 8440 deletions(-) delete mode 100644 src/devices/ROS/ControlBoard_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp delete mode 100644 src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.h delete mode 100644 src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.cpp delete mode 100644 src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.h delete mode 100644 src/devices/ROS/RGBDRosConversionUtils/CMakeLists.txt delete mode 100644 src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp delete mode 100644 src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.h delete mode 100644 src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.cpp delete mode 100644 src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.h delete mode 100644 src/devices/ROS/RGBDSensorFromRosTopic/CMakeLists.txt delete mode 100644 src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp delete mode 100644 src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h delete mode 100644 src/devices/ROS/RGBDSensor_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp delete mode 100644 src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h delete mode 100644 src/devices/ROS/RGBDToPointCloudSensor_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.cpp delete mode 100644 src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h delete mode 100644 src/devices/ROS/Rangefinder2D_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp delete mode 100644 src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h delete mode 100644 src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.cpp delete mode 100644 src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.h delete mode 100644 src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.cpp delete mode 100644 src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.h delete mode 100644 src/devices/ROS/laserFromRosTopic/CMakeLists.txt delete mode 100644 src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.cpp delete mode 100644 src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.h delete mode 100644 src/devices/ROS/localization2D_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.cpp delete mode 100644 src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.h delete mode 100644 src/devices/ROS/map2D_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.cpp delete mode 100644 src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h delete mode 100644 src/devices/ROS/mobileBaseVelocityControl_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp delete mode 100644 src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/CMakeLists.txt delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.h delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp delete mode 100644 src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h delete mode 100644 src/devices/ROS/odometry2D_nws_ros/CMakeLists.txt delete mode 100644 src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.cpp delete mode 100644 src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.h diff --git a/src/devices/ROS/ControlBoard_nws_ros/CMakeLists.txt b/src/devices/ROS/ControlBoard_nws_ros/CMakeLists.txt deleted file mode 100644 index eaa5bdae3c1..00000000000 --- a/src/devices/ROS/ControlBoard_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,54 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin( - controlBoard_nws_ros - CATEGORY device - TYPE ControlBoard_nws_ros - INCLUDE ControlBoard_nws_ros.h - EXTRA_CONFIG - WRAPPER=controlBoard_nws_ros - DEFAULT ON -) - -if(NOT SKIP_controlBoard_nws_ros) - yarp_add_plugin(yarp_controlBoard_nws_ros) - - target_compile_definitions(yarp_controlBoard_nws_ros - PRIVATE - LOG_COMPONENT="yarp.devices.controlBoard_nws_ros" - ) - - target_sources(yarp_controlBoard_nws_ros - PRIVATE - ControlBoard_nws_ros.cpp - ControlBoard_nws_ros.h - ) - - target_link_libraries(yarp_controlBoard_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_controlBoard_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_controlBoard_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp b/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp deleted file mode 100644 index 4d785fc190c..00000000000 --- a/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.cpp +++ /dev/null @@ -1,335 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "ControlBoard_nws_ros.h" - -#include -#include - -#include - -#include - -#include - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - -namespace { - YARP_LOG_COMPONENT(CONTROLBOARD, "yarp.device.controlBoard_nws_ros") -} - -ControlBoard_nws_ros::ControlBoard_nws_ros() : - yarp::os::PeriodicThread(default_period) -{ -} - - -void ControlBoard_nws_ros::closePorts() -{ - publisherPort.interrupt(); - publisherPort.close(); - - delete node; - node = nullptr; -} - -bool ControlBoard_nws_ros::close() -{ - // Ensure that the device is not running - if (isRunning()) { - stop(); - } - - closeDevice(); - closePorts(); - - return true; -} - - -bool ControlBoard_nws_ros::open(Searchable& config) -{ - Property prop; - prop.fromString(config.toString()); - - // Check parameter, so if both are present we use the correct one - if (prop.check("period")) { - if (!prop.find("period").isFloat64()) { - yCError(CONTROLBOARD) << "'period' parameter is not a double value"; - return false; - } - period = prop.find("period").asFloat64(); - if (period <= 0) { - yCError(CONTROLBOARD) << "'period' parameter is not valid, read value is" << period; - return false; - } - } else { - yCDebug(CONTROLBOARD) << "'period' parameter missing, using default thread period = 0.02s"; - period = default_period; - } - - // Check if we need to create subdevice or if they are - // passed later on thorugh attachAll() - if (prop.check("subdevice")) { - prop.setMonitor(config.getMonitor()); - if (!openAndAttachSubDevice(prop)) { - yCError(CONTROLBOARD, "Error while opening subdevice"); - return false; - } - subdevice_ready = true; - } - - // check for node_name parameter - if (!config.check("node_name")) { - yCError(CONTROLBOARD) << nodeName << " cannot find node_name parameter"; - return false; - } - nodeName = config.find("node_name").asString(); - if(nodeName[0] != '/'){ - yCError(CONTROLBOARD) << "node_name must begin with an initial /"; - return false; - } - - // check for topic_name parameter - if (!config.check("topic_name")) { - yCError(CONTROLBOARD) << nodeName << " cannot find topic_name parameter"; - return false; - } - topicName = config.find("topic_name").asString(); - if(topicName[0] != '/'){ - yCError(CONTROLBOARD) << "topic_name must begin with an initial /"; - return false; - } - yCInfo(CONTROLBOARD) << "topic_name is " << topicName; - // call ROS node/topic initialization - node = new yarp::os::Node(nodeName); - if (!publisherPort.topic(topicName)) { - yCError(CONTROLBOARD) << " opening " << topicName << " Topic, check your configuration"; - return false; - } - - // In case attach is not deferred and the controlboard already owns a valid device - // we can start the thread. Otherwise this will happen when attachAll is called - if (subdevice_ready) { - setPeriod(period); - if (!start()) { - yCError(CONTROLBOARD) << "Error starting thread"; - return false; - } - } - - return true; -} - - - -// For the simulator, if a subdevice parameter is given to the wrapper, it will -// open it and attach to immediately. -bool ControlBoard_nws_ros::openAndAttachSubDevice(Property& prop) -{ - Property p; - auto* subDeviceOwned = new PolyDriver; - p.fromString(prop.toString()); - - std::string subdevice = prop.find("subdevice").asString(); - p.setMonitor(prop.getMonitor(), subdevice.c_str()); // pass on any monitoring - p.unput("device"); - p.put("device", subdevice); // subdevice was already checked before - - // if errors occurred during open, quit here. - yCDebug(CONTROLBOARD, "opening subdevice"); - subDeviceOwned->open(p); - - if (!subDeviceOwned->isValid()) { - yCError(CONTROLBOARD, "opening subdevice... FAILED"); - return false; - } - - return setDevice(subDeviceOwned, true); -} - - -bool ControlBoard_nws_ros::setDevice(yarp::dev::DeviceDriver* driver, bool owned) -{ - yCAssert(CONTROLBOARD, driver); - - // Save the pointer and subDeviceOwned - subdevice_ptr = driver; - subdevice_owned = owned; - - subdevice_ptr->view(iPositionControl); - if (!iPositionControl) { - yCError(CONTROLBOARD, "<%s - %s>: IPositionControl interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str()); - return false; - } - - subdevice_ptr->view(iEncodersTimed); - if (!iEncodersTimed) { - yCError(CONTROLBOARD, "<%s - %s>: IEncodersTimed interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str()); - return false; - } - - subdevice_ptr->view(iTorqueControl); - if (!iTorqueControl) { - yCWarning(CONTROLBOARD, "<%s - %s>: ITorqueControl interface was not found in subdevice.", nodeName.c_str(), topicName.c_str()); - } - - subdevice_ptr->view(iAxisInfo); - if (!iAxisInfo) { - yCError(CONTROLBOARD, "<%s - %s>: IAxisInfo interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str()); - return false; - } - - // Get the number of controlled joints - int tmp_axes; - if (!iPositionControl->getAxes(&tmp_axes)) { - yCError(CONTROLBOARD, "<%s - %s>: Failed to get axes number for subdevice ", nodeName.c_str(), topicName.c_str()); - return false; - } - if (tmp_axes <= 0) { - yCError(CONTROLBOARD, "<%s - %s>: attached device has an invalid number of joints (%d)", nodeName.c_str(), topicName.c_str(), tmp_axes); - return false; - } - subdevice_joints = static_cast(tmp_axes); - times.resize(subdevice_joints); - ros_struct.name.resize(subdevice_joints); - ros_struct.position.resize(subdevice_joints); - ros_struct.velocity.resize(subdevice_joints); - ros_struct.effort.resize(subdevice_joints); - - if (!updateAxisName()) { - return false; - } - - return true; -} - - -void ControlBoard_nws_ros::closeDevice() -{ - // If the subdevice is owned, close and delete the device - if (subdevice_owned) { - yCAssert(CONTROLBOARD, subdevice_ptr); - subdevice_ptr->close(); - delete subdevice_ptr; - } - subdevice_ptr = nullptr; - subdevice_owned = false; - subdevice_joints = 0; - subdevice_ready = false; - - times.clear(); - - // Clear all interfaces - iPositionControl = nullptr; - iEncodersTimed = nullptr; - iTorqueControl = nullptr; - iAxisInfo = nullptr; -} - -bool ControlBoard_nws_ros::attach(yarp::dev::PolyDriver* poly) -{ - // Check if we already instantiated a subdevice previously - if (subdevice_ready) { - return false; - } - - if (!setDevice(poly, false)) { - return false; - } - - setPeriod(period); - if (!start()) { - yCError(CONTROLBOARD) << "Error starting thread"; - return false; - } - - return true; -} - -bool ControlBoard_nws_ros::detach() -{ - //check if we already instantiated a subdevice previously - if (subdevice_owned) { - return false; - } - - // Ensure that the device is not running - if (isRunning()) { - stop(); - } - - closeDevice(); - - return true; -} - - -bool ControlBoard_nws_ros::updateAxisName() -{ - // IMPORTANT!! This function has to be called BEFORE the thread starts, - // the name has to be correct right from the first message!! - - yCAssert(CONTROLBOARD, iAxisInfo); - - std::vector tmpVect; - for (size_t i = 0; i < subdevice_joints; i++) { - std::string tmp; - bool ret = iAxisInfo->getAxisName(i, tmp); - if (!ret) { - yCError(CONTROLBOARD, "Joint name for axis %zu not found!", i); - return false; - } - tmpVect.emplace_back(tmp); - } - - yCAssert(CONTROLBOARD, tmpVect.size() == subdevice_joints); - - jointNames = tmpVect; - - return true; -} - - -void ControlBoard_nws_ros::run() -{ - yCAssert(CONTROLBOARD, iEncodersTimed); - yCAssert(CONTROLBOARD, iAxisInfo); - - bool positionsOk = iEncodersTimed->getEncodersTimed(ros_struct.position.data(), times.data()); - YARP_UNUSED(positionsOk); - - bool speedsOk = iEncodersTimed->getEncoderSpeeds(ros_struct.velocity.data()); - YARP_UNUSED(speedsOk); - - if (iTorqueControl) { - bool torqueOk = iTorqueControl->getTorques(ros_struct.effort.data()); - YARP_UNUSED(torqueOk); - } - - // Update the port envelope time by averaging all timestamps - time.update(std::accumulate(times.begin(), times.end(), 0.0) / subdevice_joints); - yarp::os::Stamp averageTime = time; - - // Data from HW have been gathered few lines before - JointTypeEnum jType; - for (size_t i = 0; i < subdevice_joints; i++) { - iAxisInfo->getJointType(i, jType); - if (jType == VOCAB_JOINTTYPE_REVOLUTE) { - ros_struct.position[i] = convertDegreesToRadians(ros_struct.position[i]); - ros_struct.velocity[i] = convertDegreesToRadians(ros_struct.velocity[i]); - } - } - - ros_struct.name = jointNames; - - ros_struct.header.seq = counter++; - ros_struct.header.stamp = averageTime.getTime(); - - publisherPort.write(ros_struct); -} diff --git a/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.h b/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.h deleted file mode 100644 index bfb7e99a76b..00000000000 --- a/src/devices/ROS/ControlBoard_nws_ros/ControlBoard_nws_ros.h +++ /dev/null @@ -1,109 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_CONTROLBOARD_NWS_ROS_H -#define YARP_DEV_CONTROLBOARD_NWS_ROS_H - -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -#include -#include - -#include -#include -#include - - -/** - * @ingroup dev_impl_nws_ros - * - * \brief `controlBoard_nws_ros`: A controlBoard network wrapper server for ROS. - * - * \section controlBoard_nws_ros_device_parameters Description of input parameters - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:---------------:|:--------------:|:-------:|:--------------:|:-------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | node_name | - | string | - | - | Yes | set the name for ROS node | must start with a leading '/' | - * | topic_name | - | string | - | - | Yes | set the name for ROS topic | must start with a leading '/', recommended value is /joint_states | - * | period | - | double | s | 0.02 | No | refresh period of the broadcasted values in s | optional, default 20ms | - * | subdevice | - | string | - | - | No | name of the subdevice to instantiate | when used, parameters for the subdevice must be provided as well | - * - * ROS message type used is sensor_msgs/JointState.msg (http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html) - */ - -class ControlBoard_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::os::PeriodicThread, - public yarp::dev::WrapperSingle -{ -private: - yarp::rosmsg::sensor_msgs::JointState ros_struct; - - yarp::sig::Vector times; // time for each joint - - std::vector jointNames; // name of the joints - std::string nodeName; // name of the rosNode - std::string topicName; // name of the rosTopic - - yarp::os::Node* node; // ROS node - std::uint32_t counter {0}; // incremental counter in the ROS message - - yarp::os::PortWriterBuffer outputState_buffer; // Buffer associated to the ROS topic - yarp::os::Publisher publisherPort; // Dedicated ROS topic publisher - - static constexpr double default_period = 0.02; // s - double period {default_period}; - - yarp::os::Stamp time; // envelope to attach to the state port - - yarp::dev::DeviceDriver* subdevice_ptr{nullptr}; - bool subdevice_owned {true}; - size_t subdevice_joints {0}; - bool subdevice_ready = false; - - yarp::dev::IPositionControl* iPositionControl{nullptr}; - yarp::dev::IEncodersTimed* iEncodersTimed{nullptr}; - yarp::dev::ITorqueControl* iTorqueControl{nullptr}; - yarp::dev::IAxisInfo* iAxisInfo{nullptr}; - - bool setDevice(yarp::dev::DeviceDriver* device, bool owned); - bool openAndAttachSubDevice(yarp::os::Property& prop); - - void closeDevice(); - void closePorts(); - bool updateAxisName(); - -public: - ControlBoard_nws_ros(); - ControlBoard_nws_ros(const ControlBoard_nws_ros&) = delete; - ControlBoard_nws_ros(ControlBoard_nws_ros&&) = delete; - ControlBoard_nws_ros& operator=(const ControlBoard_nws_ros&) = delete; - ControlBoard_nws_ros& operator=(ControlBoard_nws_ros&&) = delete; - ~ControlBoard_nws_ros() override = default; - - // yarp::dev::DeviceDriver - bool close() override; - bool open(yarp::os::Searchable& prop) override; - - // yarp::dev::WrapperSingle - bool attach(yarp::dev::PolyDriver* poly) override; - bool detach() override; - - // yarp::os::PeriodicThread - void run() override; -}; - -#endif // YARP_DEV_CONTROLBOARD_NWS_ROS_H diff --git a/src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt b/src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt deleted file mode 100644 index 9329963d1b2..00000000000 --- a/src/devices/ROS/FrameGrabber_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,52 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(frameGrabber_nws_ros - CATEGORY device - TYPE FrameGrabber_nws_ros - INCLUDE FrameGrabber_nws_ros.h - EXTRA_CONFIG - WRAPPER=frameGrabber_nws_ros - DEFAULT ON -) - -if(NOT SKIP_frameGrabber_nws_ros) - yarp_add_plugin(yarp_frameGrabber_nws_ros) - - target_sources(yarp_frameGrabber_nws_ros - PRIVATE - FrameGrabber_nws_ros.cpp - FrameGrabber_nws_ros.h - ) - - target_sources(yarp_frameGrabber_nws_ros PRIVATE $) - target_include_directories(yarp_frameGrabber_nws_ros PRIVATE $) - - target_link_libraries(yarp_frameGrabber_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_frameGrabber_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameGrabber_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.cpp b/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.cpp deleted file mode 100644 index 688923ef294..00000000000 --- a/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.cpp +++ /dev/null @@ -1,366 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "FrameGrabber_nws_ros.h" - -#include -#include - -#include - -#include - -namespace { -YARP_LOG_COMPONENT(FRAMEGRABBER_NWS_ROS, "yarp.device.frameGrabber_nws_ros") -} // namespace - - -FrameGrabber_nws_ros::FrameGrabber_nws_ros() : - PeriodicThread(s_default_period) -{ -} - - -FrameGrabber_nws_ros::~FrameGrabber_nws_ros() -{ - close(); -} - - -bool FrameGrabber_nws_ros::close() -{ - if (!m_active) { - return false; - } - m_active = false; - - detach(); - - publisherPort_image.interrupt(); - publisherPort_image.close(); - - publisherPort_cameraInfo.interrupt(); - publisherPort_cameraInfo.close(); - - if (node != nullptr) { - node->interrupt(); - delete node; - node = nullptr; - } - - if (subdevice) { - subdevice->close(); - delete subdevice; - subdevice = nullptr; - } - - isSubdeviceOwned = false; - - return true; -} - - -bool FrameGrabber_nws_ros::open(yarp::os::Searchable& config) -{ - if (m_active) { - yCError(FRAMEGRABBER_NWS_ROS, "Device is already opened"); - return false; - } - - // Check "period" option - if (config.check("period", "refresh period(in s) of the broadcasted values through yarp ports") && config.find("period").isFloat64()) { - m_period = config.find("period").asFloat64(); - } else { - yCInfo(FRAMEGRABBER_NWS_ROS) - << "Period parameter not found, using default of" - << s_default_period - << "seconds"; - } - PeriodicThread::setPeriod(m_period); - - // Check "node_name" option and open node - if (!config.check("node_name")) - { - yCError(FRAMEGRABBER_NWS_ROS) << "Missing node_name parameter"; - return false; - } - std::string nodeName = config.find("node_name").asString(); - if (nodeName.c_str()[0] != '/') { - yCError(FRAMEGRABBER_NWS_ROS) << "Missing '/' in node_name parameter"; - return false; - } - - node = new yarp::os::Node(nodeName); - - // Check "topic_name" option and open publisher - if (!config.check("topic_name")) - { - yCError(FRAMEGRABBER_NWS_ROS) << "Missing topic_name parameter"; - return false; - } - std::string topicName = config.find("topic_name").asString(); - if (topicName.c_str()[0] != '/') { - yCError(FRAMEGRABBER_NWS_ROS) << "Missing '/' in topic_name parameter"; - return false; - } - - // set "imageTopicName" and open publisher - if (!publisherPort_image.topic(topicName)) { - yCError(FRAMEGRABBER_NWS_ROS) << "Unable to publish data on " << topicName << " topic, check your yarp-ROS network configuration"; - return false; - } - - // set "cameraInfoTopicName" and open publisher - - - std::string cameraInfoTopicName = topicName.substr(0,topicName.rfind('/')) + "/camera_info"; - if (!publisherPort_cameraInfo.topic(cameraInfoTopicName)) { - yCError(FRAMEGRABBER_NWS_ROS) << "Unable to publish data on" << cameraInfoTopicName << "topic, check your yarp-ROS network configuration"; - return false; - } - - // Check "frame_id" option - if (!config.check("frame_id")) - { - yCError(FRAMEGRABBER_NWS_ROS) << "Missing frame_id parameter"; - return false; - } - m_frameId = config.find("frame_id").asString(); - - // Check "subdevice" option and eventually open the device - isSubdeviceOwned = config.check("subdevice"); - if (isSubdeviceOwned) { - yarp::os::Property p; - subdevice = new yarp::dev::PolyDriver; - p.fromString(config.toString()); - p.put("pixelType", VOCAB_PIXEL_RGB); - p.setMonitor(config.getMonitor(), "subdevice"); // pass on any monitoring - p.unput("device"); - p.put("device", config.find("subdevice").asString()); // subdevice was already checked before - - // if errors occurred during open, quit here. - subdevice->open(p); - - if (!(subdevice->isValid())) { - yCError(FRAMEGRABBER_NWS_ROS, "Unable to open subdevice"); - return false; - } - if (!attach(subdevice)) { - yCError(FRAMEGRABBER_NWS_ROS, "Unable to attach subdevice"); - return false; - } - } else { - yCInfo(FRAMEGRABBER_NWS_ROS) << "Running, waiting for attach..."; - } - - m_active = true; - - return true; -} - -bool FrameGrabber_nws_ros::attach(yarp::dev::PolyDriver* poly) -{ - if (!poly->isValid()) { - yCError(FRAMEGRABBER_NWS_ROS) << "Device " << poly << " to attach to is not valid ... cannot proceed"; - return false; - } - - poly->view(iRgbVisualParams); - poly->view(iFrameGrabberImage); - poly->view(iPreciselyTimed); - - if (iFrameGrabberImage == nullptr) { - yCError(FRAMEGRABBER_NWS_ROS) << "IFrameGrabberImage interface is not available on the device"; - return false; - } - - if (iRgbVisualParams == nullptr) { - yCWarning(FRAMEGRABBER_NWS_ROS) << "IRgbVisualParams interface is not available on the device"; - } - - return PeriodicThread::start(); -} - - -bool FrameGrabber_nws_ros::detach() -{ - if (yarp::os::PeriodicThread::isRunning()) { - yarp::os::PeriodicThread::stop(); - } - - iRgbVisualParams = nullptr; - iFrameGrabberImage = nullptr; - iPreciselyTimed = nullptr; - - return true; -} - -bool FrameGrabber_nws_ros::threadInit() -{ - img = new yarp::sig::ImageOf; - return true; -} - -void FrameGrabber_nws_ros::threadRelease() -{ - delete img; - img = nullptr; -} - - -// Publish the images on the buffered port -void FrameGrabber_nws_ros::run() -{ - if (publisherPort_image.getOutputCount() == 0 && publisherPort_cameraInfo.getOutputCount() == 0) { - // If no ports are connected, do not call getImage on the interface. - return; - } - - if (iPreciselyTimed) { - m_stamp = iPreciselyTimed->getLastInputStamp(); - } else { - m_stamp.update(yarp::os::Time::now()); - } - - if (iFrameGrabberImage && publisherPort_image.getOutputCount() > 0) { - iFrameGrabberImage->getImage(*img); - auto& image = publisherPort_image.prepare(); - - image.data.resize(img->getRawImageSize()); - image.width = img->width(); - image.height = img->height(); - image.encoding = yarp::dev::ROSPixelCode::yarp2RosPixelCode(img->getPixelCode()); - image.step = img->getRowSize(); - image.header.frame_id = m_frameId; - image.header.stamp = m_stamp.getTime(); - image.header.seq = m_stamp.getCount(); - image.is_bigendian = 0; - - memcpy(image.data.data(), img->getRawImage(), img->getRawImageSize()); - - publisherPort_image.setEnvelope(m_stamp); - publisherPort_image.write(); - } - - if (iRgbVisualParams && publisherPort_cameraInfo.getOutputCount() > 0) { - auto& cameraInfo = publisherPort_cameraInfo.prepare(); - - if (setCamInfo(cameraInfo)) { - publisherPort_cameraInfo.setEnvelope(m_stamp); - publisherPort_cameraInfo.write(); - } else { - publisherPort_cameraInfo.unprepare(); - } - } -} - -namespace { -template -struct param -{ - param(T& inVar, std::string inName) : - var(&inVar), - parname(std::move(inName)) - { - } - T* var; - std::string parname; -}; -} // namespace - -bool FrameGrabber_nws_ros::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo) -{ - yCAssert(FRAMEGRABBER_NWS_ROS, iRgbVisualParams); - - yarp::os::Property camData; - if (!iRgbVisualParams->getRgbIntrinsicParam(camData)) { - yCErrorThreadOnce(FRAMEGRABBER_NWS_ROS) << "Unable to get intrinsic param from rgb sensor!"; - return false; - } - - if (!camData.check("distortionModel")) { - yCWarning(FRAMEGRABBER_NWS_ROS) << "Missing distortion model"; - return false; - } - - std::string distModel = camData.find("distortionModel").asString(); - if (distModel != "plumb_bob") { - yCError(FRAMEGRABBER_NWS_ROS) << "Distortion model not supported"; - return false; - } - - double phyF = 0.0; - double fx = 0.0; - double fy = 0.0; - double cx = 0.0; - double cy = 0.0; - double k1 = 0.0; - double k2 = 0.0; - double t1 = 0.0; - double t2 = 0.0; - double k3 = 0.0; - - std::vector> parVector; - parVector.emplace_back(phyF,"physFocalLength"); - parVector.emplace_back(fx,"focalLengthX"); - parVector.emplace_back(fy,"focalLengthY"); - parVector.emplace_back(cx,"principalPointX"); - parVector.emplace_back(cy,"principalPointY"); - parVector.emplace_back(k1,"k1"); - parVector.emplace_back(k2,"k2"); - parVector.emplace_back(t1,"t1"); - parVector.emplace_back(t2,"t2"); - parVector.emplace_back(k3,"k3"); - - for(auto& par : parVector) { - if(!camData.check(par.parname)) { - yCWarning(FRAMEGRABBER_NWS_ROS) << "Driver has not the param:" << par.parname; - return false; - } - *(par.var) = camData.find(par.parname).asFloat64(); - } - - cameraInfo.header.frame_id = m_frameId; - cameraInfo.header.seq = m_stamp.getCount(); - cameraInfo.header.stamp = m_stamp.getTime(); - cameraInfo.width = iRgbVisualParams->getRgbWidth(); - cameraInfo.height = iRgbVisualParams->getRgbHeight(); - cameraInfo.distortion_model = distModel; - - cameraInfo.D.resize(5); - cameraInfo.D[0] = k1; - cameraInfo.D[1] = k2; - cameraInfo.D[2] = t1; - cameraInfo.D[3] = t2; - cameraInfo.D[4] = k3; - - cameraInfo.K.resize(9); - cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx; - cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy; - cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1; - - /* - * ROS documentation on cameraInfo message: - * "Rectification matrix (stereo cameras only) - * A rotation matrix aligning the camera coordinate system to the ideal - * stereo image plane so that epipolar lines in both stereo images are - * parallel." - * useless in our case, it will be an identity matrix - */ - - cameraInfo.R.assign(9, 0); - cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1; - - cameraInfo.P.resize(12); - cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0; - cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0; - cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0; - - cameraInfo.binning_x = cameraInfo.binning_y = 0; - cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0; - cameraInfo.roi.do_rectify = false; - return true; -} diff --git a/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.h b/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.h deleted file mode 100644 index 6368fef357e..00000000000 --- a/src/devices/ROS/FrameGrabber_nws_ros/FrameGrabber_nws_ros.h +++ /dev/null @@ -1,102 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_FRAMEGRABBER_NWS_ROS_H -#define YARP_FRAMEGRABBER_NWS_ROS_H - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -/** - * @ingroup dev_impl_nws_ros - * - * \section FrameGrabber_nws_ros_device_parameters Description of input parameters - * - * \brief `frameGrabber_nws_ros`: A ROS NWS for camera devices. - * Parameters required by this device are: - * | Parameter name | Type | Units | Default Value | Required | Description | Notes | - * |:---------------:|:------:|:-------:|:-------------:|:--------: |:----------------------------------------:|:-----:| - * | period | float | seconds | 0.03 s | No | the period of publication | | - * | node_name | String | - | - | Yes | the name of the ros node | must begin with / | - * | topic_name | String | - | - | Yes | the name of the ros topic | must begin with / | - * | frame_id | String | - | - | Yes | the frame where the grabber is placed | | - * | subdevice | string | - | - | Yes | the name of the grabber used | - | - * - */ - -class FrameGrabber_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::dev::WrapperSingle, - public yarp::os::PeriodicThread -{ -private: - // Publishers - typedef yarp::os::Publisher ImageTopicType; - typedef yarp::os::Publisher CameraInfoTopicType; - - yarp::os::Node* node {nullptr}; - ImageTopicType publisherPort_image; - CameraInfoTopicType publisherPort_cameraInfo; - - // Subdevice - yarp::dev::PolyDriver* subdevice {nullptr}; - bool isSubdeviceOwned {false}; - - // Interfaces handled - yarp::dev::IRgbVisualParams* iRgbVisualParams {nullptr}; - yarp::dev::IFrameGrabberImage* iFrameGrabberImage {nullptr}; - yarp::dev::IPreciselyTimed* iPreciselyTimed {nullptr}; - - // Images - yarp::sig::ImageOf* img {nullptr}; - - // Internal state - bool m_active {false}; - yarp::os::Stamp m_stamp; - std::string m_frameId; - - // Options - static constexpr double s_default_period = 0.03; // seconds - double m_period {s_default_period}; - - bool setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo); - -public: - FrameGrabber_nws_ros(); - FrameGrabber_nws_ros(const FrameGrabber_nws_ros&) = delete; - FrameGrabber_nws_ros(FrameGrabber_nws_ros&&) = delete; - FrameGrabber_nws_ros& operator=(const FrameGrabber_nws_ros&) = delete; - FrameGrabber_nws_ros& operator=(FrameGrabber_nws_ros&&) = delete; - ~FrameGrabber_nws_ros() override; - - // DeviceDriver - bool close() override; - bool open(yarp::os::Searchable& config) override; - - // IWrapper interface - bool attach(yarp::dev::PolyDriver* poly) override; - bool detach() override; - - //RateThread - bool threadInit() override; - void threadRelease() override; - void run() override; -}; - -#endif // YARP_FRAMEGRABBER_NWS_ROS_H diff --git a/src/devices/ROS/RGBDRosConversionUtils/CMakeLists.txt b/src/devices/ROS/RGBDRosConversionUtils/CMakeLists.txt deleted file mode 100644 index a39e2e78613..00000000000 --- a/src/devices/ROS/RGBDRosConversionUtils/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -if(NOT YARP_COMPILE_DEVICE_PLUGINS) - return() -endif() - -add_library(RGBDRosConversionUtils OBJECT) - -target_sources(RGBDRosConversionUtils - PRIVATE - RGBDRosConversionUtils.cpp - RGBDRosConversionUtils.h - rosPixelCode.h - rosPixelCode.cpp -) - -target_include_directories(RGBDRosConversionUtils PUBLIC ${CMAKE_CURRENT_LIST_DIR}) - -target_link_libraries(RGBDRosConversionUtils - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_rosmsg - YARP::YARP_dev -) - -set_property(TARGET RGBDRosConversionUtils PROPERTY FOLDER "Devices/Shared") diff --git a/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp b/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp deleted file mode 100644 index eebf879ec90..00000000000 --- a/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.cpp +++ /dev/null @@ -1,240 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "RGBDRosConversionUtils.h" -#include "rosPixelCode.h" - -using namespace yarp::dev; -using namespace yarp::sig; -using namespace yarp::os; -using namespace yarp::dev::RGBDRosConversionUtils; - -namespace { -YARP_LOG_COMPONENT(RGBD_ROS, "yarp.device.RGBDRosConversion") -} - -commonImageProcessor::commonImageProcessor(std::string cameradata_topic_name, std::string camerainfo_topic_name) -{ - if (this->topic(cameradata_topic_name)==false) - { - yCError(RGBD_ROS) << "Error opening topic:" << cameradata_topic_name; - } - if (m_subscriber_camera_info.topic(camerainfo_topic_name) == false) - { - yCError(RGBD_ROS) << "Error opening topic:" << camerainfo_topic_name; - } - m_cameradata_topic_name = cameradata_topic_name; - m_camerainfo_topic_name = camerainfo_topic_name; - m_contains_rgb_data = false; - m_contains_depth_data = false; -} -commonImageProcessor::~commonImageProcessor() -{ - this->close(); - m_subscriber_camera_info.close(); -} - -bool commonImageProcessor::getLastRGBData(yarp::sig::FlexImage& data, yarp::os::Stamp& stmp) -{ - if (m_contains_rgb_data == false) { return false;} - - //this blocks untils the first data is received; - /*size_t counter = 0; - while (m_contains_rgb_data == false) - { - yarp::os::Time::delay(0.1); - if (counter++ > 100) { yCDebug(RGBD_ROS) << "Waiting for incoming rgb data..."; counter = 0; } - }*/ - - m_port_mutex.lock(); - data = m_lastRGBImage; - stmp = m_lastStamp; - m_port_mutex.unlock(); - return true; -} - -bool commonImageProcessor::getLastDepthData(yarp::sig::ImageOf& data, yarp::os::Stamp& stmp) -{ - if (m_contains_depth_data == false) { return false;} - - //this blocks untils the first data is received; - /*size_t counter = 0; - while (m_contains_depth_data == false) - { - yarp::os::Time::delay(0.1); - if (counter++ > 100) { yCDebug(RGBD_ROS) << "Waiting for incoming depth data..."; counter = 0; } - }*/ - - m_port_mutex.lock(); - data = m_lastDepthImage; - stmp = m_lastStamp; - m_port_mutex.unlock(); - return true; -} - -size_t commonImageProcessor::getWidth() const -{ - return m_lastDepthImage.width(); -} - -size_t commonImageProcessor::getHeight() const -{ - return m_lastDepthImage.height(); -} - -void commonImageProcessor::onRead(yarp::rosmsg::sensor_msgs::Image& v) -{ - m_port_mutex.lock(); - int yarp_pixcode = yarp::dev::ROSPixelCode::Ros2YarpPixelCode(v.encoding); - if (yarp_pixcode == VOCAB_PIXEL_RGB || - yarp_pixcode == VOCAB_PIXEL_BGR) - { - m_lastRGBImage.setPixelCode(yarp_pixcode); - m_lastRGBImage.resize(v.width, v.height); - size_t c = 0; - for (auto it = v.data.begin(); it != v.data.end(); it++) - { - m_lastRGBImage.getRawImage()[c++]=*it; - } - m_lastStamp.update(); - m_contains_rgb_data = true; - } - else if (v.encoding == TYPE_16UC1) - { - m_lastDepthImage.resize(v.width, v.height); - size_t c = 0; - uint16_t* p = (uint16_t*)(v.data.data()); - uint16_t* siz = (uint16_t*)(v.data.data()) + (v.data.size() / sizeof(uint16_t)); - int count = 0; - for (; p < siz; p++) - { - float value = float(*p) / 1000.0; - ((float*)(m_lastDepthImage.getRawImage()))[c++] = value; - count++; - } - m_lastStamp.update(); - m_contains_depth_data = true; - } - else if (v.encoding == TYPE_32FC1) - { - m_lastDepthImage.resize(v.width, v.height); - size_t c = 0; - for (auto it = v.data.begin(); it != v.data.end(); it++) - { - m_lastDepthImage.getRawImage()[c++] = *it; - } - m_lastStamp.update(); - m_contains_depth_data = true; - } - else - { - yCError(RGBD_ROS) << "Unsupported rgb/depth format:" << v.encoding; - } - m_port_mutex.unlock(); -} - -bool commonImageProcessor::getFOV(double& horizontalFov, double& verticalFov) const -{ - yarp::rosmsg::sensor_msgs::CameraInfo* tmp = m_subscriber_camera_info.read(true); - m_lastCameraInfo = *tmp; - yarp::sig::IntrinsicParams params; - params.focalLengthX = m_lastCameraInfo.K[0]; - params.focalLengthY = m_lastCameraInfo.K[4]; - params.principalPointX = m_lastCameraInfo.K[2]; - params.principalPointY = m_lastCameraInfo.K[5]; - yCError(RGBD_ROS) << "getIntrinsicParam not yet implemented"; - return false; -} - -bool commonImageProcessor::getIntrinsicParam(yarp::os::Property& intrinsic) const -{ - yarp::rosmsg::sensor_msgs::CameraInfo* tmp = m_subscriber_camera_info.read(true); - m_lastCameraInfo = *tmp; - intrinsic.clear(); - yarp::sig::IntrinsicParams params; - params.focalLengthX = m_lastCameraInfo.K[0]; - params.focalLengthY = m_lastCameraInfo.K[4]; - params.principalPointX = m_lastCameraInfo.K[2]; - params.principalPointY = m_lastCameraInfo.K[5]; - // distortion model - if (m_lastCameraInfo.distortion_model=="plumb_bob") - { - params.distortionModel.type = YarpDistortion::YARP_PLUMB_BOB; - params.distortionModel.k1 = m_lastCameraInfo.D[0]; - params.distortionModel.k2 = m_lastCameraInfo.D[1]; - params.distortionModel.t1 = m_lastCameraInfo.D[2]; - params.distortionModel.t2 = m_lastCameraInfo.D[3]; - params.distortionModel.k3 = m_lastCameraInfo.D[4]; - } - else - { - yCError(RGBD_ROS) << "Unsupported distortion model"; - } - params.toProperty(intrinsic); - return false; -} - - -void yarp::dev::RGBDRosConversionUtils::shallowCopyImages(const yarp::sig::FlexImage& src, yarp::sig::FlexImage& dest) -{ - dest.setPixelCode(src.getPixelCode()); - dest.setQuantum(src.getQuantum()); - dest.setExternal(src.getRawImage(), src.width(), src.height()); -} - -void yarp::dev::RGBDRosConversionUtils::shallowCopyImages(const ImageOf& src, ImageOf& dest) -{ - dest.setQuantum(src.getQuantum()); - dest.setExternal(src.getRawImage(), src.width(), src.height()); -} - -void yarp::dev::RGBDRosConversionUtils::deepCopyImages(const yarp::sig::FlexImage& src, - yarp::rosmsg::sensor_msgs::Image& dest, - const std::string& frame_id, - const yarp::rosmsg::TickTime& timeStamp, - const unsigned int& seq) -{ - dest.data.resize(src.getRawImageSize()); - dest.width = src.width(); - dest.height = src.height(); - memcpy(dest.data.data(), src.getRawImage(), src.getRawImageSize()); - dest.encoding = yarp::dev::ROSPixelCode::yarp2RosPixelCode(src.getPixelCode()); - dest.step = src.getRowSize(); - dest.header.frame_id = frame_id; - dest.header.stamp = timeStamp; - dest.header.seq = seq; - dest.is_bigendian = 0; -} - -void yarp::dev::RGBDRosConversionUtils::deepCopyImages(const DepthImage& src, - yarp::rosmsg::sensor_msgs::Image& dest, - const std::string& frame_id, - const yarp::rosmsg::TickTime& timeStamp, - const unsigned int& seq) -{ - dest.data.resize(src.getRawImageSize()); - - dest.width = src.width(); - dest.height = src.height(); - - memcpy(dest.data.data(), src.getRawImage(), src.getRawImageSize()); - - dest.encoding = yarp::dev::ROSPixelCode::yarp2RosPixelCode(src.getPixelCode()); - dest.step = src.getRowSize(); - dest.header.frame_id = frame_id; - dest.header.stamp = timeStamp; - dest.header.seq = seq; - dest.is_bigendian = 0; -} diff --git a/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.h b/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.h deleted file mode 100644 index d39fe079819..00000000000 --- a/src/devices/ROS/RGBDRosConversionUtils/RGBDRosConversionUtils.h +++ /dev/null @@ -1,82 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef RGBD_ROS_UTILS_H -#define RGBD_ROS_UTILS_H - -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include - -typedef yarp::sig::ImageOf DepthImage; - -namespace yarp::dev::RGBDRosConversionUtils { - -class commonImageProcessor: - public yarp::os::Subscriber -{ - protected: - yarp::sig::FlexImage m_lastRGBImage; - DepthImage m_lastDepthImage; - - protected: - std::mutex m_port_mutex; - mutable yarp::os::Subscriber m_subscriber_camera_info; - std::string m_cameradata_topic_name; - std::string m_camerainfo_topic_name; - mutable yarp::rosmsg::sensor_msgs::CameraInfo m_lastCameraInfo; - yarp::os::Stamp m_lastStamp; - bool m_contains_rgb_data; - bool m_contains_depth_data; - - public: - commonImageProcessor (std::string data_topic_name, std::string camera_info_topic_name); - virtual ~commonImageProcessor(); - using yarp::os::Subscriber::onRead; - virtual void onRead(yarp::rosmsg::sensor_msgs::Image& v) override; - - public: - size_t getWidth() const; - size_t getHeight() const; - bool getFOV(double& horizontalFov, double& verticalFov) const; - bool getIntrinsicParam(yarp::os::Property& intrinsic) const; - - public: - bool getLastRGBData(yarp::sig::FlexImage& data, yarp::os::Stamp& stmp); - bool getLastDepthData(yarp::sig::ImageOf& data, yarp::os::Stamp& stmp); -}; - -void deepCopyImages(const yarp::sig::FlexImage& src, - yarp::rosmsg::sensor_msgs::Image& dest, - const std::string& frame_id, - const yarp::rosmsg::TickTime& timeStamp, - const unsigned int& seq); - -void deepCopyImages(const DepthImage& src, - yarp::rosmsg::sensor_msgs::Image& dest, - const std::string& frame_id, - const yarp::rosmsg::TickTime& timeStamp, - const unsigned int& seq); - -void shallowCopyImages(const yarp::sig::FlexImage& src, yarp::sig::FlexImage& dest); - -void shallowCopyImages(const DepthImage& src, DepthImage& dest); - -} // namespace yarp::dev::RGBDRosConversionUtils - -#endif diff --git a/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.cpp b/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.cpp deleted file mode 100644 index 53b43e7fe7c..00000000000 --- a/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.cpp +++ /dev/null @@ -1,84 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "rosPixelCode.h" - -namespace yarp::dev::ROSPixelCode { - -std::string yarp2RosPixelCode(int code) -{ - switch (code) - { - case VOCAB_PIXEL_BGR: - return BGR8; - case VOCAB_PIXEL_BGRA: - return BGRA8; - case VOCAB_PIXEL_ENCODING_BAYER_BGGR16: - return BAYER_BGGR16; - case VOCAB_PIXEL_ENCODING_BAYER_BGGR8: - return BAYER_BGGR8; - case VOCAB_PIXEL_ENCODING_BAYER_GBRG16: - return BAYER_GBRG16; - case VOCAB_PIXEL_ENCODING_BAYER_GBRG8: - return BAYER_GBRG8; - case VOCAB_PIXEL_ENCODING_BAYER_GRBG16: - return BAYER_GRBG16; - case VOCAB_PIXEL_ENCODING_BAYER_GRBG8: - return BAYER_GRBG8; - case VOCAB_PIXEL_ENCODING_BAYER_RGGB16: - return BAYER_RGGB16; - case VOCAB_PIXEL_ENCODING_BAYER_RGGB8: - return BAYER_RGGB8; - case VOCAB_PIXEL_MONO: - return MONO8; - case VOCAB_PIXEL_MONO16: - return MONO16; - case VOCAB_PIXEL_RGB: - return RGB8; - case VOCAB_PIXEL_RGBA: - return RGBA8; - case VOCAB_PIXEL_MONO_FLOAT: - return TYPE_32FC1; - default: - return RGB8; - } -} - -int Ros2YarpPixelCode(const std::string& roscode) -{ - if (roscode == BGR8) { - return VOCAB_PIXEL_BGR; - } else if (roscode == BGRA8) { - return VOCAB_PIXEL_BGRA; - } else if (roscode == BAYER_BGGR8) { - return VOCAB_PIXEL_ENCODING_BAYER_BGGR8; - } else if (roscode == BAYER_GBRG16) { - return VOCAB_PIXEL_ENCODING_BAYER_GBRG16; - } else if (roscode == BAYER_GBRG8) { - return VOCAB_PIXEL_ENCODING_BAYER_GBRG8; - } else if (roscode == BAYER_GRBG16) { - return VOCAB_PIXEL_ENCODING_BAYER_GRBG16; - } else if (roscode == BAYER_GRBG8) { - return VOCAB_PIXEL_ENCODING_BAYER_GRBG8; - } else if (roscode == BAYER_RGGB16) { - return VOCAB_PIXEL_ENCODING_BAYER_RGGB16; - } else if (roscode == BAYER_RGGB8) { - return VOCAB_PIXEL_ENCODING_BAYER_RGGB8; - } else if (roscode == MONO8) { - return VOCAB_PIXEL_MONO; - } else if (roscode == MONO16) { - return VOCAB_PIXEL_MONO16; - } else if (roscode == RGB8) { - return VOCAB_PIXEL_RGB; - } else if (roscode == RGBA8) { - return VOCAB_PIXEL_RGBA; - } else if (roscode == TYPE_32FC1) { - return VOCAB_PIXEL_MONO_FLOAT; - } else { - return VOCAB_PIXEL_INVALID; - } -} - -} // namespace yarp::dev::ROSPixelCode diff --git a/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.h b/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.h deleted file mode 100644 index f8f5e5be40c..00000000000 --- a/src/devices/ROS/RGBDRosConversionUtils/rosPixelCode.h +++ /dev/null @@ -1,68 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_RGBDSENSORWRAPPER_ROSPIXELCODE_H -#define YARP_DEV_RGBDSENSORWRAPPER_ROSPIXELCODE_H - -#include -#include - -namespace yarp::dev::ROSPixelCode { - -#define BAYER_BGGR16 "bayer_bggr16" -#define BAYER_BGGR8 "bayer_bggr8" -#define BAYER_GBRG16 "bayer_gbrg16" -#define BAYER_GBRG8 "bayer_gbrg8" -#define BAYER_GRBG16 "bayer_grbg16" -#define BAYER_GRBG8 "bayer_grbg8" -#define BAYER_RGGB16 "bayer_rggb16" -#define BAYER_RGGB8 "bayer_rggb8" -#define BGR16 "bgr16" -#define BGR8 "bgr8" -#define BGRA16 "bgra16" -#define BGRA8 "bgra8" -#define MONO16 "mono16" -#define MONO8 "mono8" -#define RGB16 "rgb16" -#define RGB8 "rgb8" -#define RGBA16 "rgba16" -#define RGBA8 "rgba8" -#define TYPE_16SC1 "16SC1" -#define TYPE_16SC2 "16SC2" -#define TYPE_16SC3 "16SC3" -#define TYPE_16SC4 "16SC4" -#define TYPE_16UC1 "16UC1" -#define TYPE_16UC2 "16UC2" -#define TYPE_16UC3 "16UC3" -#define TYPE_16UC4 "16UC4" -#define TYPE_32FC1 "32FC1" -#define TYPE_32FC2 "32FC2" -#define TYPE_32FC3 "32FC3" -#define TYPE_32FC4 "32FC4" -#define TYPE_32SC1 "32SC1" -#define TYPE_32SC2 "32SC2" -#define TYPE_32SC3 "32SC3" -#define TYPE_32SC4 "32SC4" -#define TYPE_64FC1 "64FC1" -#define TYPE_64FC2 "64FC2" -#define TYPE_64FC3 "64FC3" -#define TYPE_64FC4 "64FC4" -#define TYPE_8SC1 "8SC1" -#define TYPE_8SC2 "8SC2" -#define TYPE_8SC3 "8SC3" -#define TYPE_8SC4 "8SC4" -#define TYPE_8UC1 "8UC1" -#define TYPE_8UC2 "8UC2" -#define TYPE_8UC3 "8UC3" -#define TYPE_8UC4 "8UC4" -#define YUV422 "yuv422" - -std::string yarp2RosPixelCode(int code); - -int Ros2YarpPixelCode(const std::string& roscode); - -} // namespace yarp::dev::ROSPixelCode - -#endif // YARP_DEV_RGBDSENSORWRAPPER_ROSPIXELCODE_H diff --git a/src/devices/ROS/RGBDSensorFromRosTopic/CMakeLists.txt b/src/devices/ROS/RGBDSensorFromRosTopic/CMakeLists.txt deleted file mode 100644 index f7b21d273fd..00000000000 --- a/src/devices/ROS/RGBDSensorFromRosTopic/CMakeLists.txt +++ /dev/null @@ -1,52 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(RGBDSensorFromRosTopic - CATEGORY device - TYPE RGBDSensorFromRosTopic - INCLUDE RGBDSensorFromRosTopic.h - EXTRA_CONFIG - WRAPPER=RGBDSensorFromRosTopic -) - -if(NOT SKIP_RGBDSensorFromRosTopic) - yarp_add_plugin(yarp_RGBDSensorFromRosTopic) - - target_sources(yarp_RGBDSensorFromRosTopic - PRIVATE - RGBDSensorFromRosTopic.cpp - RGBDSensorFromRosTopic.h - ) - target_sources(yarp_RGBDSensorFromRosTopic PRIVATE $) - target_include_directories(yarp_RGBDSensorFromRosTopic PRIVATE $) - - target_link_libraries(yarp_RGBDSensorFromRosTopic - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - target_link_libraries(yarp_RGBDSensorFromRosTopic PRIVATE ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ) - - yarp_install( - TARGETS yarp_RGBDSensorFromRosTopic - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_RGBDSensorFromRosTopic PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp b/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp deleted file mode 100644 index 7035fee41db..00000000000 --- a/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.cpp +++ /dev/null @@ -1,418 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include -#include -#include - -#include "RGBDSensorFromRosTopic.h" - -using namespace yarp::dev; -using namespace yarp::sig; -using namespace yarp::os; - - -namespace { -YARP_LOG_COMPONENT(RGBD_ROS_TOPIC, "yarp.device.RGBDSensorFromRosTopic") -} - - -bool RGBDSensorFromRosTopic::open(Searchable& config) -{ - if (!config.check("depth_topic_name")) { - yCError(RGBD_ROS_TOPIC) << "missing depth_topic_name parameter, using default one"; - return false; - } - std::string depth_topic_name = config.find("depth_topic_name").asString(); - if(depth_topic_name[0] != '/'){ - yCError(RGBD_ROS_TOPIC) << "depth_topic_name must begin with an initial /"; - return false; - } - - if (!config.check("color_topic_name")) { - yCError(RGBD_ROS_TOPIC) << "missing color_topic_name parameter, using default one"; - return false; - } - std::string color_topic_name = config.find("color_topic_name").asString(); - if(color_topic_name[0] != '/'){ - yCError(RGBD_ROS_TOPIC) << "color_topic_name must begin with an initial /"; - return false; - } - std::string rgb_info_topic_name = color_topic_name.substr(0,color_topic_name.rfind('/')) + "/camera_info"; - std::string depth_info_topic_name = depth_topic_name.substr(0,depth_topic_name.rfind('/')) + "/camera_info"; - - if (!config.check("node_name")) { - yCError(RGBD_ROS_TOPIC) << "missing node_name parameter, using default one"; - return false; - } - std::string node_name = config.find("node_name").asString(); - if(node_name[0] != '/'){ - yCError(RGBD_ROS_TOPIC) << "node_name must begin with an initial /"; - return false; - } - m_ros_node = new yarp::os::Node(node_name); - - //m_rgb_input_processor.useCallback(); ///@@@<-SEGFAULT - //m_depth_input_processor.useCallback(); ///@@@<-SEGFAULT - m_rgb_input_processor = new yarp::dev::RGBDRosConversionUtils::commonImageProcessor(color_topic_name, rgb_info_topic_name); - m_depth_input_processor = new yarp::dev::RGBDRosConversionUtils::commonImageProcessor(depth_topic_name, depth_info_topic_name); - m_rgb_input_processor->useCallback(); ///@@@<-OK - m_depth_input_processor->useCallback(); ///@@@<-OK - - return true; -} - -bool RGBDSensorFromRosTopic::close() -{ - if (m_rgb_input_processor) - { - delete m_rgb_input_processor; - m_rgb_input_processor =nullptr; - } - if (m_depth_input_processor) - { - delete m_depth_input_processor; - m_depth_input_processor = nullptr; - } - if (m_ros_node) - { - delete m_ros_node; - m_ros_node=nullptr; - } - return true; -} - -int RGBDSensorFromRosTopic::getRgbHeight() -{ - if (m_rgb_input_processor==nullptr) - { - return 0; - } - return static_cast(m_rgb_input_processor->getHeight()); -} - -int RGBDSensorFromRosTopic::getRgbWidth() -{ - if (m_rgb_input_processor==nullptr) - { - return 0; - } - return static_cast(m_rgb_input_processor->getWidth()); -} - -bool RGBDSensorFromRosTopic::getRgbSupportedConfigurations(yarp::sig::VectorOf &configurations) -{ - YARP_UNUSED(configurations); - yCWarning(RGBD_ROS_TOPIC) << "getRgbSupportedConfigurations not implemented yet"; - return false; -} - -bool RGBDSensorFromRosTopic::getRgbResolution(int &width, int &height) -{ - if (m_rgb_input_processor == nullptr) - { - width=0; - height=0; - return true; - } - width = static_cast(m_rgb_input_processor->getWidth()); - height = static_cast(m_rgb_input_processor->getHeight()); - return true; -} - -bool RGBDSensorFromRosTopic::setDepthResolution(int width, int height) -{ - YARP_UNUSED(width); - YARP_UNUSED(height); - yCWarning(RGBD_ROS_TOPIC) << "setDepthResolution not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setRgbResolution(int width, int height) -{ - YARP_UNUSED(width); - YARP_UNUSED(height); - yCWarning(RGBD_ROS_TOPIC) << "setRgbResolution not supported"; - return false; -} - - -bool RGBDSensorFromRosTopic::setRgbFOV(double horizontalFov, double verticalFov) -{ - YARP_UNUSED(horizontalFov); - YARP_UNUSED(verticalFov); - yCWarning(RGBD_ROS_TOPIC) << "setRgbFOV not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setDepthFOV(double horizontalFov, double verticalFov) -{ - YARP_UNUSED(horizontalFov); - YARP_UNUSED(verticalFov); - yCWarning(RGBD_ROS_TOPIC) << "setDepthFOV not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setDepthAccuracy(double accuracy) -{ - YARP_UNUSED(accuracy); - yCWarning(RGBD_ROS_TOPIC) << "setDepthAccuracy not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getRgbFOV(double &horizontalFov, double &verticalFov) -{ - if (m_rgb_input_processor == nullptr) - { - horizontalFov=0; - verticalFov=0; - return true; - } - return m_rgb_input_processor->getFOV(horizontalFov, verticalFov); -} - -bool RGBDSensorFromRosTopic::getRgbMirroring(bool& mirror) -{ - YARP_UNUSED(mirror); - yCWarning(RGBD_ROS_TOPIC) << "Mirroring not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setRgbMirroring(bool mirror) -{ - YARP_UNUSED(mirror); - yCWarning(RGBD_ROS_TOPIC) << "Mirroring not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getRgbIntrinsicParam(Property& intrinsic) -{ - if (m_rgb_input_processor == nullptr) - { - intrinsic.clear(); - return true; - } - return m_rgb_input_processor->getIntrinsicParam(intrinsic); -} - -int RGBDSensorFromRosTopic::getDepthHeight() -{ - if (m_depth_input_processor == nullptr) - { - return 0; - } - return static_cast(m_depth_input_processor->getHeight()); -} - -int RGBDSensorFromRosTopic::getDepthWidth() -{ - if (m_depth_input_processor == nullptr) - { - return 0; - } - return static_cast(m_depth_input_processor->getWidth()); -} - -bool RGBDSensorFromRosTopic::getDepthFOV(double& horizontalFov, double& verticalFov) -{ - if (m_depth_input_processor == nullptr) - { - horizontalFov = 0; - verticalFov = 0; - return true; - } - return m_depth_input_processor->getFOV(horizontalFov, verticalFov); -} - -bool RGBDSensorFromRosTopic::getDepthIntrinsicParam(Property& intrinsic) -{ - if (m_depth_input_processor == nullptr) - { - intrinsic.clear(); - return true; - } - return m_depth_input_processor->getIntrinsicParam(intrinsic); -} - -double RGBDSensorFromRosTopic::getDepthAccuracy() -{ - yCWarning(RGBD_ROS_TOPIC) << "getDepthAccuracy not supported"; - return 0; -} - -bool RGBDSensorFromRosTopic::getDepthClipPlanes(double& nearPlane, double& farPlane) -{ - YARP_UNUSED(nearPlane); - YARP_UNUSED(farPlane); - yCWarning(RGBD_ROS_TOPIC) << "getDepthClipPlanes not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setDepthClipPlanes(double nearPlane, double farPlane) -{ - YARP_UNUSED(nearPlane); - YARP_UNUSED(farPlane); - yCWarning(RGBD_ROS_TOPIC) << "setDepthClipPlanes not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getDepthMirroring(bool& mirror) -{ - YARP_UNUSED(mirror); - yCWarning(RGBD_ROS_TOPIC) << "getDepthMirroring not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setDepthMirroring(bool mirror) -{ - YARP_UNUSED(mirror); - yCWarning(RGBD_ROS_TOPIC) << "setDepthMirroring not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getExtrinsicParam(Matrix& extrinsic) -{ - YARP_UNUSED(extrinsic); - yCWarning(RGBD_ROS_TOPIC) << "getExtrinsicParam not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getRgbImage(FlexImage& rgbImage, Stamp* timeStamp) -{ - std::lock_guard guard(m_mutex); - bool rgb_ok = false; - if (m_rgb_input_processor!=nullptr) - { rgb_ok = m_rgb_input_processor->getLastRGBData(rgbImage, *timeStamp); } - return rgb_ok; -} - -bool RGBDSensorFromRosTopic::getDepthImage(ImageOf& depthImage, Stamp* timeStamp) -{ - std::lock_guard guard(m_mutex); - bool depth_ok =false; - if (m_depth_input_processor != nullptr) - { depth_ok = m_depth_input_processor->getLastDepthData(depthImage, *timeStamp); } - return depth_ok; -} - -bool RGBDSensorFromRosTopic::getImages(FlexImage& colorFrame, ImageOf& depthFrame, Stamp* colorStamp, Stamp* depthStamp) -{ - bool rgb_ok = false; - bool depth_ok = false; - std::lock_guard guard(m_mutex); - if (m_rgb_input_processor != nullptr) - { rgb_ok = m_rgb_input_processor->getLastRGBData(colorFrame, *colorStamp); } - if (m_depth_input_processor != nullptr) - { depth_ok = m_depth_input_processor->getLastDepthData(depthFrame, *depthStamp); } - return (rgb_ok && depth_ok); -} - -RGBDSensorFromRosTopic::RGBDSensor_status RGBDSensorFromRosTopic::getSensorStatus() -{ - return RGBD_SENSOR_OK_IN_USE; -} - -std::string RGBDSensorFromRosTopic::getLastErrorMsg(Stamp* timeStamp) -{ - YARP_UNUSED(timeStamp); - return m_lastError; -} - -/* -//IFrameGrabberControls -bool RGBDSensorFromRosTopic::getCameraDescription(CameraDescriptor* camera) -{ - camera->deviceDescription = "Ros Camera"; - camera->busType = BusType::BUS_UNKNOWN; - return true; -} - -bool RGBDSensorFromRosTopic::hasFeature(int feature, bool* hasFeature) -{ - yCWarning(RGBD_ROS_TOPIC) << "hasFeature not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setFeature(int feature, double value) -{ - yCWarning(RGBD_ROS_TOPIC) << "setFeature not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getFeature(int feature, double *value) -{ - yCWarning(RGBD_ROS_TOPIC) << "getFeature not supported"; - return false; return true; -} - -bool RGBDSensorFromRosTopic::setFeature(int feature, double value1, double value2) -{ - yCWarning(RGBD_ROS_TOPIC) << "setFeature not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getFeature(int feature, double *value1, double *value2) -{ - yCWarning(RGBD_ROS_TOPIC) << "getFeature not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::hasOnOff( int feature, bool *HasOnOff) -{ - yCWarning(RGBD_ROS_TOPIC) << "hasOnOff not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setActive( int feature, bool onoff) -{ - yCWarning(RGBD_ROS_TOPIC) << "setActive not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getActive( int feature, bool *isActive) -{ - yCWarning(RGBD_ROS_TOPIC) << "getActive not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::hasAuto(int feature, bool *hasAuto) -{ - yCWarning(RGBD_ROS_TOPIC) << "hasAuto not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::hasManual( int feature, bool* hasManual) -{ - yCWarning(RGBD_ROS_TOPIC) << "hasManual not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::hasOnePush(int feature, bool* hasOnePush) -{ - yCWarning(RGBD_ROS_TOPIC) << "hasOnePush not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::setMode(int feature, FeatureMode mode) -{ - yCWarning(RGBD_ROS_TOPIC) << "setMode not supported"; - return false; -} - -bool RGBDSensorFromRosTopic::getMode(int feature, FeatureMode* mode) -{ - yCWarning(RGBD_ROS_TOPIC) << "getMode not supported"; - *mode = MODE_UNKNOWN; - return false; -} - -bool RGBDSensorFromRosTopic::setOnePush(int feature) -{ - yCWarning(RGBD_ROS_TOPIC) << "setOnePush not supported"; - return false; -} -*/ diff --git a/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h b/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h deleted file mode 100644 index 8647ca79b0b..00000000000 --- a/src/devices/ROS/RGBDSensorFromRosTopic/RGBDSensorFromRosTopic.h +++ /dev/null @@ -1,263 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef RGBD_FROM_ROS_TOPIC_H -#define RGBD_FROM_ROS_TOPIC_H - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include - -typedef yarp::sig::ImageOf depthImage; - -/** - * @ingroup dev_impl_media - * - * @brief `RGBDSensorFromRosTopic` is a driver for a virtual RGBD device: the data is not originated from a physical sensor but from a ROS topic. - * - * This device driver exposes the IRGBDSensor interface to read the images published by a ROS node. - * See the documentation for more details about each interface. - * - * This device can be used in two different ways: - * - as a client, directly opened by your application - * - as a device, wrapped by a RGBDSensorWrapper - * - * When used as a client, the RGBDSensorFromRosTopic device directly connects to the ROS publisher via `tcp_ros` carrier. - * This mode does not use a RGBDSensorWrapper and thus minimize latency. It is thus recommended when the application consists of - * a single client. However, if multiple clients are involved, as shown in the diagram below, this architecture might be inefficient, - * due to the multiple tcp_ros connections. - * - * \dot - * digraph G { - * - * subgraph cluster_4 { - * node [style=filled,color=black,fillcolor=white]; - * label = "ROS node"; - * subgraph cluster_5 { - * node [style=filled,color=black,fillcolor=white]; - * label = ""; - * SENSOR [label = "physical sensor"] - * bgcolor=palegreen3 - * } - * ROS [label=<ROS
/camera/color/image_raw
/camera/color/camera_info
/camera/depth/image_rect_raw
/camera/depth/camera_info>]; - * bgcolor=palegreen1 - * } - * - * subgraph cluster_0 { - * node [style=filled,color=black,fillcolor=white]; - * node [style=filled,color=black,fillcolor=white]; - * c1 [label = <RGBDSensorFromRosTopic
/camera/color/image_raw
/camera/color/camera_info
/camera/depth/image_rect_raw
/camera/depth/camera_info> ]; - * label = "process1"; - * bgcolor=paleturquoise1 - * } - * - * subgraph cluster_1 { - * node [style=filled,color=black,fillcolor=white]; - * c2 [label = <RGBDSensorFromRosTopic
/camera/color/image_raw
/camera/color/camera_info
/camera/depth/image_rect_raw
/camera/depth/camera_info> ]; - * label = "process2"; - * bgcolor=paleturquoise1 - * } - * - * subgraph cluster_2 { - * node [style=filled,color=black,fillcolor=white]; - * c3 [label = <RGBDSensorFromRosTopic
/camera/color/image_raw
/camera/color/camera_info
/camera/depth/image_rect_raw
/camera/depth/camera_info> ]; - * label = "process3"; - * bgcolor=paleturquoise1 - * } - * - * SENSOR -> ROS [ style="dashed" dir="none"] - * ROS -> c1 [ label=<tcp_ros> fontcolor="red" ]; - * ROS -> c2 [ label=<tcp_ros> fontcolor="red" ]; - * ROS -> c3 [ label=<tcp_ros> fontcolor="red" ]; - * } - * \enddot - * - * - * The second mode, instead, is useful if the application consists of several modules, and each of them - * employ a client connected to the same server (RGBDSensorWrapper). In this case, if all the modules run - * on the same machine, the `unix_stream` can be employed to share data between them, minimizing data transfer - * operations and greatly boosting the performance. See the digram below. - * - * \dot - * digraph G { - * - * subgraph cluster_4 { - * node [style=filled,color=black,fillcolor=white]; - * label = "ROS node"; - * subgraph cluster_5 { - * node [style=filled,color=black,fillcolor=white]; - * label = ""; - * SENSOR [label = "physical sensor"] - * bgcolor=palegreen3 - * } - * ROS [label=<ROS
/camera/color/image_raw
/camera/color/camera_info
/camera/depth/image_rect_raw
/camera/depth/camera_info>]; - * bgcolor=palegreen1 - * } - * - * subgraph cluster_0 { - * node [style=filled,color=black,fillcolor=white]; - * node [style=filled,color=black,fillcolor=white]; - * c1 [label=<RGBDSensorClient
/client1/rgbImage:i
/client1/depthImage:i>]; - * label = "process1"; - * bgcolor=paleturquoise1 - * } - * - * subgraph cluster_1 { - * node [style=filled,color=black,fillcolor=white]; - * c2 [label=<RGBDSensorClient
/client2/rgbImage:i
/client2/depthImage:i>]; - * label = "process2"; - * bgcolor=paleturquoise1 - * } - * - * subgraph cluster_2 { - * node [style=filled,color=black,fillcolor=white]; - * c3 [label=<RGBDSensorClient
/client3/rgbImage:i
/client3/depthImage:i>]; - * label = "process3"; - * bgcolor=paleturquoise1 - * } - * - * subgraph cluster_3 { - * node [style=filled,fillcolor=blue, color=black]; - * label = "yarpdev process"; - * bgcolor=paleturquoise1 - * subgraph cluster_3 { - * node [style=filled, fillcolor=white, color=black]; - * label = "RGBDSensorWrapper device"; - * bgcolor=paleturquoise3 - * subgraph cluster_3 { - * node [style=filled, fillcolor=white, color=black]; - * label = "RGBDSensorFromRosTopic device"; - * bgcolor=paleturquoise2 - * rgbtopic [label = <RGBDSensorFromRosTopic
/camera/color/image_raw
/camera/color/camera_info
/camera/depth/image_rect_raw
/camera/depth/camera_info> ]} - * w_out [label=<Wrapper
/wrapper/rgbImage:o
/wrapper/depthImage:o>]; - * } - * } - * - * SENSOR -> ROS [ style="dashed" dir="none"] - * rgbtopic -> w_out [ style="dashed" dir="none"] - * ROS-> rgbtopic [ label=<tcp_ros> fontcolor="red" ]; - * w_out -> c1 [ label=<unix_stream> fontcolor="blue"]; - * w_out -> c2 [ label=<unix_stream> fontcolor="blue" ]; - * w_out -> c3 [ label=<unix_stream> fontcolor="blue" ]; - * } - * \enddot - * - * | YARP device name | - * |:------------------:| - * | `RGBDSensorFromRosTopic` | - * - * Parameters used by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:----------------------------:|:-------------------:|:-------------------:|:--------------:|:-------------:|:---------:|:----------------------------------------------------------------------------------------------------:|:-------:| - * | color_topic_name | - | string | - | - | Yes | The device connects to this ROS topic to get RGB data (there must be also camera_info with the last subtopic)| | - * | depth_topic_name | - | string | - | - | Yes | The device connects to this ROS topic to get Depth data (there must be also camera_info with the last subtopic) | | * | node_name | - | string | - | - | Yes | the name of the ros node | | - * | node_name | - | string | - | - | Yes | the name of the ros node | | * | node_name | - | string | - | - | Yes | the name of the ros node | | - * - * Example of configuration file (using .ini format) when the device is wrapped by RGBDSensorWrapper. - * - * \code{.unparsed} - * device RGBDSensorWrapper - * subdevice RGBDSensorFromRosTopic - * color_topic_name /camera/color/image_raw - * depth_topic_name /camera/depth/image_raw - * node_name RGBDSensorFromRosTopic - * \endcode - */ - -class RGBDSensorFromRosTopic : - public yarp::dev::DeviceDriver, - public yarp::dev::IRGBDSensor -{ -private: - typedef yarp::os::Stamp Stamp; - typedef yarp::os::Property Property; - typedef yarp::sig::FlexImage FlexImage; - -public: - ~RGBDSensorFromRosTopic() override = default; - - // DeviceDriver - bool open(yarp::os::Searchable& config) override; - bool close() override; - - // IRGBDSensor - int getRgbHeight() override; - int getRgbWidth() override; - bool getRgbSupportedConfigurations(yarp::sig::VectorOf &configurations) override; - bool getRgbResolution(int &width, int &height) override; - bool setRgbResolution(int width, int height) override; - bool getRgbFOV(double& horizontalFov, double& verticalFov) override; - bool setRgbFOV(double horizontalFov, double verticalFov) override; - bool getRgbMirroring(bool& mirror) override; - bool setRgbMirroring(bool mirror) override; - - bool getRgbIntrinsicParam(Property& intrinsic) override; - int getDepthHeight() override; - int getDepthWidth() override; - bool setDepthResolution(int width, int height) override; - bool getDepthFOV(double& horizontalFov, double& verticalFov) override; - bool setDepthFOV(double horizontalFov, double verticalFov) override; - bool getDepthIntrinsicParam(Property& intrinsic) override; - double getDepthAccuracy() override; - bool setDepthAccuracy(double accuracy) override; - bool getDepthClipPlanes(double& nearPlane, double& farPlane) override; - bool setDepthClipPlanes(double nearPlane, double farPlane) override; - bool getDepthMirroring(bool& mirror) override; - bool setDepthMirroring(bool mirror) override; - - bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override; - bool getRgbImage(FlexImage& rgbImage, Stamp* timeStamp = nullptr) override; - bool getDepthImage(depthImage& depthImage, Stamp* timeStamp = nullptr) override; - bool getImages(FlexImage& colorFrame, depthImage& depthFrame, Stamp* colorStamp = nullptr, Stamp* depthStamp = nullptr) override; - - RGBDSensor_status getSensorStatus() override; - std::string getLastErrorMsg(Stamp* timeStamp = nullptr) override; - - /* - //IFrameGrabberControls - bool getCameraDescription(CameraDescriptor *camera) override; - bool hasFeature(int feature, bool* hasFeature) override; - bool setFeature(int feature, double value) override; - bool getFeature(int feature, double* value) override; - bool setFeature(int feature, double value1, double value2) override; - bool getFeature(int feature, double* value1, double* value2) override; - bool hasOnOff( int feature, bool* HasOnOff) override; - bool setActive( int feature, bool onoff) override; - bool getActive( int feature, bool* isActive) override; - bool hasAuto( int feature, bool* hasAuto) override; - bool hasManual( int feature, bool* hasManual) override; - bool hasOnePush(int feature, bool* hasOnePush) override; - bool setMode( int feature, FeatureMode mode) override; - bool getMode( int feature, FeatureMode *mode) override; - bool setOnePush(int feature) override; - */ - - // ros-topic related - mutable std::mutex m_mutex; - yarp::os::Node* m_ros_node = nullptr; - yarp::dev::RGBDRosConversionUtils::commonImageProcessor* m_rgb_input_processor = nullptr; - yarp::dev::RGBDRosConversionUtils::commonImageProcessor* m_depth_input_processor = nullptr; - - std::string m_lastError; -}; -#endif diff --git a/src/devices/ROS/RGBDSensor_nws_ros/CMakeLists.txt b/src/devices/ROS/RGBDSensor_nws_ros/CMakeLists.txt deleted file mode 100644 index 18671e953d0..00000000000 --- a/src/devices/ROS/RGBDSensor_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,56 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(rgbdSensor_nws_ros - CATEGORY device - TYPE RgbdSensor_nws_ros - INCLUDE RgbdSensor_nws_ros.h - EXTRA_CONFIG - WRAPPER=rgbdSensor_nws_ros - DEFAULT ON -) - -if(NOT SKIP_rgbdSensor_nws_ros) - yarp_add_plugin(yarp_rgbdSensor_nws_ros) - - target_sources(yarp_rgbdSensor_nws_ros - PRIVATE - RgbdSensor_nws_ros.cpp - RgbdSensor_nws_ros.h - ) - - target_sources(yarp_rgbdSensor_nws_ros PRIVATE $) - target_include_directories(yarp_rgbdSensor_nws_ros PRIVATE $) - - target_sources(yarp_rgbdSensor_nws_ros PRIVATE $) - target_include_directories(yarp_rgbdSensor_nws_ros PRIVATE $) - - target_link_libraries(yarp_rgbdSensor_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_rgbdSensor_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_rgbdSensor_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp b/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp deleted file mode 100644 index 768c7aa53e1..00000000000 --- a/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.cpp +++ /dev/null @@ -1,536 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "RgbdSensor_nws_ros.h" -#include "rosPixelCode.h" - -#include -#include -#include -#include - -#include -#include -#include -#include - -using namespace RGBDImpl; -using namespace yarp::sig; -using namespace yarp::dev; -using namespace yarp::os; - -YARP_LOG_COMPONENT(RGBDSENSORNWSROS, "yarp.devices.RgbdSensor_nws_ros") - - -RgbdSensor_nws_ros::RgbdSensor_nws_ros() : - PeriodicThread(DEFAULT_THREAD_PERIOD), - m_node(nullptr), - nodeSeq(0), - period(DEFAULT_THREAD_PERIOD), - sensor_p(nullptr), - fgCtrl(nullptr), - sensorStatus(IRGBDSensor::RGBD_SENSOR_NOT_READY), - verbose(4), - forceInfoSync(true), - isSubdeviceOwned(false), - subDeviceOwned(nullptr) -{} - -RgbdSensor_nws_ros::~RgbdSensor_nws_ros() -{ - close(); - sensor_p = nullptr; - fgCtrl = nullptr; -} - -/** Device driver interface */ - -bool RgbdSensor_nws_ros::open(yarp::os::Searchable &config) -{ - if(verbose >= 5) - { - yCTrace(RGBDSENSORNWSROS) << "\nParameters are: \n" << config.toString(); - } - if (!config.check("period", "refresh period of the broadcasted values in s")) - { - if (verbose >= 3) { - yCInfo(RGBDSENSORNWSROS) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s"; - } - } - else - { - period = config.find("period").asFloat64(); - } - - //check if param exist and assign it to corresponding variable.. if it doesn't, initialize the variable with default value. - - if (config.check("forceInfoSync")) - { - forceInfoSync = config.find("forceInfoSync").asBool(); - } - - if(config.check("subdevice")) { - isSubdeviceOwned=true; - } else { - isSubdeviceOwned=false; - } - - if(!initialize_ROS(config)) - { - return false; - } - - // check if we need to create subdevice or if they are - // passed later on through attachAll() - if(isSubdeviceOwned) - { - if(! openAndAttachSubDevice(config)) - { - yCError(RGBDSENSORNWSROS, "Error while opening subdevice"); - return false; - } - } - else - { - if (!openDeferredAttach(config)) { - return false; - } - } - - return true; -} - -bool RgbdSensor_nws_ros::openDeferredAttach(Searchable& prop) -{ - // I dunno what to do here now... - isSubdeviceOwned = false; - return true; -} - -bool RgbdSensor_nws_ros::openAndAttachSubDevice(Searchable& prop) -{ - Property p; - subDeviceOwned = new PolyDriver; - p.fromString(prop.toString()); - - p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring - p.unput("device"); - p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before - - // if errors occurred during open, quit here. - yCDebug(RGBDSENSORNWSROS, "Opening IRGBDSensor subdevice"); - subDeviceOwned->open(p); - - if (!subDeviceOwned->isValid()) - { - yCError(RGBDSENSORNWSROS, "Opening IRGBDSensor subdevice... FAILED"); - return false; - } - isSubdeviceOwned = true; - if(!attach(subDeviceOwned)) { - return false; - } - - return true; -} - -bool RgbdSensor_nws_ros::close() -{ - yCTrace(RGBDSENSORNWSROS, "Close"); - detach(); - - // close subdevice if it was created inside the open (--subdevice option) - if(isSubdeviceOwned) - { - if(subDeviceOwned) - { - delete subDeviceOwned; - subDeviceOwned=nullptr; - } - sensor_p = nullptr; - fgCtrl = nullptr; - isSubdeviceOwned = false; - } - - if(m_node !=nullptr) - { - m_node->interrupt(); - delete m_node; - m_node = nullptr; - } - - return true; -} - -/* Helper functions */ - -bool RgbdSensor_nws_ros::initialize_ROS(yarp::os::Searchable ¶ms) -{ - // depth topic base name check - if (!params.check("depth_topic_name")) { - yCError(RGBDSENSORNWSROS) << "missing depth_topic_name parameter"; - return false; - } - std::string depth_topic_name = params.find("depth_topic_name").asString(); - if(depth_topic_name[0] != '/'){ - yCError(RGBDSENSORNWSROS) << "depth_topic_name must begin with an initial /"; - return false; - } - - // color topic base name check - if (!params.check("color_topic_name")) { - yCError(RGBDSENSORNWSROS) << "missing color_topic_name parameter"; - return false; - } - std::string color_topic_name = params.find("color_topic_name").asString(); - if(color_topic_name[0] != '/'){ - yCError(RGBDSENSORNWSROS) << "color_topic_name must begin with an initial /"; - return false; - } - - // node_name check - if (!params.check("node_name")) { - yCError(RGBDSENSORNWSROS) << "missing node_name parameter"; - return false; - } - std::string node_name = params.find("node_name").asString(); - if(node_name[0] != '/'){ - yCError(RGBDSENSORNWSROS) << "node_name must begin with an initial /"; - return false; - } - - // depth_frame_id check - if (!params.check("depth_frame_id")) { - yCError(RGBDSENSORNWSROS) << "missing depth_frame_id parameter"; - return false; - } - m_depth_frame_id = params.find("depth_frame_id").asString(); - - // m_color_frame_id check - if (!params.check("color_frame_id")) { - yCError(RGBDSENSORNWSROS) << "missing color_frame_id parameter"; - return false; - } - m_color_frame_id = params.find("color_frame_id").asString(); - - // open topics here if needed - m_node = new yarp::os::Node(nodeName); - nodeSeq = 0; - - if (!publisherPort_color.topic(color_topic_name)) - { - yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << color_topic_name.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - - if (!publisherPort_depth.topic(depth_topic_name)) - { - yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << depth_topic_name.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - std::string rgb_info_topic_name = color_topic_name.substr(0,color_topic_name.rfind('/')) + "/camera_info"; - if (!publisherPort_colorCaminfo.topic(rgb_info_topic_name)) - { - yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << rgb_info_topic_name.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - - std::string depth_info_topic_name = depth_topic_name.substr(0,depth_topic_name.rfind('/')) + "/camera_info"; - if (!publisherPort_depthCaminfo.topic(depth_info_topic_name)) - { - yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << depth_info_topic_name.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - return true; -} - -/** - * WrapperSingle interface - */ - -bool RgbdSensor_nws_ros::detach() -{ - if (yarp::os::PeriodicThread::isRunning()) { - yarp::os::PeriodicThread::stop(); - } - - //check if we already instantiated a subdevice previously - if (isSubdeviceOwned) { - return false; - } - - sensor_p = nullptr; - return true; -} - -bool RgbdSensor_nws_ros::attach(PolyDriver* poly) -{ - if(poly) - { - poly->view(sensor_p); - poly->view(fgCtrl); - } - - if(sensor_p == nullptr) - { - yCError(RGBDSENSORNWSROS) << "Attached device has no valid IRGBDSensor interface."; - return false; - } - - if(fgCtrl == nullptr) - { - yCWarning(RGBDSENSORNWSROS) << "Attached device has no valid IFrameGrabberControls interface."; - } - - PeriodicThread::setPeriod(period); - return PeriodicThread::start(); -} - -/* IRateThread interface */ - -bool RgbdSensor_nws_ros::threadInit() -{ - // Get interface from attached device if any. - return true; -} - -void RgbdSensor_nws_ros::threadRelease() -{ - // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here! -} - -bool RgbdSensor_nws_ros::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, const std::string& frame_id, const UInt& seq, const SensorType& sensorType) -{ - double phyF = 0.0; - double fx = 0.0; - double fy = 0.0; - double cx = 0.0; - double cy = 0.0; - double k1 = 0.0; - double k2 = 0.0; - double t1 = 0.0; - double t2 = 0.0; - double k3 = 0.0; - double stamp = 0.0; - - std::string distModel; - std::string currentSensor; - UInt i; - Property camData; - std::vector > parVector; - param* par; - bool ok; - - currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth"; - ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData); - - if (!ok) - { - yCError(RGBDSENSORNWSROS) << "Unable to get intrinsic param from" << currentSensor << "sensor!"; - return false; - } - - if(!camData.check("distortionModel")) - { - yCWarning(RGBDSENSORNWSROS) << "Missing distortion model"; - return false; - } - - distModel = camData.find("distortionModel").asString(); - if (distModel != "plumb_bob") - { - yCError(RGBDSENSORNWSROS) << "Distortion model not supported"; - return false; - } - - //std::vector > rosStringParam; - //rosStringParam.push_back(param(nodeName, "asd")); - - parVector.emplace_back(phyF,"physFocalLength"); - parVector.emplace_back(fx,"focalLengthX"); - parVector.emplace_back(fy,"focalLengthY"); - parVector.emplace_back(cx,"principalPointX"); - parVector.emplace_back(cy,"principalPointY"); - parVector.emplace_back(k1,"k1"); - parVector.emplace_back(k2,"k2"); - parVector.emplace_back(t1,"t1"); - parVector.emplace_back(t2,"t2"); - parVector.emplace_back(k3,"k3"); - parVector.emplace_back(stamp,"stamp"); - for(i = 0; i < parVector.size(); i++) - { - par = &parVector[i]; - - if(!camData.check(par->parname)) - { - yCWarning(RGBDSENSORNWSROS) << "Driver has not the param:" << par->parname; - return false; - } - *par->var = camData.find(par->parname).asFloat64(); - } - - cameraInfo.header.frame_id = frame_id; - cameraInfo.header.seq = seq; - cameraInfo.header.stamp = stamp; - cameraInfo.width = sensorType == COLOR_SENSOR ? sensor_p->getRgbWidth() : sensor_p->getDepthWidth(); - cameraInfo.height = sensorType == COLOR_SENSOR ? sensor_p->getRgbHeight() : sensor_p->getDepthHeight(); - cameraInfo.distortion_model = distModel; - - cameraInfo.D.resize(5); - cameraInfo.D[0] = k1; - cameraInfo.D[1] = k2; - cameraInfo.D[2] = t1; - cameraInfo.D[3] = t2; - cameraInfo.D[4] = k3; - - cameraInfo.K.resize(9); - cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx; - cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy; - cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1; - - /* - * ROS documentation on cameraInfo message: - * "Rectification matrix (stereo cameras only) - * A rotation matrix aligning the camera coordinate system to the ideal - * stereo image plane so that epipolar lines in both stereo images are - * parallel." - * useless in our case, it will be an identity matrix - */ - - cameraInfo.R.assign(9, 0); - cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1; - - cameraInfo.P.resize(12); - cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0; - cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0; - cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0; - - cameraInfo.binning_x = cameraInfo.binning_y = 0; - cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0; - cameraInfo.roi.do_rectify = false; - return true; -} - -bool RgbdSensor_nws_ros::writeData() -{ - //colorImage.setPixelCode(VOCAB_PIXEL_RGB); - // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT); - - // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does? - // depthImage.resize(hDim, vDim); - if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp)) - { - return false; - } - - static Stamp oldColorStamp = Stamp(0, 0); - static Stamp oldDepthStamp = Stamp(0, 0); - bool rgb_data_ok = true; - bool depth_data_ok = true; - - if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false) - { - rgb_data_ok=false; - //return true; - } - else { oldColorStamp = colorStamp; } - - if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false) - { - depth_data_ok=false; - //return true; - } - else { oldDepthStamp = depthStamp; } - - // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves. - if (rgb_data_ok) - { - yarp::rosmsg::sensor_msgs::Image& rColorImage = publisherPort_color.prepare(); - yarp::rosmsg::sensor_msgs::CameraInfo& camInfoC = publisherPort_colorCaminfo.prepare(); - yarp::rosmsg::TickTime cRosStamp = colorStamp.getTime(); - yarp::dev::RGBDRosConversionUtils::deepCopyImages(colorImage, rColorImage, m_color_frame_id, cRosStamp, nodeSeq); - publisherPort_color.setEnvelope(colorStamp); - publisherPort_color.write(); - if (setCamInfo(camInfoC, m_color_frame_id, nodeSeq, COLOR_SENSOR)) - { - if(forceInfoSync) - {camInfoC.header.stamp = rColorImage.header.stamp;} - publisherPort_colorCaminfo.setEnvelope(colorStamp); - publisherPort_colorCaminfo.write(); - } - else - { - yCWarning(RGBDSENSORNWSROS, "Missing color camera parameters... camera info messages will be not sent"); - } - } - if (depth_data_ok) - { - yarp::rosmsg::sensor_msgs::Image& rDepthImage = publisherPort_depth.prepare(); - yarp::rosmsg::sensor_msgs::CameraInfo& camInfoD = publisherPort_depthCaminfo.prepare(); - yarp::rosmsg::TickTime dRosStamp = depthStamp.getTime(); - yarp::dev::RGBDRosConversionUtils::deepCopyImages(depthImage, rDepthImage, m_depth_frame_id, dRosStamp, nodeSeq); - publisherPort_depth.setEnvelope(depthStamp); - publisherPort_depth.write(); - if (setCamInfo(camInfoD, m_depth_frame_id, nodeSeq, DEPTH_SENSOR)) - { - if(forceInfoSync) - {camInfoD.header.stamp = rDepthImage.header.stamp;} - publisherPort_depthCaminfo.setEnvelope(depthStamp); - publisherPort_depthCaminfo.write(); - } - else - { - yCWarning(RGBDSENSORNWSROS, "Missing depth camera parameters... camera info messages will be not sent"); - } - } - - nodeSeq++; - - return true; -} - -void RgbdSensor_nws_ros::run() -{ - if (sensor_p!=nullptr) - { - static int i = 0; - sensorStatus = sensor_p->getSensorStatus(); - switch (sensorStatus) - { - case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) : - { - if (!writeData()) { - yCError(RGBDSENSORNWSROS, "Image not captured.. check hardware configuration"); - } - i = 0; - } - break; - case(IRGBDSensor::RGBD_SENSOR_NOT_READY): - { - if(i < 1000) { - if((i % 30) == 0) { - yCInfo(RGBDSENSORNWSROS) << "Device not ready, waiting..."; - } - } else { - yCWarning(RGBDSENSORNWSROS) << "Device is taking too long to start.."; - } - i++; - } - break; - default: - { - if (verbose >= 1) { // better not to print it every cycle anyway, too noisy - yCError(RGBDSENSORNWSROS, "%s: Sensor returned error", sensorId.c_str()); - } - } - } - } - else - { - if(verbose >= 6) { - yCError(RGBDSENSORNWSROS, "%s: Sensor interface is not valid", sensorId.c_str()); - } - } -} diff --git a/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h b/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h deleted file mode 100644 index f54f660ff8c..00000000000 --- a/src/devices/ROS/RGBDSensor_nws_ros/RgbdSensor_nws_ros.h +++ /dev/null @@ -1,178 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_RGBDSENSOR_NWS_ROS_H -#define YARP_DEV_RGBDSENSOR_NWS_ROS_H - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -// ROS stuff -#include -#include -#include -#include -#include -#include - -#define DEFAULT_THREAD_PERIOD 0.03 // s - -namespace RGBDImpl -{ - const std::string frameId_param = "frame_Id"; - const std::string nodeName_param = "nodeName"; - const std::string colorTopicName_param = "colorTopicName"; - const std::string depthTopicName_param = "depthTopicName"; - const std::string depthInfoTopicName_param = "depthInfoTopicName"; - const std::string colorInfoTopicName_param = "colorInfoTopicName"; -} - -/** - * @ingroup dev_impl_nws_ros - * - * \section RgbdSensor_nws_ros_device_parameters Description of input parameters - * \brief `rgbdSensor_nws_ros`: A Network grabber for kinect-like devices. - * This device will produce two streams of data through different ports, one for the color frame and the other one - * for depth image following Framegrabber and IDepthSensor interfaces specification respectively. - * See they documentation for more details about each interface. - * - * This device is paired with its client called RgbdSensor_nws_ros to receive the data streams. - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:----------------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:------------------------------: |:---------------------------------------------------------------------------------------------------:|:-----:| - * | period | - | double | s | 0.03 | No | refresh period of the broadcasted values in s | default 0.03s | - * | subdevice | - | string | - | - | alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | - * | forceInfoSync | - | string | bool | - | no | set 'true' to force the timestamp on the camera_info message to match the image one | - | - * | color_topic_name | - | string | - | - | Yes | the color topic | recommended value /camera/color/image_rect_color | - * | depth_topic_name | - | string | - | - | Yes | the depth topic | recommended value /camera/depth/image_rect | - * | color_frame_id | - | string | - | - | Yes | set the name of the reference frame for the color camera | | - * | depth_frame_id | - | string | - | - | Yes | set the name of the reference frame for the depth camera | | - * | node_name | - | string | - | - | Yes | set the name for ROS node | must start with a leading '/' | - * - * ROS message type used is sensor_msgs/Image.msg ( http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) - * Some example of configuration files: - * - * Example of configuration file using .ini format. - * - * \code{.unparsed} - * device rgbdSensor_nws_ros - * subdevice - * period 0.03 - * color_topic_name //camera/color/image_raw - * depth_topic_name //camera/depth/image_raw - * color_frame_id rgbd_color_frame - * depth_frame_id rgbd_depth_frame - * node_name rgbdsensor - * \endcode - */ - -class RgbdSensor_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::dev::WrapperSingle, - public yarp::os::PeriodicThread -{ -private: - typedef yarp::sig::ImageOf DepthImage; - typedef yarp::os::Publisher ImageTopicType; - typedef yarp::os::Publisher DepthTopicType; - typedef unsigned int UInt; - - enum SensorType{COLOR_SENSOR, DEPTH_SENSOR}; - - template - struct param - { - param(T& inVar, std::string inName) - { - var = &inVar; - parname = inName; - } - T* var; - std::string parname; - }; - - ImageTopicType publisherPort_color; - ImageTopicType publisherPort_depth; - DepthTopicType publisherPort_colorCaminfo; - DepthTopicType publisherPort_depthCaminfo; - yarp::os::Node* m_node; - std::string nodeName; - std::string m_color_frame_id; - std::string m_depth_frame_id; - yarp::sig::FlexImage colorImage; - DepthImage depthImage; - UInt nodeSeq; - - // Image data specs - // int hDim, vDim; - double period; - std::string sensorId; - yarp::dev::IRGBDSensor* sensor_p; - yarp::dev::IFrameGrabberControls* fgCtrl; - yarp::dev::IRGBDSensor::RGBDSensor_status sensorStatus; - int verbose; - bool forceInfoSync; - bool initialize_ROS(yarp::os::Searchable& config); - - // Open the wrapper only, the attach method needs to be called before using it - // Typical usage: yarprobotinterface - bool openDeferredAttach(yarp::os::Searchable& prop); - - // If a subdevice parameter is given, the wrapper will open it and attach to immediately. - // Typical usage: simulator or command line - bool isSubdeviceOwned; - yarp::dev::PolyDriver* subDeviceOwned; - bool openAndAttachSubDevice(yarp::os::Searchable& prop); - - // Synch - yarp::os::Stamp colorStamp; - yarp::os::Stamp depthStamp; - - bool writeData(); - bool setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, - const std::string& frame_id, - const UInt& seq, - const SensorType& sensorType); - -public: - RgbdSensor_nws_ros(); - RgbdSensor_nws_ros(const RgbdSensor_nws_ros&) = delete; - RgbdSensor_nws_ros(RgbdSensor_nws_ros&&) = delete; - RgbdSensor_nws_ros& operator=(const RgbdSensor_nws_ros&) = delete; - RgbdSensor_nws_ros& operator=(RgbdSensor_nws_ros&&) = delete; - ~RgbdSensor_nws_ros() override; - - bool open(yarp::os::Searchable ¶ms) override; - bool close() override; - - /** - * Specify which sensor this thread has to read from. - */ - bool attach(yarp::dev::PolyDriver *poly) override; - bool detach() override; - - bool threadInit() override; - void threadRelease() override; - void run() override; -}; - -#endif // YARP_DEV_RGBDSENSOR_NWS_ROS_H diff --git a/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/CMakeLists.txt b/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/CMakeLists.txt deleted file mode 100644 index 50b4a2477e6..00000000000 --- a/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,53 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(rgbdToPointCloudSensor_nws_ros - CATEGORY device - TYPE RGBDToPointCloudSensor_nws_ros - INCLUDE RGBDToPointCloudSensor_nws_ros.h - EXTRA_CONFIG - WRAPPER=rgbdToPointCloudSensor_nws_ros - DEFAULT ON -) - -if(NOT SKIP_rgbdToPointCloudSensor_nws_ros) - yarp_add_plugin(yarp_rgbdToPointCloudSensor_nws_ros) - - target_sources(yarp_rgbdToPointCloudSensor_nws_ros - PRIVATE - RGBDToPointCloudSensor_nws_ros.cpp - RGBDToPointCloudSensor_nws_ros.h - ) - - target_sources(yarp_rgbdToPointCloudSensor_nws_ros PRIVATE $) - target_include_directories(yarp_rgbdToPointCloudSensor_nws_ros PRIVATE $) - - target_link_libraries(yarp_rgbdToPointCloudSensor_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_rgbdToPointCloudSensor_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_rgbdToPointCloudSensor_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.cpp b/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.cpp deleted file mode 100644 index ba743273957..00000000000 --- a/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.cpp +++ /dev/null @@ -1,345 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "RGBDToPointCloudSensor_nws_ros.h" -#include -#include -#include -#include "rosPixelCode.h" -#include -#include -#include - -using namespace RGBDToPointCloudImpl; -using namespace yarp::sig; -using namespace yarp::dev; -using namespace yarp::os; - -YARP_LOG_COMPONENT(RGBDTOPOINTCLOUDSENSORNWSROS, "yarp.devices.RGBDToPointCloudSensor_nws_ros"); - -RGBDToPointCloudSensor_nws_ros::RGBDToPointCloudSensor_nws_ros() : - PeriodicThread(DEFAULT_THREAD_PERIOD) -{ -} - - -/* destructor of the wrapper */ -RGBDToPointCloudSensor_nws_ros::~RGBDToPointCloudSensor_nws_ros() -{ - close(); -} - -/** Device driver interface */ - -bool RGBDToPointCloudSensor_nws_ros::open(yarp::os::Searchable &config) -{ - // check period - if (!config.check("period", "refresh period of the broadcasted values in s")) { - if(verbose >= 3) { - yCInfo(RGBDTOPOINTCLOUDSENSORNWSROS) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s"; - } - } - else { - period = config.find("period").asFloat64(); - } - - // nodename parameter - if (!config.check("node_name", "the name of the ros node")) { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS) << "missing node_name parameter"; - return false; - } - nodeName = config.find("node_name").asString(); - - - // baseTopicName parameter - if (!config.check("topic_name", "the name of the ros node")) { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS) << "missing topic_name parameter, using default one"; - return false; - } - pointCloudTopicName = config.find("topic_name").asString(); - - // frame_id parameter - if (!config.check("frame_id", "the name of the ros node")) { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS) << "missing frame_id parameter"; - return false; - } - frameId = config.find("frame_id").asString(); - - // open topics here if needed - m_node = new yarp::os::Node(nodeName); - nodeSeq = 0; - if (!publisherPort_pointCloud.topic(pointCloudTopicName)) - { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS) << "Unable to publish data on " << pointCloudTopicName.c_str() << " topic, check your yarp-ROS network configuration"; - return false; - } - - // check if we need to create subdevice or if they are - // passed later on through attachAll() - if(config.check("subdevice")) { - if(! openAndAttachSubDevice(config)) - { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS, "Error while opening subdevice"); - return false; - } - isSubdeviceOwned=true; - } else { - isSubdeviceOwned=false; - } - return true; -} - -bool RGBDToPointCloudSensor_nws_ros::openAndAttachSubDevice(Searchable& prop) -{ - Property p; - subDeviceOwned = new PolyDriver; - p.fromString(prop.toString()); - - p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring - p.unput("device"); - p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before - - // if errors occurred during open, quit here. - yCDebug(RGBDTOPOINTCLOUDSENSORNWSROS, "Opening IRGBDSensor subdevice"); - subDeviceOwned->open(p); - - if (!subDeviceOwned->isValid()) - { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS, "Opening IRGBDSensor subdevice... FAILED"); - return false; - } - isSubdeviceOwned = true; - if(!attach(subDeviceOwned)) { - return false; - } - - return true; -} - -bool RGBDToPointCloudSensor_nws_ros::close() -{ - yCTrace(RGBDTOPOINTCLOUDSENSORNWSROS, "Close"); - detach(); - - // close subdevice if it was created inside the open (--subdevice option) - if(isSubdeviceOwned) - { - if(subDeviceOwned) - { - delete subDeviceOwned; - subDeviceOwned=nullptr; - } - sensor_p = nullptr; - fgCtrl = nullptr; - isSubdeviceOwned = false; - } - - if(m_node !=nullptr) - { - m_node->interrupt(); - delete m_node; - m_node = nullptr; - } - - return true; -} - -/** - * WrapperSingle interface - */ - -bool RGBDToPointCloudSensor_nws_ros::detach() -{ - if (yarp::os::PeriodicThread::isRunning()) - { - yarp::os::PeriodicThread::stop(); - } - - //check if we already instantiated a subdevice previously - if (isSubdeviceOwned) - { - return false; - } - sensor_p = nullptr; - return true; -} - -bool RGBDToPointCloudSensor_nws_ros::attach(PolyDriver* poly) -{ - if(poly) - { - poly->view(sensor_p); - poly->view(fgCtrl); - } - - if(sensor_p == nullptr) - { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS) << "Attached device has no valid IRGBDSensor interface."; - return false; - } - - PeriodicThread::setPeriod(period); - return PeriodicThread::start(); -} - -/* IRateThread interface */ - -bool RGBDToPointCloudSensor_nws_ros::threadInit() -{ - // Get interface from attached device if any. - return true; -} - -void RGBDToPointCloudSensor_nws_ros::threadRelease() -{ - // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here! -} - - -bool RGBDToPointCloudSensor_nws_ros::writeData() -{ - //colorImage.setPixelCode(VOCAB_PIXEL_RGB); - // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT); - - // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does? - // depthImage.resize(hDim, vDim); - if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp)) - { - return false; - } - - static Stamp oldColorStamp = Stamp(0, 0); - static Stamp oldDepthStamp = Stamp(0, 0); - yarp::os::Property propIntrinsic; - bool rgb_data_ok = true; - bool depth_data_ok = true; - - if ((colorStamp.getTime() - oldColorStamp.getTime()) <= 0) - { - rgb_data_ok=false; - //return true; - } - else { oldColorStamp = colorStamp; } - - if ((depthStamp.getTime() - oldDepthStamp.getTime()) <= 0) - { - depth_data_ok=false; - //return true; - } - else { oldDepthStamp = depthStamp; } - bool intrinsic_ok = sensor_p->getRgbIntrinsicParam(propIntrinsic); - - - // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves. - if (rgb_data_ok) - { - if (depth_data_ok) - { - if (intrinsic_ok) - { - yarp::sig::IntrinsicParams intrinsics(propIntrinsic); - yarp::sig::ImageOf colorImagePixelRGB; - colorImagePixelRGB.setExternal(colorImage.getRawImage(), colorImage.width(), colorImage.height()); - // create point cloud in yarp format - yarp::sig::PointCloud yarpCloud = yarp::sig::utils::depthRgbToPC(depthImage, - colorImagePixelRGB, - intrinsics, - yarp::sig::utils::OrganizationType::Unorganized); - PointCloud2Type& pc2Ros = publisherPort_pointCloud.prepare(); - // filling ros header - yarp::rosmsg::std_msgs::Header headerRos; - headerRos.clear(); - headerRos.seq = nodeSeq; - headerRos.frame_id = frameId; - headerRos.stamp = depthStamp.getTime(); - - // filling ros point field - std::vector pointFieldRos; - pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField()); - pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField()); - pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField()); - pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField()); - pointFieldRos[0].name = "x"; - pointFieldRos[0].offset = 0; - pointFieldRos[0].datatype = 7; - pointFieldRos[0].count = 1; - pointFieldRos[1].name = "y"; - pointFieldRos[1].offset = 4; - pointFieldRos[1].datatype = 7; - pointFieldRos[1].count = 1; - pointFieldRos[2].name = "z"; - pointFieldRos[2].offset = 8; - pointFieldRos[2].datatype = 7; - pointFieldRos[2].count = 1; - pointFieldRos[3].name = "rgb"; - pointFieldRos[3].offset = 16; - pointFieldRos[3].datatype = 7; - pointFieldRos[3].count = 1; - pc2Ros.fields = pointFieldRos; - - std::vector vec(yarpCloud.getRawData(), yarpCloud.getRawData() + yarpCloud.dataSizeBytes() ); - pc2Ros.data = vec; - pc2Ros.header = headerRos; - pc2Ros.width = yarpCloud.width() * yarpCloud.height(); - pc2Ros.height = 1; - pc2Ros.is_dense = yarpCloud.isDense(); - - pc2Ros.point_step = sizeof (yarp::sig::DataXYZRGBA); - pc2Ros.row_step = static_cast (sizeof (yarp::sig::DataXYZRGBA) * pc2Ros.width); - - publisherPort_pointCloud.write(); - } - } - } - - nodeSeq++; - - return true; -} - -void RGBDToPointCloudSensor_nws_ros::run() -{ - if (sensor_p!=nullptr) - { - static int i = 0; - sensorStatus = sensor_p->getSensorStatus(); - switch (sensorStatus) - { - case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) : - { - if (!writeData()) { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS, "Image not captured.. check hardware configuration"); - } - i = 0; - } - break; - case(IRGBDSensor::RGBD_SENSOR_NOT_READY): - { - if(i < 1000) { - if((i % 30) == 0) { - yCInfo(RGBDTOPOINTCLOUDSENSORNWSROS) << "Device not ready, waiting..."; - } - } else { - yCWarning(RGBDTOPOINTCLOUDSENSORNWSROS) << "Device is taking too long to start.."; - } - i++; - } - break; - default: - { - if (verbose >= 1) { // better not to print it every cycle anyway, too noisy - yCError(RGBDTOPOINTCLOUDSENSORNWSROS, "%s: Sensor returned error", nodeName.c_str()); - } - } - } - } - else - { - if(verbose >= 6) { - yCError(RGBDTOPOINTCLOUDSENSORNWSROS, "%s: Sensor interface is not valid", nodeName.c_str()); - } - } -} diff --git a/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h b/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h deleted file mode 100644 index 15cfccacd41..00000000000 --- a/src/devices/ROS/RGBDToPointCloudSensor_nws_ros/RGBDToPointCloudSensor_nws_ros.h +++ /dev/null @@ -1,166 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H -#define YARP_DEV_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -// ROS stuff -#include -#include -#include -#include -#include - -constexpr double DEFAULT_THREAD_PERIOD = 0.033; // s - -namespace RGBDToPointCloudImpl{ - const std::string frameId_param = "frame_Id"; - const std::string nodeName_param = "nodeName"; - const std::string pointCloudTopicName_param = "pointCloudTopicName"; -} -/** - * @ingroup dev_impl_nws_ros - * - * \section RGBDToPointCloudSensor_nws_ros_device_parameters Description of input parameters - * - * \brief `RGBDToPointCloudSensor_nws_ros`: A Network grabber for kinect-like devices. - * This device will produce one stream of data for the point cloud - * derived fron the combination of the data derived from Framegrabber and IDepthSensor interfaces. - * See they documentation for more details about each interface. - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:----------------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:------------------------------: |:---------------------------------------------------------------------------------------------------:|:-----:| - * | period | - | double | s | 0.033 | No | refresh period of the broadcasted values in s | default 0.033 s | - * | subdevice | - | string | - | - | alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | - * | topic_name | - | string | - | | Yes | set the name for ROS point cloud topic | must start with a leading '/' | - * | frame_id | - | string | - | | Yes | set the name of the reference frame | | - * | node_name | - | string | - | - | Yes | set the name for ROS node | must start with a leading '/' | - * - * ROS message type used is sensor_msgs/Image.msg ( http://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) - * Some example of configuration files: - * - * Example of configuration file using .ini format. - * - * \code{.unparsed} - * device RGBDToPointCloudSensor_nws_ros - * subdevice - * period 30 - * topic_name /camera/points - * frame_id depth_center - * node_name //RGBDToPointCloudSensorNode - * \endcode - */ - -class RGBDToPointCloudSensor_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::dev::WrapperSingle, - public yarp::os::PeriodicThread -{ -private: - // defining types for shorter names - typedef yarp::sig::ImageOf DepthImage; - typedef yarp::os::Publisher PointCloudTopicType; - typedef yarp::rosmsg::sensor_msgs::PointCloud2 PointCloud2Type; - typedef unsigned int UInt; - - enum SensorType{COLOR_SENSOR, DEPTH_SENSOR}; - - template - struct param - { - param(T& inVar, std::string inName) - { - var = &inVar; - parname = inName; - } - T* var; - std::string parname; - }; - - PointCloudTopicType publisherPort_pointCloud; - yarp::os::Node* m_node = nullptr; - std::string nodeName; - std::string pointCloudTopicName; - std::string frameId; - - // images from device - yarp::sig::FlexImage colorImage; - DepthImage depthImage; - UInt nodeSeq = 0; - - - // this is the sub device or the real device - - double period = DEFAULT_THREAD_PERIOD; - std::string sensorId; - yarp::dev::IRGBDSensor* sensor_p = nullptr; - yarp::dev::IFrameGrabberControls* fgCtrl = nullptr; - yarp::dev::IRGBDSensor::RGBDSensor_status sensorStatus = yarp::dev::IRGBDSensor::RGBD_SENSOR_NOT_READY; - - int verbose = 4; - bool forceInfoSync = true; - bool initialize_ROS(yarp::os::Searchable& config); - - // Open the wrapper only, the attach method needs to be called before using it - // Typical usage: yarprobotinterface - bool openDeferredAttach(yarp::os::Searchable& prop); - - // If a subdevice parameter is given, the wrapper will open it and attach to immediately. - // Typical usage: simulator or command line - bool isSubdeviceOwned = false; - yarp::dev::PolyDriver* subDeviceOwned = nullptr; - bool openAndAttachSubDevice(yarp::os::Searchable& prop); - - // Synch - yarp::os::Stamp colorStamp; - yarp::os::Stamp depthStamp; - yarp::os::Property m_conf; - - bool writeData(); - -public: - RGBDToPointCloudSensor_nws_ros(); - RGBDToPointCloudSensor_nws_ros(const RGBDToPointCloudSensor_nws_ros&) = delete; - RGBDToPointCloudSensor_nws_ros(RGBDToPointCloudSensor_nws_ros&&) = delete; - RGBDToPointCloudSensor_nws_ros& operator=(const RGBDToPointCloudSensor_nws_ros&) = delete; - RGBDToPointCloudSensor_nws_ros& operator=(RGBDToPointCloudSensor_nws_ros&&) = delete; - ~RGBDToPointCloudSensor_nws_ros() override; - - bool open(yarp::os::Searchable ¶ms) override; - bool fromConfig(yarp::os::Searchable ¶ms); - bool close() override; - - /** - * Specify which sensor this thread has to read from. - */ - bool attach(yarp::dev::PolyDriver *poly) override; - bool detach() override; - - bool threadInit() override; - void threadRelease() override; - void run() override; -}; - -#endif // YARP_DEV_RGBDTOPOINTCLOUDSENSOR_NWS_ROS_H diff --git a/src/devices/ROS/Rangefinder2D_nws_ros/CMakeLists.txt b/src/devices/ROS/Rangefinder2D_nws_ros/CMakeLists.txt deleted file mode 100644 index 6f1cf5a54d3..00000000000 --- a/src/devices/ROS/Rangefinder2D_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,48 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(rangefinder2D_nws_ros - CATEGORY device - TYPE Rangefinder2D_nws_ros - INCLUDE Rangefinder2D_nws_ros.h - EXTRA_CONFIG - WRAPPER=rangefinder2D_nws_ros - DEFAULT ON -) - -if(NOT SKIP_rangefinder2D_nws_ros) - yarp_add_plugin(yarp_rangefinder2D_nws_ros) - - target_sources(yarp_rangefinder2D_nws_ros - PRIVATE - Rangefinder2D_nws_ros.cpp - Rangefinder2D_nws_ros.h - ) - - target_link_libraries(yarp_rangefinder2D_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_rangefinder2D_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_rangefinder2D_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp b/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp deleted file mode 100644 index d9b9ed77bb6..00000000000 --- a/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.cpp +++ /dev/null @@ -1,290 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#define _USE_MATH_DEFINES - -#include "Rangefinder2D_nws_ros.h" - -#include - -#include - -#include -#include - -using namespace yarp::sig; -using namespace yarp::dev; -using namespace yarp::os; - -YARP_LOG_COMPONENT(RANGEFINDER2D_NWS_ROS, "yarp.devices.rangefinder2D_nws_ros") - - -/** - * It reads the data from a rangefinder sensor and sends them on one port. - * It also creates one rpc port. - */ - -Rangefinder2D_nws_ros::Rangefinder2D_nws_ros() : PeriodicThread(DEFAULT_THREAD_PERIOD), - node(nullptr), - msgCounter(0), - sens_p(nullptr), - _period(DEFAULT_THREAD_PERIOD), - minAngle(0), - maxAngle(0), - minDistance(0), - maxDistance(0), - resolution(0), - isDeviceOwned(false) -{} - -Rangefinder2D_nws_ros::~Rangefinder2D_nws_ros() -{ - sens_p = nullptr; -} - -bool Rangefinder2D_nws_ros::checkROSParams(yarp::os::Searchable &config) -{ - // check for ROS_nodeName parameter - if (!config.check("node_name")) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Cannot find node_name parameter, mandatory when using ROS message"; - return false; - } - nodeName = config.find("node_name").asString(); - if(nodeName[0] != '/'){ - yCError(RANGEFINDER2D_NWS_ROS) << "node_name must begin with an initial /"; - return false; - } - yCInfo(RANGEFINDER2D_NWS_ROS) << "node_name is " << nodeName; - - // check for ROS_topicName parameter - if (!config.check("topic_name")) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Cannot find topic_name parameter"; - return false; - } - topicName = config.find("topic_name").asString(); - if(topicName[0] != '/'){ - yCError(RANGEFINDER2D_NWS_ROS) << "topic_name parameter must begin with an initial /"; - return false; - } - yCInfo(RANGEFINDER2D_NWS_ROS) << "topic_name is " << topicName; - - // check for frame_id parameter - if (!config.check("frame_id")) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Cannot find frame_id parameter, mandatory when using ROS message"; - return false; - } - frame_id = config.find("frame_id").asString(); - yCInfo(RANGEFINDER2D_NWS_ROS) << "Frame_id is " << frame_id; - - return true; -} - -bool Rangefinder2D_nws_ros::initialize_ROS() -{ - node = new yarp::os::Node(nodeName); // add a ROS node - if (node == nullptr) - { - yCError(RANGEFINDER2D_NWS_ROS) << " opening " << nodeName << " Node, check your yarp-ROS network configuration\n"; - return false; - } - if (!publisherPort.topic(topicName)) - { - yCError(RANGEFINDER2D_NWS_ROS) << " opening " << topicName << " Topic, check your yarp-ROS network configuration\n"; - return false; - } - return true; -} - -/** - * Specify which sensor this thread has to read from. - */ - -bool Rangefinder2D_nws_ros::attach(yarp::dev::PolyDriver* driver) -{ - if (driver->isValid()) - { - driver->view(sens_p); - } - - if (nullptr == sens_p) - { - yCError(RANGEFINDER2D_NWS_ROS, "Rangefinder2DWrapper: subdevice passed to attach method is invalid"); - return false; - } - attach(sens_p); - - if(!sens_p->getDistanceRange(minDistance, maxDistance)) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Laser device does not provide min & max distance range."; - return false; - } - - if(!sens_p->getScanLimits(minAngle, maxAngle)) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Laser device does not provide min & max angle scan range."; - return false; - } - - if (!sens_p->getHorizontalResolution(resolution)) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Laser device does not provide horizontal resolution "; - return false; - } - - PeriodicThread::setPeriod(_period); - return PeriodicThread::start(); -} - -void Rangefinder2D_nws_ros::attach(yarp::dev::IRangefinder2D *s) -{ - sens_p = s; -} - -bool Rangefinder2D_nws_ros::detach() -{ - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - sens_p = nullptr; - return true; -} - -bool Rangefinder2D_nws_ros::threadInit() -{ - return true; -} - -bool Rangefinder2D_nws_ros::open(yarp::os::Searchable &config) -{ - Property params; - params.fromString(config.toString()); - - if (!config.check("period")) - { - yCError(RANGEFINDER2D_NWS_ROS) << "Rangefinder2DWrapper: missing 'period' parameter. Check you configuration file\n"; - return false; - } - _period = config.find("period").asFloat64(); - - checkROSParams(config); - - // call ROS node/topic initialization, if needed - if (!initialize_ROS()) - { - return false; - } - - if(config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if(!m_driver.open(p) || !m_driver.isValid()) - { - yCError(RANGEFINDER2D_NWS_ROS) << "failed to open subdevice.. check params"; - return false; - } - - if(!attach(&m_driver)) - { - yCError(RANGEFINDER2D_NWS_ROS) << "failed to open subdevice.. check params"; - return false; - } - isDeviceOwned = true; - } - return true; -} - - -void Rangefinder2D_nws_ros::threadRelease() -{ - publisherPort.close(); -} - -void Rangefinder2D_nws_ros::run() -{ - if (sens_p!=nullptr) - { - bool ret = true; - IRangefinder2D::Device_status status; - yarp::sig::Vector ranges; - double synchronized_timestamp=0; - ret &= sens_p->getRawData(ranges, &synchronized_timestamp); - ret &= sens_p->getDeviceStatus(status); - - if (ret) - { - if (std::isnan(synchronized_timestamp) == false) - { - lastStateStamp.update(synchronized_timestamp); - } - else - { - lastStateStamp.update(yarp::os::Time::now()); - } - - int ranges_size = ranges.size(); - - // publish ROS topic if required - yarp::rosmsg::sensor_msgs::LaserScan &rosData = publisherPort.prepare(); - rosData.header.seq = msgCounter++; - rosData.header.stamp = lastStateStamp.getTime(); - rosData.header.frame_id = frame_id; - - rosData.angle_min = minAngle * M_PI / 180.0; - rosData.angle_max = maxAngle * M_PI / 180.0; - rosData.angle_increment = resolution * M_PI / 180.0; - rosData.time_increment = 0; // all points in a single scan are considered took at the very same time - rosData.scan_time = getPeriod(); // time elapsed between two successive readings - rosData.range_min = minDistance; - rosData.range_max = maxDistance; - rosData.ranges.resize(ranges_size); - rosData.intensities.resize(ranges_size); - - for (int i = 0; i < ranges_size; i++) - { - // in yarp, NaN is used when a scan value is missing. For example when the angular range of the rangefinder is smaller than 360. - // is ros, NaN is not used. Hence this check replaces NaN with inf. - if (std::isnan(ranges[i])) - { - rosData.ranges[i] = std::numeric_limits::infinity(); - rosData.intensities[i] = 0.0; - } - else - { - rosData.ranges[i] = ranges[i]; - rosData.intensities[i] = 0.0; - } - } - publisherPort.write(); - } - else - { - yCError(RANGEFINDER2D_NWS_ROS, "Rangefinder2D_nws_ros: %s: Sensor returned error", topicName.c_str()); - } - } -} - -bool Rangefinder2D_nws_ros::close() -{ - yCTrace(RANGEFINDER2D_NWS_ROS, "Rangefinder2DWrapperROSROS::Close"); - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - if(node!=nullptr) { - node->interrupt(); - delete node; - node = nullptr; - } - - detach(); - return true; -} diff --git a/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h b/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h deleted file mode 100644 index e97483e4f74..00000000000 --- a/src/devices/ROS/Rangefinder2D_nws_ros/Rangefinder2D_nws_ros.h +++ /dev/null @@ -1,124 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#ifndef YARP_DEV_RANGEFINDER2D_NWS_ROS_H -#define YARP_DEV_RANGEFINDER2D_NWS_ROS_H - - //#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include -#include -#include -#include -#include -#include - -// ROS state publisher -#include -#include -#include -#include - - -#define DEFAULT_THREAD_PERIOD 0.02 //s - - - /** - * @ingroup dev_impl_nws_ros dev_impl_lidar - * - * \section Rangefinder2D_nws_ros_device_parameters Description of input parameters - * - * \brief `rangefinder2D_nws_ros`: A Network grabber for 2D Rangefinder devices. - * This device will publish data on the specified ROS topic. - * - * This device does not accepts YARP RPC commands, it is dedicated only to data publishing. - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:---------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:-----------------------------: |:---------------------------------------------------------------------:|:------------:| - * | period | - | int | ms | 20 | No | refresh period of the broadcasted values in ms | default 20ms | - * | subdevice | - | string | - | - | alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | - * | node_name | - | string | - | - | Yes | name of ROS node, e.g. /myRobotName | - | - * | topic_name | - | string | - | - | Yes | name of ROS topic, e.g. /Rangefinder2DSensor | - | - * | frame_id | - | string | - | - | Yes | name of the attached frame | - | - * - * Example of configuration file using .ini format. - * - * \code{.unparsed} - * device rangefinder2D_nws_ros - * subdevice - * period 20 - * node_name //Rangefinder2DSensor - * topic_name //Rangefinder2DSensortopic - * frame_id base - * \endcode - */ -class Rangefinder2D_nws_ros : - public yarp::os::PeriodicThread, - public yarp::dev::DeviceDriver, - public yarp::dev::WrapperSingle -{ -public: - Rangefinder2D_nws_ros(); - ~Rangefinder2D_nws_ros(); - - bool open(yarp::os::Searchable ¶ms) override; - bool close() override; - - void attach(yarp::dev::IRangefinder2D *s); - bool attach(yarp::dev::PolyDriver* driver) override; - bool detach() override; - - bool threadInit() override; - void threadRelease() override; - void run() override; - -private: - // ROS streaming data - std::string frame_id; // name of the frame measures are referred to - std::string nodeName; // name of the rosNode - std::string topicName; // name of the rosTopic - yarp::os::Node* node; // add a ROS node - yarp::os::NetUint32 msgCounter; // incremental counter in the ROS message - yarp::os::Publisher publisherPort; // Dedicated ROS topic publisher - -private: - //interfaces - yarp::dev::PolyDriver m_driver; - yarp::dev::IRangefinder2D* sens_p; - -private: - //device data - yarp::os::Stamp lastStateStamp; - double _period; - double minAngle, maxAngle; - double minDistance, maxDistance; - double resolution; - bool isDeviceOwned; - -private: - //private methods - bool checkROSParams(yarp::os::Searchable &config); - bool initialize_ROS(); -}; - -#endif //YARP_DEV_RANGEFINDER2D_NWS_ROS_H diff --git a/src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt b/src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt deleted file mode 100644 index 08ca3c746e8..00000000000 --- a/src/devices/ROS/frameTransformGet_nwc_ros/CMakeLists.txt +++ /dev/null @@ -1,100 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(frameTransformGet_nwc_ros - CATEGORY device - TYPE FrameTransformGet_nwc_ros - INCLUDE FrameTransformGet_nwc_ros.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=frameTransformGet_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameTransformGet_nwc_ros) - yarp_add_plugin(yarp_frameTransformGet_nwc_ros) - - target_sources(yarp_frameTransformGet_nwc_ros - PRIVATE - FrameTransformGet_nwc_ros.cpp - FrameTransformGet_nwc_ros.h - ) - - target_sources(yarp_frameTransformGet_nwc_ros PRIVATE $) - target_include_directories(yarp_frameTransformGet_nwc_ros PRIVATE $) - - target_link_libraries(yarp_frameTransformGet_nwc_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_frameTransformGet_nwc_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameTransformGet_nwc_ros PROPERTY FOLDER "Plugins/Device/NWC") -endif() - - - -yarp_prepare_plugin(frameTransformGetMultiplexer - CATEGORY device - TYPE FrameTransformGetMultiplexer - INCLUDE FrameTransformGetMultiplexer.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=frameTransformGet_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameTransformGetMultiplexer) - yarp_add_plugin(yarp_frameTransformGetMultiplexer) - - target_sources(yarp_frameTransformGetMultiplexer - PRIVATE - FrameTransformGetMultiplexer.cpp - FrameTransformGetMultiplexer.h - ) - - target_link_libraries(yarp_frameTransformGetMultiplexer - PRIVATE - YARP::YARP_os - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_dev - ) - - yarp_install( - TARGETS yarp_frameTransformGetMultiplexer - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameTransformGetMultiplexer PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.cpp b/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.cpp deleted file mode 100644 index 1c461082f3e..00000000000 --- a/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.cpp +++ /dev/null @@ -1,192 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "FrameTransformGet_nwc_ros.h" - -#include -#include -#include - -using namespace yarp::dev; -using namespace yarp::os; -using namespace yarp::sig; -using namespace yarp::math; - -namespace { -YARP_LOG_COMPONENT(FRAMETRANSFORGETNWCROS, "yarp.device.frameTransformGet_nwc_ros") -} - -//------------------------------------------------------------------------------------------------------------------------------ -FrameTransformGet_nwc_ros::FrameTransformGet_nwc_ros(double tperiod) : -PeriodicThread(tperiod), -m_period(tperiod) -{ -} - -bool FrameTransformGet_nwc_ros::open(yarp::os::Searchable& config) -{ - if (!yarp::os::NetworkBase::checkNetwork()) { - yCError(FRAMETRANSFORGETNWCROS,"Error! YARP Network is not initialized"); - return false; - } - - bool okGeneral = config.check("GENERAL"); - if(okGeneral) - { - yarp::os::Searchable& general_config = config.findGroup("GENERAL"); - if (general_config.check("period")) - { - m_period = general_config.find("period").asFloat64(); - setPeriod(m_period); - } - if (general_config.check("refresh_interval")) {m_refreshInterval = general_config.find("refresh_interval").asFloat64();} - } - m_ftContainer.m_timeout = m_refreshInterval; - - //ROS configuration - if (config.check("ROS")) - { - yCInfo(FRAMETRANSFORGETNWCROS, "Configuring ROS params"); - Bottle ROS_config = config.findGroup("ROS"); - if (ROS_config.check("ft_topic")) { - m_topic = ROS_config.find("ft_topic").asString(); - } - if (ROS_config.check("ft_topic_static")) { - m_topic_static = ROS_config.find("ft_topic_static").asString(); - } - if (ROS_config.check("ft_node")) { - m_nodeName = ROS_config.find("ft_node").asString(); - } - - //open ros publisher - if (m_rosNode == nullptr) - { - m_rosNode = new yarp::os::Node(m_nodeName); - } - if (!m_rosSubscriberPort_tf_timed.topic(m_topic)) - { - yCError(FRAMETRANSFORGETNWCROS) << "Unable to publish data on " << m_topic << " topic, check your yarp-ROS network configuration"; - return false; - } - m_rosSubscriberPort_tf_timed.setStrict(); - if (!m_rosSubscriberPort_tf_static.topic(m_topic_static)) - { - yCError(FRAMETRANSFORGETNWCROS) << "Unable to publish data on " << m_topic_static << " topic, check your yarp-ROS network configuration"; - return false; - } - m_rosSubscriberPort_tf_static.setStrict(); - } - else - { - //no ROS options - yCWarning(FRAMETRANSFORGETNWCROS) << "ROS Group not configured"; - return false; - } - - bool resp = start(); - - return resp; -} - -bool FrameTransformGet_nwc_ros::close() -{ - yCTrace(FRAMETRANSFORGETNWCROS, "Close"); - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - m_rosSubscriberPort_tf_timed.close(); - m_rosSubscriberPort_tf_static.close(); - m_rosNode = nullptr; - return true; -} - -void FrameTransformGet_nwc_ros::run() -{ - std::lock_guard lg(m_trf_mutex); - if(!m_ftContainer.checkAndRemoveExpired()) - { - yCError(FRAMETRANSFORGETNWCROS,"Unable to remove expired transforms"); - return; - } - receiveFrameTransforms(); -} - -bool FrameTransformGet_nwc_ros::getTransforms(std::vector& transforms) const -{ - std::lock_guard lock(m_trf_mutex); - if(!m_ftContainer.checkAndRemoveExpired()) - { - yCError(FRAMETRANSFORGETNWCROS,"Unable to remove expired transforms"); - return false; - } - if(!m_ftContainer.getTransforms(transforms)) - { - yCError(FRAMETRANSFORGETNWCROS,"Unable to retrieve transforms"); - return false; - } - return true; -} - -double FrameTransformGet_nwc_ros::yarpStampFromROS(const yarp::rosmsg::TickTime& rosTime) -{ - double yarpTime; - double sec_part; - double nsec_part; - sec_part = (double)rosTime.sec; - nsec_part = ((double)rosTime.nsec)/1000000000.0; - yarpTime = sec_part+nsec_part; - - return yarpTime; -} - -void FrameTransformGet_nwc_ros::rosTransformToYARPTransform(const yarp::rosmsg::geometry_msgs::TransformStamped &input, yarp::math::FrameTransform &output, bool isStatic) -{ - output.dst_frame_id = input.child_frame_id; - output.src_frame_id = input.header.frame_id; - output.timestamp = yarpStampFromROS(input.header.stamp); - output.rotation.x() = input.transform.rotation.x; - output.rotation.y() = input.transform.rotation.y; - output.rotation.z() = input.transform.rotation.z; - output.rotation.w() = input.transform.rotation.w; - output.translation.tX = input.transform.translation.x; - output.translation.tY = input.transform.translation.y; - output.translation.tZ = input.transform.translation.z; - output.isStatic = isStatic; -} - -void FrameTransformGet_nwc_ros::receiveFrameTransforms() -{ - yarp::rosmsg::tf2_msgs::TFMessage* rosInData_timed = nullptr; - do - { - rosInData_timed = m_rosSubscriberPort_tf_timed.read(false); - if (rosInData_timed != nullptr) - { - std::vector tfs = rosInData_timed->transforms; - for (auto& tf : tfs) - { - FrameTransform t; - rosTransformToYARPTransform(tf,t,false); - m_ftContainer.setTransform(t); - } - } - } while (rosInData_timed != nullptr); - yarp::rosmsg::tf2_msgs::TFMessage* rosInData_static = nullptr; - do - { - rosInData_static = m_rosSubscriberPort_tf_static.read(false); - if (rosInData_static != nullptr) - { - std::vector tfs = rosInData_static->transforms; - for (auto& tf : tfs) - { - FrameTransform t; - rosTransformToYARPTransform(tf,t,true); - m_ftContainer.setTransform(t); - } - } - } while (rosInData_static != nullptr); -} diff --git a/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.h b/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.h deleted file mode 100644 index cb741038f48..00000000000 --- a/src/devices/ROS/frameTransformGet_nwc_ros/FrameTransformGet_nwc_ros.h +++ /dev/null @@ -1,105 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_FRAMETRANSFORMGETNWCROS_H -#define YARP_DEV_FRAMETRANSFORMGETNWCROS_H - - -#include -#include -#include -#include -#include - -#include - -#include -#include -#include - -#include - -#include -#include - -#include -#include -#include - -#define ROSNODENAME "/tfNodeGet" -#define ROSTOPICNAME_TF "/tf" -#define ROSTOPICNAME_TF_STATIC "/tf_static" - -/** - * @ingroup dev_impl_nwc_ros - * - * @brief `frameTransformGet_nwc_ros`: A ros network wrapper client that receives frame transforms from a ros topic and makes them available through an IFrameTransformStorageGet interface. See \subpage FrameTransform for additional info. - * - * \section FrameTransformGet_nwc_ros_device_parameters Parameters - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description ------- | - * |:--------------:|:--------------------:|:-------:|:--------------:|:---------------------:|:-----------: |:-----------------------------------------------------------------:| - * | GENERAL | - | group | - | - | No | | - * | - | period | double | seconds | 0.01 | No | The PeriodicThread period in seconds | - * | - | refresh_interval | double | seconds | 0.1 | No | The time interval outside which timed ft will be deleted | - * | ROS | - | group | - | - | No | | - * | - | ft_topic | string | - | /tf | No | The name of the ROS topic from which fts will be received | - * | - | ft_topic_static | string | - | /tf_static | No | The name of the ROS topic from which static fts will be received | - * | - | ft_node | string | - | /tfNodeGet | No | The of the ROS node | - * **N.B.** pay attention to the difference between **tf** and **ft** - * - * \section FrameTransformGet_nwc_ros_device_example Example of configuration file using .ini format. - * - * \code{.unparsed} - * device frameTransformGet_nwc_yarp - * [GENERAL] - * period 0.05 - * refresh_interval 0.2 - * [ROS] - * ft_topic /tf - * ft_topic_static /tf_static - * ft_node /tfNodeGet - * \endcode - */ - -class FrameTransformGet_nwc_ros : - public yarp::dev::DeviceDriver, - public yarp::os::PeriodicThread, - public yarp::dev::IFrameTransformStorageGet -{ -public: - FrameTransformGet_nwc_ros(double tperiod=0.010); - ~FrameTransformGet_nwc_ros()=default; - - //DeviceDriver - bool open(yarp::os::Searchable& config) override; - bool close() override; - - //periodicThread - void run() override; - - //IFrameTransformStorageGet interface - bool getTransforms(std::vector& transforms) const override; - - //own - void receiveFrameTransforms(); - void rosTransformToYARPTransform(const yarp::rosmsg::geometry_msgs::TransformStamped &input, yarp::math::FrameTransform &output, bool isStatic); - double yarpStampFromROS(const yarp::rosmsg::TickTime& rosTime); - -private: - mutable std::mutex m_trf_mutex; - std::string m_nodeName{ROSNODENAME}; - std::string m_topic{ROSTOPICNAME_TF}; - std::string m_topic_static{ROSTOPICNAME_TF_STATIC}; - double m_period{0.01}; - double m_refreshInterval{0.1}; - yarp::os::Node* m_rosNode{nullptr}; - yarp::os::Subscriber m_rosSubscriberPort_tf_timed; - yarp::os::Subscriber m_rosSubscriberPort_tf_static; - FrameTransformContainer m_ftContainer; -}; - -#endif // YARP_DEV_FRAMETRANSFORMGETNWCROS_H diff --git a/src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt b/src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt deleted file mode 100644 index 72209907721..00000000000 --- a/src/devices/ROS/frameTransformSet_nwc_ros/CMakeLists.txt +++ /dev/null @@ -1,100 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(frameTransformSet_nwc_ros - CATEGORY device - TYPE FrameTransformSet_nwc_ros - INCLUDE FrameTransformSet_nwc_ros.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=frameTransformSet_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameTransformSet_nwc_ros) - yarp_add_plugin(yarp_frameTransformSet_nwc_ros) - - target_sources(yarp_frameTransformSet_nwc_ros - PRIVATE - FrameTransformSet_nwc_ros.cpp - FrameTransformSet_nwc_ros.h - ) - - target_sources(yarp_frameTransformSet_nwc_ros PRIVATE $) - target_include_directories(yarp_frameTransformSet_nwc_ros PRIVATE $) - - target_link_libraries(yarp_frameTransformSet_nwc_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_frameTransformSet_nwc_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameTransformSet_nwc_ros PROPERTY FOLDER "Plugins/Device/NWC") -endif() - - - -yarp_prepare_plugin(frameTransformSetMultiplexer - CATEGORY device - TYPE FrameTransformSetMultiplexer - INCLUDE FrameTransformSetMultiplexer.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=frameTransformSet_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameTransformSetMultiplexer) - yarp_add_plugin(yarp_frameTransformSetMultiplexer) - - target_sources(yarp_frameTransformSetMultiplexer - PRIVATE - FrameTransformSetMultiplexer.cpp - FrameTransformSetMultiplexer.h - ) - - target_link_libraries(yarp_frameTransformSetMultiplexer - PRIVATE - YARP::YARP_os - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_dev - ) - - yarp_install( - TARGETS yarp_frameTransformSetMultiplexer - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameTransformSetMultiplexer PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.cpp b/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.cpp deleted file mode 100644 index 55230f09fd6..00000000000 --- a/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.cpp +++ /dev/null @@ -1,234 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "FrameTransformSet_nwc_ros.h" - -#include -#include -#include - -using namespace yarp::dev; -using namespace yarp::os; -using namespace yarp::sig; -using namespace yarp::math; - -namespace { -YARP_LOG_COMPONENT(FRAMETRANSFORSETNWCROS, "yarp.device.frameTransformSet_nwc_ros") -} - -//------------------------------------------------------------------------------------------------------------------------------ -FrameTransformSet_nwc_ros::FrameTransformSet_nwc_ros(double tperiod) : -PeriodicThread(tperiod), -m_period(tperiod) -{ -} - -bool FrameTransformSet_nwc_ros::open(yarp::os::Searchable& config) -{ - if (!yarp::os::NetworkBase::checkNetwork()) { - yCError(FRAMETRANSFORSETNWCROS,"Error! YARP Network is not initialized"); - return false; - } - - bool okGeneral = config.check("GENERAL"); - if(okGeneral) - { - yarp::os::Searchable& general_config = config.findGroup("GENERAL"); - if (general_config.check("period")) - { - m_period = general_config.find("period").asFloat64(); - setPeriod(m_period); - } - if (general_config.check("refresh_interval")) {m_refreshInterval = general_config.find("refresh_interval").asFloat64();} - if (general_config.check("asynch_pub")) {m_asynchPub = general_config.find("asynch_pub").asInt16();} - } - m_ftContainer.m_timeout = m_refreshInterval; - - //ROS configuration - if (config.check("ROS")) - { - yCInfo(FRAMETRANSFORSETNWCROS, "Configuring ROS params"); - Bottle ROS_config = config.findGroup("ROS"); - if (ROS_config.check("ft_topic")) { - m_topic = ROS_config.find("ft_topic").asString(); - } - if (ROS_config.check("ft_topic_static")) { - m_topic_static = ROS_config.find("ft_topic_static").asString(); - } - if (ROS_config.check("ft_node")) { - m_nodeName = ROS_config.find("ft_node").asString(); - } - - //open ros publisher - if (m_rosNode == nullptr) - { - m_rosNode = new yarp::os::Node(m_nodeName); - } - if (!m_rosPublisherPort_tf_timed.topic(m_topic)) - { - yCError(FRAMETRANSFORSETNWCROS) << "Unable to publish data on " << m_topic << " topic, check your yarp-ROS network configuration"; - return false; - } - if (!m_rosPublisherPort_tf_static.topic(m_topic_static)) - { - yCError(FRAMETRANSFORSETNWCROS) << "Unable to publish data on " << m_topic_static << " topic, check your yarp-ROS network configuration"; - return false; - } - } - else - { - //no ROS options - yCWarning(FRAMETRANSFORSETNWCROS) << "ROS Group not configured"; - return false; - } - - start(); - - return true; -} - -bool FrameTransformSet_nwc_ros::close() -{ - yCTrace(FRAMETRANSFORSETNWCROS, "Close"); - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - m_rosPublisherPort_tf_timed.close(); - m_rosPublisherPort_tf_static.close(); - m_rosNode = nullptr; - return true; -} - -void FrameTransformSet_nwc_ros::run() -{ - std::lock_guard lg(m_trf_mutex); - if(!m_ftContainer.checkAndRemoveExpired()) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to remove expired transforms"); - return; - } - std::vector tempTfs; - if(!m_ftContainer.getTransforms(tempTfs)) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to get the transform vector)"); - return; - } - publishFrameTransforms(tempTfs); -} - -bool FrameTransformSet_nwc_ros::setTransforms(const std::vector& transforms) -{ - std::lock_guard lock(m_trf_mutex); - if(!m_ftContainer.setTransforms(transforms)) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to set transforms"); - return false; - } - if(m_asynchPub) - { - if(!m_ftContainer.checkAndRemoveExpired()) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to remove expired transforms"); - return false; - } - - std::vector tempTfs; - if(!m_ftContainer.getTransforms(tempTfs)) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to get the transform vector)"); - return false; - } - publishFrameTransforms(tempTfs); - } - return true; -} - -bool FrameTransformSet_nwc_ros::setTransform(const yarp::math::FrameTransform& t) -{ - std::lock_guard lock(m_trf_mutex); - if(!m_ftContainer.setTransform(t)) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to set transform"); - return false; - } - if(m_asynchPub) - { - if(!m_ftContainer.checkAndRemoveExpired()) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to remove expired transforms"); - return false; - } - - std::vector tempTfs; - if(!m_ftContainer.getTransforms(tempTfs)) - { - yCError(FRAMETRANSFORSETNWCROS,"Unable to get the transform vector)"); - return false; - } - publishFrameTransforms(tempTfs); - } - return true; -} - -void FrameTransformSet_nwc_ros::yarpTransformToROSTransform(const yarp::math::FrameTransform &input, yarp::rosmsg::geometry_msgs::TransformStamped& output) -{ - output.child_frame_id = input.dst_frame_id; - output.header.frame_id = input.src_frame_id; - output.header.stamp = input.timestamp; - output.transform.rotation.x = input.rotation.x(); - output.transform.rotation.y = input.rotation.y(); - output.transform.rotation.z = input.rotation.z(); - output.transform.rotation.w = input.rotation.w(); - output.transform.translation.x = input.translation.tX; - output.transform.translation.y = input.translation.tY; - output.transform.translation.z = input.translation.tZ; -} - -void FrameTransformSet_nwc_ros::publishFrameTransforms(const std::vector& transforms) -{ - static int rosMsgCounter = 0; // Ask for clarification! - - yarp::rosmsg::tf2_msgs::TFMessage& rosOutTimedData = m_rosPublisherPort_tf_timed.prepare(); - yarp::rosmsg::tf2_msgs::TFMessage& rosOutStaticData = m_rosPublisherPort_tf_static.prepare(); - yarp::rosmsg::geometry_msgs::TransformStamped transform_timed; - yarp::rosmsg::geometry_msgs::TransformStamped transform_static; - rosOutTimedData.transforms.clear(); - rosOutStaticData.transforms.clear(); - - for(auto& tf : transforms) - { - if(tf.isStatic) - { - yarpTransformToROSTransform(tf,transform_static); - transform_static.header.seq = rosMsgCounter; - rosOutStaticData.transforms.push_back(transform_static); - } - else - { - yarpTransformToROSTransform(tf,transform_timed); - transform_timed.header.seq = rosMsgCounter; - rosOutTimedData.transforms.push_back(transform_timed); - } - } - m_rosPublisherPort_tf_timed.write(); - m_rosPublisherPort_tf_static.write(); - - rosMsgCounter++; -} - -bool FrameTransformSet_nwc_ros::deleteTransform(std::string t1, std::string t2) -{ - // Not yet implemented - yCError(FRAMETRANSFORSETNWCROS, "deleteTransform not yet implemented"); - return false; -} - -bool FrameTransformSet_nwc_ros::clearAll() -{ - // Not yet implemented - yCError(FRAMETRANSFORSETNWCROS, "clearAll not yet implemented"); - return false; -} diff --git a/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.h b/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.h deleted file mode 100644 index 8e8bf5146ef..00000000000 --- a/src/devices/ROS/frameTransformSet_nwc_ros/FrameTransformSet_nwc_ros.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_FRAMETRANSFORMSETNWCROS_H -#define YARP_DEV_FRAMETRANSFORMSETNWCROS_H - - -#include -#include -#include -#include -#include - -#include - -#include -#include -#include - -#include - -#include -#include - -#include -#include -#include - -#define ROSNODENAME "/tfNodeSet" -#define ROSTOPICNAME_TF "/tf" -#define ROSTOPICNAME_TF_STATIC "/tf_static" - -/** - * @ingroup dev_impl_nwc_ros - * - * @brief `frameTransformSet_nwc_ros`: A network wrapper client which publishes the transforms received on the yarp::dev::IFrameTransformStorageSet interface to a ROS topic. - * - * \section FrameTransformSet_nwc_ros_device_parameters Parameters - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Valu | Required | Description | - * |:--------------:|:--------------------:|:-------:|:--------------:|:---------------------:|:-----------: |:-------------------------------------------------------------------------------------------------------:| - * | GENERAL | - | group | - | - | No | | - * | - | period | double | seconds | 0.01 | No | The PeriodicThread period in seconds | - * | - | refresh_interval | double | seconds | 0.1 | No | The time interval outside which timed fts will be deleted | - * | - | asynch_pub | int | - | 1 | No | If 1, the fts will be published not only every "period" seconds but also when set functions are called | - * | ROS | - | group | - | - | No | | - * | - | ft_topic | string | - | /tf | No | The name of the ROS topic on which fts will be published | - * | - | ft_topic_static | string | - | /tf_static | No | The name of the ROS topic on which static fts will be published | - * | - | ft_node | string | - | /tfNodeSet | No | The of the ROS node | - * - * **N.B.** pay attention to the difference between **tf** and **ft** - * - * \section FrameTransformSet_nwc_ros_configuration Example of configuration file using .ini format. - * - * \code{.unparsed} - * device frameTransformSet_nwc_yarp - * [GENERAL] - * period 0.05 - * refresh_interval 0.2 - * [ROS] - * ft_topic /tf - * ft_topic_static /tf_static - * ft_node /tfNodeSet - * \endcode - */ - -class FrameTransformSet_nwc_ros : - public yarp::dev::DeviceDriver, - public yarp::os::PeriodicThread, - public yarp::dev::IFrameTransformStorageSet -{ -public: - FrameTransformSet_nwc_ros(double tperiod=0.010); - ~FrameTransformSet_nwc_ros()=default; - - //DeviceDriver - bool open(yarp::os::Searchable& config) override; - bool close() override; - - //periodicThread - void run() override; - - //IFrameTransformStorageSet interface - bool setTransforms(const std::vector& transforms) override; - bool setTransform(const yarp::math::FrameTransform& transform) override; - bool deleteTransform(std::string t1, std::string t2) override; - bool clearAll() override; - - //own - void publishFrameTransforms(const std::vector& transforms); - void yarpTransformToROSTransform(const yarp::math::FrameTransform &input, yarp::rosmsg::geometry_msgs::TransformStamped& output); - -private: - mutable std::mutex m_trf_mutex; - std::string m_nodeName{ROSNODENAME}; - std::string m_topic{ROSTOPICNAME_TF}; - std::string m_topic_static{ROSTOPICNAME_TF_STATIC}; - double m_period{0.01}; - double m_refreshInterval{0.1}; - bool m_asynchPub{true}; - yarp::os::Node* m_rosNode{nullptr}; - yarp::os::Publisher m_rosPublisherPort_tf_timed; - yarp::os::Publisher m_rosPublisherPort_tf_static; - FrameTransformContainer m_ftContainer; -}; - -#endif // YARP_DEV_FRAMETRANSFORMSETNWCROS_H diff --git a/src/devices/ROS/laserFromRosTopic/CMakeLists.txt b/src/devices/ROS/laserFromRosTopic/CMakeLists.txt deleted file mode 100644 index da40538425a..00000000000 --- a/src/devices/ROS/laserFromRosTopic/CMakeLists.txt +++ /dev/null @@ -1,48 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(laserFromRosTopic - CATEGORY device - TYPE LaserFromRosTopic - INCLUDE LaserFromRosTopic.h - DEPENDS "TARGET YARP::YARP_math" -) - -if(NOT SKIP_laserFromRosTopic) - yarp_add_plugin(yarp_laserFromRosTopic) - - target_sources(yarp_laserFromRosTopic - PRIVATE - LaserFromRosTopic.h - LaserFromRosTopic.cpp - ) - - target_link_libraries(yarp_laserFromRosTopic - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_laserFromRosTopic - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_laserFromRosTopic PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.cpp b/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.cpp deleted file mode 100644 index 6184c6a2e71..00000000000 --- a/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.cpp +++ /dev/null @@ -1,491 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#define _USE_MATH_DEFINES - -#include "LaserFromRosTopic.h" - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; - -#ifndef DEG2RAD -#define DEG2RAD M_PI/180.0 -#endif - -#ifndef RAD2DEG -#define RAD2DEG 180/M_PI -#endif - -YARP_LOG_COMPONENT(LASER_FROM_ROS_TOPIC, "yarp.devices.laserFromRosTopic") - -/* - -yarpdev --device transformServer --ROS::enable_ros_publisher 0 --ROS::enable_ros_subscriber 1 - -yarpdev --device Rangefinder2DWrapper --subdevice laserFromRosTopic \ ---SENSOR::input_topics_name "(/base_scan)" \ ---TRANSFORM_CLIENT::local /LaserFromRosTopic/tfClient \ ---TRANSFORM_CLIENT::remote /transformServer \ ---TRANSFORMS::src_frames "(/frame1)" \ ---TRANSFORMS::dst_frame /output_frame \ ---period 10 \ ---SENSOR::min_angle 0 \ ---SENSOR::max_angle 360 \ ---SENSOR::resolution 0.5 \ ---name /outlaser:o - -yarpdev --device Rangefinder2DWrapper --subdevice laserFromRosTopic \ ---SENSOR::min_angle 0 \ ---SENSOR::max_angle 360 \ ---SENSOR::resolution 0.5 \ ---SENSOR::input_topics_name "(/topic1 /topic2)" \ ---TRANSFORM_CLIENT::local /LaserFromRosTopic/tfClient \ ---TRANSFORM_CLIENT::remote /transformServer \ ---TRANSFORMS::src_frames "(/frame1 /frame2)" \ ---TRANSFORMS::dst_frame /output_frame \ ---period 10 \ ---name /outlaser:o -*/ - -double constrainAngle(double x) -{ - x = fmod(x, 360); - if (x < 0) { - x += 360; - } - return x; -} - -InputPortProcessor::InputPortProcessor() -{ - m_contains_data=false; -} - -void InputPortProcessor::onRead(yarp::rosmsg::sensor_msgs::LaserScan& b) -{ - m_port_mutex.lock(); - m_lastScan.angle_max = b.angle_max; - m_lastScan.angle_min = b.angle_min; - m_lastScan.range_max = b.range_max; - m_lastScan.range_min = b.range_min; - size_t ros_size = b.ranges.size(); - if (ros_size != m_lastScan.scans.size()) - { - m_lastScan.scans.resize (ros_size); - } - for (size_t i = 0; i < ros_size; i++) - { - m_lastScan.scans[i] = b.ranges[i]; - } - getEnvelope(m_lastStamp); - m_contains_data=true; - m_port_mutex.unlock(); -} - -inline void InputPortProcessor::getLast(yarp::dev::LaserScan2D& data, Stamp& stmp) -{ - //this blocks untils the first data is received; - size_t counter =0; - while (m_contains_data==false) - { - yarp::os::Time::delay(0.1); - if (counter++ > 100) {yDebug() << "Waiting for incoming data..."; counter=0;} - } - - m_port_mutex.lock(); - data = m_lastScan; - stmp = m_lastStamp; - m_port_mutex.unlock(); -} - -//------------------------------------------------------------------------------------- - -bool LaserFromRosTopic::open(yarp::os::Searchable& config) -{ - Property subConfig; - m_info = "LaserFromRosTopic device"; - -#ifdef LASER_DEBUG - yCDebug(LASER_FROM_ROS_TOPIC) << "%s\n", config.toString().c_str()); -#endif - - if (this->parseConfiguration(config) == false) - { - yCError(LASER_FROM_ROS_TOPIC) << "Error parsing parameters"; - return false; - } - - yarp::os::Searchable& general_config = config.findGroup("SENSOR"); - - if (general_config.check("input_topics_name")) //this parameter is optional - { - yarp::os::Bottle* portlist = general_config.find("input_topics_name").asList(); - if (portlist) - { - for (size_t i = 0; i < portlist->size(); i++) { - m_port_names.push_back(portlist->get(i).asString()); - } - } - else - { - m_port_names.push_back("/laserFromExternalPort:i"); - } - - for (size_t i = 0; i < m_port_names.size(); i++) - { - InputPortProcessor proc; - m_input_ports.push_back(proc); - } - m_last_stamp.resize(m_port_names.size()); - m_last_scan_data.resize(m_port_names.size()); - } - - if (general_config.check("base_type")) //this parameter is optional - { - std::string bt = general_config.find("base_type").asString(); - if (bt=="infinity") { m_base_type = base_enum::BASE_IS_INF; } - else if (bt=="nan") { m_base_type = base_enum::BASE_IS_NAN; } - else if (bt=="zero") {m_base_type = base_enum::BASE_IS_ZERO;} - else { yCError(LASER_FROM_ROS_TOPIC) << "Invalid value of param base_type"; return false; - } - } - - //set the base value - m_empty_laser_data = m_laser_data; - if (m_base_type == base_enum::BASE_IS_INF) - { - for (size_t i = 0; i < m_empty_laser_data.size(); i++) { - m_empty_laser_data[i] = std::numeric_limits::infinity(); - } - } - else if (m_base_type == base_enum::BASE_IS_NAN) - { - for (size_t i = 0; i < m_empty_laser_data.size(); i++) { - m_empty_laser_data[i] = std::nanf(""); - } - } - else if (m_base_type == base_enum::BASE_IS_ZERO) - { - for (size_t i = 0; i < m_empty_laser_data.size(); i++) { - m_empty_laser_data[i] = 0; - } - } - else - { - yCError(LASER_FROM_ROS_TOPIC) << "Invalid m_base_type"; - return false; - } - - if (general_config.check("override")) //this parameter is optional - { - if (m_input_ports.size() != 1) - { - yCError(LASER_FROM_ROS_TOPIC) << "option override cannot be used when multiple ports are involved"; - return false; - } - else - { - m_option_override_limits = true; - } - } - - //open the tc client - if (config.check("TRANSFORMS") && config.check("TRANSFORM_CLIENT")) - { - yarp::os::Searchable& transforms_config = config.findGroup("TRANSFORMS"); - yarp::os::Bottle* src_frames_list = transforms_config.find("src_frames").asList(); - if (src_frames_list) - { - if (src_frames_list->size() != m_input_ports.size()) - { - yCError(LASER_FROM_ROS_TOPIC) << "src_frames invalid number"; - return false; - } - for (size_t i = 0; i < src_frames_list->size(); i++) - { - m_src_frame_id.push_back(src_frames_list->get(i).asString()); - } - } - else - { - yCError(LASER_FROM_ROS_TOPIC) << "src_frames invalid value or param not found"; - return false; - } - m_dst_frame_id = transforms_config.find("dst_frame").asString(); - if (m_dst_frame_id=="") - { - yCError(LASER_FROM_ROS_TOPIC) << "dst_frame param not found"; - return false; - } - - - std::string client_cfg_string = config.findGroup("TRANSFORM_CLIENT").toString(); - if (client_cfg_string=="") - { - yCError(LASER_FROM_ROS_TOPIC) << "TRANSFORM_CLIENT param not found"; - return false; - } - - Property tcprop; - tcprop.fromString(client_cfg_string); - tcprop.put("device", "transformClient"); - - m_tc_driver.open(tcprop); - if (!m_tc_driver.isValid()) - { - yCError(LASER_FROM_ROS_TOPIC) << "Error opening PolyDriver check parameters"; - return false; - } - m_tc_driver.view(m_iTc); - if (!m_iTc) - { - yCError(LASER_FROM_ROS_TOPIC) << "Error opening iFrameTransform interface. Device not available"; - return false; - } - yarp::os::Time::delay(0.1); - } - - m_ros_node = new yarp::os::Node("/laserFromRosTopicNode"); - for (size_t i = 0; i < m_input_ports.size(); i++) - { - //m_input_ports[i].useCallback(); ///@@@<-SEGFAULT - if (m_input_ports[i].topic(m_port_names[i]) == false) - { - yCError(LASER_FROM_ROS_TOPIC) << "Error opening port:" << m_port_names[i]; - return false; - } - m_input_ports[i].useCallback(); ///@@@<-OK - } - PeriodicThread::start(); - - yInfo("LaserFromRosTopic: Sensor ready"); - return true; -} - -bool LaserFromRosTopic::close() -{ - PeriodicThread::stop(); - - for (auto it=m_input_ports.begin(); it!= m_input_ports.end(); it++) - { - it->close(); - } - if (m_ros_node) { delete m_ros_node; m_ros_node = nullptr; } - - yCInfo(LASER_FROM_ROS_TOPIC) << "LaserFromRosTopic closed"; - return true; -} - - - -bool LaserFromRosTopic::setDistanceRange(double min, double max) -{ - std::lock_guard guard(m_mutex); - m_min_distance = min; - m_max_distance = max; - return true; -} - -bool LaserFromRosTopic::setScanLimits(double min, double max) -{ - std::lock_guard guard(m_mutex); - yCWarning(LASER_FROM_ROS_TOPIC) << "setScanLimits not yet implemented"; - return true; -} - - - -bool LaserFromRosTopic::setHorizontalResolution(double step) -{ - std::lock_guard guard(m_mutex); - yCWarning(LASER_FROM_ROS_TOPIC, "setHorizontalResolution not yet implemented"); - return true; -} - -bool LaserFromRosTopic::setScanRate(double rate) -{ - std::lock_guard guard(m_mutex); - yCWarning(LASER_FROM_ROS_TOPIC, "setScanRate not yet implemented"); - return false; -} - - - -bool LaserFromRosTopic::threadInit() -{ -#ifdef LASER_DEBUG - yCDebug(LASER_FROM_ROS_TOPIC) <<"LaserFromRosTopic:: thread initialising...\n"); - yCDebug(LASER_FROM_ROS_TOPIC) <<"... done!\n"); -#endif - - return true; -} - -void LaserFromRosTopic::calculate(yarp::dev::LaserScan2D scan_data, yarp::sig::Matrix m) -{ - yarp::sig::Vector temp(3); - temp = yarp::math::dcm2rpy(m); - double t_off_rad = temp[2]; - double x_off = m[0][3]; - double y_off = m[1][3]; - -#ifdef DO_NOTHING_DEBUG - double x_off = 0; - double y_off = 0; - double t_off_deg = 0; - double t_off_rad = 0; -#endif - -//////////////////////////// - double resolution = (scan_data.angle_max - scan_data.angle_min)/ scan_data.scans.size(); // deg/elem - for (size_t i = 0; i < scan_data.scans.size(); i++) - { - double distance = scan_data.scans[i]; - if (distance == std::numeric_limits::infinity()) - { - distance = 100; - } - if (std::isnan(distance)) - { - //skip nan - } - else - { - //if we received a valid value, process it and put it in the right slot - double angle_input_deg = (i * resolution) + scan_data.angle_min; - double angle_input_rad = (angle_input_deg) * DEG2RAD; - - //calculate vertical and horizontal components of input angle - double Ay = (sin(angle_input_rad + t_off_rad) * distance); - double Ax = (cos(angle_input_rad + t_off_rad) * distance); - - //calculate vertical and horizontal components of new angle with offset. - double By = Ay + y_off; - double Bx = Ax + x_off; - - double angle_output_rad = atan2(By, Bx); //the output is (-pi +pi) - double angle_output_deg = angle_output_rad * RAD2DEG; //the output is (-180 +180) - angle_output_deg = constrainAngle(angle_output_deg); //the output is (0 360( - - //check if angle is inside the min max limits of the target vector, otherwise skip it - if (angle_output_deg > m_max_angle) { continue; } - if (angle_output_deg < m_min_angle) { continue; } - - //compute the new slot - int new_i = lrint ((angle_output_deg - m_min_angle) / m_resolution); - if (new_i == static_cast(m_laser_data.size())) {new_i=0;} - - yAssert (new_i >= 0); - yAssert (new_i < static_cast(m_laser_data.size())); - - //compute the distance - double newdistance = std::sqrt((Bx * Bx) + (By * By)); - - //assignment on empty (nan) slots or in valid slots if distance is shorter - if (std::isnan(m_laser_data[new_i])) - { - m_laser_data[new_i] = newdistance; - } - else if (newdistance < m_laser_data[new_i]) - { - m_laser_data[new_i] = newdistance; - } - } - } -} - -bool LaserFromRosTopic::acquireDataFromHW() -{ -#ifdef DEBUG_TIMING - double t1 = yarp::os::Time::now(); -#endif - std::lock_guard guard(m_mutex); - m_laser_data = m_empty_laser_data; - - size_t nports = m_input_ports.size(); - if (nports == 1) //one single port, optimes version - { - m_input_ports[0].getLast(m_last_scan_data[0], m_last_stamp[0]); - size_t received_scans = m_last_scan_data[0].scans.size(); - - if (m_option_override_limits) - { - //this overrides user setting with parameters received from the port - m_sensorsNum = received_scans; - m_max_angle = m_last_scan_data[0].angle_max; - m_min_angle = m_last_scan_data[0].angle_min; - m_max_distance = m_last_scan_data[0].range_max; - m_min_distance = m_last_scan_data[0].range_min; - m_resolution = received_scans / (m_max_angle - m_min_angle); - if (m_laser_data.size() != m_sensorsNum) { - m_laser_data.resize(m_sensorsNum); - } - } - - if (m_iTc == nullptr) - { - for (size_t elem = 0; elem < m_sensorsNum; elem++) - { - m_laser_data[elem] = m_last_scan_data[0].scans[elem]; //m - } - } - else - { - yarp::sig::Matrix m(4, 4); m.eye(); - bool frame_exists = m_iTc->getTransform(m_src_frame_id[0], m_dst_frame_id, m); - if (frame_exists == false) - { - yCWarning(LASER_FROM_ROS_TOPIC) << "Unable to found m matrix" << "and" << m_dst_frame_id; - } - calculate(m_last_scan_data[0], m); - } - } - else //multiple ports - { - for (size_t i = 0; i < nports; i++) - { - yarp::sig::Matrix m(4, 4); m.eye(); - bool frame_exists = m_iTc->getTransform(m_src_frame_id[i], m_dst_frame_id, m); - if (frame_exists == false) - { - yCWarning(LASER_FROM_ROS_TOPIC) << "Unable to found m matrix between" << "and" << m_dst_frame_id; - } - m_input_ports[i].getLast(m_last_scan_data[i], m_last_stamp[i]); - calculate(m_last_scan_data[i], m); - } - } - - return true; -} - -void LaserFromRosTopic::run() -{ - m_mutex.lock(); - updateLidarData(); - m_mutex.unlock(); -} - -void LaserFromRosTopic::threadRelease() -{ -#ifdef LASER_DEBUG - yCDebug(LASER_FROM_ROS_TOPIC) <<"Thread releasing..."); - yCDebug(LASER_FROM_ROS_TOPIC) <<"... done."); -#endif - - return; -} diff --git a/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.h b/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.h deleted file mode 100644 index c4cd0756768..00000000000 --- a/src/devices/ROS/laserFromRosTopic/LaserFromRosTopic.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#ifndef LASER_FROM_ROS_TOPIC_H -#define LASER_FROM_ROS_TOPIC_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - // ROS state publisher -#include -#include -#include -#include - -#include -#include -#include - -typedef unsigned char byte; - -//--------------------------------------------------------------------------------------------------------------- -enum base_enum -{ - BASE_IS_NAN = 0, - BASE_IS_INF = 1, - BASE_IS_ZERO = 2 -}; - -class InputPortProcessor : - public yarp::os::Subscriber -{ - std::mutex m_port_mutex; - yarp::dev::LaserScan2D m_lastScan; - yarp::os::Stamp m_lastStamp; - bool m_contains_data; - -public: - InputPortProcessor(const InputPortProcessor& alt) : - yarp::os::Subscriber(), - m_lastScan(alt.m_lastScan), - m_lastStamp(alt.m_lastStamp), - m_contains_data(alt.m_contains_data) - { - } - - InputPortProcessor(); - using yarp::os::Subscriber::onRead; - virtual void onRead(yarp::rosmsg::sensor_msgs::LaserScan& v) override; - void getLast(yarp::dev::LaserScan2D& data, yarp::os::Stamp& stmp); -}; - -/** - * @ingroup dev_impl_lidar - * - * \brief `laserFromRosTopic`: Documentation to be added - */ -class LaserFromRosTopic : public yarp::dev::Lidar2DDeviceBase, - public yarp::os::PeriodicThread, - public yarp::dev::DeviceDriver -{ -protected: - bool m_option_override_limits; - std::vector m_port_names; - yarp::os::Node* m_ros_node = nullptr; - std::vector m_input_ports; - std::vector m_last_stamp; - std::vector m_last_scan_data; - yarp::dev::PolyDriver m_tc_driver; - yarp::dev::IFrameTransform* m_iTc = nullptr; - - std::vector m_src_frame_id; - std::string m_dst_frame_id; - yarp::sig::Vector m_empty_laser_data; - base_enum m_base_type; - - void calculate(yarp::dev::LaserScan2D scan, yarp::sig::Matrix m); - -public: - LaserFromRosTopic(double period = 0.01) : Lidar2DDeviceBase(), PeriodicThread(period) - { - m_option_override_limits=false; - m_base_type = base_enum::BASE_IS_NAN; - } - - ~LaserFromRosTopic() - { - } - - bool open(yarp::os::Searchable& config) override; - bool close() override; - bool threadInit() override; - void threadRelease() override; - void run() override; - -public: - //IRangefinder2D interface - bool setDistanceRange (double min, double max) override; - bool setScanLimits (double min, double max) override; - bool setHorizontalResolution (double step) override; - bool setScanRate (double rate) override; - -public: - //Lidar2DDeviceBase - bool acquireDataFromHW() override final; -}; - -#endif diff --git a/src/devices/ROS/localization2D_nws_ros/CMakeLists.txt b/src/devices/ROS/localization2D_nws_ros/CMakeLists.txt deleted file mode 100644 index 8f8fd50674c..00000000000 --- a/src/devices/ROS/localization2D_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,50 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(localization2D_nws_ros - CATEGORY device - TYPE Localization2D_nws_ros - INCLUDE Localization2D_nws_ros.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=localization2D_nws_ros - DEFAULT ON -) - -if(NOT SKIP_localization2D_nws_ros) - yarp_add_plugin(yarp_localization2D_nws_ros) - - target_sources(yarp_localization2D_nws_ros - PRIVATE - Localization2D_nws_ros.h - Localization2D_nws_ros.cpp - ) - - target_link_libraries(yarp_localization2D_nws_ros - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - YARP::YARP_math - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - YARP_math - ) - - yarp_install( - TARGETS yarp_localization2D_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_localization2D_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.cpp b/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.cpp deleted file mode 100644 index 2dcd2dce544..00000000000 --- a/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.cpp +++ /dev/null @@ -1,404 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#define _USE_MATH_DEFINES - -#include "Localization2D_nws_ros.h" - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include -#include -#include - -#include - -#include - -/*! \file Localization2D_nws_ros.cpp */ - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; - -#define DEFAULT_THREAD_PERIOD 0.01 - -namespace { -YARP_LOG_COMPONENT(LOCALIZATION2D_NWS_ROS, "yarp.device.localization2D_nws_ros") -} - -//------------------------------------------------------------------------------------------------------------------------------ - -Localization2D_nws_ros::Localization2D_nws_ros() : PeriodicThread(DEFAULT_THREAD_PERIOD), - m_period(DEFAULT_THREAD_PERIOD) -{ - m_stats_time_last = yarp::os::Time::now(); -} - -bool Localization2D_nws_ros::attach(PolyDriver* driver) -{ - if (driver->isValid()) - { - driver->view(iLoc); - } - - if (nullptr == iLoc) - { - yCError(LOCALIZATION2D_NWS_ROS, "Subdevice passed to attach method is invalid"); - return false; - } - - //initialize m_current_position and m_current_status, if available - bool ret = true; - yarp::dev::Nav2D::LocalizationStatusEnum status; - Map2DLocation loc; - ret &= iLoc->getLocalizationStatus(status); - ret &= iLoc->getCurrentPosition(loc); - if (ret) - { - m_current_status = status; - m_current_position = loc; - } - else - { - yCWarning(LOCALIZATION2D_NWS_ROS) << "Localization data not yet available during server initialization"; - } - - PeriodicThread::setPeriod(m_period); - return PeriodicThread::start(); -} - -bool Localization2D_nws_ros::detach() -{ - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - iLoc = nullptr; - return true; -} - -bool Localization2D_nws_ros::open(Searchable& config) -{ - Property params; - params.fromString(config.toString().c_str()); - yCDebug(LOCALIZATION2D_NWS_ROS) << "Configuration: \n" << config.toString().c_str(); - - if (!config.check("period")) - { - yCInfo(LOCALIZATION2D_NWS_ROS) << "Missing 'period' parameter. Using default value: " << DEFAULT_THREAD_PERIOD; - m_period = DEFAULT_THREAD_PERIOD; - } - else - { - m_period = config.find("period").asFloat64(); - yCInfo(LOCALIZATION2D_NWS_ROS) << "Period requested: " << m_period; - } - - if (!config.check("publish_odometry")) - { - m_enable_publish_odometry_topic = config.find("publish_odometry").asBool(); - yCInfo(LOCALIZATION2D_NWS_ROS) << "publish_odometry=" << m_enable_publish_odometry_topic; - } - if (!config.check("publish_tf")) - { - m_enable_publish_odometry_tf = config.find("publish_tf").asBool(); - yCInfo(LOCALIZATION2D_NWS_ROS) << "publish_tf=" << m_enable_publish_odometry_tf; - } - - if (!config.check("yarp_base_name")) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Missing yarp_base_name parameter"; - return false; - } - m_local_name = config.find("yarp_base_name").asString(); - if (m_local_name.c_str()[0] != '/') { - yCError(LOCALIZATION2D_NWS_ROS) << "Missing '/' in yarp_base_name parameter"; - return false; - } - - m_rpcPortName = m_local_name + "/rpc"; - - if (config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!pLoc.open(p) || !pLoc.isValid()) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Failed to open subdevice.. check params"; - return false; - } - if (!attach(&pLoc)) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Failed to open subdevice.. check params"; - return false; - } - } - else - { - yCInfo(LOCALIZATION2D_NWS_ROS) << "Waiting for device to attach"; - } - m_stats_time_last = yarp::os::Time::now(); - - if (!initialize_YARP(config)) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Error initializing YARP ports"; - return false; - } - - if (!initialize_ROS(config)) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Error initializing ROS system"; - return false; - } - - return true; -} - -bool Localization2D_nws_ros::initialize_ROS(yarp::os::Searchable& params) -{ - if (params.check("parent_frame_id")) - { - m_parent_frame_id = params.find("parent_frame_id").asString(); - } - - if (params.check("child_frame_id")) - { - m_child_frame_id = params.find("child_frame_id").asString(); - } - - if (params.check("topic_name")) - { - m_odom_topic_name = params.find("topic_name").asString(); - } - - if (params.check("node_name")) - { - m_node_name = params.find("node_name").asString(); - } - m_odom_topic_name = m_odom_topic_name + "/odom"; - - if (m_node == nullptr) - { - bool b= false; - m_node = new yarp::os::Node(m_node_name); - if (m_node == nullptr) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Opening " << m_node_name << " Node, check your yarp-ROS network configuration"; - return false; - } - - b = m_odometry_publisher.topic(m_odom_topic_name); - if (!b) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Unable to publish data on" << m_odom_topic_name << "topic"; - return false; - } - b = m_tf_publisher.topic("/tf"); - if (!b) - { - yCError(LOCALIZATION2D_NWS_ROS) << "Unable to publish data on /tf topic"; - return false; - } - yCInfo(LOCALIZATION2D_NWS_ROS) << "ROS initialized"; - } - return true; -} - -bool Localization2D_nws_ros::initialize_YARP(yarp::os::Searchable ¶ms) -{ - if (!m_rpcPort.open(m_rpcPortName.c_str())) - { - yCError(LOCALIZATION2D_NWS_ROS, "Failed to open port %s", m_rpcPortName.c_str()); - return false; - } - m_rpcPort.setReader(*this); - - return true; -} - -bool Localization2D_nws_ros::close() -{ - yCTrace(LOCALIZATION2D_NWS_ROS, "Close"); - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - - detach(); - - m_rpcPort.interrupt(); - m_rpcPort.close(); - - if (m_node) - { - m_tf_publisher.close(); - m_odometry_publisher.close(); - delete m_node; - m_node = nullptr; - } - - yCDebug(LOCALIZATION2D_NWS_ROS) << "Execution terminated"; - return true; -} - -bool Localization2D_nws_ros::read(yarp::os::ConnectionReader& connection) -{ - yarp::os::Bottle command; - yarp::os::Bottle reply; - bool ok = command.read(connection); - if (!ok) { - return false; - } - - reply.clear(); - - if (command.get(0).isString() && command.get(0).asString() == "help") - { - reply.addVocab32("many"); - reply.addString("No commands currently available:"); - } - else - { - yCError(LOCALIZATION2D_NWS_ROS) << "Invalid command. Try `help`"; - reply.addVocab32(VOCAB_ERR); - } - - yarp::os::ConnectionWriter *returnToSender = connection.getWriter(); - if (returnToSender != nullptr) - { - reply.write(*returnToSender); - } - - return true; -} - -void Localization2D_nws_ros::run() -{ - double m_stats_time_curr = yarp::os::Time::now(); - if (m_stats_time_curr - m_stats_time_last > 5.0) - { - yCInfo(LOCALIZATION2D_NWS_ROS) << "Running"; - m_stats_time_last = yarp::os::Time::now(); - } - - bool ret = iLoc->getLocalizationStatus(m_current_status); - if (ret == false) - { - yCError(LOCALIZATION2D_NWS_ROS) << "getLocalizationStatus() failed"; - } - - if (m_current_status == LocalizationStatusEnum::localization_status_localized_ok) - { - bool ret2 = iLoc->getCurrentPosition(m_current_position); - if (ret2 == false) - { - yCError(LOCALIZATION2D_NWS_ROS) << "getCurrentPosition() failed"; - } - else - { - m_loc_stamp.update(); - } - bool ret3 = iLoc->getEstimatedOdometry(m_current_odometry); - if (ret3 == false) - { - //yCError(LOCALIZATION2D_NWS_ROS) << "getEstimatedOdometry() failed"; - } - else - { - m_odom_stamp.update(); - } - } - else - { - yCWarning(LOCALIZATION2D_NWS_ROS, "The system is not properly localized!"); - } - - if (m_enable_publish_odometry_topic) { - publish_odometry_on_ROS_topic(); - } - if (m_enable_publish_odometry_tf) { - publish_odometry_on_TF_topic(); - } -} - -void Localization2D_nws_ros::publish_odometry_on_TF_topic() -{ - yarp::rosmsg::tf2_msgs::TFMessage& rosData = m_tf_publisher.prepare(); - yarp::rosmsg::geometry_msgs::TransformStamped transform; - transform.child_frame_id = m_child_frame_id; - transform.header.frame_id = m_parent_frame_id; - transform.header.seq = m_odom_stamp.getCount(); - transform.header.stamp = m_odom_stamp.getTime(); - double halfYaw = m_current_odometry.odom_theta / 180.0 * M_PI * 0.5; - double cosYaw = cos(halfYaw); - double sinYaw = sin(halfYaw); - transform.transform.rotation.x = 0; - transform.transform.rotation.y = 0; - transform.transform.rotation.z = sinYaw; - transform.transform.rotation.w = cosYaw; - transform.transform.translation.x = m_current_odometry.odom_x; - transform.transform.translation.y = m_current_odometry.odom_y; - transform.transform.translation.z = 0; - if (rosData.transforms.size() == 0) - { - rosData.transforms.push_back(transform); - } - else - { - rosData.transforms[0] = transform; - } - - m_tf_publisher.write(); -} - -void Localization2D_nws_ros::publish_odometry_on_ROS_topic() -{ - if (m_node && m_odometry_publisher.asPort().getOutputCount() > 0) - { - yarp::rosmsg::nav_msgs::Odometry& odom = m_odometry_publisher.prepare(); - odom.clear(); - odom.header.frame_id = m_fixed_frame; - odom.header.seq = m_odom_stamp.getCount(); - odom.header.stamp = m_odom_stamp.getTime(); - odom.child_frame_id = m_robot_frame; - - odom.pose.pose.position.x = m_current_odometry.odom_x; - odom.pose.pose.position.y = m_current_odometry.odom_y; - odom.pose.pose.position.z = 0; - yarp::sig::Vector vecrpy(3); - vecrpy[0] = 0; - vecrpy[1] = 0; - vecrpy[2] = m_current_odometry.odom_theta; - yarp::sig::Matrix matrix = yarp::math::rpy2dcm(vecrpy); - yarp::math::Quaternion q; q.fromRotationMatrix(matrix); - odom.pose.pose.orientation.x = q.x(); - odom.pose.pose.orientation.y = q.y(); - odom.pose.pose.orientation.z = q.z(); - odom.pose.pose.orientation.w = q.w(); - //odom.pose.covariance = 0; - - odom.twist.twist.linear.x = m_current_odometry.base_vel_x; - odom.twist.twist.linear.y = m_current_odometry.base_vel_y; - odom.twist.twist.linear.z = 0; - odom.twist.twist.angular.x = 0; - odom.twist.twist.angular.y = 0; - odom.twist.twist.angular.z = m_current_odometry.base_vel_theta; - //odom.twist.covariance = 0; - - m_odometry_publisher.write(); - } -} diff --git a/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.h b/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.h deleted file mode 100644 index 8dd86cab65a..00000000000 --- a/src/devices/ROS/localization2D_nws_ros/Localization2D_nws_ros.h +++ /dev/null @@ -1,107 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#ifndef YARP_DEV_LOCALIZATION2D_NWS_ROS_H -#define YARP_DEV_LOCALIZATION2D_NWS_ROS_H - - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - /** - * @ingroup dev_impl_nws_ros dev_impl_navigation - * - * \section Localization2D_nws_ros - * - * \brief `localization2D_nws_ros`: A localization server which can be wrap multiple algorithms and devices to provide robot localization in a 2D World. - * - * - * Parameters required by this device are: - * | Parameter name | Type | Units | Default Value | Required | Description | Notes | - * |:----------------:|:-------:|:--------------:|:------------------------:|:-----------: |:-----------------------------------------------------------------: |:-----:| - * | period | double | s | 0.01 | No | The period of the working thread | | - * | yarp_base_name | string | - | | Yes | The name of the server, used as a prefix for the opened yarp ports | By default ports opened are: /xxx/rpc | - * | publish_odometry | bool | - | true | No | Periodically publish odometry data over the network | - | - * | publish_tf | bool | - | true | No | Periodically publish tf data over the network | - | - * | parent_frame_id | string | - | odom | No | The name of the of the parent frame published in the /tf topic | - | - * | child_frame_id | string | - | base_link | No | The name of the of the child frame published in the /tf topic | - | - * | topic_name | string | - | | Yes | The name of the of the odometry topic | - | - * | node_name | string | - | | Yes | The name of the of the ROS node | - | - * | subdevice | string | - | - | Yes | The name of the of Localization device to be used | - | - */ -class Localization2D_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::os::PeriodicThread, - public yarp::dev::WrapperSingle, - public yarp::os::PortReader -{ -protected: - - //yarp - std::string m_local_name = "/localization2D_nws_ros"; - yarp::os::Port m_rpcPort; - std::string m_rpcPortName; - std::string m_robot_frame; - std::string m_fixed_frame; - bool m_enable_publish_odometry_topic = true; - bool m_enable_publish_odometry_tf = true; - - //ROS - std::string m_child_frame_id = "base_link"; - std::string m_parent_frame_id = "odom"; - std::string m_node_name; - yarp::os::Node* m_node = nullptr; - std::string m_odom_topic_name; - yarp::os::Publisher m_odometry_publisher; - yarp::os::Publisher m_tf_publisher; - - //drivers and interfaces - yarp::dev::PolyDriver pLoc; - yarp::dev::Nav2D::ILocalization2D* iLoc = nullptr; - - double m_stats_time_last; - double m_period; - yarp::os::Stamp m_loc_stamp; - yarp::os::Stamp m_odom_stamp; - - yarp::dev::OdometryData m_current_odometry; - yarp::dev::Nav2D::Map2DLocation m_current_position; - yarp::dev::Nav2D::LocalizationStatusEnum m_current_status = yarp::dev::Nav2D::LocalizationStatusEnum::localization_status_not_yet_localized; - -private: - void publish_odometry_on_ROS_topic(); - void publish_odometry_on_TF_topic(); - -public: - Localization2D_nws_ros(); - -public: - bool open(yarp::os::Searchable& prop) override; - bool close() override; - bool detach() override; - bool attach(yarp::dev::PolyDriver* driver) override; - void run() override; - - bool initialize_YARP(yarp::os::Searchable &config); - bool initialize_ROS(yarp::os::Searchable& config); - bool read(yarp::os::ConnectionReader& connection) override; -}; - -#endif // YARP_DEV_LOCALIZATION2D_NWS_ROS diff --git a/src/devices/ROS/map2D_nws_ros/CMakeLists.txt b/src/devices/ROS/map2D_nws_ros/CMakeLists.txt deleted file mode 100644 index aae2db78c7b..00000000000 --- a/src/devices/ROS/map2D_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,51 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(map2D_nws_ros - CATEGORY device - TYPE Map2D_nws_ros - INCLUDE Map2D_nws_ros.h - DEPENDS "TARGET YARP::YARP_math" - EXTRA_CONFIG - WRAPPER=map2D_nws_ros - DEFAULT ON -) - -if(NOT SKIP_map2D_nws_ros) - yarp_add_plugin(yarp_map2D_nws_ros) - - target_sources(yarp_map2D_nws_ros - PRIVATE - Map2D_nws_ros.cpp - Map2D_nws_ros.h - ) - - target_link_libraries(yarp_map2D_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_map2D_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_map2D_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.cpp b/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.cpp deleted file mode 100644 index 77174478aa0..00000000000 --- a/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.cpp +++ /dev/null @@ -1,422 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#include "Map2D_nws_ros.h" - -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include -#include - -#include -#include -#include -#include -#include - -using namespace yarp::sig; -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; -using namespace yarp::os; - -namespace { -YARP_LOG_COMPONENT(MAP2D_NWS_ROS, "yarp.device.map2D_nws_ros") -} - -#ifndef M_PI -#define M_PI 3.14159265358979323846 -#endif - -#define RAD2DEG 180/M_PI -#define DEG2RAD M_PI/180 - -/** - * Map2D_nws_ros - */ - -Map2D_nws_ros::Map2D_nws_ros() -{ - m_enable_publish_map = false; - m_enable_subscribe_map = false; - m_node = nullptr; -} - -Map2D_nws_ros::~Map2D_nws_ros() = default; - -bool Map2D_nws_ros::read(yarp::os::ConnectionReader& connection) -{ - yarp::os::Bottle command; - yarp::os::Bottle reply; - bool ok = command.read(connection); - if (!ok) { - return false; - } - - reply.clear(); - - if (command.get(0).isString() && command.get(0).asString() == "help") - { - reply.addVocab32("many"); - reply.addString("No commands currently available:"); - } - else - { - yCError(MAP2D_NWS_ROS) << "Invalid command. Try `help`"; - reply.addVocab32(VOCAB_ERR); - } - - yarp::os::ConnectionWriter* returnToSender = connection.getWriter(); - if (returnToSender != nullptr) - { - reply.write(*returnToSender); - } - - return true; -} - -bool Map2D_nws_ros::open(yarp::os::Searchable &config) -{ - Property params; - params.fromString(config.toString()); - - if (!config.check("name")) - { - m_rpcPortName = "/map2D_nws_ros/rpc"; - } - else - { - m_rpcPortName = config.find("name").asString(); - } - - //subdevice handling - if (config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!m_drv.open(p) || !m_drv.isValid()) - { - yCError(MAP2D_NWS_ROS) << "Failed to open subdevice.. check params"; - return false; - } - - if (!attach(&m_drv)) - { - yCError(MAP2D_NWS_ROS) << "Failed to open subdevice.. check params"; - return false; - } - } - else - { - yCInfo(MAP2D_NWS_ROS) << "Waiting for device to attach"; - } - - //open rpc port - if (!m_rpcPort.open(m_rpcPortName)) - { - yCError(MAP2D_NWS_ROS, "Failed to open port %s", m_rpcPortName.c_str()); - return false; - } - m_rpcPort.setReader(*this); - - //ROS configuration - if (config.check("ROS")) - { - yCInfo(MAP2D_NWS_ROS, "Configuring ROS params"); - Bottle ROS_config = config.findGroup("ROS"); - - if (ROS_config.find("enable_publisher").asInt32() == 1 || ROS_config.find("enable_publisher").asString() == "true") - { - m_enable_publish_map = true; - yCInfo(MAP2D_NWS_ROS) << "Enabled ROS publisher"; - } - - if (ROS_config.find("enable_subscriber").asInt32() == 1 || ROS_config.find("enable_subscriber").asString() == "true") - { - m_enable_subscribe_map = true; - yCInfo(MAP2D_NWS_ROS) << "Enabled ROS subscriber"; - } - - if (m_enable_publish_map) - { - if (m_node == nullptr) - { - m_node = new yarp::os::Node(ROSNODENAME); - } - if (!m_publisherPort_map.topic(ROSTOPICNAME_MAP)) - { - yCError(MAP2D_NWS_ROS) << "Unable to publish to" << ROSTOPICNAME_MAP << "topic, check your YARP-ROS network configuration"; - return false; - } - if (!m_publisherPort_metamap.topic(ROSTOPICNAME_MAPMETADATA)) - { - yCError(MAP2D_NWS_ROS) << "Unable to publish to " << ROSTOPICNAME_MAPMETADATA << " topic, check your YARP-ROS network configuration"; - return false; - } - //should I publish the map now? with which name ? - //publishMapToRos(); - } - - if (m_enable_subscribe_map) - { - if (!m_subscriberPort_map.topic(ROSTOPICNAME_MAP)) - { - yCError(MAP2D_NWS_ROS) << "Unable to subscribe to " << ROSTOPICNAME_MAP << " topic, check your YARP-ROS network configuration"; - return false; - } - if (!m_subscriberPort_metamap.topic(ROSTOPICNAME_MAPMETADATA)) - { - yCError(MAP2D_NWS_ROS) << "Unable to subscribe to " << ROSTOPICNAME_MAPMETADATA << " topic, check your YARP-ROS network configuration"; - return false; - } - m_subscriberPort_map.setStrict(); - m_subscriberPort_metamap.setStrict(); - - //should I subscribe the map now ? with which name ? - //subscribeMapFromRos(); - } - } - else - { - //no ROS options - yCWarning(MAP2D_NWS_ROS) << "ROS Group not configured"; - } - - return true; -} - -bool Map2D_nws_ros::publishMapToRos(std::string map_name) -{ - MapGrid2D current_map; - if (!m_iMap2D->get_map(map_name, current_map)) - { - yCError(MAP2D_NWS_ROS) << "publishMapToRos() " << map_name << " does not exists"; - return false; - } - - double tmp = 0; - yarp::rosmsg::nav_msgs::OccupancyGrid& ogrid = m_publisherPort_map.prepare(); - ogrid.clear(); - ogrid.info.height = current_map.height(); - ogrid.info.width = current_map.width(); - current_map.getResolution(tmp); - ogrid.info.resolution = tmp; - ogrid.header.frame_id = "map"; - ogrid.info.map_load_time.sec = 0; - ogrid.info.map_load_time.nsec = 0; - double x, y, t; - current_map.getOrigin(x, y, t); - ogrid.info.origin.position.x = x; - ogrid.info.origin.position.y = y; - yarp::math::Quaternion q; - yarp::sig::Vector v(4); - v[0] = 0; v[1] = 0; v[2] = 1; v[3] = t * DEG2RAD; - q.fromAxisAngle(v); - ogrid.info.origin.orientation.x = q.x(); - ogrid.info.origin.orientation.y = q.y(); - ogrid.info.origin.orientation.z = q.z(); - ogrid.info.origin.orientation.w = q.w(); - ogrid.data.resize(current_map.width() * current_map.height()); - int index = 0; - yarp::dev::Nav2D::XYCell cell; - for (cell.y = current_map.height(); cell.y-- > 0;) { - for (cell.x = 0; cell.x < current_map.width(); cell.x++) - { - current_map.getOccupancyData(cell, tmp); - ogrid.data[index++] = (int)tmp; - } - } - - m_publisherPort_map.write(); - - //what about the m_publisherPort_metamap ? - //I don't know... - - return true; -} - -bool Map2D_nws_ros::subscribeMapFromRos(std::string map_name) -{ - //In this block receives data from a ROS topic and stores data on attached device - //yarp::os::Time::delay(5); - yarp::rosmsg::nav_msgs::OccupancyGrid* map_ros = nullptr; - yarp::rosmsg::nav_msgs::MapMetaData* metamap_ros = nullptr; - - map_ros = m_subscriberPort_map.read(true); - metamap_ros = m_subscriberPort_metamap.read(true); - if (map_ros != nullptr && metamap_ros != nullptr) - { - yCInfo(MAP2D_NWS_ROS) << "Received map for ROS"; - std::string map_name = "ros_map"; - MapGrid2D map; - map.setSize_in_cells(map_ros->info.width,map_ros->info.height); - map.setResolution(map_ros->info.resolution); - map.setMapName(map_name); - yarp::math::Quaternion quat(map_ros->info.origin.orientation.x, - map_ros->info.origin.orientation.y, - map_ros->info.origin.orientation.z, - map_ros->info.origin.orientation.w); - yarp::sig::Matrix mat = quat.toRotationMatrix4x4(); - yarp::sig::Vector vec = yarp::math::dcm2rpy(mat); - double orig_angle = vec[2]; - map.setOrigin(map_ros->info.origin.position.x,map_ros->info.origin.position.y,orig_angle); - for (size_t y = 0; y < map_ros->info.height; y++) - { - for (size_t x = 0; x < map_ros->info.width; x++) - { - XYCell cell(x,map_ros->info.height - 1 - y); - double occ = map_ros->data[x + y * map_ros->info.width]; - map.setOccupancyData(cell,occ); - - if (occ >= 0 && occ <= 70) { - map.setMapFlag(cell, MapGrid2D::MAP_CELL_FREE); - } else if (occ >= 71 && occ <= 100) { - map.setMapFlag(cell, MapGrid2D::MAP_CELL_WALL); - } else { - map.setMapFlag(cell, MapGrid2D::MAP_CELL_UNKNOWN); - } - } - } - if (m_iMap2D->store_map(map)) - { - yCInfo(MAP2D_NWS_ROS) << "Added map " << map.getMapName() << " to storage"; - return true; - } - - yCInfo(MAP2D_NWS_ROS) << "Unable to add map " << map.getMapName() << " to storage"; - return false; - } - - return false; -} - -bool Map2D_nws_ros::close() -{ - yCTrace(MAP2D_NWS_ROS, "Close"); - if (m_enable_publish_map) - { - m_publisherPort_map.interrupt(); - m_publisherPort_metamap.interrupt(); - m_publisherPort_map.close(); - m_publisherPort_metamap.close(); - } - if (m_enable_subscribe_map) - { - m_subscriberPort_map.interrupt(); - m_subscriberPort_metamap.interrupt(); - m_subscriberPort_map.close(); - m_subscriberPort_metamap.close(); - } - return true; -} - -bool Map2D_nws_ros::updateVizMarkers(std::string map_name) -{ - if (m_publisherPort_markers.asPort().isOpen()==false) - { - m_publisherPort_markers.topic("/locationServerMarkers"); - } - yarp::rosmsg::TickDuration dur; dur.sec = 0xFFFFFFFF; - double yarpTimeStamp = yarp::os::Time::now(); - uint64_t time; - uint64_t nsec_part; - uint64_t sec_part; - yarp::rosmsg::TickTime ret; - time = (uint64_t)(yarpTimeStamp * 1000000000UL); - nsec_part = (time % 1000000000UL); - sec_part = (time / 1000000000UL); - if (sec_part > std::numeric_limits::max()) - { - yCWarning(MAP2D_NWS_ROS) << "Timestamp exceeded the 64 bit representation, resetting it to 0"; - sec_part = 0; - } - - yarp::rosmsg::visualization_msgs::Marker marker; - yarp::rosmsg::TickTime tt; - yarp::sig::Vector rpy(3); - yarp::math::Quaternion q; - - yarp::rosmsg::visualization_msgs::MarkerArray& markers = m_publisherPort_markers.prepare(); - markers.markers.clear(); - - std::vector locations; - int count = 1; - m_iMap2D->getLocationsList(locations); - for (auto it : locations) - { - yarp::dev::Nav2D::Map2DLocation loc; - m_iMap2D->getLocation(it, loc); - rpy[0] = 0; //x - rpy[1] = 0; //y - rpy[2] = loc.theta / 180 * 3.14159265359; //z - yarp::sig::Matrix m = yarp::math::rpy2dcm(rpy); - q.fromRotationMatrix(m); - - marker.header.frame_id = "map"; - tt.sec = (yarp::os::NetUint32) sec_part;; - tt.nsec = (yarp::os::NetUint32) nsec_part;; - marker.header.stamp = tt; - marker.ns = "my_namespace"; - marker.id = count; - marker.type = yarp::rosmsg::visualization_msgs::Marker::ARROW; - marker.action = yarp::rosmsg::visualization_msgs::Marker::ADD; - marker.pose.position.x = loc.x; - marker.pose.position.y = loc.y; - marker.pose.position.z = 0; - marker.pose.orientation.x = q.x(); - marker.pose.orientation.y = q.y(); - marker.pose.orientation.z = q.z(); - marker.pose.orientation.w = q.w(); - marker.scale.x = 1; - marker.scale.y = 0.1; - marker.scale.z = 0.1; - marker.color.a = 1.0; - marker.color.r = 0.0; - marker.color.g = 1.0; - marker.color.b = 0.0; - marker.lifetime = dur; - marker.text = it; - markers.markers.push_back(marker); - count++; - } - - m_publisherPort_markers.write(); - return true; -} - - -bool Map2D_nws_ros::detach() -{ - m_iMap2D = nullptr; - return true; -} - -bool Map2D_nws_ros::attach(PolyDriver* driver) -{ - if (driver->isValid()) - { - driver->view(m_iMap2D); - } - - if (nullptr == m_iMap2D) - { - yCError(MAP2D_NWS_ROS, "Subdevice passed to attach method is invalid"); - return false; - } - - return true; -} diff --git a/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h b/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h deleted file mode 100644 index 83867faddd8..00000000000 --- a/src/devices/ROS/map2D_nws_ros/Map2D_nws_ros.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#ifndef YARP_DEV_MAP2D_NWS_ROS_H -#define YARP_DEV_MAP2D_NWS_ROS_H - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/** - * @ingroup dev_impl_nws_ros dev_impl_navigation - * - * \section Map2D_nws_ros - * - * \brief `map2D_nws_ros`: A device capable of read/save collections of maps from disk, and make them accessible to any Map2DClient device. - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:----------------------:|:-------:|:--------------:|:----------------:|:-----------: |:-----------------------------------------------------------------:|:-----:| - * | name | - | string | - | /map2D_nws_ros/rpc | No | Full name of the rpc port opened by the Map2DServer device. | | - * | ROS | enable_publisher | bool | - | false | No | Publishes maps stored in a map2DStorage on a ROS topic | | - * | ROS | enable_subscriber | bool | - | false | No | Receives maps from a ROS topic and stores them in a map2DStorage | | - - * \section Notes: - * Integration with ROS map server is currently under development. - */ - -class Map2D_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::os::PortReader, - public yarp::dev::WrapperSingle -{ -public: - Map2D_nws_ros(); - ~Map2D_nws_ros(); - bool open(yarp::os::Searchable ¶ms) override; - bool close() override; - bool detach() override; - bool attach(yarp::dev::PolyDriver* driver) override; - -private: - //drivers and interfaces - yarp::dev::Nav2D::IMap2D* m_iMap2D = nullptr; - yarp::dev::PolyDriver m_drv; - - std::mutex m_mutex; - std::string m_rpcPortName; - yarp::os::Node* m_node = nullptr; - bool m_enable_publish_map; - bool m_enable_subscribe_map; - - #define ROSNODENAME "/map2DServerNode" - #define ROSTOPICNAME_MAP "/map" - #define ROSTOPICNAME_MAPMETADATA "/map_metadata" - - yarp::os::RpcServer m_rpcPort; - yarp::os::Publisher m_publisherPort_map; - yarp::os::Publisher m_publisherPort_metamap; - yarp::os::Subscriber m_subscriberPort_map; - yarp::os::Subscriber m_subscriberPort_metamap; - yarp::os::Publisher m_publisherPort_markers; - - bool read(yarp::os::ConnectionReader& connection) override; - - bool updateVizMarkers(std::string map_name = "ros_map"); - bool subscribeMapFromRos(std::string map_name = "ros_map"); - bool publishMapToRos(std::string map_name = "ros_map"); -}; - -#endif // YARP_DEV_MAP2D_NWS_ROS_H diff --git a/src/devices/ROS/mobileBaseVelocityControl_nws_ros/CMakeLists.txt b/src/devices/ROS/mobileBaseVelocityControl_nws_ros/CMakeLists.txt deleted file mode 100644 index 47f9d2b3dc5..00000000000 --- a/src/devices/ROS/mobileBaseVelocityControl_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,49 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(mobileBaseVelocityControl_nws_ros - CATEGORY device - TYPE MobileBaseVelocityControl_nws_ros - INCLUDE MobileBaseVelocityControl_nws_ros.h - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(NOT SKIP_mobileBaseVelocityControl_nws_ros) - yarp_add_plugin(yarp_mobileBaseVelocityControl_nws_ros) - - target_sources(yarp_mobileBaseVelocityControl_nws_ros - PRIVATE - MobileBaseVelocityControl_nws_ros.cpp - MobileBaseVelocityControl_nws_ros.h - ) - - target_link_libraries(yarp_mobileBaseVelocityControl_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_mobileBaseVelocityControl_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_mobileBaseVelocityControl_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp b/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp deleted file mode 100644 index 8207e757a5f..00000000000 --- a/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.cpp +++ /dev/null @@ -1,147 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#define _USE_MATH_DEFINES -#include - -#include "MobileBaseVelocityControl_nws_ros.h" -#include -#include -#include -#include -#include - -/*! \file MobileBaseVelocityControl_nws_ros.cpp */ - -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; -using namespace yarp::os; -using namespace yarp::sig; - -namespace { - YARP_LOG_COMPONENT(MOBVEL_NWS_ROS, "yarp.device.MobileBaseVelocityControl_nws_ros") -} - -//------------------------------------------------------------------------------------------------------------------------------ - -void commandSubscriber::init(yarp::dev::Nav2D::INavigation2DVelocityActions* _iNavVel) -{ - m_iNavVel = _iNavVel; -} - -void commandSubscriber::deinit() -{ - m_iNavVel = nullptr; -} - -commandSubscriber::commandSubscriber() -{ -} - -commandSubscriber::~commandSubscriber() -{ - this->close(); -} - -void commandSubscriber::onRead(yarp::rosmsg::geometry_msgs::Twist& v) -{ - if (m_iNavVel) - { - m_iNavVel->applyVelocityCommand(v.linear.x, v.linear.y, v.angular.z * 180 / M_PI); - } - else - { - yCError(MOBVEL_NWS_ROS, "Subdevice interface not yet initialized"); - } -} - -//------------------------------------------------------------------------------------------------------------------------------ - -bool MobileBaseVelocityControl_nws_ros::open(yarp::os::Searchable& config) -{ - if (config.check("node_name") == true) - { - m_ros_node_name = config.find("node_name").asString(); - } - - if (config.check("topic_name") == true) - { - m_ros_topic_name = config.find("topic_name").asString(); - } - - //attach subdevice if required - if (config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!m_subdev.open(p) || !m_subdev.isValid()) - { - yCError(MOBVEL_NWS_ROS) << "Failed to open subdevice.. check params"; - return false; - } - - if (!attach(&m_subdev)) - { - yCError(MOBVEL_NWS_ROS) << "Failed to attach subdevice.. check params"; - return false; - } - } - else - { - yCInfo(MOBVEL_NWS_ROS) << "Waiting for device to attach"; - } - - //open the subscriber - m_ros_node = new yarp::os::Node(m_ros_node_name); - m_command_subscriber = new commandSubscriber(); - - if (!m_command_subscriber->topic(m_ros_topic_name)) - { - yCError(MOBVEL_NWS_ROS) << " opening " << m_ros_topic_name << " Topic, check your yarp-ROS network configuration\n"; - return false; - } - - //m_command_subscriber->setStrict(); - m_command_subscriber->useCallback(); - - return true; -} - -bool MobileBaseVelocityControl_nws_ros::close() -{ - if (m_command_subscriber) {delete m_command_subscriber;} - if (m_ros_node) {delete m_ros_node;} - if (m_subdev.isValid()) { m_subdev.close(); } - return true; -} - - -bool MobileBaseVelocityControl_nws_ros::detach() -{ - m_command_subscriber->deinit(); - return true; -} - -bool MobileBaseVelocityControl_nws_ros::attach(PolyDriver* driver) -{ - yarp::dev::Nav2D::INavigation2DVelocityActions* iNavVel=nullptr; - - if (driver->isValid()) - { - driver->view(iNavVel); - } - - if (nullptr == iNavVel) - { - yCError(MOBVEL_NWS_ROS, "Subdevice passed to attach method is invalid"); - return false; - } - - m_command_subscriber->init(iNavVel); - - return true; -} diff --git a/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h b/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h deleted file mode 100644 index 36155a380d3..00000000000 --- a/src/devices/ROS/mobileBaseVelocityControl_nws_ros/MobileBaseVelocityControl_nws_ros.h +++ /dev/null @@ -1,80 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#ifndef YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS -#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -class commandSubscriber : - public yarp::os::Subscriber -{ - public: - void init(yarp::dev::Nav2D::INavigation2DVelocityActions* m_iNavVel); - void deinit(); - - ~commandSubscriber (); - commandSubscriber (); - yarp::dev::Nav2D::INavigation2DVelocityActions* m_iNavVel = nullptr; - - using yarp::os::Subscriber::onRead; - virtual void onRead (yarp::rosmsg::geometry_msgs::Twist& v) override; -}; - -/** - * @ingroup dev_impl_nws_ros dev_impl_navigation - * - * \section MobileBaseVelocityControl_nws_ros - * - * \brief `MobileBaseVelocityControl_nws_ros`: A device which allows a client application to control the velocity of a mobile base from ROS. - * The device opens a topic of type `yarp::rosmsg::geometry_msgs::Twist` to receive user commands - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:------------------------------:|:------------:|:-----------------------------------------------------------------:|:-----:| - * | node_name | - | string | - | /mobileBase_VelControl_nws_ros | No | Full name of the opened ROS node | | - * | topic_name | - | string | - | /velocity_input | No | Full name of the opened ROS topic | | - * | subdevice | - | string | - | - | No | name of the subdevice to instantiate | when used, parameters for the subdevice must be provided as well | - */ - -class MobileBaseVelocityControl_nws_ros : - public yarp::dev::DeviceDriver, - public yarp::dev::WrapperSingle -{ -protected: - std::string m_ros_node_name = "/mobileBase_VelControl_nws_ros"; - std::string m_ros_topic_name = "/velocity_input"; - yarp::os::Node* m_ros_node = nullptr; - commandSubscriber* m_command_subscriber = nullptr; - - yarp::dev::PolyDriver m_subdev; - -public: - virtual ~MobileBaseVelocityControl_nws_ros () {}; - MobileBaseVelocityControl_nws_ros() {}; - - /* DeviceDriver methods */ - bool open(yarp::os::Searchable& config) override; - bool close() override; - -private: - bool detach() override; - bool attach(yarp::dev::PolyDriver* driver) override; -}; - -#endif // YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/CMakeLists.txt b/src/devices/ROS/multipleAnalogSensorsRosPublishers/CMakeLists.txt deleted file mode 100644 index 46ceb681d83..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/CMakeLists.txt +++ /dev/null @@ -1,258 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(IMURosPublisher - CATEGORY device - TYPE IMURosPublisher - INCLUDE IMURosPublisher.h - EXTRA_CONFIG - WRAPPER=IMURosPublisher - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(ENABLE_IMURosPublisher) - yarp_add_plugin(yarp_IMURosPublisher) - - target_sources(yarp_IMURosPublisher - PRIVATE - IMURosPublisher.cpp - IMURosPublisher.h - GenericSensorRosPublisher.h - ) - - target_link_libraries(yarp_IMURosPublisher - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install(TARGETS yarp_IMURosPublisher - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_IMURosPublisher PROPERTY FOLDER "Plugins/Device") -endif() - - - -yarp_prepare_plugin(WrenchStampedRosPublisher - CATEGORY device - TYPE WrenchStampedRosPublisher - INCLUDE WrenchStampedRosPublisher.h - EXTRA_CONFIG - WRAPPER=WrenchStampedRosPublisher - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(ENABLE_WrenchStampedRosPublisher) - yarp_add_plugin(yarp_WrenchStampedRosPublisher) - - target_sources(yarp_WrenchStampedRosPublisher - PRIVATE - WrenchStampedRosPublisher.cpp - WrenchStampedRosPublisher.h - GenericSensorRosPublisher.h - ) - - target_link_libraries(yarp_WrenchStampedRosPublisher - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_WrenchStampedRosPublisher - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_WrenchStampedRosPublisher PROPERTY FOLDER "Plugins/Device") -endif() - - - -yarp_prepare_plugin(TemperatureRosPublisher - CATEGORY device - TYPE TemperatureRosPublisher - INCLUDE TemperatureRosPublisher.h - EXTRA_CONFIG - WRAPPER=TemperatureRosPublisher - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(ENABLE_TemperatureRosPublisher) - yarp_add_plugin(yarp_TemperatureRosPublisher) - - target_sources(yarp_TemperatureRosPublisher - PRIVATE - TemperatureRosPublisher.cpp - TemperatureRosPublisher.h - GenericSensorRosPublisher.h - ) - - target_link_libraries(yarp_TemperatureRosPublisher - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_TemperatureRosPublisher - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_TemperatureRosPublisher PROPERTY FOLDER "Plugins/Device") -endif() - - - -yarp_prepare_plugin(PoseStampedRosPublisher - CATEGORY device - TYPE PoseStampedRosPublisher - INCLUDE PoseStampedRosPublisher.h - EXTRA_CONFIG - WRAPPER=PoseStampedRosPublisher - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(ENABLE_PoseStampedRosPublisher) - yarp_add_plugin(yarp_PoseStampedRosPublisher) - - target_sources(yarp_PoseStampedRosPublisher - PRIVATE - PoseStampedRosPublisher.cpp - PoseStampedRosPublisher.h - GenericSensorRosPublisher.h - ) - - target_link_libraries(yarp_PoseStampedRosPublisher - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_math - YARP::YARP_rosmsg - ) - - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_math - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_PoseStampedRosPublisher - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_PoseStampedRosPublisher PROPERTY FOLDER "Plugins/Device") -endif() - - - -yarp_prepare_plugin(MagneticFieldRosPublisher - CATEGORY device - TYPE MagneticFieldRosPublisher - INCLUDE MagneticFieldRosPublisher.h - EXTRA_CONFIG - WRAPPER=MagneticFieldRosPublisher - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(ENABLE_MagneticFieldRosPublisher) - yarp_add_plugin(yarp_MagneticFieldRosPublisher) - - target_sources(yarp_MagneticFieldRosPublisher - PRIVATE - MagneticFieldRosPublisher.cpp - MagneticFieldRosPublisher.h - GenericSensorRosPublisher.h - ) - - target_link_libraries(yarp_MagneticFieldRosPublisher - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_MagneticFieldRosPublisher - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_MagneticFieldRosPublisher PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h deleted file mode 100644 index 7cf338d59ce..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/GenericSensorRosPublisher.h +++ /dev/null @@ -1,251 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#ifndef YARP_DEV_GENERICSENSORSROSPUBLISHER_H -#define YARP_DEV_GENERICSENSORSROSPUBLISHER_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -// The log component is defined in each device, with a specialized name -YARP_DECLARE_LOG_COMPONENT(GENERICSENSORROSPUBLISHER) - - -/** - * @ingroup dev_impl_wrapper - * - * \brief This abstract template needs to be specialized in a ROS Publisher, for a specific ROS mesagge/sensor type. - * - * | YARP device name | - * |:-----------------:| - * | `GenericSensorRosPublisher` | - * - * The parameters accepted by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | topic | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character | - * | node_name | - | string | - | $topic + "_node" | No | The name of the ROS node opened by this device | Autogenerated by default | - * | period | - | double | s | - | Yes | Refresh period of the broadcasted values in seconds | | - */ - -template -class GenericSensorRosPublisher : - public yarp::os::PeriodicThread, - public yarp::dev::DeviceDriver, - public yarp::dev::IMultipleWrapper -{ -protected: - double m_periodInS{0.01}; - std::string m_publisherName; - std::string m_rosNodeName; - yarp::os::Node* m_rosNode; - yarp::os::Publisher m_publisher; - yarp::dev::PolyDriver* m_poly; - size_t m_msg_counter; - double m_timestamp; - std::string m_framename; - const size_t m_sens_index = 0; - yarp::dev::PolyDriver m_subdevicedriver; - -public: - GenericSensorRosPublisher(); - virtual ~GenericSensorRosPublisher(); - - /* DevideDriver methods */ - bool open(yarp::os::Searchable ¶ms) override; - bool close() override; - - /* IMultipleWrapper methods */ - bool attachAll(const yarp::dev::PolyDriverList &p) override; - bool detachAll() override; - - /* PeriodicRateThread methods */ - void threadRelease() override; - void run() override; - -protected: - virtual bool viewInterfaces() = 0; -}; - -template -GenericSensorRosPublisher::GenericSensorRosPublisher() : - PeriodicThread(0.02) -{ - m_rosNode = nullptr; - m_poly = nullptr; - m_msg_counter=0; - m_timestamp=0; -} - -template -GenericSensorRosPublisher::~GenericSensorRosPublisher() = default; - -template -bool GenericSensorRosPublisher::open(yarp::os::Searchable & config) -{ - if (!config.check("topic")) { - yCError(GENERICSENSORROSPUBLISHER, "Missing `topic` parameter, exiting."); - return false; - } - - if (!config.check("period")) { - yCError(GENERICSENSORROSPUBLISHER, "Missing `period` parameter, exiting."); - return false; - } - - if (config.find("period").isFloat32()==false && config.find("period").isFloat64()==false) { - yCError(GENERICSENSORROSPUBLISHER, "`period` parameter is present but it is not a float, exiting."); - return false; - } - - m_periodInS = config.find("period").asFloat64(); - - if (m_periodInS <= 0) { - yCError(GENERICSENSORROSPUBLISHER, "`period` parameter is present (%f) but it is not a positive value, exiting.", m_periodInS); - return false; - } - - std::string name = config.find("topic").asString(); - - // TODO(traversaro) Add port name validation when ready, - // see https://github.com/robotology/yarp/pull/1508 - - m_rosNodeName = name+ "_node"; - m_publisherName = name; - - if (config.check("node_name")) - { - m_rosNodeName = config.find("node_name").asString(); - } - - if (m_rosNodeName == "") - { - yCError(GENERICSENSORROSPUBLISHER) << "Invalid node name: " << m_rosNodeName; - return false; - } - - m_rosNode = new yarp::os::Node(m_rosNodeName); // add a ROS node - - if (m_rosNode == nullptr) { - yCError(GENERICSENSORROSPUBLISHER) << "Opening " << m_rosNodeName << " Node, check your yarp-ROS network configuration\n"; - return false; - } - - if (!m_publisher.topic(m_publisherName)) { - yCError(GENERICSENSORROSPUBLISHER) << "Opening " << m_publisherName << " Topic, check your yarp-ROS network configuration\n"; - return false; - } - - if (config.check("subdevice")) - { - yarp::os::Property p; - yarp::dev::PolyDriverList driverlist; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!m_subdevicedriver.open(p) || !m_subdevicedriver.isValid()) - { - yCError(GENERICSENSORROSPUBLISHER) << "Failed to open subdevice.. check params"; - return false; - } - - driverlist.push(&m_subdevicedriver, "1"); - if (!attachAll(driverlist)) - { - yCError(GENERICSENSORROSPUBLISHER) << "Failed to open subdevice.. check params"; - return false; - } - } - - return true; -} - -template -bool GenericSensorRosPublisher::close() -{ - return this->detachAll(); - - m_publisher.close(); - if (m_rosNode) - { - delete m_rosNode; - m_rosNode = nullptr; - } -} - -template -bool GenericSensorRosPublisher::attachAll(const yarp::dev::PolyDriverList & p) -{ - // Attach the device - if (p.size() > 1) - { - yCError(GENERICSENSORROSPUBLISHER, "This device only supports exposing a " - "single MultipleAnalogSensors device on YARP ports, but %d devices have been passed in attachAll.", - p.size()); - yCError(GENERICSENSORROSPUBLISHER, "Please use the multipleanalogsensorsremapper device to combine several device in a new device."); - detachAll(); - return false; - } - - if (p.size() == 0) - { - yCError(GENERICSENSORROSPUBLISHER, "No device passed to attachAll, please pass a device to expose on YARP ports."); - return false; - } - - m_poly = p[0]->poly; - - if (!m_poly) - { - yCError(GENERICSENSORROSPUBLISHER, "Null pointer passed to attachAll."); - return false; - } - - // View all the interfaces - bool ok = viewInterfaces(); - if (!ok) - { - yCError(GENERICSENSORROSPUBLISHER, "viewInterfaces() method failed."); - return false; - } - - // Set rate period - ok &= this->setPeriod(m_periodInS); - ok &= this->start(); - - return ok; -} - -template -bool GenericSensorRosPublisher::detachAll() -{ - // Stop the thread on detach - if (this->isRunning()) { - this->stop(); - } - return true; -} - -template -void GenericSensorRosPublisher::run() -{ -} - -template -void GenericSensorRosPublisher::threadRelease() -{ - return; -} - -#endif diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp deleted file mode 100644 index f4e1e684fa9..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.cpp +++ /dev/null @@ -1,79 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "IMURosPublisher.h" -#include "Yarp/math/Quaternion.h" -#include "Yarp/math/Math.h" - -#ifndef M_PI -#define M_PI (3.14159265358979323846) -#endif - -YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.IMURosPublisher") - -bool IMURosPublisher::viewInterfaces() -{ - // View all the interfaces - bool ok = true; - ok = m_poly->view(m_iThreeAxisGyroscopes); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisGyroscopes interface is not available"; - return false; - } - ok = m_poly->view(m_iThreeAxisLinearAccelerometers); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisLinearAccelerometers interface is not available"; - return false; - } - ok = m_poly->view(m_iThreeAxisMagnetometers); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisMagnetometers interface is not available"; - return false; - } - ok = m_poly->view(m_iOrientationSensors); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IOrientationSensors interface is not available"; - return false; - } - - ok = m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename); - return ok; -} - -void IMURosPublisher::run() -{ - if (m_publisher.asPort().isOpen()) - { - yarp::sig::Vector vecgyr(3); - yarp::sig::Vector vecacc(3); - yarp::sig::Vector vecrpy(3); - yarp::rosmsg::sensor_msgs::Imu& imu_ros_data = m_publisher.prepare(); - m_iThreeAxisGyroscopes->getThreeAxisGyroscopeMeasure(m_sens_index, vecgyr, m_timestamp); - m_iThreeAxisLinearAccelerometers->getThreeAxisLinearAccelerometerMeasure(m_sens_index, vecacc, m_timestamp); - m_iOrientationSensors->getOrientationSensorMeasureAsRollPitchYaw(m_sens_index, vecrpy, m_timestamp); - imu_ros_data.clear(); - imu_ros_data.header.frame_id = m_framename; - imu_ros_data.header.seq = m_msg_counter++; - imu_ros_data.header.stamp = m_timestamp; - imu_ros_data.angular_velocity.x = vecgyr[0] * M_PI / 180.0; - imu_ros_data.angular_velocity.y = vecgyr[1] * M_PI / 180.0; - imu_ros_data.angular_velocity.z = vecgyr[2] * M_PI / 180.0; - imu_ros_data.linear_acceleration.x = vecacc[0]; - imu_ros_data.linear_acceleration.y = vecacc[1]; - imu_ros_data.linear_acceleration.z = vecacc[2]; - vecrpy[0] = vecrpy[0] * M_PI / 180.0; - vecrpy[1] = vecrpy[1] * M_PI / 180.0; - vecrpy[2] = vecrpy[2] * M_PI / 180.0; - yarp::sig::Matrix matrix = yarp::math::rpy2dcm(vecrpy); - yarp::math::Quaternion q; q.fromRotationMatrix(matrix); - imu_ros_data.orientation.x = q.x(); - imu_ros_data.orientation.y = q.y(); - imu_ros_data.orientation.z = q.z(); - imu_ros_data.orientation.w = q.w(); - - //imu_ros_data.orientation_covariance = 0; - m_publisher.write(); - } - } diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.h deleted file mode 100644 index 6bf3aa77580..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/IMURosPublisher.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#ifndef YARP_DEV_IMUROSPUBLISHER_H -#define YARP_DEV_IMUROSPUBLISHER_H - -#include "GenericSensorRosPublisher.h" - - // Thrift-generated classes -#include - - /** - * @ingroup dev_impl_wrapper - * - * \brief `IMURosPublisher`: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu. - * - * | YARP device name | - * |:-----------------:| - * | `IMURosPublisher` | - * - * The parameters accepted by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | topic | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character | - * | node_name | - | string | - | $topic + "_node" | No | The name of the ROS node opened by this device | Autogenerated by default | - * | period | - | double | s | - | Yes | Refresh period of the broadcasted values in seconds | | - */ -class IMURosPublisher : public GenericSensorRosPublisher -{ - // Interface of the wrapped device - yarp::dev::IThreeAxisLinearAccelerometers* m_iThreeAxisLinearAccelerometers{ nullptr }; - yarp::dev::IThreeAxisGyroscopes* m_iThreeAxisGyroscopes{ nullptr }; - yarp::dev::IOrientationSensors* m_iOrientationSensors{ nullptr }; - yarp::dev::IThreeAxisMagnetometers* m_iThreeAxisMagnetometers{ nullptr }; - -public: - using GenericSensorRosPublisher::GenericSensorRosPublisher; - - using GenericSensorRosPublisher::open; - using GenericSensorRosPublisher::close; - using GenericSensorRosPublisher::attachAll; - using GenericSensorRosPublisher::detachAll; - - /* PeriodicRateThread methods */ - void run() override; - -protected: - bool viewInterfaces() override; -}; - -#endif diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp deleted file mode 100644 index 0af90759675..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "MagneticFieldRosPublisher.h" - -YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.MagneticFieldRosPublisher") - -bool MagneticFieldRosPublisher::viewInterfaces() -{ - // View all the interfaces - bool ok = true; - ok = m_poly->view(m_iThreeAxisMagnetometers); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisMagnetometers interface is not available"; - return false; - } - - ok = m_iThreeAxisMagnetometers->getThreeAxisMagnetometerFrameName(0, m_framename); - return ok; -} - -void MagneticFieldRosPublisher::run() -{ - if (m_publisher.asPort().isOpen()) - { - yarp::sig::Vector vecmagn(3); - yarp::rosmsg::sensor_msgs::MagneticField& magfield_ros_data = m_publisher.prepare(); - m_iThreeAxisMagnetometers->getThreeAxisMagnetometerMeasure(m_sens_index, vecmagn, m_timestamp); - magfield_ros_data.clear(); - magfield_ros_data.header.frame_id = m_framename;; - magfield_ros_data.header.seq = m_msg_counter++; - magfield_ros_data.header.stamp = m_timestamp; - magfield_ros_data.magnetic_field.x = vecmagn[0]; - magfield_ros_data.magnetic_field.y = vecmagn[1]; - magfield_ros_data.magnetic_field.z = vecmagn[2]; - //magfield_ros_data.magnetic_field_covariance = 0; - m_publisher.write(); - } - } diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h deleted file mode 100644 index 5279fc68866..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/MagneticFieldRosPublisher.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#ifndef YARP_DEV_MAGFIELDROSPUBLISHER_H -#define YARP_DEV_MAGFIELDROSPUBLISHER_H - -#include "GenericSensorRosPublisher.h" -#include - - /** - * @ingroup dev_impl_wrapper - * - * \brief `MagneticFieldRosPublisher`: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::MagneticField. - * - * | YARP device name | - * |:-----------------:| - * | `MagneticFieldRosPublisher` | - * - * The parameters accepted by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | topic | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character | - * | node_name | - | string | - | $topic + "_node" | No | The name of the ROS node opened by this device | Autogenerated by default | - * | period | - | double | s | - | Yes | Refresh period of the broadcasted values in seconds | | - */ -class MagneticFieldRosPublisher : public GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField> -{ -protected: - // Interface of the wrapped device - yarp::dev::IThreeAxisMagnetometers* m_iThreeAxisMagnetometers{nullptr}; - -public: - using GenericSensorRosPublisher::GenericSensorRosPublisher; - - using GenericSensorRosPublisher::open; - using GenericSensorRosPublisher::close; - - using GenericSensorRosPublisher::attachAll; - using GenericSensorRosPublisher::detachAll; - - /* PeriodicRateThread methods */ - void run() override; - -protected: - virtual bool viewInterfaces() override; -}; - -#endif diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp deleted file mode 100644 index 197e251168d..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.cpp +++ /dev/null @@ -1,62 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "PoseStampedRosPublisher.h" -#include -#include - -#ifndef M_PI -#define M_PI (3.14159265358979323846) -#endif - -YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.PoseStampedRosPublisher") - -bool PoseStampedRosPublisher::viewInterfaces() -{ - // View all the interfaces - bool ok = true; - ok = m_poly->view(m_iOrientationSensors); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IOrientationSensors interface is not available"; - return false; - } - ok = m_poly->view(m_iPositionSensors); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "IPositionSensors interface is not available"; - return false; - } - ok = m_iPositionSensors->getPositionSensorFrameName(m_sens_index, m_framename); - return ok; -} - -void PoseStampedRosPublisher::run() -{ - if (m_publisher.asPort().isOpen()) - { - yarp::sig::Vector vecpos(3); - yarp::sig::Vector vecrpy(3); - yarp::rosmsg::geometry_msgs::PoseStamped& pose_data = m_publisher.prepare(); - m_iPositionSensors->getPositionSensorMeasure(m_sens_index, vecpos, m_timestamp); - m_iOrientationSensors->getOrientationSensorMeasureAsRollPitchYaw(m_sens_index, vecrpy, m_timestamp); - pose_data.clear(); - pose_data.header.frame_id = m_framename; - pose_data.header.seq = m_msg_counter++; - pose_data.header.stamp = m_timestamp; - pose_data.pose.position.x = vecpos[0]; - pose_data.pose.position.y = vecpos[1]; - pose_data.pose.position.z = vecpos[2]; - vecrpy[0] = vecrpy[0] * M_PI / 180.0; - vecrpy[1] = vecrpy[1] * M_PI / 180.0; - vecrpy[2] = vecrpy[2] * M_PI / 180.0; - yarp::sig::Matrix matrix = yarp::math::rpy2dcm(vecrpy); - yarp::math::Quaternion q; q.fromRotationMatrix(matrix); - pose_data.pose.orientation.x = q.x(); - pose_data.pose.orientation.y = q.y(); - pose_data.pose.orientation.z = q.z(); - pose_data.pose.orientation.w = q.w(); - //imu_ros_data.orientation_covariance = 0; - m_publisher.write(); - } - } diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h deleted file mode 100644 index 9c45358a555..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/PoseStampedRosPublisher.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#ifndef YARP_DEV_POSEROSPUBLISHER_H -#define YARP_DEV_POSEROSPUBLISHER_H - -#include "GenericSensorRosPublisher.h" -#include - -/** - * @ingroup dev_impl_wrapper - * - * \brief `PoseStampedRosPublisher`: This wrapper connects to a device and publishes a ROS topic of type geometry_msgs::PoseStamped. - * - * | YARP device name | - * |:-----------------:| - * | `PoseStampedRosPublisher` | - * - * The parameters accepted by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | topic | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character | - * | node_name | - | string | - | $topic + "_node" | No | The name of the ROS node opened by this device | Autogenerated by default | - * | period | - | double | s | - | Yes | Refresh period of the broadcasted values in seconds | | - */ -class PoseStampedRosPublisher : public GenericSensorRosPublisher -{ - // Interface of the wrapped device - yarp::dev::IOrientationSensors* m_iOrientationSensors{ nullptr }; - yarp::dev::IPositionSensors* m_iPositionSensors {nullptr}; - -public: - using GenericSensorRosPublisher::GenericSensorRosPublisher; - - using GenericSensorRosPublisher::open; - using GenericSensorRosPublisher::close; - - using GenericSensorRosPublisher::attachAll; - using GenericSensorRosPublisher::detachAll; - - /* PeriodicRateThread methods */ - void run() override; - -protected: - bool viewInterfaces() override; -}; - -#endif diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp deleted file mode 100644 index c5e44a81a57..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.cpp +++ /dev/null @@ -1,40 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "TemperatureRosPublisher.h" - -YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.PoseStampedRosPublisher") - -bool TemperatureRosPublisher::viewInterfaces() -{ - // View all the interfaces - bool ok = true; - ok = m_poly->view(m_ITemperature); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "ITemperatureSensors interface is not available"; - return false; - } - - ok = m_ITemperature->getTemperatureSensorFrameName(0,m_framename); - return ok; -} - -void TemperatureRosPublisher::run() -{ - if (m_publisher.asPort().isOpen()) - { - size_t index = 0; - double temperature; - yarp::rosmsg::sensor_msgs::Temperature& temp_ros_data = m_publisher.prepare(); - m_ITemperature->getTemperatureSensorMeasure(index, temperature, m_timestamp); - temp_ros_data.clear(); - temp_ros_data.header.frame_id = m_framename; - temp_ros_data.header.seq = m_msg_counter++; - temp_ros_data.header.stamp = m_timestamp; - temp_ros_data.temperature = temperature; - temp_ros_data.variance = 0; - m_publisher.write(); - } - } diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h deleted file mode 100644 index bd68edae044..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/TemperatureRosPublisher.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#ifndef YARP_DEV_TEMPERATUREROSPUBLISHER_H -#define YARP_DEV_TEMPERATUREROSPUBLISHER_H - -#include "GenericSensorRosPublisher.h" -#include - - /** - * @ingroup dev_impl_wrapper - * - * \brief `TemperatureRosPublisher`: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Temperature. - * - * | YARP device name | - * |:-----------------:| - * | `TemperatureRosPublisher` | - * - * The parameters accepted by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | topic | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character | - * | node_name | - | string | - | $topic + "_node" | No | The name of the ROS node opened by this device | Autogenerated by default | - * | period | - | double | s | - | Yes | Refresh period of the broadcasted values in seconds | | - */ -class TemperatureRosPublisher : public GenericSensorRosPublisher -{ - // Interface of the wrapped device - yarp::dev::ITemperatureSensors* m_ITemperature{ nullptr }; - -public: - using GenericSensorRosPublisher::GenericSensorRosPublisher; - - using GenericSensorRosPublisher::open; - using GenericSensorRosPublisher::close; - - using GenericSensorRosPublisher::attachAll; - using GenericSensorRosPublisher::detachAll; - - /* PeriodicRateThread methods */ - void run() override; - - bool viewInterfaces() override; -}; - -#endif diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp b/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp deleted file mode 100644 index 0af65507707..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.cpp +++ /dev/null @@ -1,42 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "WrenchStampedRosPublisher.h" - -YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.WrenchStampedRosPublisher") - -bool WrenchStampedRosPublisher::viewInterfaces() -{ - // View all the interfaces - bool ok = m_poly->view(m_iFTsens); - if (!ok) { - yCError(GENERICSENSORROSPUBLISHER) << "ISixAxisForceTorqueSensors interface is not available"; - return false; - } - - ok = m_iFTsens->getSixAxisForceTorqueSensorFrameName(m_sens_index, m_framename); - return ok; -} - -void WrenchStampedRosPublisher::run() -{ - if (m_publisher.asPort().isOpen()) - { - yarp::sig::Vector vecwrench(6); - yarp::rosmsg::geometry_msgs::WrenchStamped& wrench_ros_data = m_publisher.prepare(); - m_iFTsens->getSixAxisForceTorqueSensorMeasure(m_sens_index, vecwrench, m_timestamp); - wrench_ros_data.clear(); - wrench_ros_data.header.frame_id = m_framename; - wrench_ros_data.header.seq = m_msg_counter++; - wrench_ros_data.header.stamp = m_timestamp; - wrench_ros_data.wrench.force.x = vecwrench[0]; - wrench_ros_data.wrench.force.y = vecwrench[1]; - wrench_ros_data.wrench.force.z = vecwrench[2]; - wrench_ros_data.wrench.torque.x = vecwrench[4]; - wrench_ros_data.wrench.torque.y = vecwrench[5]; - wrench_ros_data.wrench.torque.z = vecwrench[6]; - m_publisher.write(); - } -} diff --git a/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h b/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h deleted file mode 100644 index 4a822bcaf05..00000000000 --- a/src/devices/ROS/multipleAnalogSensorsRosPublishers/WrenchStampedRosPublisher.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#ifndef YARP_DEV_WRENCHROSPUBLISHER_H -#define YARP_DEV_WRENCHROSPUBLISHER_H - -#include "GenericSensorRosPublisher.h" -#include - - /** - * @ingroup dev_impl_wrapper - * - * \brief `WrenchStampedRosPublisher`: This wrapper connects to a device and publishes a ROS topic of type geometry_msgs::WrenchStamped. - * - * | YARP device name | - * |:-----------------:| - * | `WrenchStampedRosPublisher` | - * - * The parameters accepted by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:--------------:|:-------:|:--------------:|:----------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| - * | topic | - | string | - | - | Yes | The name of the ROS topic opened by this device. | MUST start with a '/' character | - * | node_name | - | string | - | $topic + "_node" | No | The name of the ROS node opened by this device | Autogenerated by default | - * | period | - | double | s | - | Yes | Refresh period of the broadcasted values in seconds | | - */ -class WrenchStampedRosPublisher : public GenericSensorRosPublisher -{ - // Interface of the wrapped device - yarp::dev::ISixAxisForceTorqueSensors* m_iFTsens{ nullptr }; - -public: - using GenericSensorRosPublisher::GenericSensorRosPublisher; - - using GenericSensorRosPublisher::open; - using GenericSensorRosPublisher::close; - using GenericSensorRosPublisher::attachAll; - using GenericSensorRosPublisher::detachAll; - - /* PeriodicRateThread methods */ - void run() override; - -protected: - bool viewInterfaces() override; -}; - -#endif diff --git a/src/devices/ROS/odometry2D_nws_ros/CMakeLists.txt b/src/devices/ROS/odometry2D_nws_ros/CMakeLists.txt deleted file mode 100644 index dbc3689cb46..00000000000 --- a/src/devices/ROS/odometry2D_nws_ros/CMakeLists.txt +++ /dev/null @@ -1,50 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(odometry2D_nws_ros - CATEGORY device - TYPE Odometry2D_nws_ros - INCLUDE Odometry2D_nws_ros.h - EXTRA_CONFIG - WRAPPER=odometry2D_nws_ros - DEPENDS "TARGET YARP::YARP_math" - DEFAULT ON -) - -if(NOT SKIP_odometry2D_nws_ros) - yarp_add_plugin(yarp_odometry2D_nws_ros) - - target_sources(yarp_odometry2D_nws_ros - PRIVATE - Odometry2D_nws_ros.cpp - Odometry2D_nws_ros.h - ) - - target_link_libraries(yarp_odometry2D_nws_ros - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - YARP::YARP_rosmsg - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - YARP_rosmsg - ) - - yarp_install( - TARGETS yarp_odometry2D_nws_ros - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_odometry2D_nws_ros PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.cpp b/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.cpp deleted file mode 100644 index 98d2a2568ce..00000000000 --- a/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.cpp +++ /dev/null @@ -1,260 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#define _USE_MATH_DEFINES - -#include "Odometry2D_nws_ros.h" -#include -#include -#include - -#include - -YARP_LOG_COMPONENT(ODOMETRY2D_NWS_ROS, "yarp.devices.Odometry2D_nws_ros") - -Odometry2D_nws_ros::Odometry2D_nws_ros() : yarp::os::PeriodicThread(DEFAULT_THREAD_PERIOD) -{ -} - -Odometry2D_nws_ros::~Odometry2D_nws_ros() -{ - m_odometry2D_interface = nullptr; -} - - -bool Odometry2D_nws_ros::attach(yarp::dev::PolyDriver* driver) -{ - - if (driver->isValid()) - { - driver->view(m_odometry2D_interface); - } else { - yCError(ODOMETRY2D_NWS_ROS) << "not valid driver"; - } - - if (m_odometry2D_interface == nullptr) - { - yCError(ODOMETRY2D_NWS_ROS, "Subdevice passed to attach method is invalid"); - return false; - } - - PeriodicThread::setPeriod(m_period); - return PeriodicThread::start(); -} - - -bool Odometry2D_nws_ros::detach() -{ - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - m_odometry2D_interface = nullptr; - return true; -} - -bool Odometry2D_nws_ros::threadInit() -{ - return true; -} - -bool Odometry2D_nws_ros::open(yarp::os::Searchable &config) -{ - yarp::os::Property params; - params.fromString(config.toString()); - - if (config.check("publish_tf_topic")) { - m_enable_publish_tf = true; - } - if (config.check("skip_tf_topic")) { - m_enable_publish_tf = false; - } - - if (!config.check("period")) { - yCWarning(ODOMETRY2D_NWS_ROS) << "missing 'period' parameter, using default value of" << DEFAULT_THREAD_PERIOD; - } else { - m_period = config.find("period").asFloat64(); - } - - if (!config.check("node_name")) { - yCError(ODOMETRY2D_NWS_ROS) << "missing node_name parameter"; - return false; - } - m_nodeName = config.find("node_name").asString(); - if (m_nodeName[0] != '/') { - yCError(ODOMETRY2D_NWS_ROS) << "missing initial / in node_name parameter"; - return false; - } - - if (!config.check("topic_name")) { - yCError(ODOMETRY2D_NWS_ROS) << "missing topic_name parameter"; - return false; - } - m_topicName = config.find("topic_name").asString(); - if (m_topicName[0] != '/') { - yCError(ODOMETRY2D_NWS_ROS) << "missing initial / in topic_name parameter"; - return false; - } - - if (!config.check("odom_frame")) { - yCError(ODOMETRY2D_NWS_ROS) << "missing odom_frame parameter"; - return false; - } - m_odomFrame = config.find("odom_frame").asString(); - - - if (!config.check("base_frame")) { - yCError(ODOMETRY2D_NWS_ROS) << "missing base_frame parameter"; - return false; - } - m_baseFrame = config.find("base_frame").asString(); - - if (config.check("subdevice")) { - yarp::os::Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!m_driver.open(p) || !m_driver.isValid()) { - yCError(ODOMETRY2D_NWS_ROS) << "failed to open subdevice.. check params"; - return false; - } - - if (!attach(&m_driver)) { - yCError(ODOMETRY2D_NWS_ROS) << "failed to open subdevice.. check params"; - return false; - } - } - m_node = new yarp::os::Node(m_nodeName); - if (m_node == nullptr) { - yCError(ODOMETRY2D_NWS_ROS) << " opening " << m_nodeName << " Node, check your yarp-ROS network configuration\n"; - return false; - } - if (!rosPublisherPort_odometry.topic(m_topicName)) { - yCError(ODOMETRY2D_NWS_ROS) << " opening " << m_topicName << " Topic, check your yarp-ROS network configuration\n"; - return false; - } - - if (m_enable_publish_tf) - { - if (!rosPublisherPort_tf.topic("/tf")) { - yCError(ODOMETRY2D_NWS_ROS) << " opening " << "/tf" << " Topic, check your yarp-ROS network configuration\n"; - return false; - } - } - return true; -} - -void Odometry2D_nws_ros::threadRelease() -{ -} - -void Odometry2D_nws_ros::run() -{ - if (m_odometry2D_interface!=nullptr) - { - yarp::dev::OdometryData odometryData; - double synchronized_timestamp = 0; - m_odometry2D_interface->getOdometry(odometryData, &synchronized_timestamp); - - if (std::isnan(synchronized_timestamp) == false) - { - m_lastStateStamp.update(synchronized_timestamp); - } - else - { - m_lastStateStamp.update(yarp::os::Time::now()); - } - - if (1) - { - yarp::rosmsg::nav_msgs::Odometry& rosData = rosPublisherPort_odometry.prepare(); - rosData.header.seq = m_lastStateStamp.getCount(); - rosData.header.stamp = m_lastStateStamp.getTime(); - rosData.header.frame_id = m_odomFrame; - rosData.child_frame_id = m_baseFrame; - - rosData.pose.pose.position.x = odometryData.odom_x; - rosData.pose.pose.position.y = odometryData.odom_y; - rosData.pose.pose.position.z = 0.0; - yarp::rosmsg::geometry_msgs::Quaternion odom_quat; - double halfYaw = odometryData.odom_theta * DEG2RAD * 0.5; - double cosYaw = cos(halfYaw); - double sinYaw = sin(halfYaw); - odom_quat.x = 0; - odom_quat.y = 0; - odom_quat.z = sinYaw; - odom_quat.w = cosYaw; - rosData.pose.pose.orientation = odom_quat; - rosData.twist.twist.linear.x = odometryData.base_vel_x; - rosData.twist.twist.linear.y = odometryData.base_vel_y; - rosData.twist.twist.linear.z = 0; - rosData.twist.twist.angular.x = 0; - rosData.twist.twist.angular.y = 0; - rosData.twist.twist.angular.z = odometryData.base_vel_theta * DEG2RAD; - rosPublisherPort_odometry.write(); - } - - if (m_enable_publish_tf) - { - yarp::rosmsg::tf2_msgs::TFMessage& rosData = rosPublisherPort_tf.prepare(); - yarp::rosmsg::geometry_msgs::TransformStamped transform; - transform.header.frame_id = m_odomFrame; - transform.child_frame_id = m_baseFrame; - transform.header.seq = m_lastStateStamp.getCount(); - transform.header.stamp = m_lastStateStamp.getTime(); - double halfYaw = odometryData.odom_theta * DEG2RAD * 0.5; - double cosYaw = cos(halfYaw); - double sinYaw = sin(halfYaw); - transform.transform.rotation.x = 0; - transform.transform.rotation.y = 0; - transform.transform.rotation.z = sinYaw; - transform.transform.rotation.w = cosYaw; - transform.transform.translation.x = odometryData.odom_x; - transform.transform.translation.y = odometryData.odom_y; - transform.transform.translation.z = 0; - if (rosData.transforms.size() == 0) - { - rosData.transforms.push_back(transform); - } - else if (rosData.transforms.size() == 1) - { - rosData.transforms[0] = transform; - } - else - { - yCWarning(ODOMETRY2D_NWS_ROS) << "Size of /tf topic should be 1, instead it is:" << rosData.transforms.size(); - } - rosPublisherPort_tf.write(); - } - - } else{ - yCError(ODOMETRY2D_NWS_ROS) << "the interface is not valid"; - } -} - -bool Odometry2D_nws_ros::close() -{ - yCTrace(ODOMETRY2D_NWS_ROS, "Close"); - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - - detach(); - - if (m_node) - { - rosPublisherPort_odometry.close(); - if (m_enable_publish_tf) - { - rosPublisherPort_tf.close(); - } - delete m_node; - m_node = nullptr; - } - - yCDebug(ODOMETRY2D_NWS_ROS) << "Execution terminated"; - return true; -} diff --git a/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.h b/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.h deleted file mode 100644 index ee27cb3c74e..00000000000 --- a/src/devices/ROS/odometry2D_nws_ros/Odometry2D_nws_ros.h +++ /dev/null @@ -1,140 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: LGPL-2.1-or-later - */ - -#ifndef YARP_ODOMETRY2D_NWS_YARP_H -#define YARP_ODOMETRY2D_NWS_YARP_H - -#include -#include -#include -#include - -#include -#include -#include - -#include -#include -#include - -#ifndef _USE_MATH_DEFINES -#define _USE_MATH_DEFINES -#endif - -#define DEG2RAD M_PI/180.0 -#define DEFAULT_THREAD_PERIOD 0.02 //s - -/** - * @ingroup dev_impl_nws_ros dev_impl_navigation - * - * \section Odometry2D_nws_ros_parameters Device description - * \brief `Odometry2D_nws_ros`: A ros nws to get odometry and publish it on a ros topic. - * The attached device must implement a `yarp::dev::Nav2D::IOdometry2D` interface. - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:-------------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:-----------------------------: |:-------------------------------------------------------:|:-----:| - * | period | - | double | s | 0.02 | No | refresh period of the broadcasted values in s | default 0.02s | - * | node_name | - | string | - | - | Yes | name of the ros node | must begin with an initial '/' | - * | topic_name | - | string | - | - | Yes | name of the topic where the device must publish the data| must begin with an initial '/' | - * | odom_frame | - | string | - | - | Yes | name of the reference frame for odometry | | - * | base_frame | - | string | - | - | Yes | name of the base frame for odometry | | - * | subdevice | - | string | - | - | alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | - * - * Example of configuration file using .ini format. - * - * \code{.unparsed} - * device odometry2D_nws_ros - * period 0.02 - * node_name /odometry_ros - * topic_name /odometry - * odom_frame odom - * base_frame base - * - * subdevice fakeOdometry - * \endcode - * - * example of xml file with a fake odometer - * - * \code{.unparsed} - * - * - * - * - * - * - * - * /odometry_ros - * /odometry - * odom - * base - * - * - * fakeOdometry_device - * - * - * - * - * - * - * \endcode - * - * example of command via terminal. - * - * \code{.unparsed} - * yarpdev --device odometry2D_nws_ros --node_name /odometry_ros --topic_name /odometry --odom_frame odom --base_frame base --subdevice fakeOdometry - * \endcode - */ - -class Odometry2D_nws_ros : - public yarp::os::PeriodicThread, - public yarp::dev::DeviceDriver, - public yarp::dev::WrapperSingle -// public yarp::os::PortReader -{ -public: - Odometry2D_nws_ros(); - ~Odometry2D_nws_ros(); - - // DeviceDriver - bool open(yarp::os::Searchable ¶ms) override; - bool close() override; - - // WrapperSingle - bool attach(yarp::dev::PolyDriver* driver) override; - bool detach() override; - - // PeriodicThread - bool threadInit() override; - void threadRelease() override; - void run() override; - - -private: - // parameters from configuration - std::string m_topicName; - std::string m_nodeName; - std::string m_odomFrame; - std::string m_baseFrame; - bool m_enable_publish_tf = true; - - // timestamp - yarp::os::Stamp m_lastStateStamp; - - // period for thread - double m_period{DEFAULT_THREAD_PERIOD}; - - //ros node - yarp::os::Node* m_node; - - //interfaces - yarp::dev::PolyDriver m_driver; - yarp::dev::Nav2D::IOdometry2D *m_odometry2D_interface{nullptr}; - yarp::os::Publisher rosPublisherPort_odometry; - yarp::os::Publisher rosPublisherPort_tf; - -}; - -#endif // YARP_ODOMETRY2D_NWS_YARP_H From 3a62f2d4b4a6df1be0089e0df94c0224cfff606a Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 16 Nov 2022 15:14:13 +0100 Subject: [PATCH 018/267] Removed parser of unused 'subdevice' xml tag from yarprobotinerface XMLReaderFileV3. This option was wrongly implemented (and never used) --- .../robotinterface/impl/XMLReaderFileV3.cpp | 50 +------------------ 1 file changed, 1 insertion(+), 49 deletions(-) diff --git a/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp b/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp index 6938f326338..3e4269bb7d7 100644 --- a/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp +++ b/src/libYARP_robotinterface/src/yarp/robotinterface/impl/XMLReaderFileV3.cpp @@ -50,7 +50,6 @@ class yarp::robotinterface::impl::XMLReaderFileV3::Private yarp::robotinterface::Param readParamTag(TiXmlElement* paramElem, yarp::robotinterface::XMLReaderResult& result); yarp::robotinterface::Param readGroupTag(TiXmlElement* groupElem, yarp::robotinterface::XMLReaderResult& result); yarp::robotinterface::ParamList readParamListTag(TiXmlElement* paramListElem, yarp::robotinterface::XMLReaderResult& result); - yarp::robotinterface::ParamList readSubDeviceTag(TiXmlElement* subDeviceElem, yarp::robotinterface::XMLReaderResult& result); yarp::robotinterface::ParamList readParamsTag(TiXmlElement* paramsElem, yarp::robotinterface::XMLReaderResult& result); yarp::robotinterface::ActionList readActions(TiXmlElement* actionsElem, yarp::robotinterface::XMLReaderResult& result); @@ -484,8 +483,6 @@ yarp::robotinterface::DeviceList yarp::robotinterface::impl::XMLReaderFileV3::Pr yarp::robotinterface::ParamList params; for (TiXmlElement* childElem = devicesElem->FirstChildElement(); childElem != nullptr; childElem = childElem->NextSiblingElement()) { - // FIXME Check DTD >= 3.2 - // "subdevice" is not allowed in the "devices" tag if (childElem->ValueStr() == "param" || childElem->ValueStr() == "group" || childElem->ValueStr() == "paramlist" || childElem->ValueStr() == "params") { for (const auto& childParam : readParams(childElem, result)) { params.push_back(childParam); @@ -523,14 +520,11 @@ yarp::robotinterface::ParamList yarp::robotinterface::impl::XMLReaderFileV3::Pri if (valueStr == "paramlist") { return readParamListTag(paramsElem, result); } - if (valueStr == "subdevice") { - return readSubDeviceTag(paramsElem, result); - } if (valueStr == "params") { return readParamsTag(paramsElem, result); } - SYNTAX_ERROR(paramsElem->Row()) << R"(Expected "param", "group", "paramlist", "subdevice", or "params". Found)" << valueStr; + SYNTAX_ERROR(paramsElem->Row()) << R"(Expected "param", "group", "paramlist", or "params". Found)" << valueStr; result.parsingIsSuccessful = false; return yarp::robotinterface::ParamList(); } @@ -711,48 +705,6 @@ yarp::robotinterface::ParamList yarp::robotinterface::impl::XMLReaderFileV3::Pri return params; } -yarp::robotinterface::ParamList yarp::robotinterface::impl::XMLReaderFileV3::Private::readSubDeviceTag(TiXmlElement* subDeviceElem, - yarp::robotinterface::XMLReaderResult& result) -{ - if (subDeviceElem->ValueStr() != "subdevice") { - SYNTAX_ERROR(subDeviceElem->Row()) << "Expected \"subdevice\". Found" << subDeviceElem->ValueStr(); - result.parsingIsSuccessful = false; - return yarp::robotinterface::ParamList(); - } - - yarp::robotinterface::ParamList params; - - //FIXME yarp::robotinterface::Param featIdParam; - yarp::robotinterface::Param subDeviceParam; - - //FIXME featIdParam.name() = "FeatId"; - subDeviceParam.name() = "subdevice"; - - //FIXME if (subDeviceElem->QueryStringAttribute("name", &featIdParam.value()) != TIXML_SUCCESS) { - // SYNTAX_ERROR(subDeviceElem->Row()) << "\"subdevice\" element should contain the \"name\" attribute"; - // } - - if (subDeviceElem->QueryStringAttribute("type", &subDeviceParam.value()) != TIXML_SUCCESS) { - SYNTAX_ERROR(subDeviceElem->Row()) << R"("subdevice" element should contain the "type" attribute)"; - result.parsingIsSuccessful = false; - return yarp::robotinterface::ParamList(); - } - - //FIXME params.push_back(featIdParam); - params.push_back(subDeviceParam); - - // yDebug() << "Found subdevice [" << params.at(0).value() << "]"; - - for (TiXmlElement* childElem = subDeviceElem->FirstChildElement(); childElem != nullptr; childElem = childElem->NextSiblingElement()) { - for (const auto& childParam : readParams(childElem, result)) { - params.push_back(yarp::robotinterface::Param(childParam.name(), childParam.value())); - } - } - - // yDebug() << params; - return params; -} - yarp::robotinterface::ParamList yarp::robotinterface::impl::XMLReaderFileV3::Private::readParamsTag(TiXmlElement* paramsElem, yarp::robotinterface::XMLReaderResult& result) { From 90cbb8697823dba9b81f2fe1186bd14470d59dd9 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 16 Nov 2022 17:08:55 +0100 Subject: [PATCH 019/267] ControlBoard_nws_yarp files moved away from folder ControlBoardWrapper. No functional changes. ControlBoardWrapper folder (and its deprecated device ControlBoardWrapper2) will be removed in the near future. --- src/devices/CMakeLists.txt | 1 + .../ControlBoardWrapper/CMakeLists.txt | 57 - .../ControlBoard_nws_yarp/CMakeLists.txt | 58 + .../ControlBoardLogComponent.cpp | 8 + .../ControlBoardLogComponent.h | 13 + .../ControlBoardWrapper.cpp | 872 ++++++ .../ControlBoardWrapper.h | 300 ++ .../ControlBoard_nws_yarp.cpp | 536 ++++ .../ControlBoard_nws_yarp.h | 143 + .../RPCMessagesParser.cpp | 2555 +++++++++++++++++ .../ControlBoard_nws_yarp/RPCMessagesParser.h | 149 + .../StreamingMessagesParser.cpp | 291 ++ .../StreamingMessagesParser.h | 86 + 13 files changed, 5012 insertions(+), 57 deletions(-) create mode 100644 src/devices/ControlBoard_nws_yarp/CMakeLists.txt create mode 100644 src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.cpp create mode 100644 src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.h create mode 100644 src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.cpp create mode 100644 src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.h create mode 100644 src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.cpp create mode 100644 src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.h create mode 100644 src/devices/ControlBoard_nws_yarp/RPCMessagesParser.cpp create mode 100644 src/devices/ControlBoard_nws_yarp/RPCMessagesParser.h create mode 100644 src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.cpp create mode 100644 src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.h diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index 8ef769f2f79..d9390ae9d27 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -88,6 +88,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(RGBDSensorClient) add_subdirectory(RGBDSensor_nws_yarp) add_subdirectory(ControlBoardWrapper) + add_subdirectory(ControlBoard_nws_yarp) add_subdirectory(ControlBoardRemapper) add_subdirectory(RobotDescriptionClient) add_subdirectory(RobotDescriptionServer) diff --git a/src/devices/ControlBoardWrapper/CMakeLists.txt b/src/devices/ControlBoardWrapper/CMakeLists.txt index 478de45fabd..56221cc6662 100644 --- a/src/devices/ControlBoardWrapper/CMakeLists.txt +++ b/src/devices/ControlBoardWrapper/CMakeLists.txt @@ -104,60 +104,3 @@ if(NOT SKIP_controlboardwrapper2) set_property(TARGET yarp_controlboardwrapper2 PROPERTY FOLDER "Plugins/Device") endif() - - -yarp_prepare_plugin( - controlBoard_nws_yarp - CATEGORY device - TYPE ControlBoard_nws_yarp - INCLUDE ControlBoard_nws_yarp.h - EXTRA_CONFIG - WRAPPER=controlBoard_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_controlBoard_nws_yarp) - yarp_add_plugin(yarp_controlBoard_nws_yarp) - - target_compile_definitions(yarp_controlBoard_nws_yarp - PRIVATE - LOG_COMPONENT="yarp.devices.controlBoard_nws_yarp" - ) - - target_sources(yarp_controlBoard_nws_yarp - PRIVATE - ControlBoard_nws_yarp.cpp - ControlBoard_nws_yarp.h - RPCMessagesParser.cpp - RPCMessagesParser.h - StreamingMessagesParser.cpp - StreamingMessagesParser.h - ControlBoardLogComponent.cpp - ControlBoardLogComponent.h - ) - - target_link_libraries(yarp_controlBoard_nws_yarp - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_controlBoard_nws_yarp - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_controlBoard_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") -endif() diff --git a/src/devices/ControlBoard_nws_yarp/CMakeLists.txt b/src/devices/ControlBoard_nws_yarp/CMakeLists.txt new file mode 100644 index 00000000000..5941d8abc52 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/CMakeLists.txt @@ -0,0 +1,58 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +yarp_prepare_plugin( + controlBoard_nws_yarp + CATEGORY device + TYPE ControlBoard_nws_yarp + INCLUDE ControlBoard_nws_yarp.h + EXTRA_CONFIG + WRAPPER=controlBoard_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_controlBoard_nws_yarp) + yarp_add_plugin(yarp_controlBoard_nws_yarp) + + target_compile_definitions(yarp_controlBoard_nws_yarp + PRIVATE + LOG_COMPONENT="yarp.devices.controlBoard_nws_yarp" + ) + + target_sources(yarp_controlBoard_nws_yarp + PRIVATE + ControlBoard_nws_yarp.cpp + ControlBoard_nws_yarp.h + RPCMessagesParser.cpp + RPCMessagesParser.h + StreamingMessagesParser.cpp + StreamingMessagesParser.h + ControlBoardLogComponent.cpp + ControlBoardLogComponent.h + ) + + target_link_libraries(yarp_controlBoard_nws_yarp + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + ) + + yarp_install( + TARGETS yarp_controlBoard_nws_yarp + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_controlBoard_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") +endif() diff --git a/src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.cpp b/src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.cpp new file mode 100644 index 00000000000..38ccb98581b --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.cpp @@ -0,0 +1,8 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "ControlBoardLogComponent.h" + +YARP_LOG_COMPONENT(CONTROLBOARD, LOG_COMPONENT) diff --git a/src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.h b/src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.h new file mode 100644 index 00000000000..11ea3f0be34 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/ControlBoardLogComponent.h @@ -0,0 +1,13 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPERLOGCOMPONENT_H +#define YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPERLOGCOMPONENT_H + +#include + +YARP_DECLARE_LOG_COMPONENT(CONTROLBOARD) + +#endif // YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPERLOGCOMPONENT_H diff --git a/src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.cpp b/src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.cpp new file mode 100644 index 00000000000..36ac3da3b74 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.cpp @@ -0,0 +1,872 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "ControlBoardWrapper.h" + +#include +#include + +#include + +#include "ControlBoardLogComponent.h" +#include "RPCMessagesParser.h" +#include "StreamingMessagesParser.h" +#include +#include // for memset function +#include +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::dev::impl; +using namespace yarp::sig; + + +ControlBoardWrapper::ControlBoardWrapper() : + yarp::os::PeriodicThread(default_period) +{ + streaming_parser.init(this); + RPC_parser.init(this); +} + +void ControlBoardWrapper::cleanup_yarpPorts() +{ + //shut down control port + inputRPCPort.interrupt(); + inputRPCPort.removeCallbackLock(); + inputRPCPort.close(); + + inputStreamingPort.interrupt(); + inputStreamingPort.close(); + + outputPositionStatePort.interrupt(); + outputPositionStatePort.close(); + + extendedOutputStatePort.interrupt(); + extendedOutputStatePort.close(); + + rpcData.destroy(); +} + +ControlBoardWrapper::~ControlBoardWrapper() = default; + +bool ControlBoardWrapper::close() +{ + //stop thread if running + detachAll(); + + if (yarp::os::PeriodicThread::isRunning()) { + yarp::os::PeriodicThread::stop(); + } + + if (useROS != ROS_only) { + cleanup_yarpPorts(); + } + + if (rosNode != nullptr) { + delete rosNode; + rosNode = nullptr; + } + + //if we own a deviced we have to close and delete it + if (ownDevices) { + // we should have created a new devices which we need to delete + if (subDeviceOwned != nullptr) { + subDeviceOwned->close(); + delete subDeviceOwned; + subDeviceOwned = nullptr; + } + } else { + detachAll(); + } + return true; +} + +bool ControlBoardWrapper::checkPortName(Searchable& params) +{ + /* see if rootName is present in the config file, this param is not used from long time, so it'll be + * marked as deprecated. + */ + if (params.check("rootName")) { + yCWarning(CONTROLBOARD) << + "************************************************************************************\n" + "* controlboardwrapper2 is using the deprecated parameter 'rootName' for port name, *\n" + "* It has to be removed and substituted with: *\n" + "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n" + "************************************************************************************"; + rootName = params.find("rootName").asString(); + } + + // find name as port name (similar both in new and old policy + if (!params.check("name")) { + yCError(CONTROLBOARD) << + "************************************************************************************\n" + "* controlboardwrapper2 missing mandatory parameter 'name' for port name, usage is: *\n" + "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n" + "************************************************************************************"; + return false; + } + + partName = params.find("name").asString(); + if (partName[0] != '/') { + yCWarning(CONTROLBOARD) << + "************************************************************************************\n" + "* controlboardwrapper2 'name' parameter for port name does not follow convention, *\n" + "* it MUST start with a leading '/' since it is used as the full prefix port name *\n" + "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n" + "* A temporary automatic fix will be done for you, but please fix your config file *\n" + "************************************************************************************"; + rootName = "/" + partName; + } else { + rootName = partName; + } + + return true; +} + +bool ControlBoardWrapper::checkROSParams(Searchable& config) +{ + // check for ROS parameter group + if (!config.check("ROS")) { + useROS = ROS_disabled; + return true; + } + + yCInfo(CONTROLBOARD) << "ROS group was FOUND in config file."; + + Bottle& rosGroup = config.findGroup("ROS"); + if (rosGroup.isNull()) { + yCError(CONTROLBOARD) << partName << "ROS group params is not a valid group or empty"; + useROS = ROS_config_error; + return false; + } + + // check for useROS parameter + if (!rosGroup.check("useROS")) { + yCError(CONTROLBOARD) << partName << " cannot find useROS parameter, mandatory when using ROS message. \n \ + Allowed values are true, false, ROS_only"; + useROS = ROS_config_error; + return false; + } + std::string ros_use_type = rosGroup.find("useROS").asString(); + if (ros_use_type == "false") { + yCInfo(CONTROLBOARD) << partName << "useROS topic if set to 'false'"; + useROS = ROS_disabled; + return true; + } + + if (ros_use_type == "true") { + yCInfo(CONTROLBOARD) << partName << "useROS topic if set to 'true'"; + useROS = ROS_enabled; + } else if (ros_use_type == "only") { + yCInfo(CONTROLBOARD) << partName << "useROS topic if set to 'only"; + useROS = ROS_only; + } else { + yCInfo(CONTROLBOARD) << partName << "useROS parameter is seet to unvalid value ('" << ros_use_type << "'), supported values are 'true', 'false', 'only'"; + useROS = ROS_config_error; + return false; + } + + // check for ROS_nodeName parameter + if (!rosGroup.check("ROS_nodeName")) { + yCError(CONTROLBOARD) << partName << " cannot find ROS_nodeName parameter, mandatory when using ROS message"; + useROS = ROS_config_error; + return false; + } + rosNodeName = rosGroup.find("ROS_nodeName").asString(); + if(rosNodeName[0] != '/'){ + yCError(CONTROLBOARD) << "ros node name must begin with an initial /"; + return false; + } + yCInfo(CONTROLBOARD) << partName << "rosNodeName is " << rosNodeName; + + // check for ROS_topicName parameter + if (!rosGroup.check("ROS_topicName")) { + yCError(CONTROLBOARD) << partName << " cannot find rosTopicName parameter, mandatory when using ROS message"; + useROS = ROS_config_error; + return false; + } + rosTopicName = rosGroup.find("ROS_topicName").asString(); + yCInfo(CONTROLBOARD) << partName << "rosTopicName is " << rosTopicName; + + // check for rosNodeName parameter + // UPDATE: joint names are got from MotionControl subdevice now. + // An error should be thrown later on in case we fail getting names from device + if (!rosGroup.check("jointNames")) { + yCInfo(CONTROLBOARD) << partName << "ROS topic has been required, jointNames will be got from motionControl subdevice."; + } else // if names are there, store them. They will be used for back compatibility if old policy is used. + { + Bottle nameList = rosGroup.findGroup("jointNames").tail(); + if (nameList.isNull()) { + yCError(CONTROLBOARD) << partName << " jointNames not found"; + useROS = ROS_config_error; + return false; + } + + if (nameList.size() != static_cast(controlledJoints)) { + yCError(CONTROLBOARD) << partName << " jointNames incorrect number of entries. \n jointNames is " << nameList.toString() << "while expected length is " << controlledJoints; + useROS = ROS_config_error; + return false; + } + + jointNames.clear(); + for (size_t i = 0; i < controlledJoints; i++) { + jointNames.push_back(nameList.get(i).toString()); + } + } + return true; +} + +bool ControlBoardWrapper::initialize_ROS() +{ + bool success = false; + switch (useROS) { + case ROS_enabled: + case ROS_only: { + rosNode = new yarp::os::Node(rosNodeName); // add a ROS node + + if (rosNode == nullptr) { + yCError(CONTROLBOARD) << " opening " << rosNodeName << " Node, check your yarp-ROS network configuration"; + success = false; + break; + } + + if (!rosPublisherPort.topic(rosTopicName)) { + yCError(CONTROLBOARD) << " opening " << rosTopicName << " Topic, check your yarp-ROS network configuration"; + success = false; + break; + } + success = true; + } break; + + case ROS_disabled: { + yCInfo(CONTROLBOARD) << partName << ": no ROS initialization required"; + success = true; + } break; + + case ROS_config_error: { + yCError(CONTROLBOARD) << partName << " ROS parameter are not correct, check your configuration file"; + success = false; + } break; + + default: + { + yCError(CONTROLBOARD) << partName << " something went wrong with ROS configuration, we should never be here!!!"; + success = false; + } break; + } + return success; +} + +bool ControlBoardWrapper::initialize_YARP(yarp::os::Searchable& prop) +{ + bool success = false; + + switch (useROS) { + case ROS_only: { + yCInfo(CONTROLBOARD) << partName << " No YARP initialization required"; + success = true; + } break; + + default: + { + yCInfo(CONTROLBOARD) << partName << " initting YARP initialization"; + // initialize callback + if (!streaming_parser.initialize()) { + yCError(CONTROLBOARD) << "Error could not initialize callback object"; + success = false; + break; + } + + rootName = prop.check("rootName", Value("/"), "starting '/' if needed.").asString(); + partName = prop.check("name", Value("controlboard"), "prefix for port names").asString(); + rootName += (partName); + if (rootName.find("//") != std::string::npos) { + rootName.replace(rootName.find("//"), 2, "/"); + } + + ///// We now open ports, then attach the readers or callbacks + if (!inputRPCPort.open((rootName + "/rpc:i"))) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/rpc:i"; + success = false; + break; + } + inputRPCPort.setReader(RPC_parser); + inputRPC_buffer.attach(inputRPCPort); + RPC_parser.attach(inputRPC_buffer); + + if (!inputStreamingPort.open(rootName + "/command:i")) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/rpc:i"; + success = false; + break; + } + + // attach callback. + inputStreamingPort.setStrict(); + inputStreamingPort.useCallback(streaming_parser); + + if (!outputPositionStatePort.open(rootName + "/state:o")) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/state:o"; + success = false; + break; + } + + // new extended output state port + if (!extendedOutputStatePort.open(rootName + "/stateExt:o")) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/state:o"; + success = false; + break; + } + extendedOutputState_buffer.attach(extendedOutputStatePort); + success = true; + } break; + } // end switch + + // cleanup if something went wrong + if (!success) { + cleanup_yarpPorts(); + } + return success; +} + + +bool ControlBoardWrapper::open(Searchable& config) +{ + yCWarning(CONTROLBOARD) << "The 'controlboardwrapper2' device is deprecated in favour of 'controlboardremapper' + 'controlBoard_nws_yarp'."; + yCWarning(CONTROLBOARD) << "The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4."; + yCWarning(CONTROLBOARD) << "Please update your scripts."; + + Property prop; + prop.fromString(config.toString()); + + if (prop.check("verbose", "Deprecated flag. Use log components instead")) { + yCWarning(CONTROLBOARD) << "'verbose' flag is deprecated. Use log components instead"; + } + + if (!checkPortName(config)) { + yCError(CONTROLBOARD) << "'portName' was not correctly set, check you r configuration file"; + return false; + } + + // check FIRST for deprecated parameter + if (prop.check("threadrate")) { + yCError(CONTROLBOARD) << "Using removed parameter 'threadrate', use 'period' instead"; + return false; + } + + // NOW, check for correct parameter, so if both are present we use the correct one + if (prop.check("period")) { + if (!prop.find("period").isInt32()) { + yCError(CONTROLBOARD) << "'period' parameter is not an integer value"; + return false; + } + period = prop.find("period").asInt32() / 1000.0; + if (period <= 0) { + yCError(CONTROLBOARD) << "'period' parameter is not valid, read value is" << period; + return false; + } + } else { + yCDebug(CONTROLBOARD) << "'period' parameter missing, using default thread period = 20ms"; + period = default_period; + } + + // check if we need to create subdevice or if they are + // passed later on thorugh attachAll() + if (prop.check("subdevice")) { + ownDevices = true; + prop.setMonitor(config.getMonitor()); + if (!openAndAttachSubDevice(prop)) { + yCError(CONTROLBOARD, "Error while opening subdevice"); + return false; + } + } else { + ownDevices = false; + if (!openDeferredAttach(prop)) { + return false; + } + } + + // using controlledJoints here will allocate more memory than required, but not so much. + rpcData.resize(device.subdevices.size(), controlledJoints, &device); + + /* This must be after the openAndAttachSubDevice() or openDeferredAttach() in order to have the correct number of controlledJoints, + but before the initialize_ROS and initialize_YARP */ + if (!checkROSParams(config)) { + yCError(CONTROLBOARD) << partName << " ROS parameter are not correct, check your configuration file"; + return false; + } + + // call ROS node/topic initialization, if needed + if (!initialize_ROS()) { + return false; + } + + // call YARP port initialization, if needed + if (!initialize_YARP(prop)) { + yCError(CONTROLBOARD) << partName << "Something wrong when initting yarp ports"; + return false; + } + + times.resize(controlledJoints); + ros_struct.name.resize(controlledJoints); + ros_struct.position.resize(controlledJoints); + ros_struct.velocity.resize(controlledJoints); + ros_struct.effort.resize(controlledJoints); + + // In case attach is not deferred and the controlboard already owns a valid device + // we can start the thread. Otherwise this will happen when attachAll is called + if (ownDevices) { + PeriodicThread::setPeriod(period); + if (!PeriodicThread::start()) { + return false; + } + } + return true; +} + + +// Default usage +// Open the wrapper only, the attach method needs to be called before using it +bool ControlBoardWrapper::openDeferredAttach(Property& prop) +{ + if (!prop.check("networks", "list of networks merged by this wrapper")) { + yCError(CONTROLBOARD) << "List of networks to attach to was not found."; + return false; + } + + Bottle* nets = prop.find("networks").asList(); + if (nets == nullptr) { + yCError(CONTROLBOARD) << "Error parsing parameters: \"networks\" should be followed by a list"; + return false; + } + + if (!prop.check("joints", "number of joints of the part")) { + return false; + } + + controlledJoints = prop.find("joints").asInt32(); + + size_t nsubdevices = nets->size(); + device.lut.resize(controlledJoints); + device.subdevices.resize(nsubdevices); + + // configure the devices + size_t totalJ = 0; + for (size_t k = 0; k < nets->size(); k++) { + Bottle parameters; + size_t wBase; + size_t wTop; + size_t base; + size_t top; + + parameters = prop.findGroup(nets->get(k).asString()); + + if (parameters.size() == 2) { + Bottle* bot = parameters.get(1).asList(); + Bottle tmpBot; + if (bot == nullptr) { + // probably data are not passed in the correct way, try to read them as a string. + std::string bString(parameters.get(1).asString()); + tmpBot.fromString(bString); + + if (tmpBot.size() != 4) { + yCError(CONTROLBOARD) << "Error: check network parameters in part description" + << "--> I was expecting " << nets->get(k).asString() << " followed by a list of four integers in parenthesis" + << "Got: " << parameters.toString(); + return false; + } + + bot = &tmpBot; + } + + // If I came here, bot is correct + wBase = static_cast(bot->get(0).asInt32()); + wTop = static_cast(bot->get(1).asInt32()); + base = static_cast(bot->get(2).asInt32()); + top = static_cast(bot->get(3).asInt32()); + } else if (parameters.size() == 5) { + yCError(CONTROLBOARD) << "Parameter networks use deprecated syntax"; + wBase = static_cast(parameters.get(1).asInt32()); + wTop = static_cast(parameters.get(2).asInt32()); + base = static_cast(parameters.get(3).asInt32()); + top = static_cast(parameters.get(4).asInt32()); + } else { + yCError(CONTROLBOARD) << "Error: check network parameters in part description" + << "--> I was expecting " << nets->get(k).asString() << " followed by a list of four integers in parenthesis" + << "Got: " << parameters.toString(); + return false; + } + + SubDevice* tmpDevice = device.getSubdevice(k); + if (!tmpDevice) { + yCError(CONTROLBOARD) << "Get of subdevice returned null"; + return false; + } + + size_t axes = top - base + 1; + if (!tmpDevice->configure(wBase, wTop, base, top, axes, nets->get(k).asString(), getId())) { + yCError(CONTROLBOARD) << "Configure of subdevice ret false"; + return false; + } + + // Check input values are in range + if ((wBase == static_cast(-1)) || (wBase >= controlledJoints)) { + yCError(CONTROLBOARD) << "Input configuration for device " << partName << "has a wrong attach map." + << "First index " << wBase << "must be inside range from 0 to 'joints' (" << controlledJoints << ")"; + return false; + } + + if ((wTop == static_cast(-1)) || (wTop >= controlledJoints)) { + yCError(CONTROLBOARD) << "Input configuration for device " << partName << "has a wrong attach map." + << "Second index " << wTop << "must be inside range from 0 to 'joints' (" << controlledJoints << ")"; + return false; + } + + if (wBase > wTop) { + yCError(CONTROLBOARD) << "Input configuration for device " << partName << "has a wrong attach map." + << "First index " << wBase << "must be lower than second index " << wTop; + return false; + } + + for (size_t j = wBase, jInDev = base; j <= wTop; j++, jInDev++) { + device.lut[j].deviceEntry = k; + device.lut[j].offset = static_cast(j - wBase); + device.lut[j].jointIndexInDev = jInDev; + } + + totalJ += axes; + } + + if (totalJ != controlledJoints) { + yCError(CONTROLBOARD) << "Error total number of mapped joints (" << totalJ << ") does not correspond to part joints (" << controlledJoints << ")"; + return false; + } + return true; +} + +// For the simulator, if a subdevice parameter is given to the wrapper, it will +// open it and attach to immediately. +bool ControlBoardWrapper::openAndAttachSubDevice(Property& prop) +{ + Property p; + subDeviceOwned = new PolyDriver; + p.fromString(prop.toString()); + + std::string subdevice = prop.find("subdevice").asString(); + p.setMonitor(prop.getMonitor(), subdevice.c_str()); // pass on any monitoring + p.unput("device"); + p.put("device", subdevice); // subdevice was already checked before + + // if errors occurred during open, quit here. + yCDebug(CONTROLBOARD, "opening subdevice"); + subDeviceOwned->open(p); + + if (!subDeviceOwned->isValid()) { + yCError(CONTROLBOARD, "opening subdevice... FAILED"); + return false; + } + + yarp::dev::IEncoders* iencs = nullptr; + + subDeviceOwned->view(iencs); + + if (iencs == nullptr) { + yCError(CONTROLBOARD, "Opening IEncoders interface of subdevice... FAILED"); + return false; + } + + int tmp_axes; + bool getAx = iencs->getAxes(&tmp_axes); + + if (!getAx) { + yCError(CONTROLBOARD, "Calling getAxes of subdevice... FAILED"); + return false; + } + controlledJoints = static_cast(tmp_axes); + + yCDebug(CONTROLBOARD, "Joints parameter is %zu", controlledJoints); + + + device.lut.resize(controlledJoints); + device.subdevices.resize(1); + + // configure the device + size_t base = 0; + size_t top = controlledJoints - 1; + + size_t wbase = base; + size_t wtop = top; + SubDevice* tmpDevice = device.getSubdevice(0); + + std::string subDevName((partName + "_" + subdevice)); + if (!tmpDevice->configure(wbase, wtop, base, top, controlledJoints, subDevName, getId())) { + yCError(CONTROLBOARD) << "Configure of subdevice ret false"; + return false; + } + + for (size_t j = 0; j < controlledJoints; j++) { + device.lut[j].deviceEntry = 0; + device.lut[j].offset = j; + } + + + if (!device.subdevices[0].attach(subDeviceOwned, subDevName)) { + return false; + } + + // initialization. + RPC_parser.initialize(); + updateAxisName(); + calculateMaxNumOfJointsInDevices(); + return true; +} + +void ControlBoardWrapper::calculateMaxNumOfJointsInDevices() +{ + device.maxNumOfJointsInDevices = 0; + + for (size_t d = 0; d < device.subdevices.size(); d++) { + SubDevice* p = device.getSubdevice(d); + if (p->totalAxis > device.maxNumOfJointsInDevices) { + device.maxNumOfJointsInDevices = p->totalAxis; + } + } +} + +bool ControlBoardWrapper::updateAxisName() +{ + // If attached device has axisName update the internal values, otherwise keep the on from wrapper + // config file, if any. + // IMPORTANT!! This function has to be called BEFORE the thread starts, because if ROS is enabled, + // the name has to be correct right from the first message!! + + // FOR THE FUTURE: this double version will be dropped because it'll create confusion. Only the names + // from the motionControl device will be considered good + + // no need to update this variable if we are not using ROS. YARP RPC will always call the sudevice. + if (useROS == ROS_disabled) { + return true; + } + + std::string tmp; + // I need a temporary vector because if I'm wrapping more than one subdevice, and one of them + // does not have the axesName, then I'd stick with the old names from wrpper config file, if any. + std::vector tmpVect; + bool ret = true; + + tmpVect.clear(); + for (size_t i = 0; i < controlledJoints; i++) { + if ((ret = getAxisName(i, tmp) && ret)) { + std::string tmp2(tmp); + tmpVect.push_back(tmp2); + } + } + + if (ret) { + if (!jointNames.empty()) { + yCWarning(CONTROLBOARD) << "Found 2 instance of jointNames parameter: one in the wrapper [ROS] group and another one in the subdevice, the latter one will be used."; + std::string fullNames; + for (size_t i = 0; i < controlledJoints; i++) { + fullNames.append(tmpVect[i]); + } + } + + jointNames.clear(); + jointNames = tmpVect; + } else { + if (jointNames.empty()) { + yCError(CONTROLBOARD) << "Joint names were not found! they are mandatory when using ROS topic"; + return false; + } + + yCWarning(CONTROLBOARD) << "\n" << + "************************************************************************************************** \n" << + "* Joint names for ROS topic were found in the [ROS] group in the wrapper config file for\n" << + "* '" << partName << "' device.\n" << + "* They should be in the MotionControl device(s) instead. Please update the config files.\n" << + "**************************************************************************************************"; + } + return true; +} + + +bool ControlBoardWrapper::attachAll(const PolyDriverList& polylist) +{ + //check if we already instantiated a subdevice previously + if (ownDevices) { + return false; + } + + for (int p = 0; p < polylist.size(); p++) { + // look if we have to attach to a calibrator + std::string tmpKey = polylist[p]->key; + if (tmpKey == "Calibrator" || tmpKey == "calibrator") { + // Set the IRemoteCalibrator interface, the wrapper must point to the calibrator device + yarp::dev::IRemoteCalibrator* calibrator; + polylist[p]->poly->view(calibrator); + + IRemoteCalibrator::setCalibratorDevice(calibrator); + continue; + } + + // find appropriate entry in list of subdevices and attach + size_t k = 0; + for (k = 0; k < device.subdevices.size(); k++) { + if (device.subdevices[k].id == tmpKey) { + if (!device.subdevices[k].attach(polylist[p]->poly, tmpKey)) { + yCError(CONTROLBOARD, "Attach to subdevice %s failed", polylist[p]->key.c_str()); + return false; + } + } + } + } + + //check if all devices are attached to the driver + bool ready = true; + for (auto& subdevice : device.subdevices) { + if (!subdevice.isAttached()) { + yCError(CONTROLBOARD, "Device %s was not found in the list passed to attachAll", subdevice.id.c_str()); + ready = false; + } + } + + if (!ready) { + yCError(CONTROLBOARD, "AttachAll failed, some subdevice was not found or its attach failed"); + std::stringstream ss; + for (int p = 0; p < polylist.size(); p++) { + ss << polylist[p]->key.c_str() << " "; + } + yCError(CONTROLBOARD, "List of devices keys passed to attachAll: %s", ss.str().c_str()); + return false; + } + + // initialization. + RPC_parser.initialize(); + + updateAxisName(); + calculateMaxNumOfJointsInDevices(); + PeriodicThread::setPeriod(period); + return PeriodicThread::start(); +} + +bool ControlBoardWrapper::detachAll() +{ + //check if we already instantiated a subdevice previously + if (ownDevices) { + return false; + } + + if (yarp::os::PeriodicThread::isRunning()) { + yarp::os::PeriodicThread::stop(); + } + + int devices = device.subdevices.size(); + + for (int k = 0; k < devices; k++) { + SubDevice* sub = device.getSubdevice(k); + if (sub) { + sub->detach(); + } + } + + IRemoteCalibrator::releaseCalibratorDevice(); + return true; +} + +void ControlBoardWrapper::run() +{ + // check we are not overflowing with input messages + if (inputStreamingPort.getPendingReads() >= 20) { + yCWarning(CONTROLBOARD) << "Number of streaming input messages to be read is " << inputStreamingPort.getPendingReads() << " and can overflow"; + } + + // Small optimization: Avoid to call getEncoders twice, one for YARP port + // and again for ROS topic. + // + // Calling getStuff here on ros_struct because it is a class member, hence + // always available. In the other side, to have the yarp struct to write into + // it will be rewuired to call port.prepare, that it is something I should + // not do if the wrapper is in ROS_only configuration. + + bool positionsOk = getEncodersTimed(ros_struct.position.data(), times.data()); + bool speedsOk = getEncoderSpeeds(ros_struct.velocity.data()); + bool torqueOk = getTorques(ros_struct.effort.data()); + + // Update the port envelope time by averaging all timestamps + timeMutex.lock(); + time.update(std::accumulate(times.begin(), times.end(), 0.0) / controlledJoints); + yarp::os::Stamp averageTime = time; + timeMutex.unlock(); + + if (useROS != ROS_only) { + // handle stateExt first + jointData& yarp_struct = extendedOutputState_buffer.get(); + + yarp_struct.jointPosition.resize(controlledJoints); + yarp_struct.jointVelocity.resize(controlledJoints); + yarp_struct.jointAcceleration.resize(controlledJoints); + yarp_struct.motorPosition.resize(controlledJoints); + yarp_struct.motorVelocity.resize(controlledJoints); + yarp_struct.motorAcceleration.resize(controlledJoints); + yarp_struct.torque.resize(controlledJoints); + yarp_struct.pwmDutycycle.resize(controlledJoints); + yarp_struct.current.resize(controlledJoints); + yarp_struct.controlMode.resize(controlledJoints); + yarp_struct.interactionMode.resize(controlledJoints); + + // Get already stored data from before. This is to avoid a double call to HW device, + // which may require more time. // + yarp_struct.jointPosition_isValid = positionsOk; + std::copy(ros_struct.position.begin(), ros_struct.position.end(), yarp_struct.jointPosition.begin()); + + yarp_struct.jointVelocity_isValid = speedsOk; + std::copy(ros_struct.velocity.begin(), ros_struct.velocity.end(), yarp_struct.jointVelocity.begin()); + + yarp_struct.torque_isValid = torqueOk; + std::copy(ros_struct.effort.begin(), ros_struct.effort.end(), yarp_struct.torque.begin()); + + // Get remaining data from HW + yarp_struct.jointAcceleration_isValid = getEncoderAccelerations(yarp_struct.jointAcceleration.data()); + yarp_struct.motorPosition_isValid = getMotorEncoders(yarp_struct.motorPosition.data()); + yarp_struct.motorVelocity_isValid = getMotorEncoderSpeeds(yarp_struct.motorVelocity.data()); + yarp_struct.motorAcceleration_isValid = getMotorEncoderAccelerations(yarp_struct.motorAcceleration.data()); + yarp_struct.pwmDutycycle_isValid = getDutyCycles(yarp_struct.pwmDutycycle.data()); + yarp_struct.current_isValid = ControlBoardWrapperCommon::getCurrents(yarp_struct.current.data()); + yarp_struct.controlMode_isValid = getControlModes(yarp_struct.controlMode.data()); + yarp_struct.interactionMode_isValid = getInteractionModes(reinterpret_cast(yarp_struct.interactionMode.data())); + + extendedOutputStatePort.setEnvelope(averageTime); + extendedOutputState_buffer.write(); + + // handle state:o + yarp::sig::Vector& v = outputPositionStatePort.prepare(); + v.resize(controlledJoints); + std::copy(yarp_struct.jointPosition.begin(), yarp_struct.jointPosition.end(), v.begin()); + + outputPositionStatePort.setEnvelope(averageTime); + outputPositionStatePort.write(); + } + + if (useROS != ROS_disabled) { + // Data from HW have been gathered few lines before + JointTypeEnum jType; + for (size_t i = 0; i < controlledJoints; i++) { + getJointType(i, jType); + if (jType == VOCAB_JOINTTYPE_REVOLUTE) { + ros_struct.position[i] = convertDegreesToRadians(ros_struct.position[i]); + ros_struct.velocity[i] = convertDegreesToRadians(ros_struct.velocity[i]); + } + } + + ros_struct.name = jointNames; + + ros_struct.header.seq = rosMsgCounter++; + ros_struct.header.stamp = averageTime.getTime(); + + rosPublisherPort.write(ros_struct); + } +} diff --git a/src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.h b/src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.h new file mode 100644 index 00000000000..b6c9c39ebd5 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/ControlBoardWrapper.h @@ -0,0 +1,300 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H +#define YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H + + +// ControlBoardWrapper +// A modified version of the remote control board class +// which remaps joints, it can also merge networks into a single part. + + +#include +#include + +#include +#include +#include +#include +#include + +#include // struct for YARP extended port + +#include +#include +#include + +// ROS state publisher +#include +#include +#include +#include + + +#include "ControlBoardWrapperPidControl.h" +#include "ControlBoardWrapperPositionControl.h" +#include "ControlBoardWrapperPositionDirect.h" +#include "ControlBoardWrapperVelocityControl.h" +#include "ControlBoardWrapperEncodersTimed.h" +#include "ControlBoardWrapperMotor.h" +#include "ControlBoardWrapperMotorEncoders.h" +#include "ControlBoardWrapperAmplifierControl.h" +#include "ControlBoardWrapperControlLimits.h" +#include "ControlBoardWrapperRemoteCalibrator.h" +#include "ControlBoardWrapperControlCalibration.h" +#include "ControlBoardWrapperTorqueControl.h" +#include "ControlBoardWrapperImpedanceControl.h" +#include "ControlBoardWrapperControlMode.h" +#include "ControlBoardWrapperAxisInfo.h" +#include "ControlBoardWrapperInteractionMode.h" +#include "ControlBoardWrapperRemoteVariables.h" +#include "ControlBoardWrapperPWMControl.h" +#include "ControlBoardWrapperCurrentControl.h" +#include "ControlBoardWrapperPreciselyTimed.h" + +#include "SubDevice.h" +#include "StreamingMessagesParser.h" +#include "RPCMessagesParser.h" + + +#ifdef MSVC + #pragma warning(disable:4355) +#endif + +/* + * To optimize memory allocation, for group of joints we can have one mem reserver for rpc port + * and on e for streaming. The size could be numOfSubDevices*maxNumOfjointForSubdevice. + * (we could also use the actual joint number for each subdevice using a for loop). TODO + */ + +class CommandsHelper; +class SubDevice; + + +/** + * @ingroup dev_impl_wrapper dev_impl_deprecated + * + * \brief `controlboardwrapper2` *deprecated*: An updated version of the controlBoard network wrapper. + * It can merge together more than one control board device, or use only a + * portion of it by remapping functionality. + * Allows also deferred attach/detach of a subdevice. + * + * \section controlboardwrapper2_device_parameters Description of input parameters + * + * Parameters required by this device are: + * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | + * |:--------------:|:--------------:|:-------:|:--------------:|:-------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| + * | name | - | string | - | - | Yes | full name of the port opened by the device, like /robotName/part/ | MUST start with a '/' character | + * | period | - | int | ms | 20 | No | refresh period of the broadcasted values in ms | optional, default 20ms | + * | subdevice | - | string | - | - | alternative to netwok group | name of the subdevice to instantiate | when used, parameters for the subdevice must be provided as well | + * | networks | - | group | - | - | alternative to subdevice | this is expected to be a group parameter in xml format, a list in .ini file format. SubParameter are mandatory if this is used| - | + * | - | networkName_1 | 4 * int | joint number | - | if networks is used | describe how to match subdevice_1 joints with the wrapper joints. First 2 numbers indicate first/last wrapper joint, last 2 numbers are subdevice first/last joint | The joints are intended to be consequent | + * | - | ... | 4 * int | joint number | - | if networks is used | same as above | The joints are intended to be consequent | + * | - | networkName_n | 4 * int | joint number | - | if networks is used | same as above | The joints are intended to be consequent | + * | - | joints | int | - | - | if networks is used | total number of joints handled by the wrapper | MUST match the sum of joints from all the networks | + * | ROS | - | group | - | - | No | Group containing parameter for ROS topic initialization | if missing, it is assumed to not use ROS topics | + * | - | useROS | string | true/false/only| - | if ROS group is present | set 'true' to have both yarp ports and ROS topic, set 'only' to have only ROS topic and no yarp port| - | + * | - | ROS_topicName | string | - | - | if ROS group is present | set the name for ROS topic | must start with a leading '/' | + * | - | ROS_nodeName | string | - | - | if ROS group is present | set the name for ROS node | must start with a leading '/' | + * | - | jointNames | string | - | - | deprecated | joints names are now got from attached motionControl device | names order must match with the joint order, from 0 to N | + * + * ROS message type used is sensor_msgs/JointState.msg (http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html) + * Some example of configuration files: + * + * Configuration file using .ini format, using subdevice keyword. + * + * \code{.unparsed} + * device controlboardwrapper2 + * subdevice fakebot + * name /icub/head + * + * ** parameter for 'fakebot' subdevice follows here ** + * ... + * \endcode + * + * XML format, using 'networks' keyword. This file is meant to be used in junction with yarprobotinterface executable, + * therefore has an addictional section at the end. + * + * \code{.xml} + * + * + * (0 3 0 3) + * (4 6 0 2) + * + * + * 20 + * /icub/left_arm + * 7 + * + * + * + * + * + * + * left_upper_arm_mc + * left_lower_arm_mc + * + * + * + * \endcode + * + * Configuration file using .ini format, using network keyword + * + * \code{.unparsed} + * device controlboardwrapper2 + * name /robotName/partName + * period 10 + * networks (net_larm net_lhand) + * joints 16 + * net_larm 0 3 0 3 + * net_lhand 4 6 0 2 + * \endcode + * + * Configuration for ROS topic using .ini format + * \code{.unparsed} + * [ROS] + * useROS true + * ROS_topicName /JointState + * ROS_nodeName /robotPublisher + * jointNames r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow r_wrist_prosup r_wrist_pitch r_wrist_yaw + * \endcode + * + * Configuration for ROS topic using .xml format + * \code{.unparsed} + * + * true // use 'only' if you want only ROS topic and NOT yarp port + * /JointState + * /robotPublisher + * r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow r_wrist_prosup r_wrist_pitch r_wrist_yaw + * + * \endcode + */ + +class ControlBoardWrapper : + public yarp::dev::DeprecatedDeviceDriver, + public yarp::os::PeriodicThread, + public yarp::dev::IMultipleWrapper, + virtual public ControlBoardWrapperCommon, + public ControlBoardWrapperPidControl, + public ControlBoardWrapperPositionControl, + public ControlBoardWrapperPositionDirect, + public ControlBoardWrapperVelocityControl, + public ControlBoardWrapperEncodersTimed, + public ControlBoardWrapperMotor, + public ControlBoardWrapperMotorEncoders, + public ControlBoardWrapperAmplifierControl, + public ControlBoardWrapperControlLimits, + public ControlBoardWrapperRemoteCalibrator, + public ControlBoardWrapperControlCalibration, + public ControlBoardWrapperTorqueControl, + public ControlBoardWrapperImpedanceControl, + public ControlBoardWrapperControlMode, + public ControlBoardWrapperAxisInfo, + public ControlBoardWrapperPreciselyTimed, + public ControlBoardWrapperInteractionMode, + public ControlBoardWrapperRemoteVariables, + public ControlBoardWrapperPWMControl, + public ControlBoardWrapperCurrentControl +{ +private: + std::string rootName; + + bool checkPortName(yarp::os::Searchable ¶ms); + + yarp::rosmsg::sensor_msgs::JointState ros_struct; + + yarp::os::BufferedPort outputPositionStatePort; // Port /state:o streaming out the encoder positions + yarp::os::BufferedPort inputStreamingPort; // Input streaming port for high frequency commands + yarp::os::Port inputRPCPort; // Input RPC port for set/get remote calls + yarp::sig::Vector times; // time for each joint + + // Buffer associated to the extendedOutputStatePort port; in this case we will use the type generated + // from the YARP .thrift file + yarp::os::PortWriterBuffer extendedOutputState_buffer; + yarp::os::Port extendedOutputStatePort; // Port /stateExt:o streaming out the struct with the robot data + + // ROS state publisher + ROSTopicUsageType useROS {ROS_disabled}; // decide if open ROS topic or not + std::vector jointNames; // name of the joints + std::string rosNodeName; // name of the rosNode + std::string rosTopicName; // name of the rosTopic + yarp::os::Node *rosNode {nullptr}; // add a ROS node + yarp::os::NetUint32 rosMsgCounter {0}; // incremental counter in the ROS message + yarp::os::PortWriterBuffer rosOutputState_buffer; // Buffer associated to the ROS topic + yarp::os::Publisher rosPublisherPort; // Dedicated ROS topic publisher + + yarp::os::PortReaderBuffer inputRPC_buffer; // Buffer associated to the inputRPCPort port + RPCMessagesParser RPC_parser; // Message parser associated to the inputRPCPort port + StreamingMessagesParser streaming_parser; // Message parser associated to the inputStreamingPort port + + static constexpr double default_period = 0.02; // s + double period {default_period}; + + yarp::os::Bottle getOptions(); + bool updateAxisName(); + bool checkROSParams(yarp::os::Searchable &config); + bool initialize_ROS(); + bool initialize_YARP(yarp::os::Searchable &prop); + void cleanup_yarpPorts(); + + // Default usage + // Open the wrapper only, the attach method needs to be called before using it + bool openDeferredAttach(yarp::os::Property& prop); + + // For the simulator, if a subdevice parameter is given to the wrapper, it will + // open it and attach to it immediately. + yarp::dev::PolyDriver *subDeviceOwned {nullptr}; + bool openAndAttachSubDevice(yarp::os::Property& prop); + + bool ownDevices {true}; + + void calculateMaxNumOfJointsInDevices(); + +public: + ControlBoardWrapper(); + ControlBoardWrapper(const ControlBoardWrapper&) = delete; + ControlBoardWrapper(ControlBoardWrapper&&) = delete; + ControlBoardWrapper& operator=(const ControlBoardWrapper&) = delete; + ControlBoardWrapper& operator=(ControlBoardWrapper&&) = delete; + ~ControlBoardWrapper() override; + + + /* Return id of this device */ + std::string getId() + { + return partName; + } + + /** + * Close the device driver by deallocating all resources and closing ports. + * @return true if successful or false otherwise. + */ + bool close() override; + + + /** + * Open the device driver. + * @param prop is a Searchable object which contains the parameters. + * Allowed parameters are: + * - name to specify the prefix of the port names. + * - subdevice [optional] if specified, the openAndAttachSubDevice will be + * called, otherwise openDeferredAttach is called. + * and all parameters required by the wrapper. + */ + bool open(yarp::os::Searchable& prop) override; + + bool detachAll() override; + + bool attachAll(const yarp::dev::PolyDriverList &l) override; + + /** + * The thread main loop deals with writing on ports here. + */ + void run() override; +}; + + +#endif // YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H diff --git a/src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.cpp b/src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.cpp new file mode 100644 index 00000000000..2cbd41db98c --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.cpp @@ -0,0 +1,536 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "ControlBoard_nws_yarp.h" + +#include "ControlBoardLogComponent.h" +#include "RPCMessagesParser.h" +#include "StreamingMessagesParser.h" + +#include +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::sig; +using yarp::dev::impl::jointData; + +ControlBoard_nws_yarp::ControlBoard_nws_yarp() : + yarp::os::PeriodicThread(default_period) +{ +} + +void ControlBoard_nws_yarp::closePorts() +{ + inputRPCPort.interrupt(); + inputRPCPort.removeCallbackLock(); + inputRPCPort.close(); + + inputStreamingPort.interrupt(); + inputStreamingPort.close(); + + outputPositionStatePort.interrupt(); + outputPositionStatePort.close(); + + extendedOutputStatePort.interrupt(); + extendedOutputStatePort.close(); +} + +bool ControlBoard_nws_yarp::close() +{ + // Ensure that the device is not running + if (isRunning()) { + stop(); + } + + closeDevice(); + closePorts(); + + return true; +} + +bool ControlBoard_nws_yarp::checkPortName(Searchable& params) +{ + // find name as port name (similar both in new and old policy) + if (!params.check("name")) { + yCError(CONTROLBOARD) << + "*************************************************************************************\n" + "* controlBoard_nws_yarp missing mandatory parameter 'name' for port name, usage is: *\n" + "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n" + "*************************************************************************************"; + return false; + } + + partName = params.find("name").asString(); + if (partName[0] != '/') { + yCWarning(CONTROLBOARD) << + "*************************************************************************************\n" + "* controlBoard_nws_yarp 'name' parameter for port name does not follow convention, *\n" + "* it MUST start with a leading '/' since it is used as the full prefix port name *\n" + "* name: full port prefix name with leading '/', e.g. /robotName/part/ *\n" + "* A temporary automatic fix will be done for you, but please fix your config file *\n" + "*************************************************************************************"; + rootName = "/" + partName; + } else { + rootName = partName; + } + + return true; +} + + +bool ControlBoard_nws_yarp::open(Searchable& config) +{ + Property prop; + prop.fromString(config.toString()); + + if (!checkPortName(config)) { + yCError(CONTROLBOARD) << "'portName' was not correctly set, check you r configuration file"; + return false; + } + + // Check parameter, so if both are present we use the correct one + if (prop.check("period")) { + if (!prop.find("period").isFloat64()) { + yCError(CONTROLBOARD) << "'period' parameter is not a double value"; + return false; + } + period = prop.find("period").asFloat64(); + if (period <= 0) { + yCError(CONTROLBOARD) << "'period' parameter is not valid, read value is" << period; + return false; + } + } else { + yCDebug(CONTROLBOARD) << "'period' parameter missing, using default thread period = 0.02s"; + period = default_period; + } + + // Check if we need to create subdevice or if they are + // passed later on through attachAll() + if (prop.check("subdevice")) { + prop.setMonitor(config.getMonitor()); + if (!openAndAttachSubDevice(prop)) { + yCError(CONTROLBOARD, "Error while opening subdevice"); + return false; + } + subdevice_ready = true; + } + + rootName = prop.check("rootName", Value("/"), "starting '/' if needed.").asString(); + partName = prop.check("name", Value("controlboard"), "prefix for port names").asString(); + rootName += (partName); + if (rootName.find("//") != std::string::npos) { + rootName.replace(rootName.find("//"), 2, "/"); + } + + // Open ports, then attach the readers or callbacks + if (!inputRPCPort.open((rootName + "/rpc:i"))) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/rpc:i"; + closePorts(); + return false; + } + inputRPCPort.setReader(RPC_parser); + inputRPC_buffer.attach(inputRPCPort); + RPC_parser.attach(inputRPC_buffer); + + if (!inputStreamingPort.open(rootName + "/command:i")) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/rpc:i"; + closePorts(); + return false; + } + inputStreamingPort.setStrict(); + inputStreamingPort.useCallback(streaming_parser); + + if (!outputPositionStatePort.open(rootName + "/state:o")) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/state:o"; + closePorts(); + return false; + } + + // Extended output state port + if (!extendedOutputStatePort.open(rootName + "/stateExt:o")) { + yCError(CONTROLBOARD) << "Error opening port " << rootName + "/state:o"; + closePorts(); + return false; + } + extendedOutputState_buffer.attach(extendedOutputStatePort); + + // In case attach is not deferred and the controlboard already owns a valid device + // we can start the thread. Otherwise this will happen when attachAll is called + if (subdevice_ready) { + setPeriod(period); + if (!start()) { + yCError(CONTROLBOARD) << "Error starting thread"; + return false; + } + } + + return true; +} + + +// For the simulator, if a subdevice parameter is given to the wrapper, it will +// open it and attach to immediately. +bool ControlBoard_nws_yarp::openAndAttachSubDevice(Property& prop) +{ + Property p; + auto* subDeviceOwned = new PolyDriver; + p.fromString(prop.toString()); + + std::string subdevice = prop.find("subdevice").asString(); + p.setMonitor(prop.getMonitor(), subdevice.c_str()); // pass on any monitoring + p.unput("device"); + p.put("device", subdevice); // subdevice was already checked before + + // if errors occurred during open, quit here. + yCDebug(CONTROLBOARD, "opening subdevice"); + subDeviceOwned->open(p); + + if (!subDeviceOwned->isValid()) { + yCError(CONTROLBOARD, "opening subdevice... FAILED"); + return false; + } + + return setDevice(subDeviceOwned, true); +} + + +bool ControlBoard_nws_yarp::setDevice(yarp::dev::DeviceDriver* driver, bool owned) +{ + // Save the pointer and subDeviceOwned + subdevice_ptr = driver; + subdevice_owned = owned; + + // yarp::dev::IJointFault* iJointFault{nullptr}; + subdevice_ptr->view(iJointFault); + if (!iJointFault) { + yCWarning(CONTROLBOARD, "Part <%s>: iJointFault interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IPidControl* iPidControl{nullptr}; + subdevice_ptr->view(iPidControl); + if (!iPidControl) { + yCWarning(CONTROLBOARD, "Part <%s>: IPidControl interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IPositionControl* iPositionControl{nullptr}; + subdevice_ptr->view(iPositionControl); + if (!iPositionControl) { + yCError(CONTROLBOARD, "Part <%s>: IPositionControl interface was not found in subdevice. Quitting", partName.c_str()); + return false; + } + + // yarp::dev::IPositionDirect* iPositionDirect{nullptr}; + subdevice_ptr->view(iPositionDirect); + if (!iPositionDirect) { + yCWarning(CONTROLBOARD, "Part <%s>: IPositionDirect interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IVelocityControl* iVelocityControl{nullptr}; + subdevice_ptr->view(iVelocityControl); + if (!iVelocityControl) { + yCError(CONTROLBOARD, "Part <%s>: IVelocityControl interface was not found in subdevice. Quitting", partName.c_str()); + return false; + } + + // yarp::dev::IEncodersTimed* iEncodersTimed{nullptr}; + subdevice_ptr->view(iEncodersTimed); + if (!iEncodersTimed) { + yCError(CONTROLBOARD, "Part <%s>: IEncodersTimed interface was not found in subdevice. Quitting", partName.c_str()); + return false; + } + + // yarp::dev::IMotor* iMotor{nullptr}; + subdevice_ptr->view(iMotor); + if (!iMotor) { + yCWarning(CONTROLBOARD, "Part <%s>: IMotor interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IMotorEncoders* iMotorEncoders{nullptr}; + subdevice_ptr->view(iMotorEncoders); + if (!iMotorEncoders) { + yCWarning(CONTROLBOARD, "Part <%s>: IMotorEncoders interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IAmplifierControl* iAmplifierControl{nullptr}; + subdevice_ptr->view(iAmplifierControl); + if (!iAmplifierControl) { + yCWarning(CONTROLBOARD, "Part <%s>: IAmplifierControl interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IControlLimits* iControlLimits{nullptr}; + subdevice_ptr->view(iControlLimits); + if (!iControlLimits) { + yCWarning(CONTROLBOARD, "Part <%s>: IControlLimits interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IControlCalibration* iControlCalibration{nullptr}; + subdevice_ptr->view(iControlCalibration); + if (!iControlCalibration) { + yCWarning(CONTROLBOARD, "Part <%s>: IControlCalibration interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::ITorqueControl* iTorqueControl{nullptr}; + subdevice_ptr->view(iTorqueControl); + if (!iTorqueControl) { + yCWarning(CONTROLBOARD, "Part <%s>: ITorqueControl interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IImpedanceControl* iImpedanceControl{nullptr}; + subdevice_ptr->view(iImpedanceControl); + if (!iImpedanceControl) { + yCWarning(CONTROLBOARD, "Part <%s>: IImpedanceControl interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IControlMode* iControlMode{nullptr}; + subdevice_ptr->view(iControlMode); + if (!iControlMode) { + yCWarning(CONTROLBOARD, "Part <%s>: IControlMode interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IAxisInfo* iAxisInfo{nullptr}; + subdevice_ptr->view(iAxisInfo); + if (!iAxisInfo) { + yCWarning(CONTROLBOARD, "Part <%s>: IAxisInfo interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IPreciselyTimed* iPreciselyTimed{nullptr}; + subdevice_ptr->view(iPreciselyTimed); + if (!iPreciselyTimed) { + yCWarning(CONTROLBOARD, "Part <%s>: IPreciselyTimed interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IInteractionMode* iInteractionMode{nullptr}; + subdevice_ptr->view(iInteractionMode); + if (!iInteractionMode) { + yCWarning(CONTROLBOARD, "Part <%s>: IInteractionMode interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IRemoteVariables* iRemoteVariables{nullptr}; + subdevice_ptr->view(iRemoteVariables); + if (!iRemoteVariables) { + yCWarning(CONTROLBOARD, "Part <%s>: IRemoteVariables interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::IPWMControl* iPWMControl{nullptr}; + subdevice_ptr->view(iPWMControl); + if (!iPWMControl) { + yCWarning(CONTROLBOARD, "Part <%s>: IPWMControl interface was not found in subdevice.", partName.c_str()); + } + + // yarp::dev::ICurrentControl* iCurrentControl{nullptr}; + subdevice_ptr->view(iCurrentControl); + if (!iCurrentControl) { + yCWarning(CONTROLBOARD, "Part <%s>: ICurrentControl interface was not found in subdevice.", partName.c_str()); + } + + + // Get the number of controlled joints + int tmp_axes; + if (!iPositionControl->getAxes(&tmp_axes)) { + yCError(CONTROLBOARD) << "Part <%s>: Failed to get axes number for subdevice " << partName.c_str(); + return false; + } + if (tmp_axes <= 0) { + yCError(CONTROLBOARD, "Part <%s>: attached device has an invalid number of joints (%d)", partName.c_str(), tmp_axes); + return false; + } + subdevice_joints = static_cast(tmp_axes); + times.resize(subdevice_joints); + + // Initialization + streaming_parser.init(subdevice_ptr); + streaming_parser.initialize(); + + RPC_parser.init(subdevice_ptr); + RPC_parser.initialize(); + + return true; +} + +void ControlBoard_nws_yarp::closeDevice() +{ + // Reset callbacks + streaming_parser.reset(); + RPC_parser.reset(); + + // If the subdevice is owned, close and delete the device + if (subdevice_owned) { + subdevice_ptr->close(); + delete subdevice_ptr; + } + subdevice_ptr = nullptr; + subdevice_owned = false; + subdevice_joints = 0; + subdevice_ready = false; + + times.clear(); + + // Clear all interfaces + iPidControl = nullptr; + iPositionControl = nullptr; + iPositionDirect = nullptr; + iVelocityControl = nullptr; + iEncodersTimed = nullptr; + iMotor = nullptr; + iMotorEncoders = nullptr; + iAmplifierControl = nullptr; + iControlLimits = nullptr; + iControlCalibration = nullptr; + iTorqueControl = nullptr; + iImpedanceControl = nullptr; + iControlMode = nullptr; + iAxisInfo = nullptr; + iPreciselyTimed = nullptr; + iInteractionMode = nullptr; + iRemoteVariables = nullptr; + iPWMControl = nullptr; + iCurrentControl = nullptr; + iJointFault = nullptr; +} + +bool ControlBoard_nws_yarp::attach(yarp::dev::PolyDriver* poly) +{ + // Check if we already instantiated a subdevice previously + if (subdevice_ready) { + return false; + } + + if (!setDevice(poly, false)) { + return false; + } + + setPeriod(period); + if (!start()) { + yCError(CONTROLBOARD) << "Error starting thread"; + return false; + } + + return true; +} + +bool ControlBoard_nws_yarp::detach() +{ + //check if we already instantiated a subdevice previously + if (subdevice_owned) { + return false; + } + + // Ensure that the device is not running + if (isRunning()) { + stop(); + } + + closeDevice(); + + return true; +} + +void ControlBoard_nws_yarp::run() +{ + // check we are not overflowing with input messages + constexpr int reads_for_warning = 20; + if (inputStreamingPort.getPendingReads() >= reads_for_warning) { + yCWarning(CONTROLBOARD) << "Number of streaming input messages to be read is " << inputStreamingPort.getPendingReads() << " and can overflow"; + } + + // handle stateExt first + jointData& data = extendedOutputState_buffer.get(); + + data.jointPosition.resize(subdevice_joints); + data.jointVelocity.resize(subdevice_joints); + data.jointAcceleration.resize(subdevice_joints); + data.motorPosition.resize(subdevice_joints); + data.motorVelocity.resize(subdevice_joints); + data.motorAcceleration.resize(subdevice_joints); + data.torque.resize(subdevice_joints); + data.pwmDutycycle.resize(subdevice_joints); + data.current.resize(subdevice_joints); + data.controlMode.resize(subdevice_joints); + data.interactionMode.resize(subdevice_joints); + + // Get data from HW + if (iEncodersTimed) { + data.jointPosition_isValid = iEncodersTimed->getEncodersTimed(data.jointPosition.data(), times.data()); + data.jointVelocity_isValid = iEncodersTimed->getEncoderSpeeds(data.jointVelocity.data()); + data.jointAcceleration_isValid = iEncodersTimed->getEncoderAccelerations(data.jointAcceleration.data()); + } else { + data.jointPosition_isValid = false; + data.jointVelocity_isValid = false; + data.jointAcceleration_isValid = false; + } + + if (iMotorEncoders) { + data.motorPosition_isValid = iMotorEncoders->getMotorEncoders(data.motorPosition.data()); + data.motorVelocity_isValid = iMotorEncoders->getMotorEncoderSpeeds(data.motorVelocity.data()); + data.motorAcceleration_isValid = iMotorEncoders->getMotorEncoderAccelerations(data.motorAcceleration.data()); + } else { + data.motorPosition_isValid = false; + data.motorVelocity_isValid = false; + data.motorAcceleration_isValid = false; + } + + if (iTorqueControl) { + data.torque_isValid = iTorqueControl->getTorques(data.torque.data()); + } else { + data.torque_isValid = false; + } + + if (iPWMControl) { + data.pwmDutycycle_isValid = iPWMControl->getDutyCycles(data.pwmDutycycle.data()); + } else { + data.pwmDutycycle_isValid = false; + } + + if (iCurrentControl) { + data.current_isValid = iCurrentControl->getCurrents(data.current.data()); + } else if (iAmplifierControl) { + data.current_isValid = iAmplifierControl->getCurrents(data.current.data()); + } else { + data.current_isValid = false; + } + + if (iControlMode) { + data.controlMode_isValid = iControlMode->getControlModes(data.controlMode.data()); + } else { + data.controlMode_isValid = false; + } + + if (iInteractionMode) { + data.interactionMode_isValid = iInteractionMode->getInteractionModes(reinterpret_cast(data.interactionMode.data())); + } else { + data.interactionMode_isValid = false; + } + + // Check if the encoders timestamps are consistent. + for (double tt : times) + { + if (std::abs(times[0] - tt) > 1.0) + { + yCError(CONTROLBOARD, "Encoder Timestamps are not consistent! Data will not be published."); + yarp::sig::Vector _data(subdevice_joints); + return; + } + } + + // Update the port envelope time by averaging all timestamps + time.update(std::accumulate(times.begin(), times.end(), 0.0) / subdevice_joints); + yarp::os::Stamp averageTime = time; + + extendedOutputStatePort.setEnvelope(averageTime); + extendedOutputState_buffer.write(); + + // handle state:o + yarp::sig::Vector& v = outputPositionStatePort.prepare(); + v.resize(subdevice_joints); + std::copy(data.jointPosition.begin(), data.jointPosition.end(), v.begin()); + + outputPositionStatePort.setEnvelope(averageTime); + outputPositionStatePort.write(); +} diff --git a/src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.h b/src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.h new file mode 100644 index 00000000000..72b59d0fc73 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/ControlBoard_nws_yarp.h @@ -0,0 +1,143 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef YARP_DEV_CONTROLBOARD_NWS_YARP_H +#define YARP_DEV_CONTROLBOARD_NWS_YARP_H + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include + +#include "StreamingMessagesParser.h" +#include "RPCMessagesParser.h" + + +/** + * @ingroup dev_impl_nws_yarp + * + * \brief `controlBoard_nws_yarp`: A controlBoard network wrapper server for YARP. + * + * \section controlBoard_nws_yarp_device_parameters Description of input parameters + * + * Parameters required by this device are: + * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | + * |:--------------:|:--------------:|:-------:|:--------------:|:-------------:|:--------------------------: |:-----------------------------------------------------------------:|:-----:| + * | name | - | string | - | - | Yes | full name of the port opened by the device, like /robotName/part/ | MUST start with a '/' character | + * | period | - | double | s | 0.02 | No | refresh period of the broadcasted values in s | optional, default 0.02s period| + * | subdevice | - | string | - | - | No | name of the subdevice to instantiate | when used, parameters for the subdevice must be provided as well | + */ + +class ControlBoard_nws_yarp : + public yarp::dev::DeviceDriver, + public yarp::os::PeriodicThread, + public yarp::dev::WrapperSingle +{ +private: + std::string rootName; + + bool checkPortName(yarp::os::Searchable ¶ms); + + yarp::os::BufferedPort outputPositionStatePort; // Port /state:o streaming out the encoder positions + yarp::os::BufferedPort inputStreamingPort; // Input streaming port for high frequency commands + yarp::os::Port inputRPCPort; // Input RPC port for set/get remote calls + yarp::os::Port extendedOutputStatePort; // Port /stateExt:o streaming out the struct with the robot data + + yarp::os::PortWriterBuffer extendedOutputState_buffer; // Buffer associated to the extendedOutputStatePort port + yarp::os::PortReaderBuffer inputRPC_buffer; // Buffer associated to the inputRPCPort port + + RPCMessagesParser RPC_parser; // Message parser associated to the inputRPCPort port + StreamingMessagesParser streaming_parser; // Message parser associated to the inputStreamingPort port + + static constexpr double default_period = 0.02; // s + double period {default_period}; + + std::string partName; // to open ports and print more detailed debug messages + yarp::sig::Vector times; // time for each joint + yarp::os::Stamp time; // envelope to attach to the state port + + yarp::dev::DeviceDriver* subdevice_ptr{nullptr}; + bool subdevice_owned = false; + size_t subdevice_joints {0}; + bool subdevice_ready = false; + + yarp::dev::IPidControl* iPidControl{nullptr}; + yarp::dev::IPositionControl* iPositionControl{nullptr}; + yarp::dev::IPositionDirect* iPositionDirect{nullptr}; + yarp::dev::IVelocityControl* iVelocityControl{nullptr}; + yarp::dev::IEncodersTimed* iEncodersTimed{nullptr}; + yarp::dev::IMotor* iMotor{nullptr}; + yarp::dev::IMotorEncoders* iMotorEncoders{nullptr}; + yarp::dev::IAmplifierControl* iAmplifierControl{nullptr}; + yarp::dev::IControlLimits* iControlLimits{nullptr}; + yarp::dev::IControlCalibration* iControlCalibration{nullptr}; + yarp::dev::ITorqueControl* iTorqueControl{nullptr}; + yarp::dev::IImpedanceControl* iImpedanceControl{nullptr}; + yarp::dev::IControlMode* iControlMode{nullptr}; + yarp::dev::IAxisInfo* iAxisInfo{nullptr}; + yarp::dev::IPreciselyTimed* iPreciselyTimed{nullptr}; + yarp::dev::IInteractionMode* iInteractionMode{nullptr}; + yarp::dev::IRemoteVariables* iRemoteVariables{nullptr}; + yarp::dev::IPWMControl* iPWMControl{nullptr}; + yarp::dev::ICurrentControl* iCurrentControl{nullptr}; + yarp::dev::IJointFault* iJointFault{ nullptr }; + + bool setDevice(yarp::dev::DeviceDriver* device, bool owned); + bool openAndAttachSubDevice(yarp::os::Property& prop); + + void closeDevice(); + void closePorts(); + +public: + ControlBoard_nws_yarp(); + ControlBoard_nws_yarp(const ControlBoard_nws_yarp&) = delete; + ControlBoard_nws_yarp(ControlBoard_nws_yarp&&) = delete; + ControlBoard_nws_yarp& operator=(const ControlBoard_nws_yarp&) = delete; + ControlBoard_nws_yarp& operator=(ControlBoard_nws_yarp&&) = delete; + ~ControlBoard_nws_yarp() override = default; + + // yarp::dev::DeviceDriver + bool close() override; + bool open(yarp::os::Searchable& prop) override; + + // yarp::dev::WrapperSingle + bool attach(yarp::dev::PolyDriver* poly) override; + bool detach() override; + + // yarp::os::PeriodicThread + void run() override; +}; + + +#endif // YARP_DEV_CONTROLBOARD_NWS_YARP_H diff --git a/src/devices/ControlBoard_nws_yarp/RPCMessagesParser.cpp b/src/devices/ControlBoard_nws_yarp/RPCMessagesParser.cpp new file mode 100644 index 00000000000..35a04cbae87 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/RPCMessagesParser.cpp @@ -0,0 +1,2555 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "RPCMessagesParser.h" + +#include + +#include "ControlBoardLogComponent.h" +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::dev::impl; +using namespace yarp::sig; + + +inline void appendTimeStamp(Bottle& bot, Stamp& st) +{ + int count = st.getCount(); + double time = st.getTime(); + bot.addVocab32(VOCAB_TIMESTAMP); + bot.addInt32(count); + bot.addFloat64(time); +} + +void RPCMessagesParser::handleProtocolVersionRequest(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok) +{ + if (cmd.get(0).asVocab32() != VOCAB_GET) { + *rec = false; + *ok = false; + return; + } + + response.addVocab32(VOCAB_PROTOCOL_VERSION); + response.addInt32(PROTOCOL_VERSION_MAJOR); + response.addInt32(PROTOCOL_VERSION_MINOR); + response.addInt32(PROTOCOL_VERSION_TWEAK); + + *rec = true; + *ok = true; +} + +void RPCMessagesParser::handleImpedanceMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling IImpedance message"); + if (!rpc_IImpedance) { + yCError(CONTROLBOARD, "I do not have a valid interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + *ok = false; + switch (code) { + case VOCAB_SET: { + yCTrace(CONTROLBOARD, "handleImpedanceMsg::VOCAB_SET command"); + switch (cmd.get(2).asVocab32()) { + case VOCAB_IMP_PARAM: { + Bottle* b = cmd.get(4).asList(); + if (b != nullptr) { + double stiff = b->get(0).asFloat64(); + double damp = b->get(1).asFloat64(); + *ok = rpc_IImpedance->setImpedance(cmd.get(3).asInt32(), stiff, damp); + *rec = true; + } + } break; + case VOCAB_IMP_OFFSET: { + Bottle* b = cmd.get(4).asList(); + if (b != nullptr) { + double offs = b->get(0).asFloat64(); + *ok = rpc_IImpedance->setImpedanceOffset(cmd.get(3).asInt32(), offs); + *rec = true; + } + } break; + } + } break; + case VOCAB_GET: { + double stiff = 0; + double damp = 0; + double offs = 0; + yCTrace(CONTROLBOARD, "handleImpedanceMsg::VOCAB_GET command"); + + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + switch (cmd.get(2).asVocab32()) { + case VOCAB_IMP_PARAM: { + *ok = rpc_IImpedance->getImpedance(cmd.get(3).asInt32(), &stiff, &damp); + Bottle& b = response.addList(); + b.addFloat64(stiff); + b.addFloat64(damp); + *rec = true; + } break; + case VOCAB_IMP_OFFSET: { + *ok = rpc_IImpedance->getImpedanceOffset(cmd.get(3).asInt32(), &offs); + Bottle& b = response.addList(); + b.addFloat64(offs); + *rec = true; + } break; + case VOCAB_LIMITS: { + double min_stiff = 0; + double max_stiff = 0; + double min_damp = 0; + double max_damp = 0; + *ok = rpc_IImpedance->getCurrentImpedanceLimit(cmd.get(3).asInt32(), &min_stiff, &max_stiff, &min_damp, &max_damp); + Bottle& b = response.addList(); + b.addFloat64(min_stiff); + b.addFloat64(max_stiff); + b.addFloat64(min_damp); + b.addFloat64(max_damp); + *rec = true; + } break; + } + } + lastRpcStamp.update(); + appendTimeStamp(response, lastRpcStamp); + break; // case VOCAB_GET + default: + { + *rec = false; + } break; + } +} + +void RPCMessagesParser::handleJointFaultMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok) +{ + //handle here messages about IControlMode interface + int code = cmd.get(0).asVocab32(); + *ok = true; + *rec = true; //or false + + switch (code) + { + case VOCAB_GET: + yCTrace(CONTROLBOARD, "GET command"); + + int method = cmd.get(2).asVocab32(); + + switch (method) + { + case VOCAB_JF_GET_JOINTFAULT: + yCTrace(CONTROLBOARD, "getJointFault"); + int axis = cmd.get(3).asInt32(); + int faultcode=0; + std::string faultmessage; + if (rpc_IJointFault) + { + *ok = rpc_IJointFault->getLastJointFault(axis, faultcode, faultmessage); + *rec = true; + } + response.addVocab32(VOCAB_IS); + response.addInt32(faultcode); + response.addString(faultmessage); + + yCTrace(CONTROLBOARD, "Returning %d %s", faultcode, faultmessage.c_str()); + *rec = true; + break; + } + + break; + } +} + +void RPCMessagesParser::handleControlModeMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling IControlMode message"); + if (!(rpc_iCtrlMode)) { + yCError(CONTROLBOARD, "I do not have a valid iControlMode interface"); + *ok = false; + return; + } + + //handle here messages about IControlMode interface + int code = cmd.get(0).asVocab32(); + *ok = true; + *rec = true; //or false + + switch (code) { + case VOCAB_SET: { + yCTrace(CONTROLBOARD, "handleControlModeMsg::VOCAB_SET command"); + + int method = cmd.get(2).asVocab32(); + + switch (method) { + case VOCAB_CM_CONTROL_MODE: { + int axis = cmd.get(3).asInt32(); + yCTrace(CONTROLBOARD) << "got VOCAB_CM_CONTROL_MODE"; + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, cmd.get(4).asVocab32()); + } else { + yCError(CONTROLBOARD) << "Unable to handle setControlMode request! This should not happen!"; + *rec = false; + } + } break; + + case VOCAB_CM_CONTROL_MODE_GROUP: { + int n_joints = cmd.get(3).asInt32(); + Bottle& jList = *(cmd.get(4).asList()); + Bottle& modeList = *(cmd.get(5).asList()); + + int* js = new int[n_joints]; + int* modes = new int[n_joints]; + + for (int i = 0; i < n_joints; i++) { + js[i] = jList.get(i).asInt32(); + } + + for (int i = 0; i < n_joints; i++) { + modes[i] = modeList.get(i).asVocab32(); + } + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlModes(n_joints, js, modes); + } else { + *rec = false; + *ok = false; + } + delete[] js; + delete[] modes; + } break; + + case VOCAB_CM_CONTROL_MODES: { + yarp::os::Bottle* modeList; + modeList = cmd.get(3).asList(); + + if (modeList->size() != controlledJoints) { + yCError(CONTROLBOARD, "received an invalid setControlMode message. Size of vector doesn´t match the number of controlled joints"); + *ok = false; + break; + } + int* modes = new int[controlledJoints]; + for (size_t i = 0; i < controlledJoints; i++) { + modes[i] = modeList->get(i).asVocab32(); + } + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlModes(modes); + } else { + *rec = false; + *ok = false; + } + delete[] modes; + } break; + + default: + { + // if I´m here, someone is probably sending command using the old interface. + // try to be compatible as much as I can + + yCError(CONTROLBOARD) << " Error, received a set control mode message using a legacy version, trying to be handle the message anyway " + << " but please update your client to be compatible with the IControlMode interface"; + + yCTrace(CONTROLBOARD) << " cmd.get(4).asVocab32() is " << Vocab32::decode(cmd.get(4).asVocab32()); + int axis = cmd.get(3).asInt32(); + + switch (cmd.get(4).asVocab32()) { + case VOCAB_CM_POSITION: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_POSITION); + } + break; + + case VOCAB_CM_POSITION_DIRECT: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_POSITION_DIRECT); + } else { + *rec = false; + *ok = false; + } + break; + + + case VOCAB_CM_VELOCITY: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_VELOCITY); + } + break; + + case VOCAB_CM_TORQUE: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_TORQUE); + } + break; + + case VOCAB_CM_IMPEDANCE_POS: + yCError(CONTROLBOARD) << "The 'impedancePosition' control mode is deprecated. \nUse setInteractionMode(axis, VOCAB_IM_COMPLIANT) + setControlMode(axis, VOCAB_CM_POSITION) instead"; + break; + + case VOCAB_CM_IMPEDANCE_VEL: + yCError(CONTROLBOARD) << "The 'impedanceVelocity' control mode is deprecated. \nUse setInteractionMode(axis, VOCAB_IM_COMPLIANT) + setControlMode(axis, VOCAB_CM_VELOCITY) instead"; + break; + + case VOCAB_CM_PWM: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_PWM); + } else { + *rec = false; + *ok = false; + } + break; + + case VOCAB_CM_CURRENT: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_CURRENT); + } else { + *rec = false; + *ok = false; + } + break; + + case VOCAB_CM_MIXED: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_MIXED); + } else { + *rec = false; + *ok = false; + } + break; + + case VOCAB_CM_FORCE_IDLE: + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->setControlMode(axis, VOCAB_CM_FORCE_IDLE); + } else { + *rec = false; + *ok = false; + } + break; + + default: + yCError(CONTROLBOARD, "SET unknown controlMode : %s ", cmd.toString().c_str()); + *ok = false; + *rec = false; + break; + } + } break; // close default case + } + } break; // close SET case + + case VOCAB_GET: { + yCTrace(CONTROLBOARD, "GET command"); + + int method = cmd.get(2).asVocab32(); + + switch (method) { + + case VOCAB_CM_CONTROL_MODES: { + yCTrace(CONTROLBOARD, "getControlModes"); + int* p = new int[controlledJoints]; + for (size_t i = 0; i < controlledJoints; ++i) { + p[i] = -1; + } + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->getControlModes(p); + } + + response.addVocab32(VOCAB_IS); + response.addVocab32(VOCAB_CM_CONTROL_MODES); + + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addVocab32(p[i]); + } + delete[] p; + + *rec = true; + } break; + + case VOCAB_CM_CONTROL_MODE: { + yCTrace(CONTROLBOARD, "getControlMode"); + + int p = -1; + int axis = cmd.get(3).asInt32(); + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->getControlMode(axis, &p); + } + + response.addVocab32(VOCAB_IS); + response.addInt32(axis); + response.addVocab32(p); + + yCTrace(CONTROLBOARD, "Returning %d", p); + *rec = true; + } break; + + case VOCAB_CM_CONTROL_MODE_GROUP: { + yCTrace(CONTROLBOARD, "getControlMode group"); + + int n_joints = cmd.get(3).asInt32(); + Bottle& lIn = *(cmd.get(4).asList()); + + int* js = new int[n_joints]; + int* modes = new int[n_joints]; + for (int i = 0; i < n_joints; i++) { + js[i] = lIn.get(i).asInt32(); + modes[i] = -1; + } + if (rpc_iCtrlMode) { + *ok = rpc_iCtrlMode->getControlModes(n_joints, js, modes); + } else { + *rec = false; + *ok = false; + } + + response.addVocab32(VOCAB_IS); + response.addVocab32(VOCAB_CM_CONTROL_MODE_GROUP); + Bottle& b = response.addList(); + for (int i = 0; i < n_joints; i++) { + b.addVocab32(modes[i]); + } + + delete[] js; + delete[] modes; + + *rec = true; + } break; + + default: + yCError(CONTROLBOARD, "received a GET ICONTROLMODE command not understood"); + break; + } + } + + lastRpcStamp.update(); + appendTimeStamp(response, lastRpcStamp); + break; // case VOCAB_GET + + default: + { + *rec = false; + } break; + } +} + + +void RPCMessagesParser::handleTorqueMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling ITorqueControl message"); + + if (!rpc_ITorque) { + yCError(CONTROLBOARD, "Error, I do not have a valid ITorque interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + switch (code) { + case VOCAB_SET: { + *rec = true; + yCTrace(CONTROLBOARD, "set command received"); + + switch (cmd.get(2).asVocab32()) { + case VOCAB_REF: { + *ok = rpc_ITorque->setRefTorque(cmd.get(3).asInt32(), cmd.get(4).asFloat64()); + } break; + + case VOCAB_MOTOR_PARAMS: { + yarp::dev::MotorTorqueParameters params; + int joint = cmd.get(3).asInt32(); + Bottle* b = cmd.get(4).asList(); + + if (b == nullptr) { + break; + } + + if (b->size() != 8) { + yCError(CONTROLBOARD, "received a SET VOCAB_MOTOR_PARAMS command not understood, size != 8"); + break; + } + + params.bemf = b->get(0).asFloat64(); + params.bemf_scale = b->get(1).asFloat64(); + params.ktau = b->get(2).asFloat64(); + params.ktau_scale = b->get(3).asFloat64(); + params.viscousPos = b->get(4).asFloat64(); + params.viscousNeg = b->get(5).asFloat64(); + params.coulombPos = b->get(6).asFloat64(); + params.coulombNeg = b->get(7).asFloat64(); + + *ok = rpc_ITorque->setMotorTorqueParams(joint, params); + } break; + + case VOCAB_REFS: { + Bottle* b = cmd.get(3).asList(); + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs == controlledJoints) { + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + *ok = rpc_ITorque->setRefTorques(p); + delete[] p; + } + } break; + + case VOCAB_TORQUE_MODE: { + if (rpc_iCtrlMode) { + int* modes = new int[controlledJoints]; + for (size_t i = 0; i < controlledJoints; i++) { + modes[i] = VOCAB_CM_TORQUE; + } + *ok = rpc_iCtrlMode->setControlModes(modes); + delete[] modes; + } else { + *ok = false; + } + } break; + } + } break; + + case VOCAB_GET: { + *rec = true; + yCTrace(CONTROLBOARD, "get command received"); + double dtmp = 0.0; + double dtmp2 = 0.0; + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + + switch (cmd.get(2).asVocab32()) { + case VOCAB_AXES: { + int tmp; + *ok = rpc_ITorque->getAxes(&tmp); + response.addInt32(tmp); + } break; + + case VOCAB_TRQ: { + *ok = rpc_ITorque->getTorque(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_MOTOR_PARAMS: { + yarp::dev::MotorTorqueParameters params; + int joint = cmd.get(3).asInt32(); + + // get the data + *ok = rpc_ITorque->getMotorTorqueParams(joint, ¶ms); + + // convert it back to yarp message + Bottle& b = response.addList(); + + b.addFloat64(params.bemf); + b.addFloat64(params.bemf_scale); + b.addFloat64(params.ktau); + b.addFloat64(params.ktau_scale); + b.addFloat64(params.viscousPos); + b.addFloat64(params.viscousNeg); + b.addFloat64(params.coulombPos); + b.addFloat64(params.coulombNeg); + } break; + case VOCAB_RANGE: { + *ok = rpc_ITorque->getTorqueRange(cmd.get(3).asInt32(), &dtmp, &dtmp2); + response.addFloat64(dtmp); + response.addFloat64(dtmp2); + } break; + + case VOCAB_TRQS: { + auto* p = new double[controlledJoints]; + *ok = rpc_ITorque->getTorques(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_RANGES: { + auto* p1 = new double[controlledJoints]; + auto* p2 = new double[controlledJoints]; + *ok = rpc_ITorque->getTorqueRanges(p1, p2); + Bottle& b1 = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b1.addFloat64(p1[i]); + } + Bottle& b2 = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b2.addFloat64(p2[i]); + } + delete[] p1; + delete[] p2; + } break; + + case VOCAB_REFERENCE: { + *ok = rpc_ITorque->getRefTorque(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_REFERENCES: { + auto* p = new double[controlledJoints]; + *ok = rpc_ITorque->getRefTorques(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + } + } + lastRpcStamp.update(); + appendTimeStamp(response, lastRpcStamp); + break; // case VOCAB_GET + } +} + +void RPCMessagesParser::handleInteractionModeMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok) +{ + yCTrace(CONTROLBOARD, "\nHandling IInteractionMode message"); + if (!rpc_IInteract) { + yCError(CONTROLBOARD, "Error I do not have a valid IInteractionMode interface"); + *ok = false; + return; + } + + yCTrace(CONTROLBOARD) << "received command: " << cmd.toString(); + + int action = cmd.get(0).asVocab32(); + + switch (action) { + case VOCAB_SET: { + switch (cmd.get(2).asVocab32()) { + yarp::os::Bottle* jointList; + yarp::os::Bottle* modeList; + yarp::dev::InteractionModeEnum* modes; + + case VOCAB_INTERACTION_MODE: { + *ok = rpc_IInteract->setInteractionMode(cmd.get(3).asInt32(), static_cast(cmd.get(4).asVocab32())); + } break; + + case VOCAB_INTERACTION_MODE_GROUP: { + yCTrace(CONTROLBOARD) << "CBW.h set interactionMode GROUP"; + + auto n_joints = static_cast(cmd.get(3).asInt32()); + jointList = cmd.get(4).asList(); + modeList = cmd.get(5).asList(); + if ((jointList->size() != n_joints) || (modeList->size() != n_joints)) { + yCWarning(CONTROLBOARD, "Received an invalid setInteractionMode message. Size of vectors doesn´t match"); + *ok = false; + break; + } + int* joints = new int[n_joints]; + modes = new yarp::dev::InteractionModeEnum[n_joints]; + for (size_t i = 0; i < n_joints; i++) { + joints[i] = jointList->get(i).asInt32(); + modes[i] = static_cast(modeList->get(i).asVocab32()); + yCTrace(CONTROLBOARD) << "CBW.cpp received vocab " << yarp::os::Vocab32::decode(modes[i]); + } + *ok = rpc_IInteract->setInteractionModes(n_joints, joints, modes); + delete[] joints; + delete[] modes; + + } break; + + case VOCAB_INTERACTION_MODES: { + yCTrace(CONTROLBOARD) << "CBW.c set interactionMode ALL"; + + modeList = cmd.get(3).asList(); + if (modeList->size() != controlledJoints) { + yCWarning(CONTROLBOARD, "Received an invalid setInteractionMode message. Size of vector doesn´t match the number of controlled joints"); + *ok = false; + break; + } + modes = new yarp::dev::InteractionModeEnum[controlledJoints]; + for (size_t i = 0; i < controlledJoints; i++) { + modes[i] = static_cast(modeList->get(i).asVocab32()); + } + *ok = rpc_IInteract->setInteractionModes(modes); + delete[] modes; + } break; + + default: + { + yCWarning(CONTROLBOARD, "Error while Handling IInteractionMode message, SET command not understood %s", cmd.get(2).asString().c_str()); + *ok = false; + } break; + } + *rec = true; //or false + } break; + + case VOCAB_GET: { + yarp::os::Bottle* jointList; + + switch (cmd.get(2).asVocab32()) { + case VOCAB_INTERACTION_MODE: { + yarp::dev::InteractionModeEnum mode; + *ok = rpc_IInteract->getInteractionMode(cmd.get(3).asInt32(), &mode); + response.addVocab32(mode); + yCTrace(CONTROLBOARD) << " resp is " << response.toString(); + } break; + + case VOCAB_INTERACTION_MODE_GROUP: { + yarp::dev::InteractionModeEnum* modes; + + int n_joints = cmd.get(3).asInt32(); + jointList = cmd.get(4).asList(); + if (jointList->size() != static_cast(n_joints)) { + yCError(CONTROLBOARD, "Received an invalid getInteractionMode message. Size of vectors doesn´t match"); + *ok = false; + break; + } + int* joints = new int[n_joints]; + modes = new yarp::dev::InteractionModeEnum[n_joints]; + for (int i = 0; i < n_joints; i++) { + joints[i] = jointList->get(i).asInt32(); + } + *ok = rpc_IInteract->getInteractionModes(n_joints, joints, modes); + + Bottle& c = response.addList(); + for (int i = 0; i < n_joints; i++) { + c.addVocab32(modes[i]); + } + + yCTrace(CONTROLBOARD, "got response bottle: %s", response.toString().c_str()); + + delete[] joints; + delete[] modes; + } break; + + case VOCAB_INTERACTION_MODES: { + yarp::dev::InteractionModeEnum* modes; + modes = new yarp::dev::InteractionModeEnum[controlledJoints]; + + *ok = rpc_IInteract->getInteractionModes(modes); + + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addVocab32(modes[i]); + } + + yCTrace(CONTROLBOARD, "got response bottle: %s", response.toString().c_str()); + + delete[] modes; + } break; + } + lastRpcStamp.update(); + appendTimeStamp(response, lastRpcStamp); + } break; // case VOCAB_GET + + default: + yCError(CONTROLBOARD, "Error while Handling IInteractionMode message, command was not SET nor GET"); + *ok = false; + break; + } +} + +void RPCMessagesParser::handleCurrentMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling ICurrentControl message"); + + if (!rpc_ICurrent) { + yCError(CONTROLBOARD, "I do not have a valid ICurrentControl interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + int action = cmd.get(2).asVocab32(); + + *ok = false; + *rec = true; + switch (code) { + case VOCAB_SET: { + switch (action) { + case VOCAB_CURRENT_REF: { + yCError(CONTROLBOARD, "VOCAB_CURRENT_REF methods is implemented as streaming"); + *ok = false; + } break; + + case VOCAB_CURRENT_REFS: { + yCError(CONTROLBOARD, "VOCAB_CURRENT_REFS methods is implemented as streaming"); + *ok = false; + } break; + + case VOCAB_CURRENT_REF_GROUP: { + yCError(CONTROLBOARD, "VOCAB_CURRENT_REF_GROUP methods is implemented as streaming"); + *ok = false; + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received"; + *rec = false; + *ok = false; + } break; + } + } break; + + case VOCAB_GET: { + *rec = true; + yCTrace(CONTROLBOARD, "get command received"); + double dtmp = 0.0; + double dtmp2 = 0.0; + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + + switch (action) { + case VOCAB_CURRENT_REF: { + *ok = rpc_ICurrent->getRefCurrent(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_CURRENT_REFS: { + auto* p = new double[controlledJoints]; + *ok = rpc_ICurrent->getRefCurrents(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_CURRENT_RANGE: { + + *ok = rpc_ICurrent->getCurrentRange(cmd.get(3).asInt32(), &dtmp, &dtmp2); + response.addFloat64(dtmp); + response.addFloat64(dtmp2); + } break; + + case VOCAB_CURRENT_RANGES: { + auto* p1 = new double[controlledJoints]; + auto* p2 = new double[controlledJoints]; + *ok = rpc_ICurrent->getCurrentRanges(p1, p2); + Bottle& b1 = response.addList(); + Bottle& b2 = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b1.addFloat64(p1[i]); + } + for (size_t i = 0; i < controlledJoints; i++) { + b2.addFloat64(p2[i]); + } + delete[] p1; + delete[] p2; + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received"; + *rec = false; + *ok = false; + } break; + } + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handleCurrentMsg message received"; + *rec = false; + *ok = false; + } break; + } +} + +void RPCMessagesParser::handlePidMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling IPidControl message"); + + if (!rpc_IPid) { + yCError(CONTROLBOARD, "I do not have a valid IPidControl interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + int action = cmd.get(2).asVocab32(); + auto pidtype = static_cast(cmd.get(3).asVocab32()); + + *ok = false; + *rec = true; + switch (code) { + case VOCAB_SET: { + *rec = true; + yCTrace(CONTROLBOARD, "set command received"); + + switch (action) { + case VOCAB_OFFSET: { + double v; + int j = cmd.get(4).asInt32(); + v = cmd.get(5).asFloat64(); + *ok = rpc_IPid->setPidOffset(pidtype, j, v); + } break; + + case VOCAB_PID: { + Pid p; + int j = cmd.get(4).asInt32(); + Bottle* b = cmd.get(5).asList(); + + if (b == nullptr) { + break; + } + + p.kp = b->get(0).asFloat64(); + p.kd = b->get(1).asFloat64(); + p.ki = b->get(2).asFloat64(); + p.max_int = b->get(3).asFloat64(); + p.max_output = b->get(4).asFloat64(); + p.offset = b->get(5).asFloat64(); + p.scale = b->get(6).asFloat64(); + p.stiction_up_val = b->get(7).asFloat64(); + p.stiction_down_val = b->get(8).asFloat64(); + p.kff = b->get(9).asFloat64(); + *ok = rpc_IPid->setPid(pidtype, j, p); + } break; + + case VOCAB_PIDS: { + Bottle* b = cmd.get(4).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs == controlledJoints) { + Pid* p = new Pid[njs]; + + bool allOK = true; + + for (size_t i = 0; i < njs; i++) { + Bottle* c = b->get(i).asList(); + if (c != nullptr) { + p[i].kp = c->get(0).asFloat64(); + p[i].kd = c->get(1).asFloat64(); + p[i].ki = c->get(2).asFloat64(); + p[i].max_int = c->get(3).asFloat64(); + p[i].max_output = c->get(4).asFloat64(); + p[i].offset = c->get(5).asFloat64(); + p[i].scale = c->get(6).asFloat64(); + p[i].stiction_up_val = c->get(7).asFloat64(); + p[i].stiction_down_val = c->get(8).asFloat64(); + p[i].kff = c->get(9).asFloat64(); + } else { + allOK = false; + } + } + if (allOK) { + *ok = rpc_IPid->setPids(pidtype, p); + } else { + *ok = false; + } + + delete[] p; + } + } break; + + case VOCAB_REF: { + *ok = rpc_IPid->setPidReference(pidtype, cmd.get(4).asInt32(), cmd.get(5).asFloat64()); + } break; + + case VOCAB_REFS: { + Bottle* b = cmd.get(4).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs == controlledJoints) { + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + *ok = rpc_IPid->setPidReferences(pidtype, p); + delete[] p; + } + } break; + + case VOCAB_LIM: { + *ok = rpc_IPid->setPidErrorLimit(pidtype, cmd.get(4).asInt32(), cmd.get(5).asFloat64()); + } break; + + case VOCAB_LIMS: { + Bottle* b = cmd.get(4).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs == controlledJoints) { + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + *ok = rpc_IPid->setPidErrorLimits(pidtype, p); + delete[] p; + } + } break; + + case VOCAB_RESET: { + *ok = rpc_IPid->resetPid(pidtype, cmd.get(4).asInt32()); + } break; + + case VOCAB_DISABLE: { + *ok = rpc_IPid->disablePid(pidtype, cmd.get(4).asInt32()); + } break; + + case VOCAB_ENABLE: { + *ok = rpc_IPid->enablePid(pidtype, cmd.get(4).asInt32()); + } break; + } + } break; + + case VOCAB_GET: { + *rec = true; + yCTrace(CONTROLBOARD, "get command received"); + double dtmp = 0.0; + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + + switch (action) { + case VOCAB_LIMS: { + auto* p = new double[controlledJoints]; + *ok = rpc_IPid->getPidErrorLimits(pidtype, p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_ENABLE: { + bool booltmp = false; + *ok = rpc_IPid->isPidEnabled(pidtype, cmd.get(4).asInt32(), &booltmp); + response.addInt32(booltmp); + } break; + + case VOCAB_ERR: { + *ok = rpc_IPid->getPidError(pidtype, cmd.get(4).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_ERRS: { + auto* p = new double[controlledJoints]; + *ok = rpc_IPid->getPidErrors(pidtype, p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_OUTPUT: { + *ok = rpc_IPid->getPidOutput(pidtype, cmd.get(4).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_OUTPUTS: { + auto* p = new double[controlledJoints]; + *ok = rpc_IPid->getPidOutputs(pidtype, p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_PID: { + Pid p; + *ok = rpc_IPid->getPid(pidtype, cmd.get(4).asInt32(), &p); + Bottle& b = response.addList(); + b.addFloat64(p.kp); + b.addFloat64(p.kd); + b.addFloat64(p.ki); + b.addFloat64(p.max_int); + b.addFloat64(p.max_output); + b.addFloat64(p.offset); + b.addFloat64(p.scale); + b.addFloat64(p.stiction_up_val); + b.addFloat64(p.stiction_down_val); + b.addFloat64(p.kff); + } break; + + case VOCAB_PIDS: { + Pid* p = new Pid[controlledJoints]; + *ok = rpc_IPid->getPids(pidtype, p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + Bottle& c = b.addList(); + c.addFloat64(p[i].kp); + c.addFloat64(p[i].kd); + c.addFloat64(p[i].ki); + c.addFloat64(p[i].max_int); + c.addFloat64(p[i].max_output); + c.addFloat64(p[i].offset); + c.addFloat64(p[i].scale); + c.addFloat64(p[i].stiction_up_val); + c.addFloat64(p[i].stiction_down_val); + c.addFloat64(p[i].kff); + } + delete[] p; + } break; + + case VOCAB_REFERENCE: { + *ok = rpc_IPid->getPidReference(pidtype, cmd.get(4).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_REFERENCES: { + auto* p = new double[controlledJoints]; + *ok = rpc_IPid->getPidReferences(pidtype, p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_LIM: { + *ok = rpc_IPid->getPidErrorLimit(pidtype, cmd.get(4).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + } + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received"; + *rec = false; + *ok = false; + } break; + } +} + +void RPCMessagesParser::handlePWMMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling IPWMControl message"); + + if (!rpc_IPWM) { + yCError(CONTROLBOARD, "I do not have a valid IPWMControl interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + int action = cmd.get(2).asVocab32(); + + *ok = false; + *rec = true; + switch (code) { + case VOCAB_SET: { + *rec = true; + yCTrace(CONTROLBOARD, "set command received"); + + switch (action) { + case VOCAB_PWMCONTROL_REF_PWM: { + //handled as streaming! + yCError(CONTROLBOARD) << "VOCAB_PWMCONTROL_REF_PWM handled as straming"; + *ok = false; + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received"; + *ok = false; + } break; + } + } break; + + case VOCAB_GET: { + yCTrace(CONTROLBOARD, "get command received"); + *rec = true; + double dtmp = 0.0; + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + + switch (action) { + case VOCAB_PWMCONTROL_REF_PWM: { + *ok = rpc_IPWM->getRefDutyCycle(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_PWMCONTROL_REF_PWMS: { + auto* p = new double[controlledJoints]; + *ok = rpc_IPWM->getRefDutyCycles(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_PWMCONTROL_PWM_OUTPUT: { + *ok = rpc_IPWM->getDutyCycle(cmd.get(3).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_PWMCONTROL_PWM_OUTPUTS: { + auto* p = new double[controlledJoints]; + *ok = rpc_IPWM->getRefDutyCycles(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received"; + *ok = false; + } break; + } + } break; + + default: + { + yCError(CONTROLBOARD) << "Unknown handlePWMMsg message received"; + *rec = false; + *ok = false; + } break; + } +} + +void RPCMessagesParser::handleRemoteVariablesMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling IRemoteCalibrator message"); + + if (!rpc_IRemoteCalibrator) { + yCError(CONTROLBOARD, "I do not have a valid IRemoteCalibrator interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + int action = cmd.get(2).asVocab32(); + + *ok = false; + *rec = true; + switch (code) { + case VOCAB_SET: { + switch (action) { + case VOCAB_VARIABLE: { + Bottle btail = cmd.tail().tail().tail().tail(); // remove the first four elements + std::string s = btail.toString(); + *ok = rpc_IVar->setRemoteVariable(cmd.get(3).asString(), btail); + } break; + + default: + { + *rec = false; + *ok = false; + } break; + } + } break; + + case VOCAB_GET: { + yCTrace(CONTROLBOARD, "get command received"); + + response.clear(); + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + Bottle btmp; + + switch (action) { + case VOCAB_VARIABLE: { + *ok = rpc_IVar->getRemoteVariable(cmd.get(3).asString(), btmp); + Bottle& b = response.addList(); + b = btmp; + } break; + + case VOCAB_LIST_VARIABLES: { + *ok = rpc_IVar->getRemoteVariablesList(&btmp); + Bottle& b = response.addList(); + b = btmp; + } break; + } + } + } //end get/set switch +} + +void RPCMessagesParser::handleRemoteCalibratorMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok) +{ + yCTrace(CONTROLBOARD, "Handling IRemoteCalibrator message"); + + if (!rpc_IRemoteCalibrator) { + yCError(CONTROLBOARD, "I do not have a valid IRemoteCalibrator interface"); + *ok = false; + return; + } + + int code = cmd.get(0).asVocab32(); + int action = cmd.get(2).asVocab32(); + + *ok = false; + *rec = true; + switch (code) { + case VOCAB_SET: { + switch (action) { + case VOCAB_CALIBRATE_SINGLE_JOINT: { + yCDebug(CONTROLBOARD) << "cmd is " << cmd.toString() << " joint is " << cmd.get(3).asInt32(); + yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter"); + *ok = rpc_IRemoteCalibrator->calibrateSingleJoint(cmd.get(3).asInt32()); + } break; + + case VOCAB_CALIBRATE_WHOLE_PART: { + yCTrace(CONTROLBOARD, "Calling calibrate whole part"); + *ok = rpc_IRemoteCalibrator->calibrateWholePart(); + } break; + + case VOCAB_HOMING_SINGLE_JOINT: { + yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter"); + *ok = rpc_IRemoteCalibrator->homingSingleJoint(cmd.get(3).asInt32()); + } break; + + case VOCAB_HOMING_WHOLE_PART: { + yCDebug(CONTROLBOARD) << "Received homing whole part"; + yCTrace(CONTROLBOARD, "Calling calibrate whole part"); + *ok = rpc_IRemoteCalibrator->homingWholePart(); + } break; + + case VOCAB_PARK_SINGLE_JOINT: { + yCTrace(CONTROLBOARD, "Calling calibrate joint with no parameter"); + *ok = rpc_IRemoteCalibrator->parkSingleJoint(cmd.get(3).asInt32()); + } break; + + case VOCAB_PARK_WHOLE_PART: { + yCTrace(CONTROLBOARD, "Calling calibrate whole part"); + *ok = rpc_IRemoteCalibrator->parkWholePart(); + } break; + + case VOCAB_QUIT_CALIBRATE: { + yCTrace(CONTROLBOARD, "Calling quit calibrate"); + *ok = rpc_IRemoteCalibrator->quitCalibrate(); + } break; + + case VOCAB_QUIT_PARK: { + yCTrace(CONTROLBOARD, "Calling quit park"); + *ok = rpc_IRemoteCalibrator->quitPark(); + } break; + + default: + { + *rec = false; + *ok = false; + } break; + } + } break; + + case VOCAB_GET: { + response.clear(); + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + + switch (action) { + case VOCAB_IS_CALIBRATOR_PRESENT: { + bool tmp; + yCTrace(CONTROLBOARD, "Calling VOCAB_IS_CALIBRATOR_PRESENT"); + *ok = rpc_IRemoteCalibrator->isCalibratorDevicePresent(&tmp); + response.addInt32(tmp); + } break; + } + } + } //end get/set switch +} + + +// rpc callback +bool RPCMessagesParser::respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& response) +{ + bool ok = false; + bool rec = false; // Tells if the command is recognized! + + yCTrace(CONTROLBOARD, "command received: %s", cmd.toString().c_str()); + + int code = cmd.get(0).asVocab32(); + + if (cmd.size() < 2) { + ok = false; + } else { + switch (cmd.get(1).asVocab32()) { + case VOCAB_PID: + handlePidMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_TORQUE: + handleTorqueMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_IJOINTFAULT: + handleJointFaultMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_ICONTROLMODE: + handleControlModeMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_IMPEDANCE: + handleImpedanceMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_INTERFACE_INTERACTION_MODE: + handleInteractionModeMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_PROTOCOL_VERSION: + handleProtocolVersionRequest(cmd, response, &rec, &ok); + break; + + case VOCAB_REMOTE_CALIBRATOR_INTERFACE: + handleRemoteCalibratorMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_REMOTE_VARIABILE_INTERFACE: + handleRemoteVariablesMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_CURRENTCONTROL_INTERFACE: + handleCurrentMsg(cmd, response, &rec, &ok); + break; + + case VOCAB_PWMCONTROL_INTERFACE: + handlePWMMsg(cmd, response, &rec, &ok); + break; + + default: + // fallback for old interfaces with no specific name + switch (code) { + case VOCAB_CALIBRATE_JOINT: { + if (!rpc_Icalib) { ok = false; break; } + rec = true; + yCTrace(CONTROLBOARD, "Calling calibrate joint"); + + int j = cmd.get(1).asInt32(); + int ui = cmd.get(2).asInt32(); + double v1 = cmd.get(3).asFloat64(); + double v2 = cmd.get(4).asFloat64(); + double v3 = cmd.get(5).asFloat64(); + if (rpc_Icalib == nullptr) { + yCError(CONTROLBOARD, "Sorry I don't have a IControlCalibration2 interface"); + } else { + ok = rpc_Icalib->calibrateAxisWithParams(j, ui, v1, v2, v3); + } + } break; + + case VOCAB_CALIBRATE_JOINT_PARAMS: { + if (!rpc_Icalib) { ok = false; break; } + rec = true; + yCTrace(CONTROLBOARD, "Calling calibrate joint"); + + int j = cmd.get(1).asInt32(); + CalibrationParameters params; + params.type = cmd.get(2).asInt32(); + params.param1 = cmd.get(3).asFloat64(); + params.param2 = cmd.get(4).asFloat64(); + params.param3 = cmd.get(5).asFloat64(); + params.param4 = cmd.get(6).asFloat64(); + if (rpc_Icalib == nullptr) { + yCError(CONTROLBOARD, "Sorry I don't have a IControlCalibration2 interface"); + } else { + ok = rpc_Icalib->setCalibrationParameters(j, params); + } + } break; + + case VOCAB_CALIBRATE: { + if (!rpc_Icalib) { ok = false; break; } + rec = true; + yCTrace(CONTROLBOARD, "Calling calibrate"); + ok = rpc_Icalib->calibrateRobot(); + } break; + + case VOCAB_CALIBRATE_DONE: { + if (!rpc_Icalib) { ok = false; break; } + rec = true; + yCTrace(CONTROLBOARD, "Calling calibrate done"); + int j = cmd.get(1).asInt32(); + ok = rpc_Icalib->calibrationDone(j); + } break; + + case VOCAB_PARK: { + if (!rpc_Icalib) { ok = false; break; } + rec = true; + yCTrace(CONTROLBOARD, "Calling park function"); + int flag = cmd.get(1).asInt32(); + ok = rpc_Icalib->park(flag ? true : false); + ok = true; //client would get stuck if returning false + } break; + + case VOCAB_SET: { + rec = true; + yCTrace(CONTROLBOARD, "set command received"); + + switch (cmd.get(1).asVocab32()) { + case VOCAB_POSITION_MOVE: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->positionMove(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + // this operation is also available on "command" port + case VOCAB_POSITION_MOVES: { + if (!rpc_IPosCtrl) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + if (b == nullptr) { + break; + } + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + tmpVect.resize(njs); + for (size_t i = 0; i < njs; i++) { + tmpVect[i] = b->get(i).asFloat64(); + } + + if (rpc_IPosCtrl != nullptr) { + ok = rpc_IPosCtrl->positionMove(&tmpVect[0]); + } + } break; + + case VOCAB_POSITION_MOVE_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto len = static_cast(cmd.get(2).asInt32()); + Bottle* jlut = cmd.get(3).asList(); + Bottle* pos_val = cmd.get(4).asList(); + + if (rpc_IPosCtrl == nullptr) { + break; + } + + if (jlut == nullptr || pos_val == nullptr) { + break; + } + if (len != jlut->size() || len != pos_val->size()) { + break; + } + + auto* j_tmp = new int[len]; + auto* pos_tmp = new double[len]; + for (size_t i = 0; i < len; i++) { + j_tmp[i] = jlut->get(i).asInt32(); + pos_tmp[i] = pos_val->get(i).asFloat64(); + } + + ok = rpc_IPosCtrl->positionMove(len, j_tmp, pos_tmp); + + delete[] j_tmp; + delete[] pos_tmp; + } break; + + // this operation is also available on "command" port + case VOCAB_VELOCITY_MOVES: { + if (!rpc_IVelCtrl) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + if (b == nullptr) { + break; + } + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + tmpVect.resize(njs); + for (size_t i = 0; i < njs; i++) { + tmpVect[i] = b->get(i).asFloat64(); + } + if (rpc_IVelCtrl != nullptr) { + ok = rpc_IVelCtrl->velocityMove(&tmpVect[0]); + } + + } break; + + case VOCAB_RELATIVE_MOVE: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->relativeMove(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_RELATIVE_MOVE_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto len = static_cast(cmd.get(2).asInt32()); + Bottle* jBottle_p = cmd.get(3).asList(); + Bottle* posBottle_p = cmd.get(4).asList(); + + if (rpc_IPosCtrl == nullptr) { + break; + } + + if (jBottle_p == nullptr || posBottle_p == nullptr) { + break; + } + if (len != jBottle_p->size() || len != posBottle_p->size()) { + break; + } + + int* j_tmp = new int[len]; + auto* pos_tmp = new double[len]; + + for (size_t i = 0; i < len; i++) { + j_tmp[i] = jBottle_p->get(i).asInt32(); + } + + for (size_t i = 0; i < len; i++) { + pos_tmp[i] = posBottle_p->get(i).asFloat64(); + } + + ok = rpc_IPosCtrl->relativeMove(len, j_tmp, pos_tmp); + + delete[] j_tmp; + delete[] pos_tmp; + } break; + + case VOCAB_RELATIVE_MOVES: { + if (!rpc_IPosCtrl) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + ok = rpc_IPosCtrl->relativeMove(p); + delete[] p; + } break; + + case VOCAB_REF_SPEED: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->setRefSpeed(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_REF_SPEED_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto len = static_cast(cmd.get(2).asInt32()); + Bottle* jBottle_p = cmd.get(3).asList(); + Bottle* velBottle_p = cmd.get(4).asList(); + + if (rpc_IPosCtrl == nullptr) { + break; + } + + if (jBottle_p == nullptr || velBottle_p == nullptr) { + break; + } + if (len != jBottle_p->size() || len != velBottle_p->size()) { + break; + } + + int* j_tmp = new int[len]; + auto* spds_tmp = new double[len]; + + for (size_t i = 0; i < len; i++) { + j_tmp[i] = jBottle_p->get(i).asInt32(); + } + + for (size_t i = 0; i < len; i++) { + spds_tmp[i] = velBottle_p->get(i).asFloat64(); + } + + ok = rpc_IPosCtrl->setRefSpeeds(len, j_tmp, spds_tmp); + delete[] j_tmp; + delete[] spds_tmp; + } break; + + case VOCAB_REF_SPEEDS: { + if (!rpc_IPosCtrl) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + ok = rpc_IPosCtrl->setRefSpeeds(p); + delete[] p; + } break; + + case VOCAB_REF_ACCELERATION: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->setRefAcceleration(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_REF_ACCELERATION_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto len = static_cast(cmd.get(2).asInt32()); + Bottle* jBottle_p = cmd.get(3).asList(); + Bottle* accBottle_p = cmd.get(4).asList(); + + if (rpc_IPosCtrl == nullptr) { + break; + } + + if (jBottle_p == nullptr || accBottle_p == nullptr) { + break; + } + if (len != jBottle_p->size() || len != accBottle_p->size()) { + break; + } + + int* j_tmp = new int[len]; + auto* accs_tmp = new double[len]; + + for (size_t i = 0; i < len; i++) { + j_tmp[i] = jBottle_p->get(i).asInt32(); + } + + for (size_t i = 0; i < len; i++) { + accs_tmp[i] = accBottle_p->get(i).asFloat64(); + } + + ok = rpc_IPosCtrl->setRefAccelerations(len, j_tmp, accs_tmp); + delete[] j_tmp; + delete[] accs_tmp; + } break; + + case VOCAB_REF_ACCELERATIONS: { + if (!rpc_IPosCtrl) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + ok = rpc_IPosCtrl->setRefAccelerations(p); + delete[] p; + } break; + + case VOCAB_STOP: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->stop(cmd.get(2).asInt32()); + } break; + + case VOCAB_STOP_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto len = static_cast(cmd.get(2).asInt32()); + Bottle* jBottle_p = cmd.get(3).asList(); + + if (rpc_IPosCtrl == nullptr) { + break; + } + + if (jBottle_p == nullptr) { + break; + } + if (len != jBottle_p->size()) { + break; + } + + int* j_tmp = new int[len]; + + for (size_t i = 0; i < len; i++) { + j_tmp[i] = jBottle_p->get(i).asInt32(); + } + + ok = rpc_IPosCtrl->stop(len, j_tmp); + delete[] j_tmp; + } break; + + case VOCAB_STOPS: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->stop(); + } break; + + case VOCAB_E_RESET: { + if (!rpc_IEncTimed) { ok = false; break; } + ok = rpc_IEncTimed->resetEncoder(cmd.get(2).asInt32()); + } break; + + case VOCAB_E_RESETS: { + if (!rpc_IEncTimed) { ok = false; break; } + ok = rpc_IEncTimed->resetEncoders(); + } break; + + case VOCAB_ENCODER: { + if (!rpc_IEncTimed) { ok = false; break; } + ok = rpc_IEncTimed->setEncoder(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_ENCODERS: { + if (!rpc_IEncTimed) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + ok = rpc_IEncTimed->setEncoders(p); + delete[] p; + } break; + + case VOCAB_MOTOR_CPR: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->setMotorEncoderCountsPerRevolution(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_MOTOR_E_RESET: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->resetMotorEncoder(cmd.get(2).asInt32()); + } break; + + case VOCAB_MOTOR_E_RESETS: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->resetMotorEncoders(); + } break; + + case VOCAB_MOTOR_ENCODER: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->setMotorEncoder(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_MOTOR_ENCODERS: { + if (!rpc_IMotEnc) { ok = false; break; } + Bottle* b = cmd.get(2).asList(); + + if (b == nullptr) { + break; + } + + const size_t njs = b->size(); + if (njs != controlledJoints) { + break; + } + auto* p = new double[njs]; // LATER: optimize to avoid allocation. + for (size_t i = 0; i < njs; i++) { + p[i] = b->get(i).asFloat64(); + } + ok = rpc_IMotEnc->setMotorEncoders(p); + delete[] p; + } break; + + case VOCAB_AMP_ENABLE: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->enableAmp(cmd.get(2).asInt32()); + } break; + + case VOCAB_AMP_DISABLE: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->disableAmp(cmd.get(2).asInt32()); + } break; + + case VOCAB_AMP_MAXCURRENT: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->setMaxCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_AMP_PEAK_CURRENT: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->setPeakCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_AMP_NOMINAL_CURRENT: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->setNominalCurrent(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_AMP_PWM_LIMIT: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->setPWMLimit(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_LIMITS: { + if (!rcp_Ilim) {ok= false; break;} + ok = rcp_Ilim->setLimits(cmd.get(2).asInt32(), cmd.get(3).asFloat64(), cmd.get(4).asFloat64()); + } break; + + + case VOCAB_TEMPERATURE_LIMIT: { + if (!rpc_IMotor) { ok = false; break; } + ok = rpc_IMotor->setTemperatureLimit(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_GEARBOX_RATIO: { + if (!rpc_IMotor) { ok = false; break; } + ok = rpc_IMotor->setGearboxRatio(cmd.get(2).asInt32(), cmd.get(3).asFloat64()); + } break; + + case VOCAB_VEL_LIMITS: { + if (!rcp_Ilim) { ok = false; break; } + ok = rcp_Ilim->setVelLimits(cmd.get(2).asInt32(), cmd.get(3).asFloat64(), cmd.get(4).asFloat64()); + } break; + + default: + { + yCError(CONTROLBOARD, "received an unknown command after a VOCAB_SET (%s)", cmd.toString().c_str()); + } break; + } //switch(cmd.get(1).asVocab32() + break; + } + + case VOCAB_GET: { + rec = true; + yCTrace(CONTROLBOARD, "get command received"); + + double dtmp = 0.0; + Bottle btmp; + response.addVocab32(VOCAB_IS); + response.add(cmd.get(1)); + + switch (cmd.get(1).asVocab32()) { + + case VOCAB_TEMPERATURE_LIMIT: { + if (!rpc_IMotor) { ok = false; break; } + ok = rpc_IMotor->getTemperatureLimit(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_TEMPERATURE: { + if (!rpc_IMotor) { ok = false; break; } + ok = rpc_IMotor->getTemperature(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_GEARBOX_RATIO: { + if (!rpc_IMotor) { ok = false; break; } + ok = rpc_IMotor->getGearboxRatio(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_TEMPERATURES: { + if (!rpc_IMotor) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IMotor->getTemperatures(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_AMP_MAXCURRENT: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getMaxCurrent(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_POSITION_MOVE: { + if (!rpc_IPosCtrl) { ok = false; break; } + yCTrace(CONTROLBOARD, "getTargetPosition"); + ok = rpc_IPosCtrl->getTargetPosition(cmd.get(2).asInt32(), &dtmp); + + response.addFloat64(dtmp); + rec = true; + } break; + + case VOCAB_POSITION_MOVE_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + int len = cmd.get(2).asInt32(); + Bottle& in = *(cmd.get(3).asList()); + int* jointList = new int[len]; + auto* refs = new double[len]; + + for (int j = 0; j < len; j++) { + jointList[j] = in.get(j).asInt32(); + } + ok = rpc_IPosCtrl->getTargetPositions(len, jointList, refs); + + Bottle& b = response.addList(); + for (int i = 0; i < len; i++) { + b.addFloat64(refs[i]); + } + + delete[] jointList; + delete[] refs; + } break; + + case VOCAB_POSITION_MOVES: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto* refs = new double[controlledJoints]; + ok = rpc_IPosCtrl->getTargetPositions(refs); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(refs[i]); + } + delete[] refs; + } break; + + case VOCAB_POSITION_DIRECT: { + if (!rpc_IPosDirect) { ok = false; break; } + yCTrace(CONTROLBOARD, "getRefPosition"); + ok = rpc_IPosDirect->getRefPosition(cmd.get(2).asInt32(), &dtmp); + + response.addFloat64(dtmp); + rec = true; + } break; + + case VOCAB_POSITION_DIRECT_GROUP: { + if (!rpc_IPosDirect) { ok = false; break; } + int len = cmd.get(2).asInt32(); + Bottle& in = *(cmd.get(3).asList()); + int* jointList = new int[len]; + auto* refs = new double[len]; + + for (int j = 0; j < len; j++) { + jointList[j] = in.get(j).asInt32(); + } + ok = rpc_IPosDirect->getRefPositions(len, jointList, refs); + + Bottle& b = response.addList(); + for (int i = 0; i < len; i++) { + b.addFloat64(refs[i]); + } + + delete[] jointList; + delete[] refs; + } break; + + case VOCAB_POSITION_DIRECTS: { + auto* refs = new double[controlledJoints]; + ok = rpc_IPosDirect->getRefPositions(refs); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(refs[i]); + } + delete[] refs; + } break; + + case VOCAB_VELOCITY_MOVE: { + if (!rpc_IVelCtrl) { ok = false; break; } + yCTrace(CONTROLBOARD, "getVelocityMove - cmd: %s", cmd.toString().c_str()); + ok = rpc_IVelCtrl->getRefVelocity(cmd.get(2).asInt32(), &dtmp); + + response.addFloat64(dtmp); + rec = true; + } break; + + case VOCAB_VELOCITY_MOVE_GROUP: { + if (!rpc_IVelCtrl) { ok = false; break; } + yCTrace(CONTROLBOARD, "getVelocityMove_group - cmd: %s", cmd.toString().c_str()); + + int len = cmd.get(2).asInt32(); + Bottle& in = *(cmd.get(3).asList()); + int* jointList = new int[len]; + auto* refs = new double[len]; + + for (int j = 0; j < len; j++) { + jointList[j] = in.get(j).asInt32(); + } + ok = rpc_IVelCtrl->getRefVelocities(len, jointList, refs); + + Bottle& b = response.addList(); + for (int i = 0; i < len; i++) { + b.addFloat64(refs[i]); + } + + delete[] jointList; + delete[] refs; + } break; + + case VOCAB_VELOCITY_MOVES: { + if (!rpc_IVelCtrl) { ok = false; break; } + yCTrace(CONTROLBOARD, "getVelocityMoves - cmd: %s", cmd.toString().c_str()); + + auto* refs = new double[controlledJoints]; + ok = rpc_IVelCtrl->getRefVelocities(refs); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(refs[i]); + } + delete[] refs; + } break; + + case VOCAB_MOTORS_NUMBER: { + if (!rpc_IMotor) { ok = false; break; } + int tmp; + ok = rpc_IMotor->getNumberOfMotors(&tmp); + response.addInt32(tmp); + } break; + + case VOCAB_AXES: { + if (!rpc_IPosCtrl) { ok = false; break; } + int tmp; + ok = rpc_IPosCtrl->getAxes(&tmp); + response.addInt32(tmp); + } break; + + case VOCAB_MOTION_DONE: { + if (!rpc_IPosCtrl) { ok = false; break; } + bool x = false; + ; + ok = rpc_IPosCtrl->checkMotionDone(cmd.get(2).asInt32(), &x); + response.addInt32(x); + } break; + + case VOCAB_MOTION_DONE_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + bool x = false; + int len = cmd.get(2).asInt32(); + Bottle& in = *(cmd.get(3).asList()); + int* jointList = new int[len]; + for (int j = 0; j < len; j++) { + jointList[j] = in.get(j).asInt32(); + } + if (rpc_IPosCtrl != nullptr) { + ok = rpc_IPosCtrl->checkMotionDone(len, jointList, &x); + } + response.addInt32(x); + + delete[] jointList; + } break; + + case VOCAB_MOTION_DONES: { + if (!rpc_IPosCtrl) { ok = false; break; } + bool x = false; + ok = rpc_IPosCtrl->checkMotionDone(&x); + response.addInt32(x); + } break; + + case VOCAB_REF_SPEED: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->getRefSpeed(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_REF_SPEED_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + int len = cmd.get(2).asInt32(); + Bottle& in = *(cmd.get(3).asList()); + int* jointList = new int[len]; + auto* speeds = new double[len]; + + for (int j = 0; j < len; j++) { + jointList[j] = in.get(j).asInt32(); + } + ok = rpc_IPosCtrl->getRefSpeeds(len, jointList, speeds); + + Bottle& b = response.addList(); + for (int i = 0; i < len; i++) { + b.addFloat64(speeds[i]); + } + + delete[] jointList; + delete[] speeds; + } break; + + case VOCAB_REF_SPEEDS: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IPosCtrl->getRefSpeeds(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_REF_ACCELERATION: { + if (!rpc_IPosCtrl) { ok = false; break; } + ok = rpc_IPosCtrl->getRefAcceleration(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_REF_ACCELERATION_GROUP: { + if (!rpc_IPosCtrl) { ok = false; break; } + int len = cmd.get(2).asInt32(); + Bottle& in = *(cmd.get(3).asList()); + int* jointList = new int[len]; + auto* accs = new double[len]; + + for (int j = 0; j < len; j++) { + jointList[j] = in.get(j).asInt32(); + } + ok = rpc_IPosCtrl->getRefAccelerations(len, jointList, accs); + + Bottle& b = response.addList(); + for (int i = 0; i < len; i++) { + b.addFloat64(accs[i]); + } + + delete[] jointList; + delete[] accs; + } break; + + case VOCAB_REF_ACCELERATIONS: { + if (!rpc_IPosCtrl) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IPosCtrl->getRefAccelerations(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_ENCODER: { + if (!rpc_IEncTimed) { ok = false; break; } + ok = rpc_IEncTimed->getEncoder(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_ENCODERS: { + if (!rpc_IEncTimed) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IEncTimed->getEncoders(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_ENCODER_SPEED: { + if (!rpc_IEncTimed) { ok = false; break; } + ok = rpc_IEncTimed->getEncoderSpeed(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_ENCODER_SPEEDS: { + if (!rpc_IEncTimed) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IEncTimed->getEncoderSpeeds(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_ENCODER_ACCELERATION: { + if (!rpc_IEncTimed) { ok = false; break; } + ok = rpc_IEncTimed->getEncoderAcceleration(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_ENCODER_ACCELERATIONS: { + if (!rpc_IEncTimed) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IEncTimed->getEncoderAccelerations(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_MOTOR_CPR: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->getMotorEncoderCountsPerRevolution(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_MOTOR_ENCODER: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->getMotorEncoder(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_MOTOR_ENCODERS: { + if (!rpc_IMotEnc) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IMotEnc->getMotorEncoders(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_MOTOR_ENCODER_SPEED: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->getMotorEncoderSpeed(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_MOTOR_ENCODER_SPEEDS: { + if (!rpc_IMotEnc) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rpc_IMotEnc->getMotorEncoderSpeeds(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_MOTOR_ENCODER_ACCELERATION: { + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->getMotorEncoderAcceleration(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_MOTOR_ENCODER_ACCELERATIONS: { + auto* p = new double[controlledJoints]; + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->getMotorEncoderAccelerations(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_MOTOR_ENCODER_NUMBER: { + int num = 0; + if (!rpc_IMotEnc) { ok = false; break; } + ok = rpc_IMotEnc->getNumberOfMotorEncoders(&num); + response.addInt32(num); + } break; + + case VOCAB_AMP_CURRENT: { + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getCurrent(cmd.get(2).asInt32(), &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_AMP_CURRENTS: { + if (!rcp_IAmp) { ok = false; break; } + auto* p = new double[controlledJoints]; + ok = rcp_IAmp->getCurrents(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addFloat64(p[i]); + } + delete[] p; + } break; + + case VOCAB_AMP_STATUS: { + if (!rcp_IAmp) { ok = false; break; } + int* p = new int[controlledJoints]; + ok = rcp_IAmp->getAmpStatus(p); + Bottle& b = response.addList(); + for (size_t i = 0; i < controlledJoints; i++) { + b.addInt32(p[i]); + } + delete[] p; + } break; + + case VOCAB_AMP_STATUS_SINGLE: { + int j = cmd.get(2).asInt32(); + int itmp; + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getAmpStatus(j, &itmp); + response.addInt32(itmp); + } break; + + case VOCAB_AMP_NOMINAL_CURRENT: { + int m = cmd.get(2).asInt32(); + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getNominalCurrent(m, &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_AMP_PEAK_CURRENT: { + int m = cmd.get(2).asInt32(); + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getPeakCurrent(m, &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_AMP_PWM: { + int m = cmd.get(2).asInt32(); + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getPWM(m, &dtmp); + yCTrace(CONTROLBOARD) << "RPC parser::getPWM: j" << m << " val " << dtmp; + response.addFloat64(dtmp); + } break; + + case VOCAB_AMP_PWM_LIMIT: { + int m = cmd.get(2).asInt32(); + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getPWMLimit(m, &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_AMP_VOLTAGE_SUPPLY: { + int m = cmd.get(2).asInt32(); + if (!rcp_IAmp) { ok = false; break; } + ok = rcp_IAmp->getPowerSupplyVoltage(m, &dtmp); + response.addFloat64(dtmp); + } break; + + case VOCAB_LIMITS: { + double min = 0.0; + double max = 0.0; + if (!rcp_Ilim) { ok = false; break; } + ok = rcp_Ilim->getLimits(cmd.get(2).asInt32(), &min, &max); + response.addFloat64(min); + response.addFloat64(max); + } break; + + case VOCAB_VEL_LIMITS: { + double min = 0.0; + double max = 0.0; + if (!rcp_Ilim) { ok = false; break; } + ok = rcp_Ilim->getVelLimits(cmd.get(2).asInt32(), &min, &max); + response.addFloat64(min); + response.addFloat64(max); + } break; + + case VOCAB_INFO_NAME: { + std::string name = "undocumented"; + if (!rpc_AxisInfo) { ok = false; break; } + ok = rpc_AxisInfo->getAxisName(cmd.get(2).asInt32(), name); + response.addString(name.c_str()); + } break; + + case VOCAB_INFO_TYPE: { + yarp::dev::JointTypeEnum type; + if (!rpc_AxisInfo) { ok = false; break; } + ok = rpc_AxisInfo->getJointType(cmd.get(2).asInt32(), type); + response.addInt32(type); + } break; + + default: + { + yCError(CONTROLBOARD, "received an unknown request after a VOCAB_GET: %s", yarp::os::Vocab32::decode(cmd.get(1).asVocab32()).c_str()); + } break; + } //switch cmd.get(1).asVocab32()) + + lastRpcStamp.update(); + appendTimeStamp(response, lastRpcStamp); + } // case VOCAB_GET + default: + break; + } //switch code + + if (!rec) { + ok = DeviceResponder::respond(cmd, response); + } + } + + if (!ok) { + // failed thus send only a VOCAB back. + response.clear(); + response.addVocab32(VOCAB_FAILED); + } else { + response.addVocab32(VOCAB_OK); + } + } + std::string ss = response.toString(); + + return ok; +} + +bool RPCMessagesParser::initialize() +{ + bool ok = false; + if (rpc_IPosCtrl) { + int tmp_axes; + ok = rpc_IPosCtrl->getAxes(&tmp_axes); + controlledJoints = static_cast(tmp_axes); + } + + DeviceResponder::makeUsage(); + addUsage("[get] [axes]", "get the number of axes"); + addUsage("[get] [name] $iAxisNumber", "get a human-readable name for an axis, if available"); + addUsage("[set] [pos] $iAxisNumber $fPosition", "command the position of an axis"); + addUsage("[set] [rel] $iAxisNumber $fPosition", "command the relative position of an axis"); + addUsage("[set] [vmo] $iAxisNumber $fVelocity", "command the velocity of an axis"); + addUsage("[get] [enc] $iAxisNumber", "get the encoder value for an axis"); + + std::string args; + for (size_t i = 0; i < controlledJoints; i++) { + if (i > 0) { + args += " "; + } + // removed dependency from yarp internals + //args = args + "$f" + yarp::yarp::conf::numeric::to_string(i); + } + addUsage((std::string("[set] [poss] (") + args + ")").c_str(), + "command the position of all axes"); + addUsage((std::string("[set] [rels] (") + args + ")").c_str(), + "command the relative position of all axes"); + addUsage((std::string("[set] [vmos] (") + args + ")").c_str(), + "command the velocity of all axes"); + + addUsage("[set] [aen] $iAxisNumber", "enable (amplifier for) the given axis"); + addUsage("[set] [adi] $iAxisNumber", "disable (amplifier for) the given axis"); + addUsage("[get] [acu] $iAxisNumber", "get current for the given axis"); + addUsage("[get] [acus]", "get current for all axes"); + + return ok; +} + +void RPCMessagesParser::init(yarp::dev::DeviceDriver* x) +{ + x->view(rpc_IPid); + x->view(rpc_IPosCtrl); + x->view(rpc_IPosDirect); + x->view(rpc_IVelCtrl); + x->view(rpc_IEncTimed); + x->view(rpc_IMotEnc); + x->view(rpc_IMotor); + x->view(rpc_IVar); + x->view(rcp_IAmp); + x->view(rcp_Ilim); + x->view(rpc_AxisInfo); + x->view(rpc_IRemoteCalibrator); + x->view(rpc_Icalib); + x->view(rpc_IImpedance); + x->view(rpc_ITorque); + x->view(rpc_iCtrlMode); + x->view(rpc_IInteract); + x->view(rpc_ICurrent); + x->view(rpc_IPWM); + x->view(rpc_IJointFault); + controlledJoints = 0; +} + +void RPCMessagesParser::reset() +{ + rpc_IPid = nullptr; + rpc_IPosCtrl = nullptr; + rpc_IPosDirect = nullptr; + rpc_IVelCtrl = nullptr; + rpc_IEncTimed = nullptr; + rpc_IMotEnc = nullptr; + rpc_IMotor = nullptr; + rpc_IVar = nullptr; + rcp_IAmp = nullptr; + rcp_Ilim = nullptr; + rpc_AxisInfo = nullptr; + rpc_IRemoteCalibrator = nullptr; + rpc_Icalib = nullptr; + rpc_IImpedance = nullptr; + rpc_ITorque = nullptr; + rpc_iCtrlMode = nullptr; + rpc_IInteract = nullptr; + rpc_ICurrent = nullptr; + rpc_IPWM = nullptr; + rpc_IJointFault = nullptr; + controlledJoints = 0; +} diff --git a/src/devices/ControlBoard_nws_yarp/RPCMessagesParser.h b/src/devices/ControlBoard_nws_yarp/RPCMessagesParser.h new file mode 100644 index 00000000000..571f094d427 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/RPCMessagesParser.h @@ -0,0 +1,149 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef YARP_DEV_CONTROLBOARDWRAPPER_RPCMESSAGESPARSER_H +#define YARP_DEV_CONTROLBOARDWRAPPER_RPCMESSAGESPARSER_H + + +// This file contains helper functions for the ControlBoardWrapper + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include +#include + +constexpr int PROTOCOL_VERSION_MAJOR = 1; +constexpr int PROTOCOL_VERSION_MINOR = 9; +constexpr int PROTOCOL_VERSION_TWEAK = 0; + +#ifdef MSVC +# pragma warning(disable : 4355) +#endif + +/* + * To optimize memory allocation, for group of joints we can have one mem reserver for rpc port + * and on e for streaming. The size could be numOfSubDevices*maxNumOfjointForSubdevice. + * (we could also use the actual joint number for each subdevice using a for loop). TODO + */ + +class ControlBoardWrapperCommon; + +/* the control command message type +* head is a Bottle which contains the specification of the message type +* body is a Vector which move the robot accordingly +*/ +typedef yarp::os::PortablePair CommandMessage; + + +/** +* Helper object for parsing RPC port messages +*/ +class RPCMessagesParser : + public yarp::dev::DeviceResponder +{ +protected: + yarp::dev::IPidControl* rpc_IPid {nullptr}; + yarp::dev::IPositionControl* rpc_IPosCtrl {nullptr}; + yarp::dev::IPositionDirect* rpc_IPosDirect {nullptr}; + yarp::dev::IVelocityControl* rpc_IVelCtrl {nullptr}; + yarp::dev::IEncodersTimed* rpc_IEncTimed {nullptr}; + yarp::dev::IMotorEncoders* rpc_IMotEnc {nullptr}; + yarp::dev::IAmplifierControl* rcp_IAmp {nullptr}; + yarp::dev::IControlLimits* rcp_Ilim {nullptr}; + yarp::dev::ITorqueControl* rpc_ITorque {nullptr}; + yarp::dev::IControlMode* rpc_iCtrlMode {nullptr}; + yarp::dev::IAxisInfo* rpc_AxisInfo {nullptr}; + yarp::dev::IRemoteCalibrator* rpc_IRemoteCalibrator {nullptr}; + yarp::dev::IControlCalibration* rpc_Icalib {nullptr}; + yarp::dev::IImpedanceControl* rpc_IImpedance {nullptr}; + yarp::dev::IInteractionMode* rpc_IInteract {nullptr}; + yarp::dev::IMotor* rpc_IMotor {nullptr}; + yarp::dev::IRemoteVariables* rpc_IVar {nullptr}; + yarp::dev::ICurrentControl* rpc_ICurrent {nullptr}; + yarp::dev::IPWMControl* rpc_IPWM {nullptr}; + yarp::dev::IJointFault* rpc_IJointFault{ nullptr }; + yarp::sig::Vector tmpVect; + yarp::os::Stamp lastRpcStamp; + std::mutex mutex; + size_t controlledJoints {0}; + +public: + /** + * Constructor. + */ + RPCMessagesParser() = default; + + /** + * Initialization. + * @param x is the pointer to the instance of the object that uses the RPCMessagesParser. + * This is required to recover the pointers to the interfaces that implement the responses + * to the commands. + */ + void init(yarp::dev::DeviceDriver* x); + void reset(); + + bool respond(const yarp::os::Bottle& cmd, yarp::os::Bottle& response) override; + + void handleTorqueMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok); + + void handleJointFaultMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok); + + void handleControlModeMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok); + + void handleImpedanceMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok); + + void handleInteractionModeMsg(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok); + + void handleProtocolVersionRequest(const yarp::os::Bottle& cmd, + yarp::os::Bottle& response, + bool* rec, + bool* ok); + + void handleRemoteCalibratorMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok); + + void handleRemoteVariablesMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok); + + void handleCurrentMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok); + + void handlePWMMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok); + + void handlePidMsg(const yarp::os::Bottle& cmd, yarp::os::Bottle& response, bool* rec, bool* ok); + + /** + * Initialize the internal data. + * @return true/false on success/failure + */ + virtual bool initialize(); +}; + +#endif // YARP_DEV_CONTROLBOARDWRAPPER_RPCMESSAGESPARSER_H diff --git a/src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.cpp b/src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.cpp new file mode 100644 index 00000000000..410d42726a8 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.cpp @@ -0,0 +1,291 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "StreamingMessagesParser.h" + +#include + +#include "ControlBoardLogComponent.h" +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::dev::impl; +using namespace yarp::sig; + + +void StreamingMessagesParser::init(yarp::dev::DeviceDriver* x) +{ + stream_nJoints = 0; + x->view(stream_IPosCtrl); + x->view(stream_IPosDirect); + x->view(stream_IVel); + x->view(stream_ITorque); + x->view(stream_IPWM); + x->view(stream_ICurrent); +} + +void StreamingMessagesParser::reset() +{ + stream_nJoints = 0; + stream_IPosCtrl = nullptr; + stream_IPosDirect = nullptr; + stream_IVel = nullptr; + stream_ITorque = nullptr; + stream_IPWM = nullptr; + stream_ICurrent = nullptr; +} + +bool StreamingMessagesParser::initialize() +{ + stream_nJoints = 0; + if (stream_IPosCtrl) { + stream_IPosCtrl->getAxes(&stream_nJoints); + } + + return true; +} + +// streaming port callback +void StreamingMessagesParser::onRead(CommandMessage& v) +{ + Bottle& b = v.head; + Vector& cmdVector = v.body; + + //Use the following only for debug, since it can heavily slow down the system + yCTrace(CONTROLBOARD, "Received command %s, %s\n", b.toString().c_str(), cmdVector.toString().c_str()); + + // some consistency checks + if (static_cast(cmdVector.size()) > stream_nJoints) { + std::string str = yarp::os::Vocab32::decode(b.get(0).asVocab32()); + yCError(CONTROLBOARD, "Received command vector with number of elements bigger than axis controlled by this wrapper (cmd: %s requested jnts: %d received jnts: %d)\n", str.c_str(), stream_nJoints, (int)cmdVector.size()); + return; + } + if (cmdVector.data() == nullptr) { + yCError(CONTROLBOARD, "Received null command vector"); + return; + } + + switch (b.get(0).asVocab32()) { + // manage commands with interface name as first + case VOCAB_PWMCONTROL_INTERFACE: { + switch (b.get(1).asVocab32()) { + case VOCAB_PWMCONTROL_REF_PWM: { + if (stream_IPWM) { + bool ok = stream_IPWM->setRefDutyCycle(b.get(2).asInt32(), cmdVector[0]); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command an pwm message"); + } + } else { + yCError(CONTROLBOARD, "PWM interface not valid"); + } + } break; + case VOCAB_PWMCONTROL_REF_PWMS: { + if (stream_IPWM) { + bool ok = stream_IPWM->setRefDutyCycles(cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command an pwm message"); + } + } else { + yCError(CONTROLBOARD, "PWM interface not valid"); + } + } break; + } + } break; + + case VOCAB_CURRENTCONTROL_INTERFACE: { + switch (b.get(1).asVocab32()) { + case VOCAB_CURRENT_REF: { + if (stream_ICurrent) { + bool ok = stream_ICurrent->setRefCurrent(b.get(2).asInt32(), cmdVector[0]); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command a streaming current message on single joint\n"); + } + } + } break; + case VOCAB_CURRENT_REFS: { + if (stream_ICurrent) { + bool ok = stream_ICurrent->setRefCurrents(cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command a streaming current message on all joints\n"); + } + } + } break; + case VOCAB_CURRENT_REF_GROUP: { + if (stream_ICurrent) { + int n_joints = b.get(2).asInt32(); + Bottle* jlut = b.get(3).asList(); + if ((static_cast(jlut->size()) != n_joints) && (static_cast(cmdVector.size()) != n_joints)) { + yCError(CONTROLBOARD, "Received VOCAB_CURRENT_REF_GROUP size of joints vector or currents vector does not match the selected joint number\n"); + } + + int* joint_list = new int[n_joints]; + for (int i = 0; i < n_joints; i++) { + joint_list[i] = jlut->get(i).asInt32(); + } + + + bool ok = stream_ICurrent->setRefCurrents(n_joints, joint_list, cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Error while trying to command a streaming current message on joint group\n"); + } + + delete[] joint_list; + } + } break; + default: + { + std::string str = yarp::os::Vocab32::decode(b.get(0).asVocab32()); + yCError(CONTROLBOARD, "Unrecognized message while receiving on command port (%s)\n", str.c_str()); + } break; + } + } break; + + // fallback to commands without interface name + case VOCAB_POSITION_MODE: { + yCError(CONTROLBOARD, "Received VOCAB_POSITION_MODE this is an send invalid message on streaming port"); + break; + } + + case VOCAB_POSITION_MOVES: { + if (stream_IPosCtrl) { + bool ok = stream_IPosCtrl->positionMove(cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to start a position move"); + } + } + + } break; + + case VOCAB_VELOCITY_MODE: { + yCError(CONTROLBOARD, "Received VOCAB_VELOCITY_MODE this is an send invalid message on streaming port"); + break; + } + + case VOCAB_VELOCITY_MOVE: { + stream_IVel->velocityMove(b.get(1).asInt32(), cmdVector[0]); + } break; + + case VOCAB_VELOCITY_MOVES: { + if (stream_IVel) { + bool ok = stream_IVel->velocityMove(cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to start a velocity move"); + } + } + } break; + + case VOCAB_POSITION_DIRECT: { + if (stream_IPosDirect) { + bool ok = stream_IPosDirect->setPosition(b.get(1).asInt32(), cmdVector[0]); // cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command an streaming position direct message on joint %d\n", b.get(1).asInt32()); + } + } + } break; + + case VOCAB_TORQUES_DIRECT: { + if (stream_ITorque) { + bool ok = stream_ITorque->setRefTorque(b.get(1).asInt32(), cmdVector[0]); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command a streaming torque direct message on single joint\n"); + } + } + } break; + + case VOCAB_TORQUES_DIRECTS: { + if (stream_ITorque) { + bool ok = stream_ITorque->setRefTorques(cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Errors while trying to command a streaming torque direct message on all joints\n"); + } + } + } break; + + case VOCAB_TORQUES_DIRECT_GROUP: { + if (stream_ITorque) { + int n_joints = b.get(1).asInt32(); + Bottle* jlut = b.get(2).asList(); + if ((static_cast(jlut->size()) != n_joints) && (static_cast(cmdVector.size()) != n_joints)) { + yCError(CONTROLBOARD, "Received VOCAB_TORQUES_DIRECT_GROUP size of joints vector or torques vector does not match the selected joint number\n"); + } + + int* joint_list = new int[n_joints]; + for (int i = 0; i < n_joints; i++) { + joint_list[i] = jlut->get(i).asInt32(); + } + + + bool ok = stream_ITorque->setRefTorques(n_joints, joint_list, cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Error while trying to command a streaming toruqe direct message on joint group\n"); + } + + delete[] joint_list; + } + } break; + + case VOCAB_POSITION_DIRECT_GROUP: { + if (stream_IPosDirect) { + int n_joints = b.get(1).asInt32(); + Bottle* jlut = b.get(2).asList(); + if ((static_cast(jlut->size()) != n_joints) && (static_cast(cmdVector.size()) != n_joints)) { + yCError(CONTROLBOARD, "Received VOCAB_POSITION_DIRECT_GROUP size of joints vector or positions vector does not match the selected joint number\n"); + } + + int* joint_list = new int[n_joints]; + for (int i = 0; i < n_joints; i++) { + joint_list[i] = jlut->get(i).asInt32(); + } + + + bool ok = stream_IPosDirect->setPositions(n_joints, joint_list, cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Error while trying to command a streaming position direct message on joint group\n"); + } + + delete[] joint_list; + } + } break; + + case VOCAB_POSITION_DIRECTS: { + if (stream_IPosDirect) { + bool ok = stream_IPosDirect->setPositions(cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Error while trying to command a streaming position direct message on all joints\n"); + } + } + } break; + + case VOCAB_VELOCITY_MOVE_GROUP: { + if (stream_IVel) { + int n_joints = b.get(1).asInt32(); + Bottle* jlut = b.get(2).asList(); + if ((static_cast(jlut->size()) != n_joints) && (static_cast(cmdVector.size()) != n_joints)) { + yCError(CONTROLBOARD, "Received VOCAB_VELOCITY_MOVE_GROUP size of joints vector or positions vector does not match the selected joint number\n"); + } + + int* joint_list = new int[n_joints]; + for (int i = 0; i < n_joints; i++) { + joint_list[i] = jlut->get(i).asInt32(); + } + + bool ok = stream_IVel->velocityMove(n_joints, joint_list, cmdVector.data()); + if (!ok) { + yCError(CONTROLBOARD, "Error while trying to command a velocity move on joint group\n"); + } + + delete[] joint_list; + } + } break; + + default: + { + std::string str = yarp::os::Vocab32::decode(b.get(0).asVocab32()); + yCError(CONTROLBOARD, "Unrecognized message while receiving on command port (%s)\n", str.c_str()); + } break; + } +} diff --git a/src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.h b/src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.h new file mode 100644 index 00000000000..6ed84a49e49 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/StreamingMessagesParser.h @@ -0,0 +1,86 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef YARP_DEV_CONTROLBOARDWRAPPER_STREAMINGMESSAGESPARSER_H +#define YARP_DEV_CONTROLBOARDWRAPPER_STREAMINGMESSAGESPARSER_H + + +// This file contains helper functions for the ControlBoardWrapper + + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#ifdef MSVC +# pragma warning(disable : 4355) +#endif + +/* + * To optimize memory allocation, for group of joints we can have one mem reserver for rpc port + * and on e for streaming. The size could be numOfSubDevices*maxNumOfjointForSubdevice. + * (we could also use the actual joint number for each subdevice using a for loop). TODO + */ + + +/* the control command message type +* head is a Bottle which contains the specification of the message type +* body is a Vector which move the robot accordingly +*/ +typedef yarp::os::PortablePair CommandMessage; + +/** +* Callback implementation after buffered input. +*/ +class StreamingMessagesParser : public yarp::os::TypedReaderCallback +{ +protected: + yarp::dev::IPositionControl* stream_IPosCtrl {nullptr}; + yarp::dev::IPositionDirect* stream_IPosDirect {nullptr}; + yarp::dev::IVelocityControl* stream_IVel {nullptr}; + yarp::dev::ITorqueControl* stream_ITorque {nullptr}; + yarp::dev::IPWMControl* stream_IPWM {nullptr}; + yarp::dev::ICurrentControl* stream_ICurrent {nullptr}; + int stream_nJoints {0}; + +public: + /** + * Constructor. + */ + StreamingMessagesParser() = default; + + /** + * Initialization. + * @param x is the instance of the container class using the callback. + */ + void init(yarp::dev::DeviceDriver* x); + + void reset(); + + using yarp::os::TypedReaderCallback::onRead; + /** + * Callback function. + * @param v is the Vector being received. + */ + void onRead(CommandMessage& v) override; + + bool initialize(); +}; + +#endif // YARP_DEV_CONTROLBOARDWRAPPER_STREAMINGMESSAGESPARSER_H From b5e5e302fd1898e89a1110c3d565869de62673f7 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 17 Nov 2022 14:21:50 +0100 Subject: [PATCH 020/267] removed `subdevice` option from some navigation-related nws devices --- .../Localization2D_nws_yarp.cpp | 24 +++--------------- .../Localization2D_nws_yarp.h | 1 - src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp | 24 +----------------- .../navigation2D_nws_yarp.cpp | 25 ++----------------- .../navigation2D_nws_yarp.h | 1 - .../Odometry2D_nws_yarp.cpp | 22 +++------------- .../odometry2D_nws_yarp/Odometry2D_nws_yarp.h | 1 - 7 files changed, 9 insertions(+), 89 deletions(-) diff --git a/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.cpp b/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.cpp index 3da8e9dd471..db3c51160c7 100644 --- a/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.cpp +++ b/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.cpp @@ -154,28 +154,8 @@ bool Localization2D_nws_yarp::open(Searchable& config) m_2DLocationPortName = m_local_name + "/streaming:o"; m_odometryPortName = m_local_name + "/odometry:o"; - if (config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!pLoc.open(p) || !pLoc.isValid()) - { - yCError(LOCALIZATION2D_NWS_YARP) << "Failed to open subdevice.. check params"; - return false; - } + yCInfo(LOCALIZATION2D_NWS_YARP) << "Waiting for device to attach"; - if (!attach(&pLoc)) - { - yCError(LOCALIZATION2D_NWS_YARP) << "Failed to attach subdevice.. check params"; - return false; - } - } - else - { - yCInfo(LOCALIZATION2D_NWS_YARP) << "Waiting for device to attach"; - } m_stats_time_last = yarp::os::Time::now(); if (!initialize_YARP(config)) @@ -184,6 +164,8 @@ bool Localization2D_nws_yarp::open(Searchable& config) return false; } + yCInfo(LOCALIZATION2D_NWS_YARP) << "Waiting for device to attach"; + return true; } diff --git a/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h b/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h index dfb235ef299..13de0e3989c 100644 --- a/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h +++ b/src/devices/localization2D_nws_yarp/Localization2D_nws_yarp.h @@ -39,7 +39,6 @@ * | GENERAL | name | string | - | /localization2D_nws_yarp | No | The name of the server, used as a prefix for the opened ports | By default ports opened are /xxx/rpc and /xxx/streaming:o | * | GENERAL | publish_odometry | bool | - | true | No | Periodically publish odometry data over the network | - | * | GENERAL | publish_location | bool | - | true | No | PEriodically publish location data over the network | - | - * | subdevice | - | string | - | - | Yes | The name of the of Localization device to be used | - | */ class Localization2D_nws_yarp : public yarp::dev::DeviceDriver, diff --git a/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp b/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp index 765377753c0..838537dad88 100644 --- a/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp +++ b/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp @@ -73,29 +73,7 @@ bool Map2D_nws_yarp::open(yarp::os::Searchable &config) } m_rpcPort.setReader(*this); - //subdevice handling - if (config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!m_drv.open(p) || !m_drv.isValid()) - { - yCError(MAP2D_NWS_YARP) << "Failed to open subdevice.. check params"; - return false; - } - - if (!attach(&m_drv)) - { - yCError(MAP2D_NWS_YARP) << "Failed to open subdevice.. check params"; - return false; - } - } - else - { - yCInfo(MAP2D_NWS_YARP) << "Waiting for device to attach"; - } + yCInfo(MAP2D_NWS_YARP) << "Waiting for device to attach"; return true; } diff --git a/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.cpp b/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.cpp index 461c401909b..df2310a3df4 100644 --- a/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.cpp +++ b/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.cpp @@ -100,35 +100,14 @@ bool navigation2D_nws_yarp::open(Searchable& config) } m_rpcPortName = m_local_name + "/rpc"; - if (config.check("subdevice")) - { - Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!pNav.open(p) || !pNav.isValid()) - { - yCError(NAVIGATION2D_NWS_YARP) << "Failed to open subdevice.. check params"; - return false; - } - - if (!attach(&pNav)) - { - yCError(NAVIGATION2D_NWS_YARP) << "Failed to attach subdevice.. check params"; - return false; - } - } - else - { - yCInfo(NAVIGATION2D_NWS_YARP) << "Waiting for device to attach"; - } - if (!initialize_YARP(config)) { yCError(NAVIGATION2D_NWS_YARP) << "Error initializing YARP ports"; return false; } + yCInfo(NAVIGATION2D_NWS_YARP) << "Waiting for device to attach"; + return true; } diff --git a/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.h b/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.h index d78f1fe2f3d..fc78e1004f0 100644 --- a/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.h +++ b/src/devices/navigation2D_nws_yarp/navigation2D_nws_yarp.h @@ -34,7 +34,6 @@ * |:--------------:|:--------------:|:-------:|:------------------:|:------------------------:|:-----------: |:-----------------------------------------------------------------:|:-----:| * | GENERAL | period | double | s | 0.01 | No | The period of the working thread | | * | GENERAL | name | string | - | /navigation_nws_yarp | No | The name of the server, used as a prefix for the opened ports | - | - * | subdevice | - | string | - | - | Yes | The name of the of Navigation device to be used | - | */ #define DEF_m_RPC 1 diff --git a/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.cpp b/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.cpp index f1d6307d1e1..ddc85b18cf4 100644 --- a/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.cpp +++ b/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.cpp @@ -88,25 +88,6 @@ bool Odometry2D_nws_yarp::open(yarp::os::Searchable &config) m_odometryStreamingPortName = m_local_name + "/odometry:o"; m_velocityStreamingPortName = m_local_name + "/velocity:o"; - if(config.check("subdevice")) - { - yarp::os::Property p; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if(!m_driver.open(p) || !m_driver.isValid()) - { - yCError(ODOMETRY2D_NWS_YARP) << "failed to open subdevice.. check params"; - return false; - } - - if(!attach(&m_driver)) - { - yCError(ODOMETRY2D_NWS_YARP) << "failed to open subdevice.. check params"; - return false; - } - } - //open rpc port if (!m_rpcPort.open(m_rpcPortName)) { @@ -134,6 +115,9 @@ bool Odometry2D_nws_yarp::open(yarp::os::Searchable &config) } PeriodicThread::setPeriod(m_period); + + yCInfo(ODOMETRY2D_NWS_YARP) << "Waiting for device to attach"; + return true; } diff --git a/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.h b/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.h index af3873152be..e5d584cdc9c 100644 --- a/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.h +++ b/src/devices/odometry2D_nws_yarp/Odometry2D_nws_yarp.h @@ -32,7 +32,6 @@ * |:-------------------:|:-----------------------:|:-------:|:--------------:|:---------------------:|:-----------------------------: |:-----------------------------------------------------:|:-----:| * | period | - | double | s | 0.02 | No | refresh period of the broadcasted values in s | default 0.02s | * | name | - | string | - | /odometry2D_nws_yarp | No | The name of the server, used as a prefix for the opened ports | | - * | subdevice | - | string | - | - | alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | * * Example of configuration file using .ini format. * From 770ff64a9299ca062fdfe38c1f2d047b6e670602 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 17 Nov 2022 16:21:12 +0100 Subject: [PATCH 021/267] Preliminary test --- src/devices/map2D_nwc_yarp/CMakeLists.txt | 2 + .../map2D_nwc_yarp/tests/CMakeLists.txt | 47 +++++++++++++++++++ .../map2D_nwc_yarp/tests}/Map2DnwcTest.cpp | 6 +-- .../libYARP_dev/src/tests}/IMap2DTest.cpp | 0 .../libYARP_dev/src/tests}/IMap2DTest.h | 0 tests/libYARP_dev/CMakeLists.txt | 4 -- 6 files changed, 52 insertions(+), 7 deletions(-) create mode 100644 src/devices/map2D_nwc_yarp/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/map2D_nwc_yarp/tests}/Map2DnwcTest.cpp (94%) rename {tests/libYARP_dev => src/libYARP_dev/src/tests}/IMap2DTest.cpp (100%) rename {tests/libYARP_dev => src/libYARP_dev/src/tests}/IMap2DTest.h (100%) diff --git a/src/devices/map2D_nwc_yarp/CMakeLists.txt b/src/devices/map2D_nwc_yarp/CMakeLists.txt index b78f21bfa8d..38ebf4cf1b8 100644 --- a/src/devices/map2D_nwc_yarp/CMakeLists.txt +++ b/src/devices/map2D_nwc_yarp/CMakeLists.txt @@ -47,4 +47,6 @@ if(NOT SKIP_map2D_nwc_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_map2D_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") + + add_subdirectory(tests) endif() diff --git a/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..45ce7cb8e00 --- /dev/null +++ b/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt @@ -0,0 +1,47 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +add_executable(harness_dev_Map2Dnwc) + +target_sources(harness_dev_Map2Dnwc + PRIVATE + Map2DnwcTest.cpp +) + +target_link_libraries(harness_dev_Map2Dnwc + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_Map2Dnwc PRIVATE YARP::YARP_math) +else() + set(_disabled_files + Map2DnwcTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_Map2Dnwc PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_Map2Dnwc) diff --git a/tests/libYARP_dev/Map2DnwcTest.cpp b/src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp similarity index 94% rename from tests/libYARP_dev/Map2DnwcTest.cpp rename to src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp index 5f0ecacee39..37d191b3d30 100644 --- a/tests/libYARP_dev/Map2DnwcTest.cpp +++ b/src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp @@ -14,7 +14,7 @@ #include #include -#include "IMap2DTest.h" +//#include "IMap2DTest.h" using namespace yarp::dev; using namespace yarp::dev::Nav2D; @@ -51,8 +51,8 @@ TEST_CASE("dev::Map2DnwcTest", "[yarp::dev]") } //execute tests - exec_iMap2D_test_1 (imap); - exec_iMap2D_test_2 (imap); + // exec_iMap2D_test_1 (imap); + // exec_iMap2D_test_2 (imap); //"Close all polydrivers and check" { diff --git a/tests/libYARP_dev/IMap2DTest.cpp b/src/libYARP_dev/src/tests/IMap2DTest.cpp similarity index 100% rename from tests/libYARP_dev/IMap2DTest.cpp rename to src/libYARP_dev/src/tests/IMap2DTest.cpp diff --git a/tests/libYARP_dev/IMap2DTest.h b/src/libYARP_dev/src/tests/IMap2DTest.h similarity index 100% rename from tests/libYARP_dev/IMap2DTest.h rename to src/libYARP_dev/src/tests/IMap2DTest.h diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index 962a00133dc..260e6d30d10 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -11,9 +11,7 @@ target_sources(harness_dev TransformClientTest.cpp GroupDriverTest.cpp IFrameTransformTest.cpp - IMap2DTest.cpp MapGrid2DTest.cpp - Map2DnwcTest.cpp Navigation2DnwcTest.cpp INavigation2DTest.cpp MultipleAnalogSensorsInterfacesTest.cpp @@ -41,9 +39,7 @@ else() TransformClientTest.cpp FrameTransformClientTest.cpp IFrameTransformTest.cpp - IMap2DTest.cpp Map2DClientTest.cpp - Map2DnwcTest.cpp INavigation2DTest.cpp Navigation2DnwcTest.cpp Navigation2DClientTest.cpp From 0bee964f05889f460c2c8fdf6f178a7cea137317 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 17 Nov 2022 17:37:24 +0100 Subject: [PATCH 022/267] added guard YARP_COMPILE_TESTS --- src/devices/map2D_nwc_yarp/CMakeLists.txt | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/devices/map2D_nwc_yarp/CMakeLists.txt b/src/devices/map2D_nwc_yarp/CMakeLists.txt index 38ebf4cf1b8..c0c6f8e7185 100644 --- a/src/devices/map2D_nwc_yarp/CMakeLists.txt +++ b/src/devices/map2D_nwc_yarp/CMakeLists.txt @@ -48,5 +48,8 @@ if(NOT SKIP_map2D_nwc_yarp) set_property(TARGET yarp_map2D_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") - add_subdirectory(tests) + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() From 8e07ae1bb806558cfdd860376b9449a430ac729e Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 21 Nov 2022 15:45:07 +0100 Subject: [PATCH 023/267] improved test separation. IMap2DTest fully functional. --- .../map2D_nwc_yarp/tests/CMakeLists.txt | 8 +- .../map2D_nwc_yarp/tests/Map2DnwcTest.cpp | 21 +- src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp | 5 + src/libYARP_dev/src/CMakeLists.txt | 33 ++ src/libYARP_dev/src/tests/IMap2DTest.cpp | 289 ----------------- src/libYARP_dev/src/tests/IMap2DTest.h | 19 -- .../src/yarp/dev/tests/IMap2DTest.cpp | 6 + .../src/yarp/dev/tests/IMap2DTest.h | 291 ++++++++++++++++++ 8 files changed, 358 insertions(+), 314 deletions(-) delete mode 100644 src/libYARP_dev/src/tests/IMap2DTest.cpp delete mode 100644 src/libYARP_dev/src/tests/IMap2DTest.h create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h diff --git a/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt index 45ce7cb8e00..7dcfca84dc3 100644 --- a/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt +++ b/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt @@ -18,6 +18,8 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### +find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Map2Dnwc) target_sources(harness_dev_Map2Dnwc @@ -31,10 +33,14 @@ target_link_libraries(harness_dev_Map2Dnwc YARP::YARP_os YARP::YARP_sig YARP::YARP_dev + YARP::YARP_dev_tests ) if(TARGET YARP::YARP_math) - target_link_libraries(harness_dev_Map2Dnwc PRIVATE YARP::YARP_math) + target_link_libraries(harness_dev_Map2Dnwc + PRIVATE + YARP::YARP_math + ) else() set(_disabled_files Map2DnwcTest.cpp diff --git a/src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp b/src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp index 37d191b3d30..36c948c2885 100644 --- a/src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp +++ b/src/devices/map2D_nwc_yarp/tests/Map2DnwcTest.cpp @@ -10,12 +10,12 @@ #include #include #include +#include +#include #include #include -//#include "IMap2DTest.h" - using namespace yarp::dev; using namespace yarp::dev::Nav2D; using namespace yarp::sig; @@ -32,6 +32,7 @@ TEST_CASE("dev::Map2DnwcTest", "[yarp::dev]") SECTION("Checking map2D_nwc_yarp <-> map2D_nws_yarp communication and yarp::dev::Nav2D::IMap2D methods") { PolyDriver ddmapserver; + PolyDriver ddmapstorage; PolyDriver ddmapclient; IMap2D* imap = nullptr; @@ -39,9 +40,16 @@ TEST_CASE("dev::Map2DnwcTest", "[yarp::dev]") { Property pmapserver_cfg; pmapserver_cfg.put("device", "map2D_nws_yarp"); - pmapserver_cfg.put("subdevice", "map2DStorage"); REQUIRE(ddmapserver.open(pmapserver_cfg)); + Property pmapstorage_cfg; + pmapstorage_cfg.put("device", "map2DStorage"); + REQUIRE(ddmapstorage.open(pmapstorage_cfg)); + + {yarp::dev::WrapperSingle* ww_nws; ddmapserver.view(ww_nws); + bool result_att = ww_nws->attach(&ddmapstorage); + REQUIRE(result_att); } + Property pmapclient_cfg; pmapclient_cfg.put("device", "map2D_nwc_yarp"); pmapclient_cfg.put("local", "/mapClientTest"); @@ -51,13 +59,16 @@ TEST_CASE("dev::Map2DnwcTest", "[yarp::dev]") } //execute tests - // exec_iMap2D_test_1 (imap); - // exec_iMap2D_test_2 (imap); + yarp::dev::tests::exec_iMap2D_test_1 (imap); + yarp::dev::tests::exec_iMap2D_test_2 (imap); //"Close all polydrivers and check" { CHECK(ddmapclient.close()); + yarp::os::Time::delay(0.1); CHECK(ddmapserver.close()); + yarp::os::Time::delay(0.1); + CHECK(ddmapstorage.close()); } } diff --git a/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp b/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp index 838537dad88..d39721ee787 100644 --- a/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp +++ b/src/devices/map2D_nws_yarp/Map2D_nws_yarp.cpp @@ -81,6 +81,10 @@ bool Map2D_nws_yarp::open(yarp::os::Searchable &config) bool Map2D_nws_yarp::close() { yCTrace(MAP2D_NWS_YARP, "Close"); + + m_rpcPort.interrupt(); + m_rpcPort.close(); + return true; } @@ -104,5 +108,6 @@ bool Map2D_nws_yarp::attach(PolyDriver* driver) return false; } + yCInfo(MAP2D_NWS_YARP, "Attach done"); return true; } diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index e6319d223dc..a0ed53aa592 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -393,3 +393,36 @@ install( set(YARP_dev_PUBLIC_DEPS ${YARP_dev_PUBLIC_DEPS} PARENT_SCOPE) set(YARP_dev_PRIVATE_DEPS ${YARP_dev_PRIVATE_DEPS} PARENT_SCOPE) + +################################################################### + +add_library(YARP_dev_tests) +add_library(YARP::YARP_dev_tests ALIAS YARP_dev_tests) + +target_sources(YARP_dev_tests + PRIVATE + yarp/dev/tests/IMap2DTest.cpp + yarp/dev/tests/IMap2DTest.h +) + +target_include_directories(YARP_dev_tests + PRIVATE + ${CMAKE_SOURCE_DIR}/extern/catch2 +) + +target_link_libraries(YARP_dev_tests PRIVATE YARP_dev) + +target_compile_features(YARP_dev_tests PRIVATE cxx_std_17) + +set_property ( +TARGET YARP_dev_tests + PROPERTY FOLDER "Test" +) + +set_property( + TARGET YARP_dev_tests + PROPERTY + PUBLIC_HEADER + ${YARP_dev_HDRS} + yarp/dev/tests/IMap2DTest.h +) diff --git a/src/libYARP_dev/src/tests/IMap2DTest.cpp b/src/libYARP_dev/src/tests/IMap2DTest.cpp deleted file mode 100644 index be29c521bcb..00000000000 --- a/src/libYARP_dev/src/tests/IMap2DTest.cpp +++ /dev/null @@ -1,289 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include "IMap2DTest.h" - -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; -using namespace yarp::sig; -using namespace yarp::os; - -void exec_iMap2D_test_1(IMap2D* imap) -{ - //////////"Checking INavigation2D methods - std::vector ll; - std::vector la; - std::vector lp; - { - Map2DLocation l1 = Map2DLocation("map_1", 10.0, 20.0, 15); - Map2DLocation l2 = Map2DLocation("map_1", 10.2, 20.1, 15.5); - Map2DArea a1("map_1", std::vector {Map2DLocation("map_1", -10, -10, 0), - Map2DLocation("map_1", -10, +10, 0), - Map2DLocation("map_1", +10, +10, 0), - Map2DLocation("map_1", +10, -10, 0)}); - Map2DPath p1(std::vector {l1, l2}); - bool b; - b = imap->storeArea("area_test1", a1); CHECK(b); - b = imap->storeLocation("loc_test1", l1); CHECK(b); - b = imap->storeLocation("loc_test2", l2); CHECK(b); - b = imap->storePath("path_test1", p1); CHECK(b); - b = imap->getLocationsList(ll); CHECK(b); CHECK(ll.size() == 2); - b = imap->getAreasList(la); CHECK(b); CHECK(la.size() == 1); - b = imap->getPathsList(lp); CHECK(b); CHECK(lp.size() == 1); - } - - { - bool b; - b = imap->saveLocationsAndExtras("locations_test.ini"); CHECK(b); - b = imap->clearAllLocations(); CHECK(b); - b = imap->clearAllAreas(); CHECK(b); - b = imap->clearAllPaths(); CHECK(b); - b = imap->getLocationsList(ll); CHECK(b); CHECK(ll.size() == 0); - b = imap->getAreasList(la); CHECK(b); CHECK(la.size() == 0); - b = imap->getPathsList(lp); CHECK(b); CHECK(lp.size() == 0); - - b = imap->loadLocationsAndExtras("locations_test.ini"); CHECK(b); - Map2DLocation l1t; - Map2DLocation l2t; - Map2DArea a1; - Map2DPath p1; - b = imap->getLocationsList(ll); CHECK(b); CHECK(ll.size() == 2); - b = imap->getAreasList(la); CHECK(b); CHECK(la.size() == 1); - b = imap->getPathsList(lp); CHECK(b); CHECK(lp.size() == 1); - - b = imap->getLocation("loc_test1", l1t); CHECK(b); - b = imap->getLocation("loc_test2", l2t); CHECK(b); - b = imap->getArea("area_test1", a1); CHECK(b); - b = imap->getPath("path_test1", p1); CHECK(b); - } -} - -void exec_iMap2D_test_2(IMap2D* imap) -{ - //////////"Checking IMap2D methods which involve usage of classes Map2DArea or Map2DLocation" - { - std::vector areas; - std::vector locs; - std::vector loc_names; - Map2DLocation loc; - Map2DArea area; - bool ret; - bool b1; - ret = imap->clearAllLocations(); CHECK(ret); - ret = imap->clearAllAreas(); CHECK(ret); - ret = imap->getAreasList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 0); - CHECK(b1); - ret = imap->getLocationsList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 0); - CHECK(b1); - - ret = imap->storeLocation("loc1", Map2DLocation("map1", 1, 2, 3)); CHECK(ret); - ret = imap->storeLocation("loc2", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); - - std::vector vec1, vec2, vec3; - Map2DLocation v; - v.x = 1.1; v.y = 1.1; vec1.push_back(v); - v.x = 1.2; v.y = 1.2; vec1.push_back(v); - v.x = 1.3; v.y = 1.3; vec1.push_back(v); - ret = imap->storeArea("area1", Map2DArea("map1", vec1)); CHECK(ret); - v.x = 2.1; v.y = 2.1; vec2 = vec1; vec2.push_back(v); - ret = imap->storeArea("area2", Map2DArea("map2", vec2)); CHECK(ret); - v.x = 3.1; v.y = 3.1; vec3 = vec2; vec3.push_back(v); - ret = imap->storeArea("area3", Map2DArea("map3", vec3)); CHECK(ret); - - ret = imap->getAreasList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 3); - CHECK(b1); - ret = imap->getLocationsList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 2); - CHECK(b1); - - ret = imap->getArea("area1", area); CHECK(ret); - b1 = (area == Map2DArea("map1", vec1)); - CHECK(b1); - ret = imap->getArea("area_err", area); CHECK(ret == false); - - ret = imap->getLocation("loc1", loc); CHECK(ret); - b1 = (loc == Map2DLocation("map1", 1, 2, 3)); - CHECK(b1); - ret = imap->getLocation("loc_err", loc); CHECK(ret == false); - - ret = imap->deleteArea("area1"); CHECK(ret); - ret = imap->deleteLocation("loc1"); CHECK(ret); - ret = imap->deleteArea("area_err"); CHECK(ret == false); - ret = imap->deleteLocation("loc_err"); CHECK(ret == false); - ret = imap->getArea("area1", area); CHECK(ret == false); - ret = imap->getLocation("loc1", loc); CHECK(ret == false); - - ret = imap->getArea("area2", area); CHECK(ret); - b1 = (area == Map2DArea("map2", vec2)); - CHECK(b1); - ret = imap->getLocation("loc2", loc); CHECK(ret); - b1 = (loc == Map2DLocation("map2", 4, 5, 6)); - CHECK(b1); - - ret = imap->clearAllLocations(); CHECK(ret); - ret = imap->clearAllAreas(); CHECK(ret); - ret = imap->getAreasList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 0); - CHECK(b1); - imap->getLocationsList(loc_names); - b1 = (loc_names.size() == 0); - CHECK(b1); - - ret = imap->storeArea("area", Map2DArea("map1", vec1)); CHECK(ret); - ret = imap->storeLocation("loc", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); - ret = imap->renameArea("area_fail", "area_new"); CHECK(ret == false); - ret = imap->renameLocation("loc_fail", "loc_new"); CHECK(ret == false); - ret = imap->renameArea("area", "area_new"); CHECK(ret); - ret = imap->renameLocation("loc", "loc_new"); CHECK(ret); - ret = imap->getArea("area", area); CHECK(ret == false); - ret = imap->getArea("area_new", area); CHECK(ret); - ret = imap->getLocation("loc", loc); CHECK(ret == false); - ret = imap->getLocation("loc_new", loc); CHECK(ret); - - //final cleanup, already tested - ret = imap->clearAllLocations(); CHECK(ret); - ret = imap->clearAllAreas(); CHECK(ret); - } - - //////////"Checking IMap2D methods which involve usage of classes Map2DPath/Map2DLocation" - { - std::vector paths; - std::vector locs; - std::vector loc_names; - std::vector path_names; - Map2DLocation loc; - Map2DPath path; - bool ret; - bool b1; - ret = imap->clearAllLocations(); CHECK(ret); - ret = imap->clearAllPaths(); CHECK(ret); - ret = imap->getPathsList(path_names); CHECK(ret); - b1 = (path_names.size() == 0); - CHECK(b1); - ret = imap->getLocationsList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 0); - CHECK(b1); - - ret = imap->storeLocation("loc1", Map2DLocation("map1", 1, 2, 3)); CHECK(ret); - ret = imap->storeLocation("loc2", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); - - std::vector vec1, vec2, vec3; - Map2DLocation v; - v.x = 1.1; v.y = 1.1; vec1.push_back(v); - v.x = 1.2; v.y = 1.2; vec1.push_back(v); - v.x = 1.3; v.y = 1.3; vec1.push_back(v); - ret = imap->storePath("path1", Map2DPath(vec1)); CHECK(ret); - v.x = 2.1; v.y = 2.1; vec2 = vec1; vec2.push_back(v); - ret = imap->storePath("path2", Map2DPath(vec2)); CHECK(ret); - v.x = 3.1; v.y = 3.1; vec3 = vec2; vec3.push_back(v); - ret = imap->storePath("path3", Map2DPath(vec3)); CHECK(ret); - - ret = imap->getPathsList(path_names); CHECK(ret); - b1 = (path_names.size() == 3); - CHECK(b1); - ret = imap->getLocationsList(loc_names); CHECK(ret); - b1 = (loc_names.size() == 2); - CHECK(b1); - - ret = imap->getPath("path1", path); CHECK(ret); - b1 = (path == Map2DPath(vec1)); - CHECK(b1); - ret = imap->getPath("path_err", path); CHECK(ret == false); - - ret = imap->getLocation("loc1", loc); CHECK(ret); - b1 = (loc == Map2DLocation("map1", 1, 2, 3)); - CHECK(b1); - ret = imap->getLocation("loc_err", loc); CHECK(ret == false); - - ret = imap->deletePath("path1"); CHECK(ret); - ret = imap->deleteLocation("loc1"); CHECK(ret); - ret = imap->deletePath("path_err"); CHECK(ret == false); - ret = imap->deleteLocation("loc_err"); CHECK(ret == false); - ret = imap->getPath("path1", path); CHECK(ret == false); - ret = imap->getLocation("loc1", loc); CHECK(ret == false); - - ret = imap->getPath("path2", path); CHECK(ret); - b1 = (path == Map2DPath(vec2)); - CHECK(b1); - ret = imap->getLocation("loc2", loc); CHECK(ret); - b1 = (loc == Map2DLocation("map2", 4, 5, 6)); - CHECK(b1); - - ret = imap->clearAllLocations(); CHECK(ret); - ret = imap->clearAllPaths(); CHECK(ret); - ret = imap->getPathsList(path_names); CHECK(ret); - b1 = (path_names.size() == 0); - CHECK(b1); - imap->getLocationsList(loc_names); - b1 = (loc_names.size() == 0); - CHECK(b1); - - ret = imap->storePath("path", Map2DPath(vec1)); CHECK(ret); - ret = imap->storeLocation("loc", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); - ret = imap->renamePath("path_fail", "path_new"); CHECK(ret == false); - ret = imap->renameLocation("loc_fail", "loc_new"); CHECK(ret == false); - ret = imap->renamePath("path", "path_new"); CHECK(ret); - ret = imap->renameLocation("loc", "loc_new"); CHECK(ret); - ret = imap->getPath("path", path); CHECK(ret == false); - ret = imap->getPath("path_new", path); CHECK(ret); - ret = imap->getLocation("loc", loc); CHECK(ret == false); - ret = imap->getLocation("loc_new", loc); CHECK(ret); - - path.toString(); - - //final cleanup, already tested - ret = imap->clearAllLocations(); CHECK(ret); - ret = imap->clearAllPaths(); CHECK(ret); - } - - //////////"Checking IMap2D methods which involve usage of classes MapGrid2D" - { - Nav2D::MapGrid2D test_store_map1; - Nav2D::MapGrid2D test_store_map2; - Nav2D::MapGrid2D test_get_map; - - test_store_map1.setMapName("test_map1"); - test_store_map2.setMapName("test_map2"); - std::vector map_names; - - imap->store_map(test_store_map1); - imap->store_map(test_store_map2); - imap->get_map("test_map1", test_get_map); - CHECK(test_store_map1.isIdenticalTo(test_get_map)); // IMap2D store/get operation successful - - imap->get_map_names(map_names); - bool b1 = (map_names.size() == 2); - bool b2 = false; - if (b1) { - b2 = (map_names[0] == "test_map1" && map_names[1] == "test_map2"); - } - CHECK(b1); - CHECK(b2); - // IMap2D get_map_names operation successful") - - imap->remove_map("test_map1"); - imap->get_map_names(map_names); - b1 = (map_names.size() == 1); - CHECK(b1); // IMap2D remove_map operation successful - - imap->clearAllMaps(); - imap->get_map_names(map_names); - b1 = (map_names.size() == 0); - CHECK(b1); // IMap2D clear operation successful - } -} diff --git a/src/libYARP_dev/src/tests/IMap2DTest.h b/src/libYARP_dev/src/tests/IMap2DTest.h deleted file mode 100644 index cb3fd9a7ec9..00000000000 --- a/src/libYARP_dev/src/tests/IMap2DTest.h +++ /dev/null @@ -1,19 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef IMAP2DTEST_H -#define IMAP2DTEST_H - -#include - -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; -using namespace yarp::sig; -using namespace yarp::os; - -void exec_iMap2D_test_1(IMap2D* imap); -void exec_iMap2D_test_2(IMap2D* imap); - -#endif diff --git a/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.cpp new file mode 100644 index 00000000000..d1080606646 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IMap2DTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h b/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h new file mode 100644 index 00000000000..f0253c52280 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h @@ -0,0 +1,291 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IMAP2DTEST_H +#define IMAP2DTEST_H + +#include +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void __declspec(dllimport) exec_iMap2D_test_1(IMap2D* imap) + { + { + //////////"Checking INavigation2D methods + std::vector ll; + std::vector la; + std::vector lp; + { + Map2DLocation l1 = Map2DLocation("map_1", 10.0, 20.0, 15); + Map2DLocation l2 = Map2DLocation("map_1", 10.2, 20.1, 15.5); + Map2DArea a1("map_1", std::vector {Map2DLocation("map_1", -10, -10, 0), + Map2DLocation("map_1", -10, +10, 0), + Map2DLocation("map_1", +10, +10, 0), + Map2DLocation("map_1", +10, -10, 0)}); + Map2DPath p1(std::vector {l1, l2}); + bool b; + b = imap->storeArea("area_test1", a1); CHECK(b); + b = imap->storeLocation("loc_test1", l1); CHECK(b); + b = imap->storeLocation("loc_test2", l2); CHECK(b); + b = imap->storePath("path_test1", p1); CHECK(b); + b = imap->getLocationsList(ll); CHECK(b); CHECK(ll.size() == 2); + b = imap->getAreasList(la); CHECK(b); CHECK(la.size() == 1); + b = imap->getPathsList(lp); CHECK(b); CHECK(lp.size() == 1); + } + + { + bool b; + b = imap->saveLocationsAndExtras("locations_test.ini"); CHECK(b); + b = imap->clearAllLocations(); CHECK(b); + b = imap->clearAllAreas(); CHECK(b); + b = imap->clearAllPaths(); CHECK(b); + b = imap->getLocationsList(ll); CHECK(b); CHECK(ll.size() == 0); + b = imap->getAreasList(la); CHECK(b); CHECK(la.size() == 0); + b = imap->getPathsList(lp); CHECK(b); CHECK(lp.size() == 0); + + b = imap->loadLocationsAndExtras("locations_test.ini"); CHECK(b); + Map2DLocation l1t; + Map2DLocation l2t; + Map2DArea a1; + Map2DPath p1; + b = imap->getLocationsList(ll); CHECK(b); CHECK(ll.size() == 2); + b = imap->getAreasList(la); CHECK(b); CHECK(la.size() == 1); + b = imap->getPathsList(lp); CHECK(b); CHECK(lp.size() == 1); + + b = imap->getLocation("loc_test1", l1t); CHECK(b); + b = imap->getLocation("loc_test2", l2t); CHECK(b); + b = imap->getArea("area_test1", a1); CHECK(b); + b = imap->getPath("path_test1", p1); CHECK(b); + } + } + } + + inline void __declspec(dllimport) exec_iMap2D_test_2(IMap2D* imap) + { + //////////"Checking IMap2D methods which involve usage of classes Map2DArea or Map2DLocation" + { + std::vector areas; + std::vector locs; + std::vector loc_names; + Map2DLocation loc; + Map2DArea area; + bool ret; + bool b1; + ret = imap->clearAllLocations(); CHECK(ret); + ret = imap->clearAllAreas(); CHECK(ret); + ret = imap->getAreasList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 0); + CHECK(b1); + ret = imap->getLocationsList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 0); + CHECK(b1); + + ret = imap->storeLocation("loc1", Map2DLocation("map1", 1, 2, 3)); CHECK(ret); + ret = imap->storeLocation("loc2", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); + + std::vector vec1, vec2, vec3; + Map2DLocation v; + v.x = 1.1; v.y = 1.1; vec1.push_back(v); + v.x = 1.2; v.y = 1.2; vec1.push_back(v); + v.x = 1.3; v.y = 1.3; vec1.push_back(v); + ret = imap->storeArea("area1", Map2DArea("map1", vec1)); CHECK(ret); + v.x = 2.1; v.y = 2.1; vec2 = vec1; vec2.push_back(v); + ret = imap->storeArea("area2", Map2DArea("map2", vec2)); CHECK(ret); + v.x = 3.1; v.y = 3.1; vec3 = vec2; vec3.push_back(v); + ret = imap->storeArea("area3", Map2DArea("map3", vec3)); CHECK(ret); + + ret = imap->getAreasList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 3); + CHECK(b1); + ret = imap->getLocationsList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 2); + CHECK(b1); + + ret = imap->getArea("area1", area); CHECK(ret); + b1 = (area == Map2DArea("map1", vec1)); + CHECK(b1); + ret = imap->getArea("area_err", area); CHECK(ret == false); + + ret = imap->getLocation("loc1", loc); CHECK(ret); + b1 = (loc == Map2DLocation("map1", 1, 2, 3)); + CHECK(b1); + ret = imap->getLocation("loc_err", loc); CHECK(ret == false); + + ret = imap->deleteArea("area1"); CHECK(ret); + ret = imap->deleteLocation("loc1"); CHECK(ret); + ret = imap->deleteArea("area_err"); CHECK(ret == false); + ret = imap->deleteLocation("loc_err"); CHECK(ret == false); + ret = imap->getArea("area1", area); CHECK(ret == false); + ret = imap->getLocation("loc1", loc); CHECK(ret == false); + + ret = imap->getArea("area2", area); CHECK(ret); + b1 = (area == Map2DArea("map2", vec2)); + CHECK(b1); + ret = imap->getLocation("loc2", loc); CHECK(ret); + b1 = (loc == Map2DLocation("map2", 4, 5, 6)); + CHECK(b1); + + ret = imap->clearAllLocations(); CHECK(ret); + ret = imap->clearAllAreas(); CHECK(ret); + ret = imap->getAreasList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 0); + CHECK(b1); + imap->getLocationsList(loc_names); + b1 = (loc_names.size() == 0); + CHECK(b1); + + ret = imap->storeArea("area", Map2DArea("map1", vec1)); CHECK(ret); + ret = imap->storeLocation("loc", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); + ret = imap->renameArea("area_fail", "area_new"); CHECK(ret == false); + ret = imap->renameLocation("loc_fail", "loc_new"); CHECK(ret == false); + ret = imap->renameArea("area", "area_new"); CHECK(ret); + ret = imap->renameLocation("loc", "loc_new"); CHECK(ret); + ret = imap->getArea("area", area); CHECK(ret == false); + ret = imap->getArea("area_new", area); CHECK(ret); + ret = imap->getLocation("loc", loc); CHECK(ret == false); + ret = imap->getLocation("loc_new", loc); CHECK(ret); + + //final cleanup, already tested + ret = imap->clearAllLocations(); CHECK(ret); + ret = imap->clearAllAreas(); CHECK(ret); + } + + //////////"Checking IMap2D methods which involve usage of classes Map2DPath/Map2DLocation" + { + std::vector paths; + std::vector locs; + std::vector loc_names; + std::vector path_names; + Map2DLocation loc; + Map2DPath path; + bool ret; + bool b1; + ret = imap->clearAllLocations(); CHECK(ret); + ret = imap->clearAllPaths(); CHECK(ret); + ret = imap->getPathsList(path_names); CHECK(ret); + b1 = (path_names.size() == 0); + CHECK(b1); + ret = imap->getLocationsList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 0); + CHECK(b1); + + ret = imap->storeLocation("loc1", Map2DLocation("map1", 1, 2, 3)); CHECK(ret); + ret = imap->storeLocation("loc2", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); + + std::vector vec1, vec2, vec3; + Map2DLocation v; + v.x = 1.1; v.y = 1.1; vec1.push_back(v); + v.x = 1.2; v.y = 1.2; vec1.push_back(v); + v.x = 1.3; v.y = 1.3; vec1.push_back(v); + ret = imap->storePath("path1", Map2DPath(vec1)); CHECK(ret); + v.x = 2.1; v.y = 2.1; vec2 = vec1; vec2.push_back(v); + ret = imap->storePath("path2", Map2DPath(vec2)); CHECK(ret); + v.x = 3.1; v.y = 3.1; vec3 = vec2; vec3.push_back(v); + ret = imap->storePath("path3", Map2DPath(vec3)); CHECK(ret); + + ret = imap->getPathsList(path_names); CHECK(ret); + b1 = (path_names.size() == 3); + CHECK(b1); + ret = imap->getLocationsList(loc_names); CHECK(ret); + b1 = (loc_names.size() == 2); + CHECK(b1); + + ret = imap->getPath("path1", path); CHECK(ret); + b1 = (path == Map2DPath(vec1)); + CHECK(b1); + ret = imap->getPath("path_err", path); CHECK(ret == false); + + ret = imap->getLocation("loc1", loc); CHECK(ret); + b1 = (loc == Map2DLocation("map1", 1, 2, 3)); + CHECK(b1); + ret = imap->getLocation("loc_err", loc); CHECK(ret == false); + + ret = imap->deletePath("path1"); CHECK(ret); + ret = imap->deleteLocation("loc1"); CHECK(ret); + ret = imap->deletePath("path_err"); CHECK(ret == false); + ret = imap->deleteLocation("loc_err"); CHECK(ret == false); + ret = imap->getPath("path1", path); CHECK(ret == false); + ret = imap->getLocation("loc1", loc); CHECK(ret == false); + + ret = imap->getPath("path2", path); CHECK(ret); + b1 = (path == Map2DPath(vec2)); + CHECK(b1); + ret = imap->getLocation("loc2", loc); CHECK(ret); + b1 = (loc == Map2DLocation("map2", 4, 5, 6)); + CHECK(b1); + + ret = imap->clearAllLocations(); CHECK(ret); + ret = imap->clearAllPaths(); CHECK(ret); + ret = imap->getPathsList(path_names); CHECK(ret); + b1 = (path_names.size() == 0); + CHECK(b1); + imap->getLocationsList(loc_names); + b1 = (loc_names.size() == 0); + CHECK(b1); + + ret = imap->storePath("path", Map2DPath(vec1)); CHECK(ret); + ret = imap->storeLocation("loc", Map2DLocation("map2", 4, 5, 6)); CHECK(ret); + ret = imap->renamePath("path_fail", "path_new"); CHECK(ret == false); + ret = imap->renameLocation("loc_fail", "loc_new"); CHECK(ret == false); + ret = imap->renamePath("path", "path_new"); CHECK(ret); + ret = imap->renameLocation("loc", "loc_new"); CHECK(ret); + ret = imap->getPath("path", path); CHECK(ret == false); + ret = imap->getPath("path_new", path); CHECK(ret); + ret = imap->getLocation("loc", loc); CHECK(ret == false); + ret = imap->getLocation("loc_new", loc); CHECK(ret); + + std::string s = path.toString(); + + //final cleanup, already tested + ret = imap->clearAllLocations(); CHECK(ret); + ret = imap->clearAllPaths(); CHECK(ret); + } + + //////////"Checking IMap2D methods which involve usage of classes MapGrid2D" + { + Nav2D::MapGrid2D test_store_map1; + Nav2D::MapGrid2D test_store_map2; + Nav2D::MapGrid2D test_get_map; + + test_store_map1.setMapName("test_map1"); + test_store_map2.setMapName("test_map2"); + std::vector map_names; + + imap->store_map(test_store_map1); + imap->store_map(test_store_map2); + imap->get_map("test_map1", test_get_map); + CHECK(test_store_map1.isIdenticalTo(test_get_map)); // IMap2D store/get operation successful + + imap->get_map_names(map_names); + bool b1 = (map_names.size() == 2); + bool b2 = false; + if (b1) { + b2 = (map_names[0] == "test_map1" && map_names[1] == "test_map2"); + } + CHECK(b1); + CHECK(b2); + // IMap2D get_map_names operation successful") + + imap->remove_map("test_map1"); + imap->get_map_names(map_names); + b1 = (map_names.size() == 1); + CHECK(b1); // IMap2D remove_map operation successful + + imap->clearAllMaps(); + imap->get_map_names(map_names); + b1 = (map_names.size() == 0); + CHECK(b1); // IMap2D clear operation successful + } + } +} + +#endif From 7991998d9e456aaf2b5121b52a18642b1253fae1 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 21 Nov 2022 16:13:21 +0100 Subject: [PATCH 024/267] fixed unknown type name 'dllimport' (clang) fixed tests when target YARP::YARP_math is not used --- src/libYARP_dev/src/CMakeLists.txt | 12 +++++++++++ .../src/yarp/dev/tests/IDummyTest.cpp | 6 ++++++ .../src/yarp/dev/tests/IDummyTest.h | 20 +++++++++++++++++++ .../src/yarp/dev/tests/IMap2DTest.h | 4 ++-- 4 files changed, 40 insertions(+), 2 deletions(-) create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IDummyTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IDummyTest.h diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index a0ed53aa592..41e7491f845 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -399,17 +399,29 @@ set(YARP_dev_PRIVATE_DEPS ${YARP_dev_PRIVATE_DEPS} PARENT_SCOPE) add_library(YARP_dev_tests) add_library(YARP::YARP_dev_tests ALIAS YARP_dev_tests) +if(TARGET YARP::YARP_math) target_sources(YARP_dev_tests PRIVATE yarp/dev/tests/IMap2DTest.cpp yarp/dev/tests/IMap2DTest.h + yarp/dev/tests/IDummyTest.cpp + yarp/dev/tests/IDummyTest.h +) +else() +target_sources(YARP_dev_tests + PRIVATE + yarp/dev/tests/IDummyTest.cpp + yarp/dev/tests/IDummyTest.h ) +endif() target_include_directories(YARP_dev_tests PRIVATE ${CMAKE_SOURCE_DIR}/extern/catch2 ) +target_compile_definitions(YARP_dev_tests PUBLIC YARP_dev_EXPORTS=1) + target_link_libraries(YARP_dev_tests PRIVATE YARP_dev) target_compile_features(YARP_dev_tests PRIVATE cxx_std_17) diff --git a/src/libYARP_dev/src/yarp/dev/tests/IDummyTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IDummyTest.cpp new file mode 100644 index 00000000000..b12cf30c1f6 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IDummyTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IDummyTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IDummyTest.h b/src/libYARP_dev/src/yarp/dev/tests/IDummyTest.h new file mode 100644 index 00000000000..44b75529008 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IDummyTest.h @@ -0,0 +1,20 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IDUMMYTEST_H +#define IDUMMYTEST_H + +#include + +namespace yarp::dev::tests +{ + inline bool YARP_dev_API exec_dummy_test() + { + bool b = true; + return b; + } +} + +#endif diff --git a/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h b/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h index f0253c52280..9f2632413b4 100644 --- a/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h +++ b/src/libYARP_dev/src/yarp/dev/tests/IMap2DTest.h @@ -17,7 +17,7 @@ using namespace yarp::os; namespace yarp::dev::tests { - inline void __declspec(dllimport) exec_iMap2D_test_1(IMap2D* imap) + inline void exec_iMap2D_test_1(IMap2D* imap) { { //////////"Checking INavigation2D methods @@ -69,7 +69,7 @@ namespace yarp::dev::tests } } - inline void __declspec(dllimport) exec_iMap2D_test_2(IMap2D* imap) + inline void exec_iMap2D_test_2(IMap2D* imap) { //////////"Checking IMap2D methods which involve usage of classes Map2DArea or Map2DLocation" { From 722853d5bb7d5e72879f8b2ca98cf9a283e65b08 Mon Sep 17 00:00:00 2001 From: elandini84 <62991576+elandini84@users.noreply.github.com> Date: Tue, 22 Nov 2022 12:48:14 +0100 Subject: [PATCH 025/267] AudioRecorderWrapper is now a WrapperSingle AudioRecorderWrapper inherits, now, from WrapperSingle and it's fully compatible with yarprobotinterface --- .../AudioRecorderWrapper.cpp | 104 ++++++------------ .../AudioRecorderWrapper.h | 11 +- 2 files changed, 41 insertions(+), 74 deletions(-) diff --git a/src/devices/audioRecorderWrapper/AudioRecorderWrapper.cpp b/src/devices/audioRecorderWrapper/AudioRecorderWrapper.cpp index 885bdf02077..40470e565c0 100644 --- a/src/devices/audioRecorderWrapper/AudioRecorderWrapper.cpp +++ b/src/devices/audioRecorderWrapper/AudioRecorderWrapper.cpp @@ -39,39 +39,13 @@ AudioRecorderWrapper::~AudioRecorderWrapper() bool AudioRecorderWrapper::open(yarp::os::Searchable& config) { + m_config.fromString(config.toString()); + if (config.check("period")) { m_period = config.find("period").asFloat64(); } - if (config.check("subdevice")) - { - yarp::os::Property p; - PolyDriverList driverlist; - p.fromString(config.toString(), false); - p.put("device", config.find("subdevice").asString()); - - if (!m_driver.open(p) || !m_driver.isValid()) - { - yCError(AUDIORECORDERWRAPPER) << "Failed to open subdevice.. check params"; - return false; - } - - driverlist.push(&m_driver, "1"); - if (!attachAll(driverlist)) - { - yCError(AUDIORECORDERWRAPPER) << "Failed to open subdevice.. check params"; - return false; - } - m_isDeviceOwned = true; - } - - if (m_mic == nullptr) - { - yCError(AUDIORECORDERWRAPPER, "Failed to open IAudioGrabberSound interface"); - return false; - } - // Get parameter samples_over_network if (config.check("min_samples_over_network")) { @@ -84,7 +58,6 @@ bool AudioRecorderWrapper::open(yarp::os::Searchable& config) yCInfo(AUDIORECORDERWRAPPER) << "Wrapper configured to produce packets with the following size (in samples): " << m_min_number_of_samples_over_network << " < samples < " << m_max_number_of_samples_over_network; - // Get parameter samples_over_network if (config.check("max_samples_timeout")) { @@ -116,18 +89,25 @@ bool AudioRecorderWrapper::open(yarp::os::Searchable& config) } m_rpcPort.setReader(*this); - bool b = m_mic->getRecordingAudioBufferMaxSize(m_max_buffer_size); - if (!b) + // Subdevice check and initialization + if (config.check("subdevice")) { - yCError(AUDIORECORDERWRAPPER, "getPlaybackAudioBufferMaxSize failed\n"); - return false; - } + yarp::os::Property p; + p.fromString(config.toString(), false); + p.put("device", config.find("subdevice").asString()); - // Wait a little and then start if requested - if (config.check("start")) { - yarp::os::SystemClock::delaySystem(1); - m_mic->startRecording(); - m_mic->isRecording(m_isRecording); + if (!m_driver.open(p) || !m_driver.isValid()) + { + yCError(AUDIORECORDERWRAPPER) << "Failed to open subdevice.. check params"; + return false; + } + + if (!attach(&m_driver)) + { + yCError(AUDIORECORDERWRAPPER) << "Failed to open subdevice.. check params"; + return false; + } + m_isDeviceOwned = true; } return true; @@ -232,56 +212,43 @@ bool AudioRecorderWrapper::read(yarp::os::ConnectionReader& connection) return true; } -bool AudioRecorderWrapper::attachAll(const PolyDriverList &device2attach) +bool AudioRecorderWrapper::attach(PolyDriver* driver) { - if (device2attach.size() != 1) + if (driver->isValid()) { - yCError(AUDIORECORDERWRAPPER, "Cannot attach more than one device"); - return false; + driver->view(m_mic); } - yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly; - - if (Idevice2attach->isValid()) + if (nullptr == m_mic) { - Idevice2attach->view(m_mic); + yCError(AUDIORECORDERWRAPPER, "Subdevice passed to attach method is invalid"); + return false; } - if (nullptr == m_mic) + if (!m_mic->getRecordingAudioBufferMaxSize(m_max_buffer_size)) { - yCError(AUDIORECORDERWRAPPER, "Subdevice passed to attach method is invalid"); + yCError(AUDIORECORDERWRAPPER, "getPlaybackAudioBufferMaxSize failed\n"); return false; } - attach(m_mic); m_dataThread = new AudioRecorderDataThread(this); m_statusThread = new AudioRecorderStatusThread(this); m_dataThread->setPeriod(m_period); m_dataThread->start(); m_statusThread->start(); - return true; -} -bool AudioRecorderWrapper::detachAll() -{ - if (m_dataThread->isRunning()) - { - m_dataThread->stop(); - } - if (m_statusThread->isRunning()) - { - m_statusThread->stop(); + // Wait a little and then start if requested + if (m_config.check("start")) { + yCDebug(AUDIORECORDERWRAPPER) << "Auto start has been evoked! Brace yourselves!"; + yarp::os::SystemClock::delaySystem(1); + m_mic->startRecording(); + m_mic->isRecording(m_isRecording); } - m_mic = nullptr; - return true; -} -void AudioRecorderWrapper::attach(yarp::dev::IAudioGrabberSound *igrab) -{ - m_mic = igrab; + return true; } -void AudioRecorderWrapper::detach() +bool AudioRecorderWrapper::detach() { if (m_dataThread->isRunning()) { @@ -292,6 +259,7 @@ void AudioRecorderWrapper::detach() m_statusThread->stop(); } m_mic = nullptr; + return true; } void AudioRecorderStatusThread::run() diff --git a/src/devices/audioRecorderWrapper/AudioRecorderWrapper.h b/src/devices/audioRecorderWrapper/AudioRecorderWrapper.h index fa29a4ab08a..391af8a3958 100644 --- a/src/devices/audioRecorderWrapper/AudioRecorderWrapper.h +++ b/src/devices/audioRecorderWrapper/AudioRecorderWrapper.h @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include #include #include @@ -45,12 +45,13 @@ class AudioRecorderDataThread; */ class AudioRecorderWrapper : public yarp::dev::DeviceDriver, - public yarp::dev::IMultipleWrapper, + public yarp::dev::WrapperSingle, public yarp::os::PortReader { private: yarp::dev::PolyDriver m_driver; yarp::dev::IAudioGrabberSound* m_mic = nullptr; //The microphone device + yarp::os::Property m_config; double m_period; yarp::os::Port m_rpcPort; yarp::os::Port m_streamingPort; @@ -84,11 +85,9 @@ class AudioRecorderWrapper : bool open(yarp::os::Searchable& config) override; bool close() override; - bool attachAll(const yarp::dev::PolyDriverList &p) override; - bool detachAll() override; - void attach(yarp::dev::IAudioGrabberSound *igrab); - void detach(); + bool attach(yarp::dev::PolyDriver* driver) override; + bool detach() override; bool read(yarp::os::ConnectionReader& connection) override; friend class AudioRecorderStatusThread; From 703b684d01e45007964fbacfbb935e72dbae0544 Mon Sep 17 00:00:00 2001 From: elandini84 <62991576+elandini84@users.noreply.github.com> Date: Tue, 22 Nov 2022 14:24:45 +0100 Subject: [PATCH 026/267] AudioPlayerWrapper is now a WrapperSingle AudioPlayerWrapper inherits, now, from WrapperSingle and it's fully compatible with yarprobotinterface --- .../audioPlayerWrapper/AudioPlayerWrapper.cpp | 84 +++++++------------ .../audioPlayerWrapper/AudioPlayerWrapper.h | 13 ++- 2 files changed, 38 insertions(+), 59 deletions(-) diff --git a/src/devices/audioPlayerWrapper/AudioPlayerWrapper.cpp b/src/devices/audioPlayerWrapper/AudioPlayerWrapper.cpp index b1aee6e6032..1d79873dd55 100644 --- a/src/devices/audioPlayerWrapper/AudioPlayerWrapper.cpp +++ b/src/devices/audioPlayerWrapper/AudioPlayerWrapper.cpp @@ -42,33 +42,30 @@ AudioPlayerWrapper::~AudioPlayerWrapper() * Specify which sensor this thread has to read from. */ -bool AudioPlayerWrapper::attachAll(const PolyDriverList &device2attach) +bool AudioPlayerWrapper::attach(PolyDriver* driver) { - if (device2attach.size() != 1) + if (driver->isValid()) { - yCError(AUDIOPLAYERWRAPPER, "Cannot attach more than one device"); - return false; + driver->view(m_irender); } - yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly; - - if (Idevice2attach->isValid()) + if (nullptr == m_irender) { - Idevice2attach->view(m_irender); + yCError(AUDIOPLAYERWRAPPER, "Subdevice passed to attach method is invalid"); + return false; } - if (nullptr == m_irender) + if (!m_irender->getPlaybackAudioBufferMaxSize(m_max_buffer_size)) { - yCError(AUDIOPLAYERWRAPPER, "Subdevice passed to attach method is invalid"); + yCError(AUDIOPLAYERWRAPPER, "getPlaybackAudioBufferMaxSize failed\n"); return false; } - attach(m_irender); PeriodicThread::setPeriod(m_period); return PeriodicThread::start(); } -bool AudioPlayerWrapper::detachAll() +bool AudioPlayerWrapper::detach() { if (PeriodicThread::isRunning()) { @@ -78,20 +75,6 @@ bool AudioPlayerWrapper::detachAll() return true; } -void AudioPlayerWrapper::attach(yarp::dev::IAudioRender *irend) -{ - m_irender = irend; -} - -void AudioPlayerWrapper::detach() -{ - if (PeriodicThread::isRunning()) - { - PeriodicThread::stop(); - } - m_irender = nullptr; -} - bool AudioPlayerWrapper::read(yarp::os::ConnectionReader& connection) { yarp::os::Bottle command; @@ -177,8 +160,7 @@ bool AudioPlayerWrapper::threadInit() bool AudioPlayerWrapper::open(yarp::os::Searchable &config) { - Property params; - params.fromString(config.toString()); + m_config.fromString(config.toString()); if (config.check("debug")) { @@ -215,7 +197,6 @@ bool AudioPlayerWrapper::open(yarp::os::Searchable &config) if(config.check("subdevice")) { Property p; - PolyDriverList driverlist; p.fromString(config.toString(), false); p.put("device", config.find("subdevice").asString()); @@ -224,33 +205,17 @@ bool AudioPlayerWrapper::open(yarp::os::Searchable &config) yCError(AUDIOPLAYERWRAPPER) << "Failed to open subdevice.. check params"; return false; } - - driverlist.push(&m_driver, "1"); - if(!attachAll(driverlist)) + if(!attach(&m_driver)) { yCError(AUDIOPLAYERWRAPPER) << "Failed to open subdevice.. check params"; return false; } m_isDeviceOwned = true; - } - - if (m_irender == nullptr) - { - yCError(AUDIOPLAYERWRAPPER, "m_irender is null\n"); - return false; - } - - bool b=m_irender->getPlaybackAudioBufferMaxSize(m_max_buffer_size); - if (!b) - { - yCError(AUDIOPLAYERWRAPPER, "getPlaybackAudioBufferMaxSize failed\n"); - return false; - } - - if (config.check("start")) - { - m_irender->startPlayback(); - m_irender->isPlaying(m_isPlaying); + if (m_irender == nullptr) + { + yCError(AUDIOPLAYERWRAPPER, "m_irender is null\n"); + return false; + } } return true; @@ -287,6 +252,18 @@ void AudioPlayerWrapper::threadRelease() m_statusPort.close(); } +void AudioPlayerWrapper::afterStart(bool success) +{ + if(success) + { + if (m_config.check("start")) + { + m_irender->startPlayback(); + m_irender->isPlaying(m_isPlaying); + } + } +} + void AudioPlayerWrapper::run() { double current_time = yarp::os::Time::now(); @@ -348,6 +325,9 @@ bool AudioPlayerWrapper::close() PeriodicThread::stop(); } - detachAll(); + if(m_config.check("subdevice")) + { + detach(); + } return true; } diff --git a/src/devices/audioPlayerWrapper/AudioPlayerWrapper.h b/src/devices/audioPlayerWrapper/AudioPlayerWrapper.h index 9f2cdcb13af..cfa784b4ede 100644 --- a/src/devices/audioPlayerWrapper/AudioPlayerWrapper.h +++ b/src/devices/audioPlayerWrapper/AudioPlayerWrapper.h @@ -29,7 +29,7 @@ #include #include #include -#include +#include #include /** @@ -52,7 +52,7 @@ class AudioPlayerWrapper : public yarp::os::PeriodicThread, public yarp::dev::DeviceDriver, - public yarp::dev::IMultipleWrapper, + public yarp::dev::WrapperSingle, public yarp::os::PortReader { @@ -77,13 +77,11 @@ class AudioPlayerWrapper : /** * Specify which sensor this thread has to read from. */ - bool attachAll(const yarp::dev::PolyDriverList &p) override; - bool detachAll() override; - - void attach(yarp::dev::IAudioRender *irend); - void detach(); + bool attach(yarp::dev::PolyDriver *driver) override; + bool detach() override; bool threadInit() override; + void afterStart(bool success) override; void threadRelease() override; void run() override; @@ -96,6 +94,7 @@ class AudioPlayerWrapper : yarp::os::BufferedPort m_audioInPort; std::string m_statusPortName; yarp::os::Port m_statusPort; + yarp::os::Property m_config; yarp::dev::IAudioRender *m_irender = nullptr; yarp::os::Stamp m_lastStateStamp; From a09f5d5bc479580ad6d978281053d8b536c47d6d Mon Sep 17 00:00:00 2001 From: elandini84 <62991576+elandini84@users.noreply.github.com> Date: Tue, 22 Nov 2022 14:25:05 +0100 Subject: [PATCH 027/267] Added markdown file for changelog --- ...tor_audioWrappers_multiWrapperToSingleWrapper.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 doc/release/master/refactor_audioWrappers_multiWrapperToSingleWrapper.md diff --git a/doc/release/master/refactor_audioWrappers_multiWrapperToSingleWrapper.md b/doc/release/master/refactor_audioWrappers_multiWrapperToSingleWrapper.md new file mode 100644 index 00000000000..4c5eb2f1dea --- /dev/null +++ b/doc/release/master/refactor_audioWrappers_multiWrapperToSingleWrapper.md @@ -0,0 +1,13 @@ +refactor_audioWrappers_multiWrapperToSingleWrapper {#master} +------------------- + +### AudioRecorderWrapper and AudioPlayerWrapper + +#### `yarp::dev` + +The two wrappers have been modified in order to be compatible with `yarprobotinterface` without losing the +compatibility with `yarpdev` and the `subdevice` option + +Now the two objects do not inherit from `yarp::dev::IMultipleWrapper` but from `yarp::dev::WrapperSingle` + +This modification has been done in order to allow the two wrappers to implement both the `IWrapper` and the `IMultipleWrapper` interfaces From 7df706ab3dc814a31b77fa93aeaa7fba11fd9e54 Mon Sep 17 00:00:00 2001 From: elandini84 <62991576+elandini84@users.noreply.github.com> Date: Wed, 23 Nov 2022 11:48:42 +0100 Subject: [PATCH 028/267] Added --title option to yarpview Now it's possibile to set a custom title for the yarpview window. --- doc/release/master/feature_yarpview_titleOption.md | 9 +++++++++ src/yarpview/plugin/VideoSurface.qml | 9 ++++++++- src/yarpview/plugin/qtyarpview.cpp | 13 +++++++++++++ src/yarpview/plugin/qtyarpview.h | 2 ++ src/yarpview/src/qml/QtYARPView/main.qml | 3 +++ src/yarpview/src/qml/QtYARPView/mainCompact.qml | 4 ++-- 6 files changed, 37 insertions(+), 3 deletions(-) create mode 100644 doc/release/master/feature_yarpview_titleOption.md diff --git a/doc/release/master/feature_yarpview_titleOption.md b/doc/release/master/feature_yarpview_titleOption.md new file mode 100644 index 00000000000..956a737ea57 --- /dev/null +++ b/doc/release/master/feature_yarpview_titleOption.md @@ -0,0 +1,9 @@ +feature_yarpview_titleOption {#master} +--------------- + +### Tools + +#### `yarpview` + +* Added the possibility to set a custom title for `yarpview` by passing `--title` + *custom title* to the executable +* If the `title` argument is not passed `yarpview` window title will be assigned as it has been until now \ No newline at end of file diff --git a/src/yarpview/plugin/VideoSurface.qml b/src/yarpview/plugin/VideoSurface.qml index e20e57d1e18..84fd31b7503 100644 --- a/src/yarpview/plugin/VideoSurface.qml +++ b/src/yarpview/plugin/VideoSurface.qml @@ -31,6 +31,7 @@ Rectangle { signal synchRate(bool check); signal autosize(bool check); signal setName(string name); + signal setTitle(string inputTitle); signal saveSetClosed(bool check); signal saveSingleClosed(bool check); signal rightClickEnabled(bool enabled); @@ -70,7 +71,13 @@ Rectangle { } onSetName:{ - setName(name) + setName(name); + } + + onSetTitle:{ + if(inputTitle.length > 0) { + setTitle(inputTitle); + } } onWidthChanged:{ diff --git a/src/yarpview/plugin/qtyarpview.cpp b/src/yarpview/plugin/qtyarpview.cpp index d1c6e0e3184..4ec413a75bc 100644 --- a/src/yarpview/plugin/qtyarpview.cpp +++ b/src/yarpview/plugin/qtyarpview.cpp @@ -277,6 +277,15 @@ void QtYARPView::setOptions(yarp::os::Searchable& options) { qsnprintf(_options.m_portName, 256, "%s", val->asString().c_str()); qDebug("%s", val->asString().c_str()); } + if (options.check("Title",val)||options.check("title",val)) { + qsnprintf(_options.m_title, 256, "%s", val->asString().c_str()); + qDebug("%s", val->asString().c_str()); + } + else{ + if(options.check("compact")){ + qsnprintf(_options.m_title, 256, "%s", _options.m_portName); + } + } if (options.check("NetName",val)||options.check("n",val)) { qsnprintf(_options.m_networkName, 256, "%s", val->asString().c_str()); } @@ -341,6 +350,8 @@ void QtYARPView::printHelp() { qDebug("yarpview usage:"); qDebug(" --name: input port name (default: /yarpview/img:i)"); + qDebug(" --title: A title for the yarpview window (default: input port name"); + qDebug(" if in compact mode, otherwise it will be \"YARP Qt Image Viewer\")"); qDebug(" --x: x position of the window in the screen"); qDebug(" --y: y position of the window in the screen"); qDebug(" --w: width of the window"); @@ -363,6 +374,7 @@ void QtYARPView::setOptionsToDefault() // Options defaults _options.m_refreshTime = 100; qsnprintf(_options.m_portName, 256, "%s","/yarpview/img:i"); + qsnprintf(_options.m_title, 256, "%s",""); qsnprintf(_options.m_networkName, 256, "%s", "default"); qsnprintf(_options.m_outPortName, 256, "%s","/yarpview/o:point"); qsnprintf(_options.m_outRightPortName, 256, "%s","/yarpview/r:o:point"); @@ -397,6 +409,7 @@ bool QtYARPView::openPorts() ptr_inputPort->setReadOnly(); ret= ptr_inputPort->open(_options.m_portName); emit setName(ptr_inputPort->getName().c_str()); + emit setTitle(_options.m_title); if (!ret){ qDebug("Error: port failed to open, quitting."); diff --git a/src/yarpview/plugin/qtyarpview.h b/src/yarpview/plugin/qtyarpview.h index cfef99b67c5..088d70e06c5 100644 --- a/src/yarpview/plugin/qtyarpview.h +++ b/src/yarpview/plugin/qtyarpview.h @@ -28,6 +28,7 @@ struct mOptions { unsigned int m_refreshTime; char m_portName[256]; + char m_title[256]; char m_networkName[256]; int m_windWidth; int m_windHeight; @@ -134,6 +135,7 @@ class QtYARPView : public QQuickItem void synchRate(bool check); void autosize(bool check); void setName(QString name); + void setTitle(QString inputTitle); private slots: void onSendFps(double portAvg, double portMin, double portMax, double dispAvg, double dispMin, double dispMax); void onWindowSizeChangeRequested(); diff --git a/src/yarpview/src/qml/QtYARPView/main.qml b/src/yarpview/src/qml/QtYARPView/main.qml index cb9ed29ed49..d87a3cb56bd 100644 --- a/src/yarpview/src/qml/QtYARPView/main.qml +++ b/src/yarpview/src/qml/QtYARPView/main.qml @@ -76,6 +76,9 @@ ApplicationWindow { onSetName:{ statusBar.setName(name) } + onSetTitle:{ + window.title=inputTitle + } onSaveSetClosed:{ menu.saveSetChecked(check); } diff --git a/src/yarpview/src/qml/QtYARPView/mainCompact.qml b/src/yarpview/src/qml/QtYARPView/mainCompact.qml index b418de34738..0925d58e05c 100644 --- a/src/yarpview/src/qml/QtYARPView/mainCompact.qml +++ b/src/yarpview/src/qml/QtYARPView/mainCompact.qml @@ -60,8 +60,8 @@ ApplicationWindow { menu.enableAutosize(check) } } - onSetName:{ - title = name + onSetTitle:{ + window.title=inputTitle } } } From 5320c434586c457ae511231cf9a099a65a474fb2 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 23 Nov 2022 11:44:52 +0100 Subject: [PATCH 029/267] Files in RemoteFrameGrabber folder split to RemoteFrameGrabber and FrameGrabber_nwc_yarp. Repo cleanup in preparation of RemoteFrameGrabber deprecation in favor of FrameGrabber_nwc_yarp --- src/devices/CMakeLists.txt | 1 + src/devices/RemoteFrameGrabber/CMakeLists.txt | 49 ------------------- .../frameGrabber_nwc_yarp/CMakeLists.txt | 49 +++++++++++++++++++ .../FrameGrabber_nwc_yarp.cpp | 0 .../FrameGrabber_nwc_yarp.h | 0 tests/devices/CMakeLists.txt | 1 - tests/devices/remote_grabber_basic.ini | 13 ----- 7 files changed, 50 insertions(+), 63 deletions(-) create mode 100644 src/devices/frameGrabber_nwc_yarp/CMakeLists.txt rename src/devices/{RemoteFrameGrabber => frameGrabber_nwc_yarp}/FrameGrabber_nwc_yarp.cpp (100%) rename src/devices/{RemoteFrameGrabber => frameGrabber_nwc_yarp}/FrameGrabber_nwc_yarp.h (100%) delete mode 100644 tests/devices/remote_grabber_basic.ini diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index d9390ae9d27..b733186e0e7 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -30,6 +30,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(frameTransformStorageMsgs) add_subdirectory(frameTransformStorage) add_subdirectory(frameTransformUtils) + add_subdirectory(frameGrabber_nwc_yarp) add_subdirectory(frameGrabber_nws_yarp) add_subdirectory(transformClient) add_subdirectory(transformServer) diff --git a/src/devices/RemoteFrameGrabber/CMakeLists.txt b/src/devices/RemoteFrameGrabber/CMakeLists.txt index 7c099359802..616f7e42d1f 100644 --- a/src/devices/RemoteFrameGrabber/CMakeLists.txt +++ b/src/devices/RemoteFrameGrabber/CMakeLists.txt @@ -48,52 +48,3 @@ if(NOT SKIP_remote_grabber) set_property(TARGET yarp_remote_grabber PROPERTY FOLDER "Plugins/Device") endif() - - - -yarp_prepare_plugin(frameGrabber_nwc_yarp - CATEGORY device - TYPE FrameGrabber_nwc_yarp - INCLUDE FrameGrabber_nwc_yarp.h - EXTRA_CONFIG - WRAPPER=frameGrabber_nws_yarp - DEFAULT ON -) - -if(NOT SKIP_frameGrabber_nwc_yarp) - yarp_add_plugin(yarp_frameGrabber_nwc_yarp) - - target_sources(yarp_frameGrabber_nwc_yarp - PRIVATE - FrameGrabber_nwc_yarp.cpp - FrameGrabber_nwc_yarp.h - ) - - target_sources(yarp_frameGrabber_nwc_yarp PRIVATE $) - target_include_directories(yarp_frameGrabber_nwc_yarp PRIVATE $) - - target_link_libraries(yarp_frameGrabber_nwc_yarp - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_frameGrabber_nwc_yarp - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_frameGrabber_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") -endif() diff --git a/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt b/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt new file mode 100644 index 00000000000..eb288a59ead --- /dev/null +++ b/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt @@ -0,0 +1,49 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +yarp_prepare_plugin(frameGrabber_nwc_yarp + CATEGORY device + TYPE FrameGrabber_nwc_yarp + INCLUDE FrameGrabber_nwc_yarp.h + EXTRA_CONFIG + WRAPPER=frameGrabber_nws_yarp + DEFAULT ON +) + +if(NOT SKIP_frameGrabber_nwc_yarp) + yarp_add_plugin(yarp_frameGrabber_nwc_yarp) + + target_sources(yarp_frameGrabber_nwc_yarp + PRIVATE + FrameGrabber_nwc_yarp.cpp + FrameGrabber_nwc_yarp.h + ) + + target_sources(yarp_frameGrabber_nwc_yarp PRIVATE $) + target_include_directories(yarp_frameGrabber_nwc_yarp PRIVATE $) + + target_link_libraries(yarp_frameGrabber_nwc_yarp + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + ) + + yarp_install( + TARGETS yarp_frameGrabber_nwc_yarp + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_frameGrabber_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") +endif() diff --git a/src/devices/RemoteFrameGrabber/FrameGrabber_nwc_yarp.cpp b/src/devices/frameGrabber_nwc_yarp/FrameGrabber_nwc_yarp.cpp similarity index 100% rename from src/devices/RemoteFrameGrabber/FrameGrabber_nwc_yarp.cpp rename to src/devices/frameGrabber_nwc_yarp/FrameGrabber_nwc_yarp.cpp diff --git a/src/devices/RemoteFrameGrabber/FrameGrabber_nwc_yarp.h b/src/devices/frameGrabber_nwc_yarp/FrameGrabber_nwc_yarp.h similarity index 100% rename from src/devices/RemoteFrameGrabber/FrameGrabber_nwc_yarp.h rename to src/devices/frameGrabber_nwc_yarp/FrameGrabber_nwc_yarp.h diff --git a/tests/devices/CMakeLists.txt b/tests/devices/CMakeLists.txt index 4a6b899b9d0..64f6b42d049 100644 --- a/tests/devices/CMakeLists.txt +++ b/tests/devices/CMakeLists.txt @@ -31,7 +31,6 @@ set(_inis group_basic.ini opencv_grabber_basic.ini portaudio_basic.ini - remote_grabber_basic.ini fakeFrameGrabber_basic.ini fakeMotionControl_basic.ini usbCamera.ini diff --git a/tests/devices/remote_grabber_basic.ini b/tests/devices/remote_grabber_basic.ini deleted file mode 100644 index ab1fbd40854..00000000000 --- a/tests/devices/remote_grabber_basic.ini +++ /dev/null @@ -1,13 +0,0 @@ -# sending images to a port called "/save" will result in them -# being saved to test.avi - -device pipe - -[source] -device remote_grabber -local /save - -[sink] -device ffmpeg_writer -out test.avi -framerate 30 From 4e9e41af18725b02e3c412165fad6e1f3cb78a68 Mon Sep 17 00:00:00 2001 From: elandini84 <62991576+elandini84@users.noreply.github.com> Date: Wed, 23 Nov 2022 14:10:06 +0100 Subject: [PATCH 030/267] Improved help text for the new option --- src/yarpview/plugin/qtyarpview.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/yarpview/plugin/qtyarpview.cpp b/src/yarpview/plugin/qtyarpview.cpp index 4ec413a75bc..85fd90786d0 100644 --- a/src/yarpview/plugin/qtyarpview.cpp +++ b/src/yarpview/plugin/qtyarpview.cpp @@ -350,8 +350,11 @@ void QtYARPView::printHelp() { qDebug("yarpview usage:"); qDebug(" --name: input port name (default: /yarpview/img:i)"); - qDebug(" --title: A title for the yarpview window (default: input port name"); - qDebug(" if in compact mode, otherwise it will be \"YARP Qt Image Viewer\")"); + qDebug(" --title: A title for the yarpview window"); + qDebug(" (default"); + qDebug(" - compact flag enabled: input port name"); + qDebug(" - compact flag disabled: \"YARP Qt Image Viewer\""); + qDebug(" )"); qDebug(" --x: x position of the window in the screen"); qDebug(" --y: y position of the window in the screen"); qDebug(" --w: width of the window"); From 80ec2f3820fa281716c00813aebb86038552bb3f Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 23 Nov 2022 13:07:40 +0100 Subject: [PATCH 031/267] device `pipe` has been removed --- .ci/initial-cache.gh.linux.cmake | 1 + doc/module_executables/cmd_yarpdev.dox | 1 - doc/release/master/device_pipe_removed.md | 6 + example/dev/grabber_client/grabber_client.cpp | 2 +- src/devices/CMakeLists.txt | 1 - src/devices/DevicePipe/CMakeLists.txt | 42 ----- src/devices/DevicePipe/DevicePipe.cpp | 157 ------------------ src/devices/DevicePipe/DevicePipe.h | 59 ------- 8 files changed, 8 insertions(+), 261 deletions(-) create mode 100644 doc/release/master/device_pipe_removed.md delete mode 100644 src/devices/DevicePipe/CMakeLists.txt delete mode 100644 src/devices/DevicePipe/DevicePipe.cpp delete mode 100644 src/devices/DevicePipe/DevicePipe.h diff --git a/.ci/initial-cache.gh.linux.cmake b/.ci/initial-cache.gh.linux.cmake index 0573b4fc8fd..35f79fc5a4a 100644 --- a/.ci/initial-cache.gh.linux.cmake +++ b/.ci/initial-cache.gh.linux.cmake @@ -91,6 +91,7 @@ set(ENABLE_yarpmod_serial ON CACHE BOOL "") set(ENABLE_yarpmod_fakeMotor ON CACHE BOOL "") set(ENABLE_yarpmod_test_motor ON CACHE BOOL "") set(ENABLE_yarpmod_remote_grabber ON CACHE BOOL "") +set(ENABLE_yarpmod_frameGrabber_nwc_yarp ON CACHE BOOL "") set(ENABLE_yarpmod_remote_controlboard ON CACHE BOOL "") set(ENABLE_yarpmod_analogsensorclient ON CACHE BOOL "") set(ENABLE_yarpmod_analogServer ON CACHE BOOL "") diff --git a/doc/module_executables/cmd_yarpdev.dox b/doc/module_executables/cmd_yarpdev.dox index d7fa872dba8..71615289e40 100644 --- a/doc/module_executables/cmd_yarpdev.dox +++ b/doc/module_executables/cmd_yarpdev.dox @@ -60,7 +60,6 @@ Device "XSensMTx", C++ class XSensMTx, wrapped by "inertial" Device "opencv_grabber", C++ class OpenCVGrabber, wrapped by "grabber" Device "ffmpeg_grabber", C++ class FfmpegGrabber, wrapped by "grabber" Device "fakeFrameGrabber", C++ class FakeFrameGrabber, wrapped by "grabber" -Device "remote_grabber", C++ class RemoteFrameGrabber, wrapped by "grabber" Device "grabber", C++ class ServerFrameGrabber, is a network wrapper. Device "inertial", C++ class ServerInertial, is a network wrapper. Device "sound_grabber", C++ class ServerSoundGrabber, is a network wrapper. diff --git a/doc/release/master/device_pipe_removed.md b/doc/release/master/device_pipe_removed.md new file mode 100644 index 00000000000..ff0f8419523 --- /dev/null +++ b/doc/release/master/device_pipe_removed.md @@ -0,0 +1,6 @@ +device_pipe_removed {#master} +----------- + +### `Devices` + +* device `pipe` has been removed because of faulty/incomplete implementation and unused. diff --git a/example/dev/grabber_client/grabber_client.cpp b/example/dev/grabber_client/grabber_client.cpp index c879bb603e3..ed9f20169e4 100644 --- a/example/dev/grabber_client/grabber_client.cpp +++ b/example/dev/grabber_client/grabber_client.cpp @@ -37,7 +37,7 @@ int main(int argc, char* argv[]) Network yarp; Property config; - config.put("device", "remote_grabber"); // device type + config.put("device", "frameGrabber_nwc_yarp"); // device type config.put("local", "/client"); // name of local port to use config.put("remote", "/fakey"); // name of remote port to connect to diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index b733186e0e7..b4f0e916df1 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -79,7 +79,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(fakeLocalizerDevice) add_subdirectory(fakeNavigationDevice) add_subdirectory(DeviceGroup) - add_subdirectory(DevicePipe) add_subdirectory(ServerSerial) add_subdirectory(RemoteFrameGrabber) add_subdirectory(RemoteControlBoard) diff --git a/src/devices/DevicePipe/CMakeLists.txt b/src/devices/DevicePipe/CMakeLists.txt deleted file mode 100644 index 2c1a4efd4d5..00000000000 --- a/src/devices/DevicePipe/CMakeLists.txt +++ /dev/null @@ -1,42 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(pipe - CATEGORY device - TYPE DevicePipe - INCLUDE DevicePipe.h - DEFAULT ON -) - -if(NOT SKIP_pipe) - yarp_add_plugin(yarp_pipe) - - target_sources(yarp_pipe - PRIVATE - DevicePipe.cpp - DevicePipe.h) - - target_link_libraries(yarp_pipe PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_pipe - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_pipe PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/DevicePipe/DevicePipe.cpp b/src/devices/DevicePipe/DevicePipe.cpp deleted file mode 100644 index 317959edd6a..00000000000 --- a/src/devices/DevicePipe/DevicePipe.cpp +++ /dev/null @@ -1,157 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "DevicePipe.h" - -#include -#include - -#include -#include -#include - -#include - -using namespace yarp::os; -using namespace yarp::sig; -using namespace yarp::dev; - -namespace { -YARP_LOG_COMPONENT(DEVICEPIPE, "yarp.devices.DevicePipe") -} - -bool DevicePipe::open(yarp::os::Searchable& config) -{ - bool ok = open("source", - source, - config, - "device to read from (string or nested properties)"); - if (!ok) { - return false; - } - ok = open("sink", - sink, - config, - "device to write to (string or nested properties)"); - if (!ok) { - source.close(); - return false; - } - return true; -} - - -bool DevicePipe::open(const char* key, - PolyDriver& poly, - yarp::os::Searchable& config, - const char* comment) -{ - - Value* name; - if (config.check(key, name, comment)) { - if (name->isString()) { - // maybe user isn't doing nested configuration - yarp::os::Property p; - p.setMonitor(config.getMonitor(), - name->toString().c_str()); // pass on any monitoring - p.fromString(config.toString()); - p.put("device", name->toString()); - p.unput("subdevice"); - p.unput("wrapped"); - poly.open(p); - } else { - Bottle subdevice = config.findGroup(key).tail(); - poly.open(subdevice); - } - if (!poly.isValid()) { - yCInfo(DEVICEPIPE, "cannot make <%s>", name->toString().c_str()); - return false; - } - } else { - yCInfo(DEVICEPIPE, "\"--%s \" not set", key); - return false; - } - return true; -} - - -bool DevicePipe::close() -{ - yCInfo(DEVICEPIPE, "Devices closing"); - source.close(); - sink.close(); - return true; -} - - -bool DevicePipe::updateService() -{ - IFrameGrabberImage* imgSource; - IAudioGrabberSound* sndSource; - IAudioVisualGrabber* imgSndSource; - IAudioVisualStream* sourceType; - - IAudioRender* sndSink; - IFrameWriterImage* imgSink; - IFrameWriterAudioVisual* imgSndSink; - IAudioVisualStream* sinkType; - - source.view(imgSource); - source.view(sndSource); - source.view(imgSndSource); - source.view(sourceType); - - sink.view(imgSink); - sink.view(sndSink); - sink.view(imgSndSink); - sink.view(sinkType); - - if (sourceType != nullptr) { - if (!(sourceType->hasAudio() && sourceType->hasVideo())) { - imgSndSource = nullptr; - } - } - if (sinkType != nullptr) { - if (!(sinkType->hasAudio() && sinkType->hasVideo())) { - imgSndSink = nullptr; - } - } - - - if (imgSndSource != nullptr && imgSndSink != nullptr) { - ImageOf tmp; - Sound tmpSound; - imgSndSource->getAudioVisual(tmp, tmpSound); - imgSndSink->putAudioVisual(tmp, tmpSound); - yCInfo(DEVICEPIPE, - "piped %zux%zu image, %zux%zu sound", - tmp.width(), - tmp.height(), - tmpSound.getSamples(), - tmpSound.getChannels()); - } else if (imgSource != nullptr && imgSink != nullptr) { - ImageOf tmp; - imgSource->getImage(tmp); - imgSink->putImage(tmp); - yCInfo(DEVICEPIPE, "piped %zux%zu image", tmp.width(), tmp.height()); - } else if (sndSource != nullptr && sndSink != nullptr) { - Sound tmp; - //the following values have been arbitrarily chosen and may be optimized. - //4410 samples correspond to 0.1s with a frequency of 44100hz. - sndSource->getSound(tmp, 4410, 4410, 0); - sndSink->renderSound(tmp); - yCInfo(DEVICEPIPE, - "piped %zux%zu sound", - tmp.getSamples(), - tmp.getChannels()); - } else { - yCInfo(DEVICEPIPE, "Don't know how to pipe between these devices."); - yCInfo(DEVICEPIPE, "Piping is very limited at the moment."); - yCInfo(DEVICEPIPE, "You're probably better off writing some short custom code."); - return false; - } - return true; -} diff --git a/src/devices/DevicePipe/DevicePipe.h b/src/devices/DevicePipe/DevicePipe.h deleted file mode 100644 index a7e1861d0a6..00000000000 --- a/src/devices/DevicePipe/DevicePipe.h +++ /dev/null @@ -1,59 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_DEVICEPIPE_H -#define YARP_DEV_DEVICEPIPE_H - -#include -#include - - -/** - * @ingroup dev_impl_other - * - * \brief `pipe`: Tries to connect the output of one device to the input of another. - */ -class DevicePipe : - public yarp::dev::DeviceDriver, - public yarp::dev::IService -{ -public: - DevicePipe() = default; - DevicePipe(const DevicePipe&) = delete; - DevicePipe(DevicePipe&&) = delete; - DevicePipe& operator=(const DevicePipe&) = delete; - DevicePipe& operator=(DevicePipe&&) = delete; - ~DevicePipe() override = default; - - bool open(yarp::os::Searchable& config) override; - - bool close() override; - - bool startService() override - { - // please call updateService - return false; - } - - bool stopService() override - { - return close(); - } - - bool updateService() override; - -protected: - yarp::dev::PolyDriver source; - yarp::dev::PolyDriver sink; - - static bool open(const char* key, - yarp::dev::PolyDriver& poly, - yarp::os::Searchable& config, - const char* comment); -}; - - -#endif // YARP_DEV_DEVICEPIPE_H From 0c16a4607575e2cac2b8642ba2b065c47c6709c8 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 21 Nov 2022 23:39:05 +0100 Subject: [PATCH 032/267] added tests for: Map2DStorage, Map2D_nws_yarp --- src/devices/map2DStorage/CMakeLists.txt | 5 ++ src/devices/map2DStorage/tests/CMakeLists.txt | 53 ++++++++++++++++++ .../map2DStorage/tests/Map2DStorageTest.cpp | 54 +++++++++++++++++++ src/devices/map2D_nws_yarp/CMakeLists.txt | 5 ++ .../map2D_nws_yarp/tests/CMakeLists.txt | 53 ++++++++++++++++++ .../map2D_nws_yarp/tests/Map2DnwsTest.cpp | 48 +++++++++++++++++ 6 files changed, 218 insertions(+) create mode 100644 src/devices/map2DStorage/tests/CMakeLists.txt create mode 100644 src/devices/map2DStorage/tests/Map2DStorageTest.cpp create mode 100644 src/devices/map2D_nws_yarp/tests/CMakeLists.txt create mode 100644 src/devices/map2D_nws_yarp/tests/Map2DnwsTest.cpp diff --git a/src/devices/map2DStorage/CMakeLists.txt b/src/devices/map2DStorage/CMakeLists.txt index f079baf70ff..09eca035c0a 100644 --- a/src/devices/map2DStorage/CMakeLists.txt +++ b/src/devices/map2DStorage/CMakeLists.txt @@ -46,4 +46,9 @@ if(NOT SKIP_map2DStorage) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_map2DStorage PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/map2DStorage/tests/CMakeLists.txt b/src/devices/map2DStorage/tests/CMakeLists.txt new file mode 100644 index 00000000000..37044ce0e1f --- /dev/null +++ b/src/devices/map2DStorage/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_Map2DStorage) + +target_sources(harness_dev_Map2DStorage + PRIVATE + Map2DStorageTest.cpp +) + +target_link_libraries(harness_dev_Map2DStorage + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_Map2DStorage + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Map2DnwcTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_Map2DStorage PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_Map2DStorage) diff --git a/src/devices/map2DStorage/tests/Map2DStorageTest.cpp b/src/devices/map2DStorage/tests/Map2DStorageTest.cpp new file mode 100644 index 00000000000..009325e23ef --- /dev/null +++ b/src/devices/map2DStorage/tests/Map2DStorageTest.cpp @@ -0,0 +1,54 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Map2DStorageTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("map2DStorage", "device"); + + Network::setLocalMode(true); + + SECTION("Checking map2DStorage device") + { + PolyDriver ddmapstorage; + IMap2D* imap = nullptr; + + ////////"Checking opening polydriver" + { + Property pmapstorage_cfg; + pmapstorage_cfg.put("device", "map2DStorage"); + REQUIRE(ddmapstorage.open(pmapstorage_cfg)); + REQUIRE(ddmapstorage.view(imap)); + } + + //execute tests + yarp::dev::tests::exec_iMap2D_test_1 (imap); + yarp::dev::tests::exec_iMap2D_test_2 (imap); + + //"Close all polydrivers and check" + { + CHECK(ddmapstorage.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/map2D_nws_yarp/CMakeLists.txt b/src/devices/map2D_nws_yarp/CMakeLists.txt index f6b5ab3a1e1..4ceb9e30968 100644 --- a/src/devices/map2D_nws_yarp/CMakeLists.txt +++ b/src/devices/map2D_nws_yarp/CMakeLists.txt @@ -54,4 +54,9 @@ if(NOT SKIP_map2D_nws_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_map2D_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/map2D_nws_yarp/tests/CMakeLists.txt b/src/devices/map2D_nws_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..5c99004c9cc --- /dev/null +++ b/src/devices/map2D_nws_yarp/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_Map2Dnws) + +target_sources(harness_dev_Map2Dnws + PRIVATE + Map2DnwsTest.cpp +) + +target_link_libraries(harness_dev_Map2Dnws + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_Map2Dnws + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Map2DnwsTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_Map2Dnws PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_Map2Dnws) diff --git a/src/devices/map2D_nws_yarp/tests/Map2DnwsTest.cpp b/src/devices/map2D_nws_yarp/tests/Map2DnwsTest.cpp new file mode 100644 index 00000000000..376a3dcd96c --- /dev/null +++ b/src/devices/map2D_nws_yarp/tests/Map2DnwsTest.cpp @@ -0,0 +1,48 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Map2DnwsTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("map2D_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking map2D_nws_yarp device") + { + PolyDriver ddmapserver; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property pmapserver_cfg; + pmapserver_cfg.put("device", "map2D_nws_yarp"); + REQUIRE(ddmapserver.open(pmapserver_cfg)); + } + + //"Close all polydrivers and check" + { + CHECK(ddmapserver.close()); + } + } + + Network::setLocalMode(false); +} From 096bed3abfb75ef2e1bb859185c7c8b4bd6cd71c Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 22 Nov 2022 12:03:35 +0100 Subject: [PATCH 033/267] added tests for: FakeNavigationDevice, Navigation2D_nwc, Navigation2D_nws --- .../fakeNavigationDevice/CMakeLists.txt | 5 + .../fakeNavigationDevice/tests/CMakeLists.txt | 53 +++++ .../tests/FakeNavigationTest.cpp | 57 ++++++ .../navigation2D_nwc_yarp/CMakeLists.txt | 5 + .../tests/CMakeLists.txt | 53 +++++ .../tests}/Navigation2DnwcTest.cpp | 11 +- .../navigation2D_nws_yarp/CMakeLists.txt | 5 + .../tests/CMakeLists.txt | 53 +++++ .../tests/Navigation2DnwsTest.cpp | 44 +++++ src/libYARP_dev/src/CMakeLists.txt | 2 + .../src/yarp/dev/tests/INavigation2DTest.cpp | 6 + .../src/yarp/dev/tests/INavigation2DTest.h | 186 +++++++++++++++++ tests/libYARP_dev/CMakeLists.txt | 6 - tests/libYARP_dev/INavigation2DTest.cpp | 187 ------------------ tests/libYARP_dev/INavigation2DTest.h | 20 -- 15 files changed, 473 insertions(+), 220 deletions(-) create mode 100644 src/devices/fakeNavigationDevice/tests/CMakeLists.txt create mode 100644 src/devices/fakeNavigationDevice/tests/FakeNavigationTest.cpp create mode 100644 src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/navigation2D_nwc_yarp/tests}/Navigation2DnwcTest.cpp (94%) create mode 100644 src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt create mode 100644 src/devices/navigation2D_nws_yarp/tests/Navigation2DnwsTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.h delete mode 100644 tests/libYARP_dev/INavigation2DTest.cpp delete mode 100644 tests/libYARP_dev/INavigation2DTest.h diff --git a/src/devices/fakeNavigationDevice/CMakeLists.txt b/src/devices/fakeNavigationDevice/CMakeLists.txt index 2e4d1b00377..0cca688af27 100644 --- a/src/devices/fakeNavigationDevice/CMakeLists.txt +++ b/src/devices/fakeNavigationDevice/CMakeLists.txt @@ -43,4 +43,9 @@ if(NOT SKIP_fakeNavigation) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeNavigation PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeNavigationDevice/tests/CMakeLists.txt b/src/devices/fakeNavigationDevice/tests/CMakeLists.txt new file mode 100644 index 00000000000..9f95c4ecb6d --- /dev/null +++ b/src/devices/fakeNavigationDevice/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeNavigation) + +target_sources(harness_dev_fakeNavigation + PRIVATE + FakeNavigationTest.cpp +) + +target_link_libraries(harness_dev_fakeNavigation + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_fakeNavigation + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + FakeNavigationTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_fakeNavigation PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeNavigation) diff --git a/src/devices/fakeNavigationDevice/tests/FakeNavigationTest.cpp b/src/devices/fakeNavigationDevice/tests/FakeNavigationTest.cpp new file mode 100644 index 00000000000..72568381823 --- /dev/null +++ b/src/devices/fakeNavigationDevice/tests/FakeNavigationTest.cpp @@ -0,0 +1,57 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::FakeNavigationTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeNavigation", "device"); + + Network::setLocalMode(true); + + SECTION("Checking fakeNavigation device") + { + PolyDriver ddfakeNavigation; + IMap2D* imap = nullptr; + INavigation2D* inav = nullptr; + INavigation2DTargetActions* inav_target = nullptr; + INavigation2DControlActions* inav_control = nullptr; + INavigation2DVelocityActions* inav_velocity = nullptr; + + ////////"Checking opening fakeNavigation polydrivers" + { + Property pfakeNavigation; + pfakeNavigation.put("device", "fakeNavigation"); + REQUIRE(ddfakeNavigation.open(pfakeNavigation)); + REQUIRE(ddfakeNavigation.view(inav_target)); + REQUIRE(ddfakeNavigation.view(inav_control)); + REQUIRE(ddfakeNavigation.view(inav_velocity)); + } + + // Do tests + //yarp::dev::tests::exec_iNav2D_test_1(inav, imap); + //yarp::dev::tests::exec_iNav2D_test_2(inav, imap); + + //"Close all polydrivers and check" + { + CHECK(ddfakeNavigation.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/navigation2D_nwc_yarp/CMakeLists.txt b/src/devices/navigation2D_nwc_yarp/CMakeLists.txt index 72569a2cca3..622bf8e6af8 100644 --- a/src/devices/navigation2D_nwc_yarp/CMakeLists.txt +++ b/src/devices/navigation2D_nwc_yarp/CMakeLists.txt @@ -56,4 +56,9 @@ if(NOT SKIP_navigation2D_nwc_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_navigation2D_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..c1b08e19f0c --- /dev/null +++ b/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_Navigation2Dnwc) + +target_sources(harness_dev_Navigation2Dnwc + PRIVATE + Navigation2DnwcTest.cpp +) + +target_link_libraries(harness_dev_Navigation2Dnwc + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_Navigation2Dnwc + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Navigation2DnwcTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_Navigation2Dnwc PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_Navigation2Dnwc) diff --git a/tests/libYARP_dev/Navigation2DnwcTest.cpp b/src/devices/navigation2D_nwc_yarp/tests/Navigation2DnwcTest.cpp similarity index 94% rename from tests/libYARP_dev/Navigation2DnwcTest.cpp rename to src/devices/navigation2D_nwc_yarp/tests/Navigation2DnwcTest.cpp index 6d6f581092e..92f60cc0749 100644 --- a/tests/libYARP_dev/Navigation2DnwcTest.cpp +++ b/src/devices/navigation2D_nwc_yarp/tests/Navigation2DnwcTest.cpp @@ -5,12 +5,11 @@ #include #include -#include -#include #include #include #include #include +#include #include #include @@ -20,8 +19,6 @@ using namespace yarp::dev::Nav2D; using namespace yarp::sig; using namespace yarp::os; -#include "INavigation2DTest.h" - TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") { YARP_REQUIRE_PLUGIN("map2D_nws_yarp", "device"); @@ -57,7 +54,7 @@ TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") pmapstorage_cfg.put("device", "map2DStorage"); REQUIRE(ddmapstorage.open(pmapstorage_cfg)); {yarp::dev::WrapperSingle* ww_nws; ddmapserver.view(ww_nws); - bool result_att = ww_nws->attach(&ddmapstorage);} + bool result_att = ww_nws->attach(&ddmapstorage); } Property pmapclient_cfg; pmapclient_cfg.put("device", "map2D_nwc_yarp"); @@ -95,8 +92,8 @@ TEST_CASE("dev::Navigation2DNwcTest", "[yarp::dev]") } // Do tests - exec_iNav2D_test_1(inav, imap); - exec_iNav2D_test_2(inav, imap); + yarp::dev::tests::exec_iNav2D_test_1(inav, imap); + yarp::dev::tests::exec_iNav2D_test_2(inav, imap); //"Close all polydrivers and check" { diff --git a/src/devices/navigation2D_nws_yarp/CMakeLists.txt b/src/devices/navigation2D_nws_yarp/CMakeLists.txt index 79f922a732a..097e600345f 100644 --- a/src/devices/navigation2D_nws_yarp/CMakeLists.txt +++ b/src/devices/navigation2D_nws_yarp/CMakeLists.txt @@ -51,4 +51,9 @@ if(NOT SKIP_navigation2D_nws_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_navigation2D_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt b/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..343591a296a --- /dev/null +++ b/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_Navigation2Dnws) + +target_sources(harness_dev_Navigation2Dnws + PRIVATE + Navigation2DnwsTest.cpp +) + +target_link_libraries(harness_dev_Navigation2Dnws + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_Navigation2Dnws + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Navigation2DnwsTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_Navigation2Dnws PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_Navigation2Dnws) diff --git a/src/devices/navigation2D_nws_yarp/tests/Navigation2DnwsTest.cpp b/src/devices/navigation2D_nws_yarp/tests/Navigation2DnwsTest.cpp new file mode 100644 index 00000000000..582b8f9e18f --- /dev/null +++ b/src/devices/navigation2D_nws_yarp/tests/Navigation2DnwsTest.cpp @@ -0,0 +1,44 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Navigation2DNwsTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("navigation2D_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking navigation2D_nws_yarp device") + { + PolyDriver ddnavserver; + + ////////"Checking opening navigation2D_nws_yarp polydrivers" + { + Property pnavserver_cfg; + pnavserver_cfg.put("device", "navigation2D_nws_yarp"); + REQUIRE(ddnavserver.open(pnavserver_cfg)); + } + + //"Close all polydrivers and check" + { + CHECK(ddnavserver.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index 41e7491f845..e615bc397c1 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -404,6 +404,8 @@ target_sources(YARP_dev_tests PRIVATE yarp/dev/tests/IMap2DTest.cpp yarp/dev/tests/IMap2DTest.h + yarp/dev/tests/INavigation2DTest.cpp + yarp/dev/tests/INavigation2DTest.h yarp/dev/tests/IDummyTest.cpp yarp/dev/tests/IDummyTest.h ) diff --git a/src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.cpp new file mode 100644 index 00000000000..a7430fd28ac --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "INavigation2DTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.h b/src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.h new file mode 100644 index 00000000000..f2e315e92c3 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/INavigation2DTest.h @@ -0,0 +1,186 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef INAVIGATION2DTEST_H +#define INAVIGATION2DTEST_H + +#include +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void test_similar_angles(INavigation2D* inav, double angle1, double angle2) + { + bool b0, b1; + b0 = inav->setInitialPose(Map2DLocation("map_1", 10.2, 20.1, angle1)); CHECK(b0); + yarp::os::Time::delay(0.1); + INFO("Testing angle" + std::to_string(angle1) + " is similar to:" + std::to_string(angle2)); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2), 0.1, 10.0); CHECK(b1); + //yInfo() << "Testing angle" << angle1 << " is similar to:" << angle2 + 5.0; + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 + 5.0), 0.1, 10.0); CHECK(b1); + //yInfo() << "Testing angle" << angle1 << " is different from:" << angle2 + 20.0; + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 + 20.0), 0.1, 10.0); CHECK(!b1); + //yInfo() << "Testing angle" << angle1 << " is similar to:" << angle2 - 5.0; + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 - 5.0), 0.1, 10.0); CHECK(b1); + //yInfo() << "Testing angle" << angle1 << " is different from:" << angle2 - 20.0; + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 - 20.0), 0.1, 10.0); CHECK(!b1); + } + + inline void exec_iNav2D_test_1(INavigation2D* inav, IMap2D* imap) + { + //////////"Checking INavigation2D methods + Map2DLocation loc_test = Map2DLocation("map_1", 10.0, 20.0, 15); + Map2DLocation my_current_loc = Map2DLocation("map_1", 10.2, 20.1, 15.5); + Map2DLocation loc_to_be_tested; + Map2DArea area_test("map_1", std::vector {Map2DLocation("map_1", -10, -10, 0), + Map2DLocation("map_1", -10, +10, 0), + Map2DLocation("map_1", +10, +10, 0), + Map2DLocation("map_1", +10, -10, 0)}, "this is a test area"); + bool b0, b1; + b0 = imap->storeArea("area_test", area_test); CHECK(b0); + b0 = imap->storeLocation("loc_test", loc_test); CHECK(b0); + + { + b0 = inav->setInitialPose(my_current_loc); CHECK(b0); + yarp::os::Time::delay(0.1); + b0 = inav->getCurrentPosition(loc_to_be_tested); CHECK(b0); CHECK(loc_to_be_tested == my_current_loc); + b1 = inav->checkInsideArea("area_test"); CHECK(b1 == false); + b1 = inav->checkInsideArea(area_test); CHECK(b1 == false); + b0 = inav->setInitialPose(Map2DLocation("map_1", 0, 0, 0)); CHECK(b0); + yarp::os::Time::delay(0.1); + b0 = inav->getCurrentPosition(loc_to_be_tested); CHECK(loc_to_be_tested == Map2DLocation("map_1", 0, 0, 0)); + b1 = inav->checkInsideArea("area_test"); CHECK(b1); + b1 = inav->checkInsideArea(area_test); CHECK(b1); + } + + { + double lin_tol = 1.0; //m + double ang_tol = 1.0; //deg + b0 = inav->setInitialPose(my_current_loc); CHECK(b0); + yarp::os::Time::delay(0.1); + b1 = inav->checkNearToLocation("loc_test", lin_tol, ang_tol); CHECK(b1); + b1 = inav->checkNearToLocation(loc_test, lin_tol, ang_tol); CHECK(b1); + } + { + double lin_tol = 0.0001; //m + double ang_tol = 0.0001; //deg + b0 = inav->setInitialPose(my_current_loc); CHECK(b0); + yarp::os::Time::delay(0.1); + b1 = inav->checkNearToLocation("loc_test", lin_tol, ang_tol); CHECK(b1 == false); + b1 = inav->checkNearToLocation(loc_test, lin_tol, ang_tol); CHECK(b1 == false); + } + { + double lin_tol = 1.0; //m + Map2DLocation my_current_loc2 = my_current_loc; my_current_loc2.theta = 90; + b0 = inav->setInitialPose(my_current_loc2); CHECK(b0); + yarp::os::Time::delay(0.1); + b1 = inav->checkNearToLocation("loc_test", lin_tol); CHECK(b1); + b1 = inav->checkNearToLocation(loc_test, lin_tol); CHECK(b1); + } + { + double lin_tol = 0.1; //m + double ang_tol = 0.1; //deg + b0 = inav->setInitialPose(my_current_loc); CHECK(b0); yarp::os::Time::delay(0.1); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5), lin_tol, ang_tol); CHECK(b1); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 + 180), lin_tol, ang_tol); CHECK(b1 == false); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 + 360), lin_tol, ang_tol); CHECK(b1); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 + 720), lin_tol, ang_tol); CHECK(b1); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 - 180), lin_tol, ang_tol); CHECK(b1 == false); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 - 360), lin_tol, ang_tol); CHECK(b1); + b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 - 720), lin_tol, ang_tol); CHECK(b1); + + //in the following tests, the tolerance is set to 10.0 deg + test_similar_angles(inav, +2.0, +2.0); + test_similar_angles(inav, -2.0, +2.0); + test_similar_angles(inav, +2.0, -2.0); + test_similar_angles(inav, -2.0, -2.0); + + test_similar_angles(inav, +182.0, +182.0); + test_similar_angles(inav, -182.0, +182.0); + test_similar_angles(inav, +182.0, -182.0); + test_similar_angles(inav, -182.0, -182.0); + + test_similar_angles(inav, 2.0, 358.0); + test_similar_angles(inav, -2.0, 358.0); + test_similar_angles(inav, 2.0, -358.0); + test_similar_angles(inav, -2.0, -358.0); + + test_similar_angles(inav, +2.0, 718.0); + test_similar_angles(inav, -2.0, 718.0); + test_similar_angles(inav, +2.0, -718.0); + test_similar_angles(inav, -2.0, -718.0); + } + { + b0 = inav->setInitialPose(my_current_loc); CHECK(b0); yarp::os::Time::delay(0.1); + yarp::dev::OdometryData my_current_odom; + b1 = inav->getEstimatedOdometry(my_current_odom); CHECK(b1); + INFO("Current position is:" + my_current_loc.toString()); + INFO("Estimated Odometry is:" + my_current_odom.toString()); + bool bodom = fabs(my_current_loc.x - my_current_odom.odom_x) < 0.0000001 && + fabs(my_current_loc.y - my_current_odom.odom_y) < 0.0000001 && + fabs(my_current_loc.theta - my_current_odom.odom_theta) < 0.0000001; + CHECK(bodom); + } + } + + inline void exec_iNav2D_test_2(INavigation2D* inav, IMap2D* imap) + { + //////////"Checking INavigation2D methods + bool b0, b1, b2; + Map2DLocation tloc("test", 1, 2, 3); + Map2DLocation gloc1; + Map2DLocation gloc_empty; + std::string tname("testLoc"); + std::string gname1; + NavigationStatusEnum gstat1; + + b0 = inav->storeLocation(tname, tloc); CHECK(b0); + + //going to a location by absolute value + b1 = inav->stopNavigation(); CHECK(b1); + b1 = inav->getNavigationStatus(gstat1); CHECK(b1); CHECK(gstat1 == NavigationStatusEnum::navigation_status_idle); + + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); + b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); + b1 = inav->gotoTargetByAbsoluteLocation(tloc); CHECK(b1); + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == tloc); + b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); + + //going to an existing location by name + b1 = inav->stopNavigation(); CHECK(b1); + b1 = inav->getNavigationStatus(gstat1); CHECK(b1); CHECK(gstat1 == NavigationStatusEnum::navigation_status_idle); + + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); + b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); + + b1 = inav->gotoTargetByLocationName(tname); CHECK(b1); + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == tloc); + b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == tname); + + //stop must clear navigation target name + b1 = inav->stopNavigation(); CHECK(b1); + b1 = inav->getNavigationStatus(gstat1); CHECK(b1); CHECK(gstat1 == NavigationStatusEnum::navigation_status_idle); + b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); + + //trying to goto to a non-existing location by name, target name must be not set + b1 = inav->gotoTargetByLocationName("non-existing-loc"); CHECK(b1 == false); + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); + b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); + + //mix of last two tests. A non existing location must clear a previously set target name + b1 = inav->gotoTargetByLocationName(tname); CHECK(b1); + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == tloc); + b1 = inav->gotoTargetByLocationName("non-existing-loc"); CHECK(b1 == false); + b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); + } +} + +#endif diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index 260e6d30d10..184cb74dab5 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -12,8 +12,6 @@ target_sources(harness_dev GroupDriverTest.cpp IFrameTransformTest.cpp MapGrid2DTest.cpp - Navigation2DnwcTest.cpp - INavigation2DTest.cpp MultipleAnalogSensorsInterfacesTest.cpp PolyDriverTest.cpp robotDescriptionTest.cpp @@ -39,10 +37,6 @@ else() TransformClientTest.cpp FrameTransformClientTest.cpp IFrameTransformTest.cpp - Map2DClientTest.cpp - INavigation2DTest.cpp - Navigation2DnwcTest.cpp - Navigation2DClientTest.cpp MapGrid2DTest.cpp ) set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) diff --git a/tests/libYARP_dev/INavigation2DTest.cpp b/tests/libYARP_dev/INavigation2DTest.cpp deleted file mode 100644 index 3df9c454e20..00000000000 --- a/tests/libYARP_dev/INavigation2DTest.cpp +++ /dev/null @@ -1,187 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "INavigation2DTest.h" - -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; -using namespace yarp::sig; -using namespace yarp::os; - -void test_similar_angles(INavigation2D* inav, double angle1, double angle2) -{ - bool b0, b1; - b0 = inav->setInitialPose(Map2DLocation("map_1", 10.2, 20.1, angle1)); CHECK(b0); - yarp::os::Time::delay(0.1); - yInfo() << "Testing angle" << angle1 << " is similar to:" << angle2; - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2), 0.1, 10.0); CHECK(b1); - yInfo() << "Testing angle" << angle1 << " is similar to:" << angle2+5.0; - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 + 5.0), 0.1, 10.0); CHECK(b1); - yInfo() << "Testing angle" << angle1 << " is different from:" << angle2 + 20.0; - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 + 20.0), 0.1, 10.0); CHECK(!b1); - yInfo() << "Testing angle" << angle1 << " is similar to:" << angle2-5.0; - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 - 5.0), 0.1, 10.0); CHECK(b1); - yInfo() << "Testing angle" << angle1 << " is different from:" << angle2 - 20.0; - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, angle2 - 20.0), 0.1, 10.0); CHECK(!b1); -} - -void exec_iNav2D_test_1(INavigation2D* inav, IMap2D* imap) -{ - //////////"Checking INavigation2D methods - Map2DLocation loc_test = Map2DLocation("map_1", 10.0, 20.0, 15); - Map2DLocation my_current_loc = Map2DLocation("map_1", 10.2, 20.1, 15.5); - Map2DLocation loc_to_be_tested; - Map2DArea area_test("map_1", std::vector {Map2DLocation("map_1", -10, -10, 0), - Map2DLocation("map_1", -10, +10, 0), - Map2DLocation("map_1", +10, +10, 0), - Map2DLocation("map_1", +10, -10, 0)}, "this is a test area"); - bool b0, b1; - b0 = imap->storeArea("area_test", area_test); CHECK(b0); - b0 = imap->storeLocation("loc_test", loc_test); CHECK(b0); - - { - b0 = inav->setInitialPose(my_current_loc); CHECK(b0); - yarp::os::Time::delay(0.1); - b0 = inav->getCurrentPosition(loc_to_be_tested); CHECK(b0); CHECK(loc_to_be_tested == my_current_loc); - b1 = inav->checkInsideArea("area_test"); CHECK(b1 == false); - b1 = inav->checkInsideArea(area_test); CHECK(b1 == false); - b0 = inav->setInitialPose(Map2DLocation("map_1", 0, 0, 0)); CHECK(b0); - yarp::os::Time::delay(0.1); - b0 = inav->getCurrentPosition(loc_to_be_tested); CHECK(loc_to_be_tested == Map2DLocation("map_1", 0, 0, 0)); - b1 = inav->checkInsideArea("area_test"); CHECK(b1); - b1 = inav->checkInsideArea(area_test); CHECK(b1); - } - - { - double lin_tol = 1.0; //m - double ang_tol = 1.0; //deg - b0 = inav->setInitialPose(my_current_loc); CHECK(b0); - yarp::os::Time::delay(0.1); - b1 = inav->checkNearToLocation("loc_test", lin_tol, ang_tol); CHECK(b1); - b1 = inav->checkNearToLocation(loc_test, lin_tol, ang_tol); CHECK(b1); - } - { - double lin_tol = 0.0001; //m - double ang_tol = 0.0001; //deg - b0 = inav->setInitialPose(my_current_loc); CHECK(b0); - yarp::os::Time::delay(0.1); - b1 = inav->checkNearToLocation("loc_test", lin_tol, ang_tol); CHECK(b1==false); - b1 = inav->checkNearToLocation(loc_test, lin_tol, ang_tol); CHECK(b1==false); - } - { - double lin_tol = 1.0; //m - Map2DLocation my_current_loc2 = my_current_loc; my_current_loc2.theta = 90; - b0 = inav->setInitialPose(my_current_loc2); CHECK(b0); - yarp::os::Time::delay(0.1); - b1 = inav->checkNearToLocation("loc_test", lin_tol); CHECK(b1); - b1 = inav->checkNearToLocation(loc_test, lin_tol); CHECK(b1); - } - { - double lin_tol = 0.1; //m - double ang_tol = 0.1; //deg - b0 = inav->setInitialPose(my_current_loc); CHECK(b0); yarp::os::Time::delay(0.1); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5) , lin_tol, ang_tol); CHECK(b1); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 + 180), lin_tol, ang_tol); CHECK(b1 == false); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 + 360), lin_tol, ang_tol); CHECK(b1); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 + 720), lin_tol, ang_tol); CHECK(b1); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 - 180), lin_tol, ang_tol); CHECK(b1 == false); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 - 360), lin_tol, ang_tol); CHECK(b1); - b1 = inav->checkNearToLocation(Map2DLocation("map_1", 10.2, 20.1, 15.5 - 720), lin_tol, ang_tol); CHECK(b1); - - //in the following tests, the tolerance is set to 10.0 deg - test_similar_angles(inav, +2.0, +2.0); - test_similar_angles(inav, -2.0, +2.0); - test_similar_angles(inav, +2.0, -2.0); - test_similar_angles(inav, -2.0, -2.0); - - test_similar_angles(inav, +182.0, +182.0); - test_similar_angles(inav, -182.0, +182.0); - test_similar_angles(inav, +182.0, -182.0); - test_similar_angles(inav, -182.0, -182.0); - - test_similar_angles(inav, 2.0, 358.0); - test_similar_angles(inav, -2.0, 358.0); - test_similar_angles(inav, 2.0, -358.0); - test_similar_angles(inav, -2.0, -358.0); - - test_similar_angles(inav, +2.0, 718.0); - test_similar_angles(inav, -2.0, 718.0); - test_similar_angles(inav, +2.0, -718.0); - test_similar_angles(inav, -2.0, -718.0); - } - { - b0 = inav->setInitialPose(my_current_loc); CHECK(b0); yarp::os::Time::delay(0.1); - yarp::dev::OdometryData my_current_odom; - b1 = inav->getEstimatedOdometry(my_current_odom); CHECK(b1); - yInfo() << "Current position is:" << my_current_loc.toString(); - yInfo() << "Estimated Odometry is:"<< my_current_odom.toString(); - bool bodom = fabs(my_current_loc.x- my_current_odom.odom_x) < 0.0000001 && - fabs(my_current_loc.y - my_current_odom.odom_y) < 0.0000001 && - fabs(my_current_loc.theta - my_current_odom.odom_theta) < 0.0000001; - CHECK(bodom); - } -} - -void exec_iNav2D_test_2(INavigation2D* inav, IMap2D* imap) -{ - //////////"Checking INavigation2D methods - bool b0,b1,b2; - Map2DLocation tloc ("test",1,2,3); - Map2DLocation gloc1; - Map2DLocation gloc_empty; - std::string tname ("testLoc"); - std::string gname1; - NavigationStatusEnum gstat1; - - b0 = inav->storeLocation(tname, tloc); CHECK(b0); - - //going to a location by absolute value - b1 = inav->stopNavigation(); CHECK(b1); - b1 = inav->getNavigationStatus(gstat1); CHECK(b1); CHECK(gstat1==NavigationStatusEnum::navigation_status_idle); - - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1==gloc_empty); - b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); - b1 = inav->gotoTargetByAbsoluteLocation(tloc); CHECK(b1); - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1==tloc); - b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); - - //going to an existing location by name - b1 = inav->stopNavigation(); CHECK(b1); - b1 = inav->getNavigationStatus(gstat1); CHECK(b1); CHECK(gstat1 == NavigationStatusEnum::navigation_status_idle); - - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); - b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); - - b1 = inav->gotoTargetByLocationName(tname); CHECK(b1); - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == tloc); - b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == tname); - - //stop must clear navigation target name - b1 = inav->stopNavigation(); CHECK(b1); - b1 = inav->getNavigationStatus(gstat1); CHECK(b1); CHECK(gstat1 == NavigationStatusEnum::navigation_status_idle); - b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); - - //trying to goto to a non-existing location by name, target name must be not set - b1 = inav->gotoTargetByLocationName("non-existing-loc"); CHECK(b1==false); - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); - b1 = inav->getNameOfCurrentTarget(gname1); CHECK(b1); CHECK(gname1 == ""); - - //mix of last two tests. A non existing location must clear a previously set target name - b1 = inav->gotoTargetByLocationName(tname); CHECK(b1); - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == tloc); - b1 = inav->gotoTargetByLocationName("non-existing-loc"); CHECK(b1 == false); - b1 = inav->getAbsoluteLocationOfCurrentTarget(gloc1); CHECK(b1); CHECK(gloc1 == gloc_empty); -} diff --git a/tests/libYARP_dev/INavigation2DTest.h b/tests/libYARP_dev/INavigation2DTest.h deleted file mode 100644 index 283a0920a73..00000000000 --- a/tests/libYARP_dev/INavigation2DTest.h +++ /dev/null @@ -1,20 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef INAVIGATION2DTEST_H -#define INAVIGATION2DTEST_H - -#include -#include - -using namespace yarp::dev; -using namespace yarp::dev::Nav2D; -using namespace yarp::sig; -using namespace yarp::os; - -void exec_iNav2D_test_1(INavigation2D* inav, IMap2D* imap); -void exec_iNav2D_test_2(INavigation2D* inav, IMap2D* imap); - -#endif From 6494ec55265e719fea1f9cb0ffcdb826145e916f Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 22 Nov 2022 14:18:06 +0100 Subject: [PATCH 034/267] cleanup: Folder location of targets frameTransformRC, frameTransformServerRC in Visual Studio project --- src/devices/frameTransformClient/CMakeLists.txt | 2 ++ src/devices/frameTransformServer/CMakeLists.txt | 1 + 2 files changed, 3 insertions(+) diff --git a/src/devices/frameTransformClient/CMakeLists.txt b/src/devices/frameTransformClient/CMakeLists.txt index 9cfa29db1f6..09669160db9 100644 --- a/src/devices/frameTransformClient/CMakeLists.txt +++ b/src/devices/frameTransformClient/CMakeLists.txt @@ -48,6 +48,8 @@ if(NOT SKIP_frameTransformClient) robotinterface_xml/ftc_yarp_only_single_client.xml robotinterface_xml/ftc_local_only.xml ) + set_property(TARGET frameTransformRC PROPERTY FOLDER "Plugins/Device/Resources") + target_sources(yarp_frameTransformClient PRIVATE $) target_include_directories(yarp_frameTransformClient PRIVATE $) diff --git a/src/devices/frameTransformServer/CMakeLists.txt b/src/devices/frameTransformServer/CMakeLists.txt index 15729cc6046..f3d0de34ffc 100644 --- a/src/devices/frameTransformServer/CMakeLists.txt +++ b/src/devices/frameTransformServer/CMakeLists.txt @@ -9,6 +9,7 @@ cmrc_add_resource_library(frameTransformServerRC PREFIX config_xml robotinterface_xml/fts_full_ros.xml robotinterface_xml/fts_yarp_only.xml) +set_property(TARGET frameTransformServerRC PROPERTY FOLDER "Plugins/Device/Resources") yarp_prepare_plugin(frameTransformServer CATEGORY device From 0ced4cb1a10434649e69f211ba59fcfa7feef418 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 22 Nov 2022 16:22:27 +0100 Subject: [PATCH 035/267] * added tests for: FrameTransformClient, FrameTransformServer, TransformClient, TransformServer --- .../frameTransformClient/CMakeLists.txt | 5 + .../frameTransformClient/tests/CMakeLists.txt | 53 ++ .../tests}/FrameTransformClientTest.cpp | 10 +- .../frameTransformServer/CMakeLists.txt | 5 + .../frameTransformServer/tests/CMakeLists.txt | 53 ++ .../tests/FrameTransformServerTest.cpp | 42 ++ src/devices/transformClient/CMakeLists.txt | 5 + .../transformClient/tests/CMakeLists.txt | 53 ++ .../tests}/TransformClientTest.cpp | 6 +- src/devices/transformServer/CMakeLists.txt | 5 + .../transformServer/tests/CMakeLists.txt | 53 ++ .../tests/TransformServerTest.cpp | 43 ++ src/libYARP_dev/src/CMakeLists.txt | 2 + .../yarp/dev/tests/IFrameTransformTest.cpp | 6 + .../src/yarp/dev/tests/IFrameTransformTest.h | 616 ++++++++++++++++++ tests/libYARP_dev/CMakeLists.txt | 6 - tests/libYARP_dev/IFrameTransformTest.cpp | 612 ----------------- tests/libYARP_dev/IFrameTransformTest.h | 18 - 18 files changed, 949 insertions(+), 644 deletions(-) create mode 100644 src/devices/frameTransformClient/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/frameTransformClient/tests}/FrameTransformClientTest.cpp (93%) create mode 100644 src/devices/frameTransformServer/tests/CMakeLists.txt create mode 100644 src/devices/frameTransformServer/tests/FrameTransformServerTest.cpp create mode 100644 src/devices/transformClient/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/transformClient/tests}/TransformClientTest.cpp (95%) create mode 100644 src/devices/transformServer/tests/CMakeLists.txt create mode 100644 src/devices/transformServer/tests/TransformServerTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.h delete mode 100644 tests/libYARP_dev/IFrameTransformTest.cpp delete mode 100644 tests/libYARP_dev/IFrameTransformTest.h diff --git a/src/devices/frameTransformClient/CMakeLists.txt b/src/devices/frameTransformClient/CMakeLists.txt index 09669160db9..b3c2a8f5506 100644 --- a/src/devices/frameTransformClient/CMakeLists.txt +++ b/src/devices/frameTransformClient/CMakeLists.txt @@ -65,4 +65,9 @@ if(NOT SKIP_frameTransformClient) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_frameTransformClient PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/frameTransformClient/tests/CMakeLists.txt b/src/devices/frameTransformClient/tests/CMakeLists.txt new file mode 100644 index 00000000000..60b6719d190 --- /dev/null +++ b/src/devices/frameTransformClient/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_FrameTransformClient) + +target_sources(harness_dev_FrameTransformClient + PRIVATE + FrameTransformClientTest.cpp +) + +target_link_libraries(harness_dev_FrameTransformClient + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_FrameTransformClient + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + FrameTransformClientTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_FrameTransformClient PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_FrameTransformClient) diff --git a/tests/libYARP_dev/FrameTransformClientTest.cpp b/src/devices/frameTransformClient/tests/FrameTransformClientTest.cpp similarity index 93% rename from tests/libYARP_dev/FrameTransformClientTest.cpp rename to src/devices/frameTransformClient/tests/FrameTransformClientTest.cpp index c426cd00842..c8754522a61 100644 --- a/tests/libYARP_dev/FrameTransformClientTest.cpp +++ b/src/devices/frameTransformClient/tests/FrameTransformClientTest.cpp @@ -10,7 +10,7 @@ #include #include -#include "IFrameTransformTest.h" +#include #include #include @@ -55,7 +55,7 @@ TEST_CASE("dev::FrameTransformClientTest", "[yarp::dev]") REQUIRE(pd.open(p)); REQUIRE(pd.view(ift)); - exec_frameTransform_test_1(ift); + yarp::dev::tests::exec_frameTransform_test_1(ift); REQUIRE(pd.close()); } @@ -71,7 +71,7 @@ TEST_CASE("dev::FrameTransformClientTest", "[yarp::dev]") REQUIRE(pd.open(p)); REQUIRE(pd.view(ift)); - exec_frameTransform_test_2(ift); + yarp::dev::tests::exec_frameTransform_test_2(ift); REQUIRE(pd.close()); } @@ -94,7 +94,7 @@ TEST_CASE("dev::FrameTransformClientTest", "[yarp::dev]") REQUIRE(client_pd.open(client_prop)); REQUIRE(client_pd.view(ift)); - exec_frameTransform_test_1(ift); + yarp::dev::tests::exec_frameTransform_test_1(ift); REQUIRE(client_pd.close()); REQUIRE(server_pd.close()); @@ -118,7 +118,7 @@ TEST_CASE("dev::FrameTransformClientTest", "[yarp::dev]") REQUIRE(client_pd.open(client_prop)); REQUIRE(client_pd.view(ift)); - exec_frameTransform_test_2(ift); + yarp::dev::tests::exec_frameTransform_test_2(ift); REQUIRE(client_pd.close()); REQUIRE(server_pd.close()); diff --git a/src/devices/frameTransformServer/CMakeLists.txt b/src/devices/frameTransformServer/CMakeLists.txt index f3d0de34ffc..21f559977fa 100644 --- a/src/devices/frameTransformServer/CMakeLists.txt +++ b/src/devices/frameTransformServer/CMakeLists.txt @@ -59,4 +59,9 @@ if(NOT SKIP_frameTransformServer) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_frameTransformServer PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/frameTransformServer/tests/CMakeLists.txt b/src/devices/frameTransformServer/tests/CMakeLists.txt new file mode 100644 index 00000000000..e0809190029 --- /dev/null +++ b/src/devices/frameTransformServer/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_FrameTransformServer) + +target_sources(harness_dev_FrameTransformServer + PRIVATE + FrameTransformServerTest.cpp +) + +target_link_libraries(harness_dev_FrameTransformServer + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_FrameTransformServer + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + FrameTransformServerTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_FrameTransformServer PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_FrameTransformServer) diff --git a/src/devices/frameTransformServer/tests/FrameTransformServerTest.cpp b/src/devices/frameTransformServer/tests/FrameTransformServerTest.cpp new file mode 100644 index 00000000000..dd0b4d2522f --- /dev/null +++ b/src/devices/frameTransformServer/tests/FrameTransformServerTest.cpp @@ -0,0 +1,42 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +TEST_CASE("dev::FrameTransformServerTest", "[yarp::dev]") +{ + #if defined(DISABLE_FAILING_TESTS) + YARP_SKIP_TEST("Skipping failing tests") + #endif + + YARP_REQUIRE_PLUGIN("frameTransformServer", "device"); + + yarp::os::Network::setLocalMode(true); + const bool verboseDebug = true; + + SECTION("test the frameTransformServer open/close") + { + yarp::dev::PolyDriver pd; + yarp::os::Property p; + + p.put("device", "frameTransformServer"); + p.put("filexml_option", "fts_yarp_only.xml"); + REQUIRE(pd.open(p)); + yarp::os::Time::delay(0.5); + REQUIRE(pd.close()); + } + + yarp::os::Network::setLocalMode(false); +} diff --git a/src/devices/transformClient/CMakeLists.txt b/src/devices/transformClient/CMakeLists.txt index e9ca68065e5..e786be42cb5 100644 --- a/src/devices/transformClient/CMakeLists.txt +++ b/src/devices/transformClient/CMakeLists.txt @@ -44,4 +44,9 @@ if(NOT SKIP_transformClient) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_transformClient PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/transformClient/tests/CMakeLists.txt b/src/devices/transformClient/tests/CMakeLists.txt new file mode 100644 index 00000000000..164ae5f9c5b --- /dev/null +++ b/src/devices/transformClient/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_TransformerClient) + +target_sources(harness_dev_TransformerClient + PRIVATE + TransformClientTest.cpp +) + +target_link_libraries(harness_dev_TransformerClient + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_TransformerClient + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + TransformClientTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_TransformerClient PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_TransformerClient) diff --git a/tests/libYARP_dev/TransformClientTest.cpp b/src/devices/transformClient/tests/TransformClientTest.cpp similarity index 95% rename from tests/libYARP_dev/TransformClientTest.cpp rename to src/devices/transformClient/tests/TransformClientTest.cpp index 5c3fd3eda93..25127145c63 100644 --- a/tests/libYARP_dev/TransformClientTest.cpp +++ b/src/devices/transformClient/tests/TransformClientTest.cpp @@ -10,7 +10,7 @@ #include #include -#include "IFrameTransformTest.h" +#include using namespace yarp::os; using namespace yarp::dev; @@ -51,7 +51,7 @@ TEST_CASE("dev::TransformClientTest", "[yarp::dev]") REQUIRE(itf != nullptr); // iTransform interface open reported successful //execute the test - exec_frameTransform_test_1(itf); + yarp::dev::tests::exec_frameTransform_test_1(itf); // Close devices CHECK(ddtransformclient.close()); // ddtransformclient successfully closed @@ -86,7 +86,7 @@ TEST_CASE("dev::TransformClientTest", "[yarp::dev]") REQUIRE(itf != nullptr); // iTransform interface open reported successful //execute the test - exec_frameTransform_test_2(itf); + yarp::dev::tests::exec_frameTransform_test_2(itf); // Close devices CHECK(ddtransformclient.close()); // ddtransformclient successfully closed diff --git a/src/devices/transformServer/CMakeLists.txt b/src/devices/transformServer/CMakeLists.txt index c78e3008d3b..662aec4bdf4 100644 --- a/src/devices/transformServer/CMakeLists.txt +++ b/src/devices/transformServer/CMakeLists.txt @@ -46,4 +46,9 @@ if(NOT SKIP_transformServer) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_transformServer PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/transformServer/tests/CMakeLists.txt b/src/devices/transformServer/tests/CMakeLists.txt new file mode 100644 index 00000000000..764bcedf900 --- /dev/null +++ b/src/devices/transformServer/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_TransformerServer) + +target_sources(harness_dev_TransformerServer + PRIVATE + TransformServerTest.cpp +) + +target_link_libraries(harness_dev_TransformerServer + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_TransformerServer + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + TransformServerTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_TransformerServer PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_TransformerServer) diff --git a/src/devices/transformServer/tests/TransformServerTest.cpp b/src/devices/transformServer/tests/TransformServerTest.cpp new file mode 100644 index 00000000000..c63d6c6fbe3 --- /dev/null +++ b/src/devices/transformServer/tests/TransformServerTest.cpp @@ -0,0 +1,43 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include + +#include +#include + +#include + +using namespace yarp::os; +using namespace yarp::dev; + + +TEST_CASE("dev::TransformServerTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("transformServer", "device"); + + Network::setLocalMode(true); + + SECTION("Test the transform server") + { + bool precision_verbose = false; + + PolyDriver ddtransformserver; + Property pTransformserver_cfg; + pTransformserver_cfg.put("device", "transformServer"); + Property& ros_prop = pTransformserver_cfg.addGroup("ROS"); + ros_prop.put("enable_ros_publisher", "0"); + ros_prop.put("enable_ros_subscriber", "0"); + pTransformserver_cfg.put("transforms_lifetime", 0.500); + bool ok_server = ddtransformserver.open(pTransformserver_cfg); + CHECK(ok_server); // ddtransformserver open reported successful + + CHECK(ddtransformserver.close()); // ddtransformserver successfully closed + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index e615bc397c1..b2b134a03ab 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -402,6 +402,8 @@ add_library(YARP::YARP_dev_tests ALIAS YARP_dev_tests) if(TARGET YARP::YARP_math) target_sources(YARP_dev_tests PRIVATE + yarp/dev/tests/IFrameTransformTest.cpp + yarp/dev/tests/IFrameTransformTest.h yarp/dev/tests/IMap2DTest.cpp yarp/dev/tests/IMap2DTest.h yarp/dev/tests/INavigation2DTest.cpp diff --git a/src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.cpp new file mode 100644 index 00000000000..49e9a2f00c5 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IFrameTransformTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.h b/src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.h new file mode 100644 index 00000000000..1b6cf755f9c --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IFrameTransformTest.h @@ -0,0 +1,616 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IFRAMETRANSFORMTEST_H +#define IFRAMETRANSFORMTEST_H + +#define _USE_MATH_DEFINES +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +#include + +#include "IFrameTransformTest.h" + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::math; + +namespace yarp::dev::tests +{ + inline bool isEqual(const yarp::sig::Vector& v1, const yarp::sig::Vector& v2, double precision) + { + if (v1.size() != v2.size()) + { + return false; + } + + for (size_t i = 0; i < v1.size(); i++) + { + double check = fabs(v1[i] - v2[i]); + if (check > precision) + { + return false; + } + } + return true; + } + + inline bool isEqual(const yarp::math::Quaternion& q1, const yarp::math::Quaternion& q2, double precision) + { + yarp::sig::Vector v1 = q1.toVector(); + yarp::sig::Vector v2 = q2.toVector(); + + for (size_t i = 0; i < v1.size(); i++) + { + double check = fabs(v1[i] - v2[i]); + if (check > precision) + { + return false; + } + } + return true; + } + + inline bool isEqual(const yarp::sig::Matrix& m1, const yarp::sig::Matrix& m2, double precision) + { + if (m1.cols() != m2.cols() || m1.rows() != m2.rows()) + { + return false; + } + + for (size_t i = 0; i < m1.rows(); i++) + { + if (!isEqual(m1.getRow(i), m2.getRow(i), precision)) + { + return false; + } + } + return true; + } + + inline void exec_frameTransform_test_1(IFrameTransform* itf) + { + bool precision_verbose= false; + + yarp::sig::Matrix m1(4, 4); + m1[0][0] = cos(M_PI / 4); m1[0][1] = -sin(M_PI / 4); m1[0][2] = 0; m1[0][3] = 3; + m1[1][0] = sin(M_PI / 4); m1[1][1] = cos(M_PI /4); m1[1][2] = 0; m1[1][3] = 1; + m1[2][0] = 0; m1[2][1] = 0; m1[2][2] = 1; m1[2][3] = 2; + m1[3][0] = 0; m1[3][1] = 0; m1[3][2] = 0; m1[3][3] = 1; + yarp::sig::Matrix m2(4, 4); + m2[0][0] = cos(M_PI / 4); m2[0][1] = 0; m2[0][2] = sin(M_PI / 4); m2[0][3] = 0.1; + m2[1][0] = 0; m2[1][1] = 1; m2[1][2] = 0; m2[1][3] = 0.2; + m2[2][0] = -sin(M_PI / 4); m2[2][1] = 0; m2[2][2] = cos(M_PI / 4); m2[2][3] = 0.3; + m2[3][0] = 0; m2[3][1] = 0; m2[3][2] = 0; m2[3][3] = 1; + yarp::sig::Matrix sibiling(4, 4); + sibiling[0][0] = 1; sibiling[0][1] = 0; sibiling[0][2] = 0; sibiling[0][3] = 10; + sibiling[1][0] = 0; sibiling[1][1] = cos(M_PI / 3); sibiling[1][2] = -sin(M_PI / 3); sibiling[1][3] = 15; + sibiling[2][0] = 0; sibiling[2][1] = sin(M_PI / 3); sibiling[2][2] = cos(M_PI / 3); sibiling[2][3] = 5; + sibiling[3][0] = 0; sibiling[3][1] = 0; sibiling[3][2] = 0; sibiling[3][3] = 1; + yarp::sig::Matrix m3(4, 4); + m3 = m1*m2; + + double precision; + precision = 0.00000001; + + itf->setTransformStatic("frame2", "frame1", m1); + itf->setTransformStatic("frame3", "frame2", m2); + itf->setTransformStatic("frame4", "frame3", m3); + itf->setTransformStatic("frame11", "frame10", m1); + itf->setTransformStatic("frame3b", "frame2", m2); + itf->setTransformStatic("sibiling_test_frame", "frame1", sibiling); + + yarp::sig::Matrix m4(4, 4); + m4[0][0] = +0.9585267399; m4[0][1] = -0.2305627908; m4[0][2] = +0.1675329472; m4[0][3] = 0.1; + m4[1][0] = +0.2433237939; m4[1][1] = +0.9680974922; m4[1][2] = -0.0598395928; m4[1][3] = 0.2; + m4[2][0] = -0.1483914426; m4[2][1] = +0.0981226021; m4[2][2] = +0.9840487461; m4[2][3] = 0.3; + m4[3][0] = 0; m4[3][1] = 0; m4[3][2] = 0; m4[3][3] = 1; + + yarp::os::Time::delay(1); + + //test 0 + { + yInfo("Running Sub-test0"); + std::vector ids; + itf->getAllFrameIds(ids); + char buff[1024]; buff[0] = 0; + for (size_t i = 0; i < ids.size(); i++) + { + sprintf(buff +strlen(buff), "%s ", ids[i].c_str()); + } + INFO("Found frames: " << buff); + bool b_ids = (ids.size() == 8); + CHECK(b_ids); // getAllFrameIds ok + yInfo() << "Sub-test complete"; + } + + //test 1 + { + yInfo() << "Running Sub-test1"; + std::string parent; + itf->getParent("frame3", parent); + CHECK(parent == "frame2"); // getParent ok + yInfo() << "Sub-test complete"; + } + + //test 2 + { + yInfo() << "Running Sub-test2"; + yarp::sig::Matrix mt(4, 4); + bool b_gt = itf->getTransform("frame3", "frame1", mt); + isEqual(mt, m3, precision); + CHECK(b_gt); // getTransform ok + if (precision_verbose || b_gt==false) + { + INFO("Precision error:\n" + (mt - m3).toString()); + } + yInfo() << "Sub-test complete"; + } + + //test3 + { + yInfo() << "Running Sub-test3"; + CHECK(itf->frameExists("frame3")); + CHECK_FALSE(itf->frameExists("frame3_err")); // frameExists ok + yInfo() << "Sub-test complete"; + } + + //test4 + { + yInfo() << "Running Sub-test4"; + CHECK(itf->canTransform("frame2", "frame1")); + CHECK_FALSE(itf->canTransform("frame11", "frame1")); // canTransform ok + yInfo() << "Sub-test complete"; + } + + //test4bis + { + yInfo() << "Running Sub-test4b"; + bool b_canb1; + b_canb1 = itf->canTransform("frame3b", "frame1"); + CHECK(b_canb1); // canTransform Bis ok + yInfo() << "Sub-test complete"; + } + + //test4 tris (transform between sibilings) + { + yInfo() << "Running Sub-test4c"; + yarp::sig::Matrix sib; + CHECK(itf->canTransform("sibiling_test_frame", "frame3")); // canTransform between sibilings ok + CHECK(itf->getTransform("sibiling_test_frame", "frame3", sib)); // getTransform between sibilings ok + CHECK(isEqual(sib, SE3inv(m2) * SE3inv(m1) * sibiling, precision)); // transform between sibilings ok + yInfo() << "Sub-test complete"; + } + + //test 5 + { + yInfo() << "Running Sub-test5"; + yarp::sig::Matrix mti(4, 4); + itf->getTransform("frame1", "frame3b", mti); + bool b_gt_inv = isEqual(mti, yarp::math::SE3inv(m3), precision); + CHECK(b_gt_inv); // inverted getTransform ok + if (precision_verbose || b_gt_inv==false) { + INFO("Precision error: " + (mti - yarp::math::SE3inv(m3)).toString()); + } + yInfo() << "Sub-test complete"; + } + + //test 6 + { + yInfo() << "Running Sub-test6"; + yarp::sig::Vector in_point1(3), out_point1(3), verPoint1(4); + yarp::sig::Vector in_pose1(6), out_pose1(6), verPose(6); + yarp::math::Quaternion in_quat1, out_quat1, verQuat; + + in_quat1.fromRotationMatrix(m4); + + in_pose1[0] = 1; in_pose1[1] = 2; in_pose1[2] = 3; + in_pose1[3] = 30; in_pose1[4] = 60; in_pose1[5] = 90; + + in_point1[0] = 10; in_point1[1] = 15; in_point1[2] = 5; + + in_point1.push_back(1); + verPoint1 = m1*m2*in_point1; + verPoint1.pop_back(); + in_point1.pop_back(); + + yarp::sig::Matrix mat(4, 4); + yarp::sig::Vector temp(3); + + double rot[3] = { in_pose1[3], in_pose1[4], in_pose1[5] }; + mat = yarp::math::rpy2dcm(yarp::sig::Vector(3, rot)); + mat[0][3] = in_pose1[0]; mat[1][3] = in_pose1[1]; mat[2][3] = in_pose1[2]; + mat = m3 * mat; + verPose[0] = mat[0][3]; verPose[1] = mat[1][3]; verPose[2] = mat[2][3]; + temp = yarp::math::dcm2rpy(mat); + verPose[3] = temp[0]; verPose[4] = temp[1]; verPose[5] = temp[2]; + + verQuat.fromRotationMatrix(m1 * m2 * m4); + + itf->transformPoint("frame3", "frame1", in_point1, out_point1); + itf->transformPose("frame3", "frame1", in_pose1, out_pose1); + itf->transformQuaternion("frame3", "frame1", in_quat1, out_quat1); + + bool b_tpoint = isEqual(verPoint1, out_point1, precision); + CHECK(b_tpoint); // transformPoint ok + if (precision_verbose || b_tpoint == false) { + INFO("Precision error:" << (verPoint1 - out_point1).toString()); + } + + bool b_tpose = isEqual(verPose, out_pose1, precision); + CHECK(b_tpose); // transformPose ok + if (precision_verbose || b_tpose == false) { + INFO("Precision error:" << (verPose - out_pose1).toString()); + } + + bool b_tquat = isEqual(verQuat, out_quat1, precision); + CHECK(b_tquat); // transformQuaternion ok + if (precision_verbose || b_tquat == false) { + INFO("Precision error:" << (verQuat.toVector() - out_quat1.toVector()).toString()); + } + yInfo() << "Sub-test complete"; + } + + //test 7 + { + yInfo() << "Running Sub-test7"; + std::string all_frames; + CHECK(itf->allFramesAsString(all_frames)); + CHECK(all_frames.find("frame1") != std::string::npos); + CHECK(all_frames.find("frame2") != std::string::npos); + CHECK(all_frames.find("frame3") != std::string::npos); + CHECK(all_frames.find("frame4") != std::string::npos); + CHECK(all_frames.find("frame10") != std::string::npos); + CHECK(all_frames.find("frame11") != std::string::npos); + CHECK(all_frames.find("frame3b") != std::string::npos); + // allFramesAsString ok + yInfo() << "Sub-test complete"; + } + + //test 8 + { + yInfo() << "Running Sub-test8"; + itf->setTransformStatic("frame_test", "frame1", m1); + yarp::os::Time::delay(1); + bool del_bool = itf->frameExists("frame_test"); + CHECK(del_bool); // frame exists + del_bool &= itf->deleteTransform("frame_test", "frame1"); + CHECK(del_bool); // deleteTransform ok + del_bool &= (!itf->frameExists("frame_test")); + CHECK(del_bool); // check if frame has been successfully removed + + //let's wait some time and check gain to be sure that + //frame does not reappears.... + yarp::os::Time::delay(0.5); + del_bool &= (!itf->frameExists("frame_test")); + CHECK(del_bool); + + //just print + std::string strs; + del_bool &= itf->allFramesAsString(strs); + INFO("Existing frames:" << strs); + CHECK(del_bool); // confirmed: frame does not exist anymore + yInfo() << "Sub-test complete"; + } + + //test 8b + { + yInfo() << "Running Sub-test8b"; + //trying to delete non existing frame. It should return false. + //Nothing bad should happen... + bool del_bool = itf->deleteTransform("not-exist1", "not-exist2"); + CHECK_FALSE(del_bool); + yInfo() << "Sub-test complete"; + } + + //test 9 + { + yInfo() << "Running Sub-test9"; + itf->clear(); + std::vector cids; + itf->getAllFrameIds(cids); + CHECK(cids.size() == 0); // clear ok + yInfo() << "Sub-test complete"; + } + + //test 10 + { + yInfo() << "Running Sub-test10"; + itf->setTransform("frame2", "frame10", m1); + yarp::os::Time::delay(0.050); + bool b_can; + b_can = itf->canTransform("frame2", "frame10"); + CHECK(b_can); // itf->setTransform ok + yarp::os::Time::delay(0.6); + b_can = itf->canTransform("frame2", "frame10"); + CHECK_FALSE(b_can); // itf->setTransform successfully expired after 0.6s + yInfo() << "Sub-test complete"; + } + + //test 11 + { + yInfo() << "Running Sub-test11"; + itf->clear(); + bool set_b1 = itf->setTransform("frame2", "frame10", m1); + yarp::os::Time::delay(0.050); + yarp::sig::Matrix mt1; + itf->getTransform("frame2", "frame10", mt1); + bool set_b2 = itf->setTransform("frame2", "frame10", m2); + yarp::os::Time::delay(0.050); + yarp::sig::Matrix mt2; + itf->getTransform("frame2", "frame10", mt2); + bool a, b; + a = isEqual(m1, mt1, precision); + b = isEqual(m2, mt2, precision); + CHECK(set_b1); + CHECK(set_b2); + CHECK(a); + CHECK(b); // itf->setTransform successfully updated + yInfo() << "Sub-test complete"; + } + + //test 11b + { + yInfo() << "Running Sub-test11b"; + itf->clear(); + bool set_b1 = itf->setTransformStatic("frame2", "frame10", m1); + yarp::os::Time::delay(0.050); + yarp::sig::Matrix mt1; + itf->getTransform("frame2", "frame10", mt1); + bool set_b2 = itf->setTransformStatic("frame2", "frame10", m2); + yarp::os::Time::delay(0.050); + yarp::sig::Matrix mt2; + itf->getTransform("frame2", "frame10", mt2); + CHECK(set_b1); + CHECK_FALSE(set_b2); + CHECK(isEqual(m1, mt1, precision)); + CHECK_FALSE(isEqual(m2, mt2, precision)); // itf->setTransformStatic successfully not-updated + yInfo() << "Sub-test complete"; + } + + //test 12 + { + yInfo() << "Running Sub-test12"; + itf->clear(); + yDebug() << "Creating Transform frame2 -> frame1 at time" << std::to_string(yarp::os::Time::now()); + CHECK(itf->setTransform("frame2", "frame1", m1)); + yDebug() << "Created at time" << std::to_string(yarp::os::Time::now()); + yarp::os::Time::delay(0.040); + yDebug() << "Creating Transform frame3 -> frame2 at time" << std::to_string(yarp::os::Time::now()); + CHECK(itf->setTransform("frame3", "frame2", m2)); + yDebug() << "Created at time" << std::to_string(yarp::os::Time::now()); + yarp::os::Time::delay(0.040); + yDebug() << "Creating Transform frame3 -> frame1 at time" << std::to_string(yarp::os::Time::now()); + CHECK_FALSE(itf->setTransform("frame3", "frame1", m1)); + yDebug() << "Intentionally skipped at time" << std::to_string(yarp::os::Time::now()); + // itf->setTransform duplicate transform successfully skipped + + yarp::sig::Matrix mt1; + yarp::sig::Matrix mt2; + yarp::sig::Matrix mt3; + itf->getTransform("frame2", "frame1", mt1); + itf->getTransform("frame3", "frame2", mt2); + itf->getTransform("frame3", "frame1", mt3); + CHECK(isEqual(mt1, m1, precision)); + CHECK(isEqual(mt2, m2, precision)); + CHECK(isEqual(mt3, (m1*m2), precision)); + // itf->setTransform still working after duplicate transform + yInfo() << "Sub-test complete"; + } + + //test 12b + { + yInfo() << "Running Sub-test12b"; + itf->clear(); + std::string strs; + itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; + + CHECK(itf->setTransformStatic("frame2", "frame1", m1)); + yarp::os::Time::delay(0.050); + itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; + + CHECK(itf->setTransformStatic("frame3", "frame2", m2)); + yarp::os::Time::delay(0.050); + itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; + + CHECK_FALSE(itf->setTransformStatic("frame3", "frame1", m1)); + //Here I checked false because itf->setTransformStatic of a duplicate transform must be skipped + itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; + + yarp::sig::Matrix mt1; + yarp::sig::Matrix mt2; + yarp::sig::Matrix mt3; + itf->getTransform("frame2", "frame1", mt1); + itf->getTransform("frame3", "frame2", mt2); + CHECK(isEqual(mt1, m1, precision)); + CHECK(isEqual(mt2, m2, precision)); + + // checking that the last itf->setTransformStatic had no effect on the values + itf->getTransform("frame3", "frame1", mt3); + CHECK_FALSE(isEqual(mt3, m1, precision)); + CHECK(isEqual(mt3, (m1*m2), precision)); + yInfo() << "Sub-test complete"; + } + + //test 13 + { + yInfo() << "Running Sub-test13"; + itf->clear(); + bool bcan = false; + bcan = itf->canTransform("not_existing_frame", "not_existing_frame"); + CHECK(bcan); + + CHECK(itf->setTransformStatic("frame2", "frame1", m1)); + bcan = itf->canTransform("frame2", "frame2"); + CHECK(bcan); + bcan = itf->canTransform("frame1", "frame1"); + CHECK(bcan); + + yarp::sig::Matrix mt1; + yarp::sig::Matrix eyemat(4, 4); eyemat.eye(); + itf->getTransform("frame1", "frame1", mt1); + CHECK(isEqual(mt1, eyemat, precision)); + itf->getTransform("frame2", "frame2", mt1); + CHECK(isEqual(mt1, eyemat, precision)); + yInfo() << "Sub-test complete"; + } + } + + + inline void exec_frameTransform_test_2(IFrameTransform* itf) + { + // Fake transform + yarp::sig::Matrix armToHand(4, 4); + yarp::sig::Matrix result(4, 4); + yarp::sig::Matrix handToFinger(4, 4); + + armToHand.zero(); + armToHand(0, 0) = 1; armToHand(0, 1) = 0; armToHand(0, 2) = 0; armToHand(0, 3) = 5; + armToHand(1, 0) = 0; armToHand(1, 1) = sqrt(2) / 2; armToHand(1, 2) = sqrt(2) / 2; armToHand(1, 3) = 4; + armToHand(2, 0) = 0; armToHand(2, 1) = -sqrt(2) / 2; armToHand(2, 2) = sqrt(2) / 2; armToHand(2, 3) = 3; + armToHand(3, 0) = 0; armToHand(3, 1) = 0; armToHand(3, 2) = 0; armToHand(3, 3) = 1; + + handToFinger(0, 0) = 1; handToFinger(0, 1) = 0; handToFinger(0, 2) = 0; handToFinger(0, 3) = 5; + handToFinger(1, 0) = 0; handToFinger(1, 1) = sqrt(2) / 2; handToFinger(1, 2) = sqrt(2) / 2; handToFinger(1, 3) = 4; + handToFinger(2, 0) = 0; handToFinger(2, 1) = -sqrt(2) / 2; handToFinger(2, 2) = sqrt(2) / 2; handToFinger(2, 3) = 3; + handToFinger(3, 0) = 0; handToFinger(3, 1) = 0; handToFinger(3, 2) = 0; handToFinger(3, 3) = 1; + + result = armToHand * handToFinger; + + // test setTransformStatic + // static transforms cannot be set if they already exists + CHECK(itf->setTransformStatic("/hand", "/arm", armToHand)); + CHECK(!itf->setTransformStatic("/hand", "/arm", handToFinger)); + + // static transforms cannot be set if an indirect connection already exists + CHECK(itf->setTransformStatic("/a", "/b", handToFinger)); + CHECK(itf->setTransformStatic("/b", "/c", handToFinger)); + CHECK(!itf->setTransformStatic("/a", "/c", handToFinger)); + CHECK(itf->deleteTransform("/a", "/b")); + CHECK(itf->deleteTransform("/b", "/c")); + + // test setTransform + CHECK(itf->setTransform("/finger", "/hand", handToFinger)); + CHECK(!itf->setTransform("/finger", "/arm", result)); + + // test getTransform + CHECK(itf->clear()); + CHECK(itf->setTransform("/finger", "/arm", result)); + yarp::sig::Matrix resultFromTransform(4, 4); + CHECK(itf->getTransform("/finger", "/arm", resultFromTransform)); + for (int i = 0; i < 4; i++) { + for (int j = 0; j < 4; j++) { + CHECK((resultFromTransform(i, j) - result(i, j)) <= pow(10, -14)); + } + } + + // test canTransform + CHECK(itf->canTransform("/finger", "/arm")); + CHECK(!itf->canTransform("/finger", "/head")); + + // test frameExists + CHECK(itf->frameExists("/finger")); + CHECK(!itf->frameExists("/head")); + + // test getAllFrameIds + CHECK(itf->clear()); + CHECK(itf->setTransformStatic("/hand", "/arm", armToHand)); + CHECK(itf->setTransformStatic("/finger", "/hand", handToFinger)); + std::vector frameIdsReturned; + std::vector correctFrameIdsReturned{ + "/arm", + "/hand", + "/finger" + }; + CHECK(itf->getAllFrameIds(frameIdsReturned)); + CHECK(frameIdsReturned.size() == correctFrameIdsReturned.size()); + CHECK(frameIdsReturned == correctFrameIdsReturned); + std::vector wrongFrameIdsReturned1{ + "/hand", + "/arm", + "/finger" + }; + CHECK(!(frameIdsReturned == wrongFrameIdsReturned1)); + + // test getParent + std::string parent; + CHECK(itf->getParent("/finger", parent)); + CHECK(parent == "/hand"); + + // test transformPoint + yarp::sig::Vector startingPoint{ 0.0,0.0,0.0 }; + yarp::sig::Vector wrongStartingPoint{ 0.0,0.0,0.0,0.0 }; + yarp::sig::Vector endPoint{ 0.0,0.0,0.0,0.0 }; + CHECK(itf->transformPoint("/finger", "/arm", startingPoint, endPoint)); + CHECK(!itf->transformPoint("/finger", "/arm", wrongStartingPoint, endPoint)); + CHECK(!itf->transformPoint("/finger", "/head", startingPoint, endPoint)); + startingPoint.push_back(1); + yarp::sig::Vector correctEndPoint = result * startingPoint; + correctEndPoint.pop_back(); + CHECK(endPoint.size() == correctEndPoint.size()); + for (int i = 0; i < 3; i++) { + CHECK((endPoint[i] - correctEndPoint[i]) <= pow(10, -14)); + } + + // test transformPose + yarp::sig::Vector startingPose{ 0,0,0,0,0,0 }; + yarp::sig::Vector wrongStartingPose{ 0,0,0,0,0,0,0 }; + yarp::sig::Vector endPose; + yarp::math::FrameTransform transform; + transform.transFromVec(startingPose[0], startingPose[1], startingPose[2]); + transform.rotFromRPY(startingPose[3], startingPose[4], startingPose[5]); + transform.fromMatrix(result * transform.toMatrix()); + CHECK(itf->transformPose("/finger", "/arm", startingPose, endPose)); + CHECK((transform.translation.tX - endPose[0]) <= pow(10, -14)); + CHECK((transform.translation.tY - endPose[1]) <= pow(10, -14)); + CHECK((transform.translation.tZ - endPose[2]) <= pow(10, -14)); + CHECK((transform.translation.tZ - endPose[2]) <= pow(10, -14)); + CHECK((transform.getRPYRot()[0] - endPose[3]) <= pow(10, -14)); + CHECK((transform.getRPYRot()[1] - endPose[4]) <= pow(10, -14)); + CHECK((transform.getRPYRot()[2] - endPose[5]) <= pow(10, -14)); + CHECK(!itf->transformPose("/finger", "/arm", wrongStartingPose, endPose)); + CHECK(!itf->transformPose("/finger", "/head", startingPose, endPose)); + + // test transformQuaternion + yarp::math::Quaternion startingPoseQuaternion = transform.rotation; + yarp::math::Quaternion endPoseQuaternion; + CHECK(itf->transformQuaternion("/finger", "/arm", startingPoseQuaternion, endPoseQuaternion)); + yarp::math::Quaternion correctedEndPoseQuaternion; + yarp::math::FrameTransform transformQuaternion; + itf->getTransform("/finger", "/arm", result); + transformQuaternion.rotation = startingPoseQuaternion; + correctedEndPoseQuaternion.fromRotationMatrix(result * transformQuaternion.toMatrix()); + CHECK((endPoseQuaternion.x() - correctedEndPoseQuaternion.x()) <= pow(10, -14)); + CHECK((endPoseQuaternion.y() - correctedEndPoseQuaternion.y()) <= pow(10, -14)); + CHECK((endPoseQuaternion.z() - correctedEndPoseQuaternion.z()) <= pow(10, -14)); + CHECK((endPoseQuaternion.w() - correctedEndPoseQuaternion.w()) <= pow(10, -14)); + CHECK(!itf->transformQuaternion("/finger", "/head", startingPoseQuaternion, endPoseQuaternion)); + + // test clear + CHECK(itf->clear()); + std::this_thread::sleep_for(std::chrono::milliseconds(250)); + CHECK(!itf->getTransform("/hand", "/arm", result)); + CHECK(!itf->getTransform("/finger", "/hand", result)); + CHECK(!itf->getTransform("/finger", "/arm", result)); + } +} + +#endif diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index 184cb74dab5..8316aa4fd70 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -7,10 +7,7 @@ target_sources(harness_dev AnalogWrapperTest.cpp ControlBoardRemapperTest.cpp ControlBoardNwsTest.cpp - FrameTransformClientTest.cpp - TransformClientTest.cpp GroupDriverTest.cpp - IFrameTransformTest.cpp MapGrid2DTest.cpp MultipleAnalogSensorsInterfacesTest.cpp PolyDriverTest.cpp @@ -34,9 +31,6 @@ if(TARGET YARP::YARP_math) target_link_libraries(harness_dev PRIVATE YARP::YARP_math) else() set(_disabled_files - TransformClientTest.cpp - FrameTransformClientTest.cpp - IFrameTransformTest.cpp MapGrid2DTest.cpp ) set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) diff --git a/tests/libYARP_dev/IFrameTransformTest.cpp b/tests/libYARP_dev/IFrameTransformTest.cpp deleted file mode 100644 index d93d8266e35..00000000000 --- a/tests/libYARP_dev/IFrameTransformTest.cpp +++ /dev/null @@ -1,612 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#define _USE_MATH_DEFINES - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include - -#include -#include - -#include "IFrameTransformTest.h" - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::math; - - -static bool isEqual(const yarp::sig::Vector& v1, const yarp::sig::Vector& v2, double precision) -{ - if (v1.size() != v2.size()) - { - return false; - } - - for (size_t i = 0; i < v1.size(); i++) - { - double check = fabs(v1[i] - v2[i]); - if (check > precision) - { - return false; - } - } - return true; -} - -static bool isEqual(const yarp::math::Quaternion& q1, const yarp::math::Quaternion& q2, double precision) -{ - yarp::sig::Vector v1 = q1.toVector(); - yarp::sig::Vector v2 = q2.toVector(); - - for (size_t i = 0; i < v1.size(); i++) - { - double check = fabs(v1[i] - v2[i]); - if (check > precision) - { - return false; - } - } - return true; -} - -static bool isEqual(const yarp::sig::Matrix& m1, const yarp::sig::Matrix& m2, double precision) -{ - if (m1.cols() != m2.cols() || m1.rows() != m2.rows()) - { - return false; - } - - for (size_t i = 0; i < m1.rows(); i++) - { - if (!isEqual(m1.getRow(i), m2.getRow(i), precision)) - { - return false; - } - } - return true; -} - - - -void exec_frameTransform_test_1(IFrameTransform* itf) -{ - bool precision_verbose= false; - - yarp::sig::Matrix m1(4, 4); - m1[0][0] = cos(M_PI / 4); m1[0][1] = -sin(M_PI / 4); m1[0][2] = 0; m1[0][3] = 3; - m1[1][0] = sin(M_PI / 4); m1[1][1] = cos(M_PI /4); m1[1][2] = 0; m1[1][3] = 1; - m1[2][0] = 0; m1[2][1] = 0; m1[2][2] = 1; m1[2][3] = 2; - m1[3][0] = 0; m1[3][1] = 0; m1[3][2] = 0; m1[3][3] = 1; - yarp::sig::Matrix m2(4, 4); - m2[0][0] = cos(M_PI / 4); m2[0][1] = 0; m2[0][2] = sin(M_PI / 4); m2[0][3] = 0.1; - m2[1][0] = 0; m2[1][1] = 1; m2[1][2] = 0; m2[1][3] = 0.2; - m2[2][0] = -sin(M_PI / 4); m2[2][1] = 0; m2[2][2] = cos(M_PI / 4); m2[2][3] = 0.3; - m2[3][0] = 0; m2[3][1] = 0; m2[3][2] = 0; m2[3][3] = 1; - yarp::sig::Matrix sibiling(4, 4); - sibiling[0][0] = 1; sibiling[0][1] = 0; sibiling[0][2] = 0; sibiling[0][3] = 10; - sibiling[1][0] = 0; sibiling[1][1] = cos(M_PI / 3); sibiling[1][2] = -sin(M_PI / 3); sibiling[1][3] = 15; - sibiling[2][0] = 0; sibiling[2][1] = sin(M_PI / 3); sibiling[2][2] = cos(M_PI / 3); sibiling[2][3] = 5; - sibiling[3][0] = 0; sibiling[3][1] = 0; sibiling[3][2] = 0; sibiling[3][3] = 1; - yarp::sig::Matrix m3(4, 4); - m3 = m1*m2; - - double precision; - precision = 0.00000001; - - itf->setTransformStatic("frame2", "frame1", m1); - itf->setTransformStatic("frame3", "frame2", m2); - itf->setTransformStatic("frame4", "frame3", m3); - itf->setTransformStatic("frame11", "frame10", m1); - itf->setTransformStatic("frame3b", "frame2", m2); - itf->setTransformStatic("sibiling_test_frame", "frame1", sibiling); - - yarp::sig::Matrix m4(4, 4); - m4[0][0] = +0.9585267399; m4[0][1] = -0.2305627908; m4[0][2] = +0.1675329472; m4[0][3] = 0.1; - m4[1][0] = +0.2433237939; m4[1][1] = +0.9680974922; m4[1][2] = -0.0598395928; m4[1][3] = 0.2; - m4[2][0] = -0.1483914426; m4[2][1] = +0.0981226021; m4[2][2] = +0.9840487461; m4[2][3] = 0.3; - m4[3][0] = 0; m4[3][1] = 0; m4[3][2] = 0; m4[3][3] = 1; - - yarp::os::Time::delay(1); - - //test 0 - { - yInfo("Running Sub-test0"); - std::vector ids; - itf->getAllFrameIds(ids); - char buff[1024]; buff[0] = 0; - for (size_t i = 0; i < ids.size(); i++) - { - sprintf(buff +strlen(buff), "%s ", ids[i].c_str()); - } - INFO("Found frames: " << buff); - bool b_ids = (ids.size() == 8); - CHECK(b_ids); // getAllFrameIds ok - yInfo() << "Sub-test complete"; - } - - //test 1 - { - yInfo() << "Running Sub-test1"; - std::string parent; - itf->getParent("frame3", parent); - CHECK(parent == "frame2"); // getParent ok - yInfo() << "Sub-test complete"; - } - - //test 2 - { - yInfo() << "Running Sub-test2"; - yarp::sig::Matrix mt(4, 4); - bool b_gt = itf->getTransform("frame3", "frame1", mt); - isEqual(mt, m3, precision); - CHECK(b_gt); // getTransform ok - if (precision_verbose || b_gt==false) - { - INFO("Precision error:\n" + (mt - m3).toString()); - } - yInfo() << "Sub-test complete"; - } - - //test3 - { - yInfo() << "Running Sub-test3"; - CHECK(itf->frameExists("frame3")); - CHECK_FALSE(itf->frameExists("frame3_err")); // frameExists ok - yInfo() << "Sub-test complete"; - } - - //test4 - { - yInfo() << "Running Sub-test4"; - CHECK(itf->canTransform("frame2", "frame1")); - CHECK_FALSE(itf->canTransform("frame11", "frame1")); // canTransform ok - yInfo() << "Sub-test complete"; - } - - //test4bis - { - yInfo() << "Running Sub-test4b"; - bool b_canb1; - b_canb1 = itf->canTransform("frame3b", "frame1"); - CHECK(b_canb1); // canTransform Bis ok - yInfo() << "Sub-test complete"; - } - - //test4 tris (transform between sibilings) - { - yInfo() << "Running Sub-test4c"; - yarp::sig::Matrix sib; - CHECK(itf->canTransform("sibiling_test_frame", "frame3")); // canTransform between sibilings ok - CHECK(itf->getTransform("sibiling_test_frame", "frame3", sib)); // getTransform between sibilings ok - CHECK(isEqual(sib, SE3inv(m2) * SE3inv(m1) * sibiling, precision)); // transform between sibilings ok - yInfo() << "Sub-test complete"; - } - - //test 5 - { - yInfo() << "Running Sub-test5"; - yarp::sig::Matrix mti(4, 4); - itf->getTransform("frame1", "frame3b", mti); - bool b_gt_inv = isEqual(mti, yarp::math::SE3inv(m3), precision); - CHECK(b_gt_inv); // inverted getTransform ok - if (precision_verbose || b_gt_inv==false) { - INFO("Precision error: " + (mti - yarp::math::SE3inv(m3)).toString()); - } - yInfo() << "Sub-test complete"; - } - - //test 6 - { - yInfo() << "Running Sub-test6"; - yarp::sig::Vector in_point1(3), out_point1(3), verPoint1(4); - yarp::sig::Vector in_pose1(6), out_pose1(6), verPose(6); - yarp::math::Quaternion in_quat1, out_quat1, verQuat; - - in_quat1.fromRotationMatrix(m4); - - in_pose1[0] = 1; in_pose1[1] = 2; in_pose1[2] = 3; - in_pose1[3] = 30; in_pose1[4] = 60; in_pose1[5] = 90; - - in_point1[0] = 10; in_point1[1] = 15; in_point1[2] = 5; - - in_point1.push_back(1); - verPoint1 = m1*m2*in_point1; - verPoint1.pop_back(); - in_point1.pop_back(); - - yarp::sig::Matrix mat(4, 4); - yarp::sig::Vector temp(3); - - double rot[3] = { in_pose1[3], in_pose1[4], in_pose1[5] }; - mat = yarp::math::rpy2dcm(yarp::sig::Vector(3, rot)); - mat[0][3] = in_pose1[0]; mat[1][3] = in_pose1[1]; mat[2][3] = in_pose1[2]; - mat = m3 * mat; - verPose[0] = mat[0][3]; verPose[1] = mat[1][3]; verPose[2] = mat[2][3]; - temp = yarp::math::dcm2rpy(mat); - verPose[3] = temp[0]; verPose[4] = temp[1]; verPose[5] = temp[2]; - - verQuat.fromRotationMatrix(m1 * m2 * m4); - - itf->transformPoint("frame3", "frame1", in_point1, out_point1); - itf->transformPose("frame3", "frame1", in_pose1, out_pose1); - itf->transformQuaternion("frame3", "frame1", in_quat1, out_quat1); - - bool b_tpoint = isEqual(verPoint1, out_point1, precision); - CHECK(b_tpoint); // transformPoint ok - if (precision_verbose || b_tpoint == false) { - INFO("Precision error:" << (verPoint1 - out_point1).toString()); - } - - bool b_tpose = isEqual(verPose, out_pose1, precision); - CHECK(b_tpose); // transformPose ok - if (precision_verbose || b_tpose == false) { - INFO("Precision error:" << (verPose - out_pose1).toString()); - } - - bool b_tquat = isEqual(verQuat, out_quat1, precision); - CHECK(b_tquat); // transformQuaternion ok - if (precision_verbose || b_tquat == false) { - INFO("Precision error:" << (verQuat.toVector() - out_quat1.toVector()).toString()); - } - yInfo() << "Sub-test complete"; - } - - //test 7 - { - yInfo() << "Running Sub-test7"; - std::string all_frames; - CHECK(itf->allFramesAsString(all_frames)); - CHECK(all_frames.find("frame1") != std::string::npos); - CHECK(all_frames.find("frame2") != std::string::npos); - CHECK(all_frames.find("frame3") != std::string::npos); - CHECK(all_frames.find("frame4") != std::string::npos); - CHECK(all_frames.find("frame10") != std::string::npos); - CHECK(all_frames.find("frame11") != std::string::npos); - CHECK(all_frames.find("frame3b") != std::string::npos); - // allFramesAsString ok - yInfo() << "Sub-test complete"; - } - - //test 8 - { - yInfo() << "Running Sub-test8"; - itf->setTransformStatic("frame_test", "frame1", m1); - yarp::os::Time::delay(1); - bool del_bool = itf->frameExists("frame_test"); - CHECK(del_bool); // frame exists - del_bool &= itf->deleteTransform("frame_test", "frame1"); - CHECK(del_bool); // deleteTransform ok - del_bool &= (!itf->frameExists("frame_test")); - CHECK(del_bool); // check if frame has been successfully removed - - //let's wait some time and check gain to be sure that - //frame does not reappears.... - yarp::os::Time::delay(0.5); - del_bool &= (!itf->frameExists("frame_test")); - CHECK(del_bool); - - //just print - std::string strs; - del_bool &= itf->allFramesAsString(strs); - INFO("Existing frames:" << strs); - CHECK(del_bool); // confirmed: frame does not exist anymore - yInfo() << "Sub-test complete"; - } - - //test 8b - { - yInfo() << "Running Sub-test8b"; - //trying to delete non existing frame. It should return false. - //Nothing bad should happen... - bool del_bool = itf->deleteTransform("not-exist1", "not-exist2"); - CHECK_FALSE(del_bool); - yInfo() << "Sub-test complete"; - } - - //test 9 - { - yInfo() << "Running Sub-test9"; - itf->clear(); - std::vector cids; - itf->getAllFrameIds(cids); - CHECK(cids.size() == 0); // clear ok - yInfo() << "Sub-test complete"; - } - - //test 10 - { - yInfo() << "Running Sub-test10"; - itf->setTransform("frame2", "frame10", m1); - yarp::os::Time::delay(0.050); - bool b_can; - b_can = itf->canTransform("frame2", "frame10"); - CHECK(b_can); // itf->setTransform ok - yarp::os::Time::delay(0.6); - b_can = itf->canTransform("frame2", "frame10"); - CHECK_FALSE(b_can); // itf->setTransform successfully expired after 0.6s - yInfo() << "Sub-test complete"; - } - - //test 11 - { - yInfo() << "Running Sub-test11"; - itf->clear(); - bool set_b1 = itf->setTransform("frame2", "frame10", m1); - yarp::os::Time::delay(0.050); - yarp::sig::Matrix mt1; - itf->getTransform("frame2", "frame10", mt1); - bool set_b2 = itf->setTransform("frame2", "frame10", m2); - yarp::os::Time::delay(0.050); - yarp::sig::Matrix mt2; - itf->getTransform("frame2", "frame10", mt2); - bool a, b; - a = isEqual(m1, mt1, precision); - b = isEqual(m2, mt2, precision); - CHECK(set_b1); - CHECK(set_b2); - CHECK(a); - CHECK(b); // itf->setTransform successfully updated - yInfo() << "Sub-test complete"; - } - - //test 11b - { - yInfo() << "Running Sub-test11b"; - itf->clear(); - bool set_b1 = itf->setTransformStatic("frame2", "frame10", m1); - yarp::os::Time::delay(0.050); - yarp::sig::Matrix mt1; - itf->getTransform("frame2", "frame10", mt1); - bool set_b2 = itf->setTransformStatic("frame2", "frame10", m2); - yarp::os::Time::delay(0.050); - yarp::sig::Matrix mt2; - itf->getTransform("frame2", "frame10", mt2); - CHECK(set_b1); - CHECK_FALSE(set_b2); - CHECK(isEqual(m1, mt1, precision)); - CHECK_FALSE(isEqual(m2, mt2, precision)); // itf->setTransformStatic successfully not-updated - yInfo() << "Sub-test complete"; - } - - //test 12 - { - yInfo() << "Running Sub-test12"; - itf->clear(); - yDebug() << "Creating Transform frame2 -> frame1 at time" << std::to_string(yarp::os::Time::now()); - CHECK(itf->setTransform("frame2", "frame1", m1)); - yDebug() << "Created at time" << std::to_string(yarp::os::Time::now()); - yarp::os::Time::delay(0.040); - yDebug() << "Creating Transform frame3 -> frame2 at time" << std::to_string(yarp::os::Time::now()); - CHECK(itf->setTransform("frame3", "frame2", m2)); - yDebug() << "Created at time" << std::to_string(yarp::os::Time::now()); - yarp::os::Time::delay(0.040); - yDebug() << "Creating Transform frame3 -> frame1 at time" << std::to_string(yarp::os::Time::now()); - CHECK_FALSE(itf->setTransform("frame3", "frame1", m1)); - yDebug() << "Intentionally skipped at time" << std::to_string(yarp::os::Time::now()); - // itf->setTransform duplicate transform successfully skipped - - yarp::sig::Matrix mt1; - yarp::sig::Matrix mt2; - yarp::sig::Matrix mt3; - itf->getTransform("frame2", "frame1", mt1); - itf->getTransform("frame3", "frame2", mt2); - itf->getTransform("frame3", "frame1", mt3); - CHECK(isEqual(mt1, m1, precision)); - CHECK(isEqual(mt2, m2, precision)); - CHECK(isEqual(mt3, (m1*m2), precision)); - // itf->setTransform still working after duplicate transform - yInfo() << "Sub-test complete"; - } - - //test 12b - { - yInfo() << "Running Sub-test12b"; - itf->clear(); - std::string strs; - itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; - - CHECK(itf->setTransformStatic("frame2", "frame1", m1)); - yarp::os::Time::delay(0.050); - itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; - - CHECK(itf->setTransformStatic("frame3", "frame2", m2)); - yarp::os::Time::delay(0.050); - itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; - - CHECK_FALSE(itf->setTransformStatic("frame3", "frame1", m1)); - //Here I checked false because itf->setTransformStatic of a duplicate transform must be skipped - itf->allFramesAsString(strs); yInfo() << "Existing frames:" << strs; - - yarp::sig::Matrix mt1; - yarp::sig::Matrix mt2; - yarp::sig::Matrix mt3; - itf->getTransform("frame2", "frame1", mt1); - itf->getTransform("frame3", "frame2", mt2); - CHECK(isEqual(mt1, m1, precision)); - CHECK(isEqual(mt2, m2, precision)); - - // checking that the last itf->setTransformStatic had no effect on the values - itf->getTransform("frame3", "frame1", mt3); - CHECK_FALSE(isEqual(mt3, m1, precision)); - CHECK(isEqual(mt3, (m1*m2), precision)); - yInfo() << "Sub-test complete"; - } - - //test 13 - { - yInfo() << "Running Sub-test13"; - itf->clear(); - bool bcan = false; - bcan = itf->canTransform("not_existing_frame", "not_existing_frame"); - CHECK(bcan); - - CHECK(itf->setTransformStatic("frame2", "frame1", m1)); - bcan = itf->canTransform("frame2", "frame2"); - CHECK(bcan); - bcan = itf->canTransform("frame1", "frame1"); - CHECK(bcan); - - yarp::sig::Matrix mt1; - yarp::sig::Matrix eyemat(4, 4); eyemat.eye(); - itf->getTransform("frame1", "frame1", mt1); - CHECK(isEqual(mt1, eyemat, precision)); - itf->getTransform("frame2", "frame2", mt1); - CHECK(isEqual(mt1, eyemat, precision)); - yInfo() << "Sub-test complete"; - } -} - - -void exec_frameTransform_test_2(IFrameTransform* itf) -{ - // Fake transform - yarp::sig::Matrix armToHand(4, 4); - yarp::sig::Matrix result(4, 4); - yarp::sig::Matrix handToFinger(4, 4); - - armToHand.zero(); - armToHand(0, 0) = 1; armToHand(0, 1) = 0; armToHand(0, 2) = 0; armToHand(0, 3) = 5; - armToHand(1, 0) = 0; armToHand(1, 1) = sqrt(2) / 2; armToHand(1, 2) = sqrt(2) / 2; armToHand(1, 3) = 4; - armToHand(2, 0) = 0; armToHand(2, 1) = -sqrt(2) / 2; armToHand(2, 2) = sqrt(2) / 2; armToHand(2, 3) = 3; - armToHand(3, 0) = 0; armToHand(3, 1) = 0; armToHand(3, 2) = 0; armToHand(3, 3) = 1; - - handToFinger(0, 0) = 1; handToFinger(0, 1) = 0; handToFinger(0, 2) = 0; handToFinger(0, 3) = 5; - handToFinger(1, 0) = 0; handToFinger(1, 1) = sqrt(2) / 2; handToFinger(1, 2) = sqrt(2) / 2; handToFinger(1, 3) = 4; - handToFinger(2, 0) = 0; handToFinger(2, 1) = -sqrt(2) / 2; handToFinger(2, 2) = sqrt(2) / 2; handToFinger(2, 3) = 3; - handToFinger(3, 0) = 0; handToFinger(3, 1) = 0; handToFinger(3, 2) = 0; handToFinger(3, 3) = 1; - - result = armToHand * handToFinger; - - // test setTransformStatic - // static transforms cannot be set if they already exists - CHECK(itf->setTransformStatic("/hand", "/arm", armToHand)); - CHECK(!itf->setTransformStatic("/hand", "/arm", handToFinger)); - - // static transforms cannot be set if an indirect connection already exists - CHECK(itf->setTransformStatic("/a", "/b", handToFinger)); - CHECK(itf->setTransformStatic("/b", "/c", handToFinger)); - CHECK(!itf->setTransformStatic("/a", "/c", handToFinger)); - CHECK(itf->deleteTransform("/a", "/b")); - CHECK(itf->deleteTransform("/b", "/c")); - - // test setTransform - CHECK(itf->setTransform("/finger", "/hand", handToFinger)); - CHECK(!itf->setTransform("/finger", "/arm", result)); - - // test getTransform - CHECK(itf->clear()); - CHECK(itf->setTransform("/finger", "/arm", result)); - yarp::sig::Matrix resultFromTransform(4, 4); - CHECK(itf->getTransform("/finger", "/arm", resultFromTransform)); - for (int i = 0; i < 4; i++) { - for (int j = 0; j < 4; j++) { - CHECK((resultFromTransform(i, j) - result(i, j)) <= pow(10, -14)); - } - } - - // test canTransform - CHECK(itf->canTransform("/finger", "/arm")); - CHECK(!itf->canTransform("/finger", "/head")); - - // test frameExists - CHECK(itf->frameExists("/finger")); - CHECK(!itf->frameExists("/head")); - - // test getAllFrameIds - CHECK(itf->clear()); - CHECK(itf->setTransformStatic("/hand", "/arm", armToHand)); - CHECK(itf->setTransformStatic("/finger", "/hand", handToFinger)); - std::vector frameIdsReturned; - std::vector correctFrameIdsReturned{ - "/arm", - "/hand", - "/finger" - }; - CHECK(itf->getAllFrameIds(frameIdsReturned)); - CHECK(frameIdsReturned.size() == correctFrameIdsReturned.size()); - CHECK(frameIdsReturned == correctFrameIdsReturned); - std::vector wrongFrameIdsReturned1{ - "/hand", - "/arm", - "/finger" - }; - CHECK(!(frameIdsReturned == wrongFrameIdsReturned1)); - - // test getParent - std::string parent; - CHECK(itf->getParent("/finger", parent)); - CHECK(parent == "/hand"); - - // test transformPoint - yarp::sig::Vector startingPoint{ 0.0,0.0,0.0 }; - yarp::sig::Vector wrongStartingPoint{ 0.0,0.0,0.0,0.0 }; - yarp::sig::Vector endPoint{ 0.0,0.0,0.0,0.0 }; - CHECK(itf->transformPoint("/finger", "/arm", startingPoint, endPoint)); - CHECK(!itf->transformPoint("/finger", "/arm", wrongStartingPoint, endPoint)); - CHECK(!itf->transformPoint("/finger", "/head", startingPoint, endPoint)); - startingPoint.push_back(1); - yarp::sig::Vector correctEndPoint = result * startingPoint; - correctEndPoint.pop_back(); - CHECK(endPoint.size() == correctEndPoint.size()); - for (int i = 0; i < 3; i++) { - CHECK((endPoint[i] - correctEndPoint[i]) <= pow(10, -14)); - } - - // test transformPose - yarp::sig::Vector startingPose{ 0,0,0,0,0,0 }; - yarp::sig::Vector wrongStartingPose{ 0,0,0,0,0,0,0 }; - yarp::sig::Vector endPose; - yarp::math::FrameTransform transform; - transform.transFromVec(startingPose[0], startingPose[1], startingPose[2]); - transform.rotFromRPY(startingPose[3], startingPose[4], startingPose[5]); - transform.fromMatrix(result * transform.toMatrix()); - CHECK(itf->transformPose("/finger", "/arm", startingPose, endPose)); - CHECK((transform.translation.tX - endPose[0]) <= pow(10, -14)); - CHECK((transform.translation.tY - endPose[1]) <= pow(10, -14)); - CHECK((transform.translation.tZ - endPose[2]) <= pow(10, -14)); - CHECK((transform.translation.tZ - endPose[2]) <= pow(10, -14)); - CHECK((transform.getRPYRot()[0] - endPose[3]) <= pow(10, -14)); - CHECK((transform.getRPYRot()[1] - endPose[4]) <= pow(10, -14)); - CHECK((transform.getRPYRot()[2] - endPose[5]) <= pow(10, -14)); - CHECK(!itf->transformPose("/finger", "/arm", wrongStartingPose, endPose)); - CHECK(!itf->transformPose("/finger", "/head", startingPose, endPose)); - - // test transformQuaternion - yarp::math::Quaternion startingPoseQuaternion = transform.rotation; - yarp::math::Quaternion endPoseQuaternion; - CHECK(itf->transformQuaternion("/finger", "/arm", startingPoseQuaternion, endPoseQuaternion)); - yarp::math::Quaternion correctedEndPoseQuaternion; - yarp::math::FrameTransform transformQuaternion; - itf->getTransform("/finger", "/arm", result); - transformQuaternion.rotation = startingPoseQuaternion; - correctedEndPoseQuaternion.fromRotationMatrix(result * transformQuaternion.toMatrix()); - CHECK((endPoseQuaternion.x() - correctedEndPoseQuaternion.x()) <= pow(10, -14)); - CHECK((endPoseQuaternion.y() - correctedEndPoseQuaternion.y()) <= pow(10, -14)); - CHECK((endPoseQuaternion.z() - correctedEndPoseQuaternion.z()) <= pow(10, -14)); - CHECK((endPoseQuaternion.w() - correctedEndPoseQuaternion.w()) <= pow(10, -14)); - CHECK(!itf->transformQuaternion("/finger", "/head", startingPoseQuaternion, endPoseQuaternion)); - - // test clear - CHECK(itf->clear()); - std::this_thread::sleep_for(std::chrono::milliseconds(250)); - CHECK(!itf->getTransform("/hand", "/arm", result)); - CHECK(!itf->getTransform("/finger", "/hand", result)); - CHECK(!itf->getTransform("/finger", "/arm", result)); -} diff --git a/tests/libYARP_dev/IFrameTransformTest.h b/tests/libYARP_dev/IFrameTransformTest.h deleted file mode 100644 index 9fd9ccbbf1d..00000000000 --- a/tests/libYARP_dev/IFrameTransformTest.h +++ /dev/null @@ -1,18 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef IFRAMETRANSFORMTEST_H -#define IFRAMETRANSFORMTEST_H - -#include - -using namespace yarp::dev; -using namespace yarp::sig; -using namespace yarp::os; - -void exec_frameTransform_test_1(IFrameTransform* iTf); -void exec_frameTransform_test_2(IFrameTransform* iTf); - -#endif From ed1d1b45b23938d011c5e430130bbca1b253a994 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 23 Nov 2022 16:55:24 +0100 Subject: [PATCH 036/267] added new device Rangefinder2D_nwc_yarp --- src/devices/CMakeLists.txt | 1 + .../Rangefinder2D_nwc_yarp/CMakeLists.txt | 47 +++ .../Rangefinder2D_nwc_yarp.cpp | 390 ++++++++++++++++++ .../Rangefinder2D_nwc_yarp.h | 110 +++++ 4 files changed, 548 insertions(+) create mode 100644 src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt create mode 100644 src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.cpp create mode 100644 src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.h diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index b4f0e916df1..f21a33cd31e 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -59,6 +59,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(batteryWrapper) add_subdirectory(upowerBattery) add_subdirectory(Rangefinder2D_nws_yarp) + add_subdirectory(Rangefinder2D_nwc_yarp) add_subdirectory(mobileBaseVelocityControl_nwc_yarp) add_subdirectory(mobileBaseVelocityControl_nws_yarp) add_subdirectory(mobileBaseVelocityControlMsgs) diff --git a/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt b/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt new file mode 100644 index 00000000000..91a38d4785c --- /dev/null +++ b/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt @@ -0,0 +1,47 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +yarp_prepare_plugin(Rangefinder2D_nwc_yarp + CATEGORY device + TYPE Rangefinder2D_nwc_yarp + INCLUDE Rangefinder2D_nwc_yarp.h + DEPENDS "TARGET YARP::YARP_math" + DEFAULT ON +) + +if(NOT SKIP_RRangefinder2D_nwc_yarp) + yarp_add_plugin(yarp_Rangefinder2D_nwc_yarp) + + target_sources(yarp_Rangefinder2D_nwc_yarp + PRIVATE + Rangefinder2D_nwc_yarp.cpp + Rangefinder2D_nwc_yarp.h + ) + + target_link_libraries(yarp_Rangefinder2D_nwc_yarp + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_math + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + YARP_math + ) + + yarp_install( + TARGETS yarp_Rangefinder2D_nwc_yarp + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_Rangefinder2D_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") +endif() diff --git a/src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.cpp b/src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.cpp new file mode 100644 index 00000000000..04695dac171 --- /dev/null +++ b/src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.cpp @@ -0,0 +1,390 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: LGPL-2.1-or-later + */ + +#define _USE_MATH_DEFINES + +#include "Rangefinder2D_nwc_yarp.h" + +#include +#include +#include + +#include +#include + +/*! \file Rangefinder2D_nwc_yarp.cpp */ + +using namespace yarp::dev; +using namespace yarp::os; +using namespace yarp::sig; + +#ifndef DEG2RAD +#define DEG2RAD M_PI/180.0 +#endif + +#define DEFAULT_THREAD_PERIOD 20 //ms +const int LASER_TIMEOUT=100; //ms + +namespace { +YARP_LOG_COMPONENT(RANGEFINDER2DCLIENT, "yarp.device.Rangefinder2D_nwc_yarp") +} + +inline void Rangefinder2DInputPortProcessor::resetStat() +{ + mutex.lock(); + count=0; + deltaT=0; + deltaTMax=0; + deltaTMin=1e22; + now=SystemClock::nowSystem(); + prev=now; + mutex.unlock(); +} + +Rangefinder2DInputPortProcessor::Rangefinder2DInputPortProcessor() +{ + state = IRangefinder2D::DEVICE_GENERAL_ERROR; + resetStat(); +} + +void Rangefinder2DInputPortProcessor::onRead(yarp::dev::LaserScan2D&b) +{ + now=SystemClock::nowSystem(); + mutex.lock(); + + if (count>0) + { + double tmpDT=now-prev; + deltaT+=tmpDT; + if (tmpDT > deltaTMax) { + deltaTMax = tmpDT; + } + if (tmpDT < deltaTMin) { + deltaTMin = tmpDT; + } + + //compare network time + if (tmpDT*1000getScanLimits(tmp_min, tmp_max); + + return true; +} + +bool Rangefinder2D_nwc_yarp::close() +{ + m_rpcPort.close(); + m_inputPort.close(); + return true; +} + +bool Rangefinder2D_nwc_yarp::getRawData(yarp::sig::Vector &data, double* timestamp) +{ + yarp::dev::LaserScan2D scan; + m_inputPort.getLast(scan, m_lastTs); + + data = scan.scans; + + if (timestamp != nullptr) + { + *timestamp = m_lastTs.getTime(); + } + return true; +} + +bool Rangefinder2D_nwc_yarp::getLaserMeasurement(std::vector &data, double* timestamp) +{ + yarp::dev::LaserScan2D scan; + m_inputPort.getLast(scan, m_lastTs); + size_t size = scan.scans.size(); + data.resize(size); + if (m_scan_angle_max < m_scan_angle_min) { yCError(RANGEFINDER2DCLIENT) << "getLaserMeasurement failed"; return false; } + double laser_angle_of_view = m_scan_angle_max - m_scan_angle_min; + for (size_t i = 0; i < size; i++) + { + double angle = (i / double(size)*laser_angle_of_view + m_scan_angle_min)* DEG2RAD; + double value = scan.scans[i]; + data[i].set_polar(value,angle); + } + if (timestamp!=nullptr) + { + *timestamp = m_lastTs.getTime(); + } + return true; +} + +bool Rangefinder2D_nwc_yarp::getDistanceRange(double& min, double& max) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_GET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_DISTANCE_RANGE); + bool ok = m_rpcPort.write(cmd, response); + if (CHECK_FAIL(ok, response) != false) + { + min = response.get(2).asFloat64(); + max = response.get(3).asFloat64(); + return true; + } + return false; +} + +bool Rangefinder2D_nwc_yarp::setDistanceRange(double min, double max) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_SET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_DISTANCE_RANGE); + cmd.addFloat64(min); + cmd.addFloat64(max); + bool ok = m_rpcPort.write(cmd, response); + if (ok) + { + m_scan_angle_min = min; + m_scan_angle_max = max; + } + return (CHECK_FAIL(ok, response)); +} + +bool Rangefinder2D_nwc_yarp::getScanLimits(double& min, double& max) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_GET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_ANGULAR_RANGE); + bool ok = m_rpcPort.write(cmd, response); + if (CHECK_FAIL(ok, response) != false) + { + min = m_scan_angle_min = response.get(2).asFloat64(); + max = m_scan_angle_max = response.get(3).asFloat64(); + return true; + } + return false; +} + +bool Rangefinder2D_nwc_yarp::setScanLimits(double min, double max) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_SET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_ANGULAR_RANGE); + cmd.addFloat64(min); + cmd.addFloat64(max); + bool ok = m_rpcPort.write(cmd, response); + return (CHECK_FAIL(ok, response)); +} + +bool Rangefinder2D_nwc_yarp::getHorizontalResolution(double& step) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_GET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_ANGULAR_STEP); + bool ok = m_rpcPort.write(cmd, response); + if (CHECK_FAIL(ok, response) != false) + { + step = response.get(2).asFloat64(); + return true; + } + return false; +} + +bool Rangefinder2D_nwc_yarp::setHorizontalResolution(double step) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_SET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_ANGULAR_STEP); + cmd.addFloat64(step); + bool ok = m_rpcPort.write(cmd, response); + return (CHECK_FAIL(ok, response)); +} + +bool Rangefinder2D_nwc_yarp::getScanRate(double& rate) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_GET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_SCAN_RATE); + bool ok = m_rpcPort.write(cmd, response); + if (CHECK_FAIL(ok, response) != false) + { + rate = response.get(2).asFloat64(); + return true; + } + return false; +} + +bool Rangefinder2D_nwc_yarp::setScanRate(double rate) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_SET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_LASER_SCAN_RATE); + cmd.addFloat64(rate); + bool ok = m_rpcPort.write(cmd, response); + return (CHECK_FAIL(ok, response)); +} + +bool Rangefinder2D_nwc_yarp::getDeviceStatus(Device_status &status) +{ + status = m_inputPort.getStatus(); + return true; +} + +bool Rangefinder2D_nwc_yarp::getDeviceInfo(std::string &device_info) +{ + Bottle cmd, response; + cmd.addVocab32(VOCAB_GET); + cmd.addVocab32(VOCAB_ILASER2D); + cmd.addVocab32(VOCAB_DEVICE_INFO); + bool ok = m_rpcPort.write(cmd, response); + if (CHECK_FAIL(ok, response)!=false) + { + device_info = response.get(2).asString(); + return true; + } + return false; +} diff --git a/src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.h b/src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.h new file mode 100644 index 00000000000..34c42a4a1b1 --- /dev/null +++ b/src/devices/Rangefinder2D_nwc_yarp/Rangefinder2D_nwc_yarp.h @@ -0,0 +1,110 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: LGPL-2.1-or-later + */ + +#ifndef YARP_DEV_RANGEFINDER2D_NWC_YARP_H +#define YARP_DEV_RANGEFINDER2D_NWC_YARP_H + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +class Rangefinder2DInputPortProcessor : + public yarp::os::BufferedPort +{ + yarp::dev::LaserScan2D lastScan; + std::mutex mutex; + yarp::os::Stamp lastStamp; + double deltaT; + double deltaTMax; + double deltaTMin; + double prev; + double now; + + int state; + int count; + +public: + + inline void resetStat(); + + Rangefinder2DInputPortProcessor(); + + using yarp::os::BufferedPort::onRead; + void onRead(yarp::dev::LaserScan2D&v) override; + + inline int getLast(yarp::dev::LaserScan2D &data, yarp::os::Stamp &stmp); + + inline int getIterations(); + + // time is in ms + void getEstFrequency(int &ite, double &av, double &min, double &max); + + yarp::dev::IRangefinder2D::Device_status getStatus(); + +}; + +/** +* @ingroup dev_impl_network_clients dev_impl_network_lidar +* +* \brief `Rangefinder2D_nwc_yarp`: The client side of any ILaserRangefinder2D capable device. +* +* Still single thread! concurrent access is unsafe. +* +* Parameters required by this device are: +* | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | +* |:--------------:|:--------------:|:-------:|:--------------:|:-------------:|:-----------: |:-----------------------------------------------------------------:|:-----:| +* | local | - | string | - | - | Yes | Full port name opened by the Rangefinder2D_nwc_yarp device. | | +* | remote | - | string | - | - | Yes | Full port name of the port opened on the server side, to which the Rangefinder2D_nwc_yarp connects to. | | +* | carrier | - | string | - | tcp | No | The carrier used for the connection with the server. | | +*/ +class Rangefinder2D_nwc_yarp: + public yarp::dev::DeviceDriver, + public yarp::dev::IRangefinder2D +{ +protected: + Rangefinder2DInputPortProcessor m_inputPort; + yarp::os::Port m_rpcPort; + std::string m_local_portname; + std::string m_remote_portname; + std::string m_carrier; + yarp::os::Stamp m_lastTs; + std::string m_deviceId; + + double m_scan_angle_min; + double m_scan_angle_max; + std::string m_laser_frame_name; + std::string m_robot_frame_name; + +public: + /* DeviceDriver methods */ + bool open(yarp::os::Searchable& config) override; + bool close() override; + + /* IRangefinder2D methods */ + bool getLaserMeasurement(std::vector &data, double* timestamp = nullptr) override; + bool getRawData(yarp::sig::Vector &data, double* timestamp = nullptr) override; + bool getDeviceStatus(Device_status &status) override; + bool getDistanceRange(double& min, double& max) override; + bool setDistanceRange(double min, double max) override; + bool getScanLimits(double& min, double& max) override; + bool setScanLimits(double min, double max) override; + bool getHorizontalResolution(double& step) override; + bool setHorizontalResolution(double step) override; + bool getScanRate(double& rate) override; + bool setScanRate(double rate) override; + bool getDeviceInfo(std::string &device_info) override; +}; + +#endif // YARP_DEV_RANGEFINDER2D_NWC_YARP_H From f2f5889fdbf64159d70644b145d3e8557ede6049 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 24 Nov 2022 10:59:48 +0100 Subject: [PATCH 037/267] added tests for: - rangefinder2D_nws_yarp - rangefinder2D_nwc_yarp - fakeLaser - Rangefinder2DClient.cpp --- doc/release/master/rangefinder2D_nwc_yarp.md | 6 ++ .../Rangefinder2DClient/CMakeLists.txt | 5 ++ .../Rangefinder2DClient.cpp | 2 +- .../Rangefinder2DClient/tests/CMakeLists.txt | 53 +++++++++++++ .../tests/Rangefinder2DClientTest.cpp | 77 +++++++++++++++++++ .../Rangefinder2D_nwc_yarp/CMakeLists.txt | 19 +++-- .../tests/CMakeLists.txt | 53 +++++++++++++ .../tests/Rangefinder2D_nwc_yarpTest.cpp | 77 +++++++++++++++++++ .../Rangefinder2D_nws_yarp/CMakeLists.txt | 5 ++ .../tests/CMakeLists.txt | 53 +++++++++++++ .../tests/Rangefinder2D_nws_yarpTest.cpp | 44 +++++++++++ src/devices/fakeLaser/CMakeLists.txt | 5 ++ src/devices/fakeLaser/fakeLaser.h | 1 + src/devices/fakeLaser/tests/CMakeLists.txt | 53 +++++++++++++ src/devices/fakeLaser/tests/fakeLaserTest.cpp | 48 ++++++++++++ src/libYARP_dev/src/CMakeLists.txt | 2 + .../src/yarp/dev/tests/IRangefinder2DTest.cpp | 6 ++ .../src/yarp/dev/tests/IRangefinder2DTest.h | 66 ++++++++++++++++ 18 files changed, 567 insertions(+), 8 deletions(-) create mode 100644 doc/release/master/rangefinder2D_nwc_yarp.md create mode 100644 src/devices/Rangefinder2DClient/tests/CMakeLists.txt create mode 100644 src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp create mode 100644 src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt create mode 100644 src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp create mode 100644 src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt create mode 100644 src/devices/Rangefinder2D_nws_yarp/tests/Rangefinder2D_nws_yarpTest.cpp create mode 100644 src/devices/fakeLaser/tests/CMakeLists.txt create mode 100644 src/devices/fakeLaser/tests/fakeLaserTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h diff --git a/doc/release/master/rangefinder2D_nwc_yarp.md b/doc/release/master/rangefinder2D_nwc_yarp.md new file mode 100644 index 00000000000..466f77529b9 --- /dev/null +++ b/doc/release/master/rangefinder2D_nwc_yarp.md @@ -0,0 +1,6 @@ +rangefinder2D_nwc_yarp {#master} +----------- + +### `Devices` + +* added new device `rangefinder2D_nwc_yarp` (including IRangefinder2D tests) diff --git a/src/devices/Rangefinder2DClient/CMakeLists.txt b/src/devices/Rangefinder2DClient/CMakeLists.txt index 40b480e34f1..e6ad954f58d 100644 --- a/src/devices/Rangefinder2DClient/CMakeLists.txt +++ b/src/devices/Rangefinder2DClient/CMakeLists.txt @@ -44,4 +44,9 @@ if(NOT SKIP_Rangefinder2DClient) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_Rangefinder2DClient PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/Rangefinder2DClient/Rangefinder2DClient.cpp b/src/devices/Rangefinder2DClient/Rangefinder2DClient.cpp index b1d946d6e6d..bc1baf4adb5 100644 --- a/src/devices/Rangefinder2DClient/Rangefinder2DClient.cpp +++ b/src/devices/Rangefinder2DClient/Rangefinder2DClient.cpp @@ -82,7 +82,7 @@ void Rangefinder2DInputPortProcessor::onRead(yarp::dev::LaserScan2D&b) Stamp newStamp; getEnvelope(newStamp); - //initialialization (first received data) + //initialization (first received data) if (lastStamp.isValid()==false) { lastStamp = newStamp; diff --git a/src/devices/Rangefinder2DClient/tests/CMakeLists.txt b/src/devices/Rangefinder2DClient/tests/CMakeLists.txt new file mode 100644 index 00000000000..f8f4484888d --- /dev/null +++ b/src/devices/Rangefinder2DClient/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_Rangefinder2DClient) + +target_sources(harness_dev_Rangefinder2DClient + PRIVATE + Rangefinder2DClientTest.cpp +) + +target_link_libraries(harness_dev_Rangefinder2DClient + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_Rangefinder2DClient + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Rangefinder2DClientTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_Rangefinder2DClient PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_Rangefinder2DClient) diff --git a/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp b/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp new file mode 100644 index 00000000000..234e9716999 --- /dev/null +++ b/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp @@ -0,0 +1,77 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Rangefinder2DClientTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeLaser", "device"); + YARP_REQUIRE_PLUGIN("rangefinder2D_nws_yarp", "device"); + YARP_REQUIRE_PLUGIN("Rangefinder2DClient", "device"); + + Network::setLocalMode(true); + + SECTION("Checking Rangefinder2DClient device") + { + PolyDriver ddlas; + PolyDriver ddnws; + PolyDriver ddnwc; + IRangefinder2D* irng = nullptr; + + ////////"Checking opening polydriver" + { + Property plas_cfg; + plas_cfg.put("device", "fakeLaser"); + plas_cfg.put("test", "use_constant"); + plas_cfg.put("const_distance", 0.5); + REQUIRE(ddlas.open(plas_cfg)); + } + { + Property pnws_cfg; + pnws_cfg.put("device", "rangefinder2D_nws_yarp"); + pnws_cfg.put("period", "0.010"); + pnws_cfg.put("name", "/laser"); + REQUIRE(ddnws.open(pnws_cfg)); + } + + //attach the nws to the fakelaser device + {yarp::dev::WrapperSingle* ww_nws; ddnws.view(ww_nws); + bool result_att = ww_nws->attach(&ddlas); + REQUIRE(result_att); } + + //create the client + { + Property pnwc_cfg; + pnwc_cfg.put("device", "Rangefinder2DClient"); + pnwc_cfg.put("local", "/local_laser"); + pnwc_cfg.put("remote", "/laser"); + REQUIRE(ddnwc.open(pnwc_cfg)); + } + REQUIRE(ddnwc.view(irng)); + + //execute tests + yarp::dev::tests::exec_iRangefinder2D_test_1 (irng); + + //Close all polydrivers and check + CHECK(ddnwc.close()); + yarp::os::Time::delay(0.1); + CHECK(ddnws.close()); + yarp::os::Time::delay(0.1); + CHECK(ddlas.close()); + } + + Network::setLocalMode(false); +} diff --git a/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt b/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt index 91a38d4785c..30ff2bb020c 100644 --- a/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt +++ b/src/devices/Rangefinder2D_nwc_yarp/CMakeLists.txt @@ -1,7 +1,7 @@ # SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) # SPDX-License-Identifier: BSD-3-Clause -yarp_prepare_plugin(Rangefinder2D_nwc_yarp +yarp_prepare_plugin(rangefinder2D_nwc_yarp CATEGORY device TYPE Rangefinder2D_nwc_yarp INCLUDE Rangefinder2D_nwc_yarp.h @@ -9,16 +9,16 @@ yarp_prepare_plugin(Rangefinder2D_nwc_yarp DEFAULT ON ) -if(NOT SKIP_RRangefinder2D_nwc_yarp) - yarp_add_plugin(yarp_Rangefinder2D_nwc_yarp) +if(NOT SKIP_rangefinder2D_nwc_yarp) + yarp_add_plugin(yarp_rangefinder2D_nwc_yarp) - target_sources(yarp_Rangefinder2D_nwc_yarp + target_sources(yarp_rangefinder2D_nwc_yarp PRIVATE Rangefinder2D_nwc_yarp.cpp Rangefinder2D_nwc_yarp.h ) - target_link_libraries(yarp_Rangefinder2D_nwc_yarp + target_link_libraries(yarp_rangefinder2D_nwc_yarp PRIVATE YARP::YARP_os YARP::YARP_sig @@ -33,7 +33,7 @@ if(NOT SKIP_RRangefinder2D_nwc_yarp) ) yarp_install( - TARGETS yarp_Rangefinder2D_nwc_yarp + TARGETS yarp_rangefinder2D_nwc_yarp EXPORT YARP_${YARP_PLUGIN_MASTER} COMPONENT ${YARP_PLUGIN_MASTER} LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} @@ -43,5 +43,10 @@ if(NOT SKIP_RRangefinder2D_nwc_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - set_property(TARGET yarp_Rangefinder2D_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") + set_property(TARGET yarp_rangefinder2D_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..7e4f311c3d2 --- /dev/null +++ b/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_rangefinder2D_nwc_yarp) + +target_sources(harness_dev_rangefinder2D_nwc_yarp + PRIVATE + Rangefinder2D_nwc_yarpTest.cpp +) + +target_link_libraries(harness_dev_rangefinder2D_nwc_yarp + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_rangefinder2D_nwc_yarp + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Rangefinder2D_nwc_yarpTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_rangefinder2D_nwc_yarp PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_rangefinder2D_nwc_yarp) diff --git a/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp b/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp new file mode 100644 index 00000000000..cd50048ab94 --- /dev/null +++ b/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp @@ -0,0 +1,77 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::rangefinder2D_nwc_yarp", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeLaser", "device"); + YARP_REQUIRE_PLUGIN("rangefinder2D_nws_yarp", "device"); + YARP_REQUIRE_PLUGIN("rangefinder2D_nwc_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking rangefinder2D_nwc_yarp device") + { + PolyDriver ddlas; + PolyDriver ddnws; + PolyDriver ddnwc; + IRangefinder2D* irng = nullptr; + + ////////"Checking opening polydriver" + { + Property plas_cfg; + plas_cfg.put("device", "fakeLaser"); + plas_cfg.put("test","use_constant"); + plas_cfg.put("const_distance", 0.5); + REQUIRE(ddlas.open(plas_cfg)); + } + { + Property pnws_cfg; + pnws_cfg.put("device", "rangefinder2D_nws_yarp"); + pnws_cfg.put("period", "0.010"); + pnws_cfg.put("name", "/laser"); + REQUIRE(ddnws.open(pnws_cfg)); + } + + //attach the nws to the fakelaser device + {yarp::dev::WrapperSingle* ww_nws; ddnws.view(ww_nws); + bool result_att = ww_nws->attach(&ddlas); + REQUIRE(result_att); } + + //create the client + { + Property pnwc_cfg; + pnwc_cfg.put("device", "rangefinder2D_nwc_yarp"); + pnwc_cfg.put("local", "/local_laser"); + pnwc_cfg.put("remote", "/laser"); + REQUIRE(ddnwc.open(pnwc_cfg)); + } + REQUIRE(ddnwc.view(irng)); + + //execute tests + yarp::dev::tests::exec_iRangefinder2D_test_1(irng); + + //Close all polydrivers and check + CHECK(ddnwc.close()); + yarp::os::Time::delay(0.1); + CHECK(ddnws.close()); + yarp::os::Time::delay(0.1); + CHECK(ddlas.close()); + } + + Network::setLocalMode(false); +} diff --git a/src/devices/Rangefinder2D_nws_yarp/CMakeLists.txt b/src/devices/Rangefinder2D_nws_yarp/CMakeLists.txt index 02231137000..f2a1b46ccd6 100644 --- a/src/devices/Rangefinder2D_nws_yarp/CMakeLists.txt +++ b/src/devices/Rangefinder2D_nws_yarp/CMakeLists.txt @@ -43,4 +43,9 @@ if(NOT SKIP_rangefinder2D_nws_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_rangefinder2D_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt b/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..74ca231fe61 --- /dev/null +++ b/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_rangefinder2D_nws_yarp) + +target_sources(harness_dev_rangefinder2D_nws_yarp + PRIVATE + Rangefinder2D_nws_yarpTest.cpp +) + +target_link_libraries(harness_dev_rangefinder2D_nws_yarp + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_rangefinder2D_nws_yarp + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Rangefinder2D_nws_yarpTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_rangefinder2D_nws_yarp PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_rangefinder2D_nws_yarp) diff --git a/src/devices/Rangefinder2D_nws_yarp/tests/Rangefinder2D_nws_yarpTest.cpp b/src/devices/Rangefinder2D_nws_yarp/tests/Rangefinder2D_nws_yarpTest.cpp new file mode 100644 index 00000000000..10c52f55dea --- /dev/null +++ b/src/devices/Rangefinder2D_nws_yarp/tests/Rangefinder2D_nws_yarpTest.cpp @@ -0,0 +1,44 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Rangefinder2D_nws_yarpTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("rangefinder2D_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking Rangefinder2D_nws_yarp device") + { + PolyDriver nws_driver; + IRangefinder2D* irng = nullptr; + + ////////"Checking opening polydriver" + { + Property nws_cfg; + nws_cfg.put("device", "rangefinder2D_nws_yarp"); + nws_cfg.put("period", "0.010"); + nws_cfg.put("name", "/laser"); + REQUIRE(nws_driver.open(nws_cfg)); + } + + //Close all polydrivers and check + CHECK(nws_driver.close()); + } + + Network::setLocalMode(false); +} diff --git a/src/devices/fakeLaser/CMakeLists.txt b/src/devices/fakeLaser/CMakeLists.txt index b661250f1b1..59bb20dcb7c 100644 --- a/src/devices/fakeLaser/CMakeLists.txt +++ b/src/devices/fakeLaser/CMakeLists.txt @@ -42,4 +42,9 @@ if(NOT SKIP_fakeLaser) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeLaser PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeLaser/fakeLaser.h b/src/devices/fakeLaser/fakeLaser.h index 20ac46c173d..d4f1ea737f8 100644 --- a/src/devices/fakeLaser/fakeLaser.h +++ b/src/devices/fakeLaser/fakeLaser.h @@ -106,6 +106,7 @@ class FakeLaser : public yarp::os::PeriodicThread, m_min_angle = 0; //degrees m_max_angle = 360; //degrees m_resolution = 1.0; //degrees + m_scan_rate = period; //s //noise generator m_rd = new std::random_device; diff --git a/src/devices/fakeLaser/tests/CMakeLists.txt b/src/devices/fakeLaser/tests/CMakeLists.txt new file mode 100644 index 00000000000..a9819eda751 --- /dev/null +++ b/src/devices/fakeLaser/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeLaser) + +target_sources(harness_dev_fakeLaser + PRIVATE + fakeLaserTest.cpp +) + +target_link_libraries(harness_dev_fakeLaser + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_fakeLaser + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + fakeLaserTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_fakeLaser PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeLaser) diff --git a/src/devices/fakeLaser/tests/fakeLaserTest.cpp b/src/devices/fakeLaser/tests/fakeLaserTest.cpp new file mode 100644 index 00000000000..a3f29dcc6d5 --- /dev/null +++ b/src/devices/fakeLaser/tests/fakeLaserTest.cpp @@ -0,0 +1,48 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::FakeLaserTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeLaser", "device"); + + Network::setLocalMode(true); + + SECTION("Checking FakeLaserTest device") + { + PolyDriver fakelaserdev; + IRangefinder2D* irng = nullptr; + + ////////"Checking opening polydriver" + { + Property las_cfg; + las_cfg.put("device", "fakeLaser"); + las_cfg.put("test", "use_constant"); + las_cfg.put("const_distance", 0.5); + REQUIRE(fakelaserdev.open(las_cfg)); + REQUIRE(fakelaserdev.view(irng)); + } + + //execute tests + yarp::dev::tests::exec_iRangefinder2D_test_1(irng); + + //"Close all polydrivers and check" + CHECK(fakelaserdev.close()); + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index b2b134a03ab..5f51afe559e 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -410,6 +410,8 @@ target_sources(YARP_dev_tests yarp/dev/tests/INavigation2DTest.h yarp/dev/tests/IDummyTest.cpp yarp/dev/tests/IDummyTest.h + yarp/dev/tests/IRangefinder2DTest.cpp + yarp/dev/tests/IRangefinder2DTest.h ) else() target_sources(YARP_dev_tests diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.cpp new file mode 100644 index 00000000000..f1569f17624 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IRangefinder2DTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h new file mode 100644 index 00000000000..965c1af725e --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h @@ -0,0 +1,66 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IRANGEFINDER2DTEST_H +#define IRANGEFINDER2DTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void exec_iRangefinder2D_test_1(IRangefinder2D* irf) + { + bool b; + + std::string info; + b = irf->getDeviceInfo(info); + CHECK(b); + CHECK(info==std::string("Fake Laser device for test/debugging")); + + double scanrate; + b = irf->getScanRate(scanrate); + CHECK(b); + CHECK(scanrate==0.02); + + yarp::dev::IRangefinder2D::Device_status status; + b = irf->getDeviceStatus(status); + CHECK(b); + CHECK(status== yarp::dev::IRangefinder2D::Device_status::DEVICE_OK_IN_USE); + + double hstep; + b = irf->getHorizontalResolution(hstep); + CHECK(b); + CHECK(hstep==1.0); + + double min,max; + b = irf->getDistanceRange(min,max); + CHECK(b); + CHECK(min == 0.1); + CHECK(max == 8.0); + + std::vector las; + double timestamp; + b = irf->getLaserMeasurement(las, ×tamp); + CHECK(b); + CHECK(timestamp != 0); + CHECK(las.size() == 360); + {double r,t; + las[0].get_polar(r, t); + CHECK(r == 0.5); + CHECK(t == 0);} + {double x,y; + las[0].get_cartesian(x, y); + CHECK(x == 0.5); + CHECK(y == 0);} + + } +} + +#endif From 2d9eb9aca0f0e1c15e102418114c74e25a956977 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 24 Nov 2022 12:22:20 +0100 Subject: [PATCH 038/267] device `group` has been removed because of faulty/incomplete implementation and unused. Please use `yarprobotinterface` instead. --- doc/release/master/device_group_removed.md | 10 + src/devices/CMakeLists.txt | 1 - src/devices/DeviceGroup/CMakeLists.txt | 44 ---- src/devices/DeviceGroup/DeviceGroup.cpp | 210 ------------------ src/devices/DeviceGroup/DeviceGroup.h | 61 ----- .../JoypadControlClient.cpp | 1 - src/libYARP_dev/src/CMakeLists.txt | 2 - .../src/yarp/dev/DriverLinkCreator.cpp | 17 -- .../src/yarp/dev/DriverLinkCreator.h | 70 ------ src/libYARP_dev/src/yarp/dev/all.h | 1 - tests/libYARP_dev/CMakeLists.txt | 1 - tests/libYARP_dev/ControlBoardNwsTest.cpp | 1 - tests/libYARP_dev/GroupDriverTest.cpp | 51 ----- tests/libYARP_dev/TorqueControlTest.cpp | 1 - 14 files changed, 10 insertions(+), 461 deletions(-) create mode 100644 doc/release/master/device_group_removed.md delete mode 100644 src/devices/DeviceGroup/CMakeLists.txt delete mode 100644 src/devices/DeviceGroup/DeviceGroup.cpp delete mode 100644 src/devices/DeviceGroup/DeviceGroup.h delete mode 100644 src/libYARP_dev/src/yarp/dev/DriverLinkCreator.cpp delete mode 100644 src/libYARP_dev/src/yarp/dev/DriverLinkCreator.h delete mode 100644 tests/libYARP_dev/GroupDriverTest.cpp diff --git a/doc/release/master/device_group_removed.md b/doc/release/master/device_group_removed.md new file mode 100644 index 00000000000..a57f99e1abf --- /dev/null +++ b/doc/release/master/device_group_removed.md @@ -0,0 +1,10 @@ +device_group_removed {#master} +----------- + +### `Devices` + +* device `group` has been removed because of faulty/incomplete implementation and unused. Please use `yarprobotinterface` instead. + +### `lib_yarp_dev` + +* Class `DriverLinkCreator`, used only by device `group`, has been removed. diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index b4f0e916df1..2e07e8820ca 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -78,7 +78,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(usbCamera) add_subdirectory(fakeLocalizerDevice) add_subdirectory(fakeNavigationDevice) - add_subdirectory(DeviceGroup) add_subdirectory(ServerSerial) add_subdirectory(RemoteFrameGrabber) add_subdirectory(RemoteControlBoard) diff --git a/src/devices/DeviceGroup/CMakeLists.txt b/src/devices/DeviceGroup/CMakeLists.txt deleted file mode 100644 index afc32bebe09..00000000000 --- a/src/devices/DeviceGroup/CMakeLists.txt +++ /dev/null @@ -1,44 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -yarp_prepare_plugin(group - CATEGORY device - TYPE DeviceGroup - INCLUDE DeviceGroup.h - DEFAULT ON -) - -if(NOT SKIP_group) - yarp_add_plugin(yarp_group) - - target_sources(yarp_group - PRIVATE - DeviceGroup.cpp - DeviceGroup.h - ) - - target_link_libraries(yarp_group - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_group - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_group PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/DeviceGroup/DeviceGroup.cpp b/src/devices/DeviceGroup/DeviceGroup.cpp deleted file mode 100644 index 492bc9f3fd9..00000000000 --- a/src/devices/DeviceGroup/DeviceGroup.cpp +++ /dev/null @@ -1,210 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "DeviceGroup.h" - -#include -#include -#include -#include -#include - -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::sig; -using namespace yarp::dev; - -namespace { -YARP_LOG_COMPONENT(DEVICEGROUP, "yarp.devices.DeviceGroup") -} - -#define HELPER(x) (*((DeviceGroupHelper*)(x))) - - -class DeviceGroupHelper -{ -private: - std::vector drivers; - std::vector names; - std::vector needDrive; - std::mutex mutex; -public: - bool needDriveSummary{false}; - - void clear() - { - mutex.lock(); - std::vector& lst = drivers; - for (unsigned int i=0; i& lst = drivers; - for (unsigned int i=0; iview(service); - if (service!=nullptr) { - service->updateService(); - } - } - } - mutex.unlock(); - } - - bool close() - { - yCTrace(DEVICEGROUP, "*** Device group closing"); - clear(); - yCTrace(DEVICEGROUP, "*** Device group closed"); - return true; - } - - ~DeviceGroupHelper() - { - clear(); - } - - bool add(const std::string& name, yarp::os::Searchable& config) - { - yCTrace(DEVICEGROUP, "ADDING %s", config.toString().c_str()); - auto* pd = new PolyDriver(); - yCAssert(DEVICEGROUP, pd!=nullptr); - bool result = pd->open(config); - if (!result) { - delete pd; - return false; - } - drivers.push_back(pd); - names.push_back(name); - IService *service = nullptr; - pd->view(service); - bool backgrounded = true; - if (service!=nullptr) { - backgrounded = service->startService(); - if (backgrounded) { - // we don't need to poll this, so forget about the - // service interface - yCInfo(DEVICEGROUP, "group: service backgrounded"); - service = nullptr; - } - } - needDrive.push_back(!backgrounded); - needDriveSummary = needDriveSummary || (!backgrounded); - Drivers::factory().add(new DriverLinkCreator(name,*pd)); - return true; - } - -}; - - - - -bool DeviceGroup::open(yarp::os::Searchable& config) -{ - if (implementation==nullptr) { - implementation = new DeviceGroupHelper; - } - if (implementation==nullptr) { - yCError(DEVICEGROUP, "Out of memory"); - return false; - } - - if (config.check("part","a list of section names, with each section containing a device")) { - Bottle bot = config.findGroup("part").tail(); - yCInfo(DEVICEGROUP, "Assembly of: %s", bot.toString().c_str()); - for (size_t i=0; i %s", name.c_str(), - config.findGroup(name).toString().c_str()); - bool result = HELPER(implementation).add(name, - config.findGroup(name)); - if (!result) { - HELPER(implementation).close(); - return false; - } - } - return true; - } - return false; -} - - -bool DeviceGroup::open(const char *key, PolyDriver& poly, - yarp::os::Searchable& config, const char *comment) -{ - Value *name; - if (config.check(key,name,comment)) { - if (name->isString()) { - // maybe user isn't doing nested configuration - yarp::os::Property p; - p.setMonitor(config.getMonitor(), - name->toString().c_str()); // pass on any monitoring - p.fromString(config.toString()); - p.put("device",name->toString()); - p.unput("subdevice"); - p.unput("wrapped"); - poly.open(p); - } else { - Bottle subdevice = config.findGroup(key).tail(); - poly.open(subdevice); - } - if (!poly.isValid()) { - yCError(DEVICEGROUP, "cannot make <%s>", name->toString().c_str()); - return false; - } - } else { - yCError(DEVICEGROUP, "\"--%s \" not set", key); - return false; - } - return true; -} - - -bool DeviceGroup::closeMain() -{ - yCInfo(DEVICEGROUP, "Devices closing"); - HELPER(implementation).close(); - source.close(); - sink.close(); - return true; -} - -bool DeviceGroup::startService() -{ - return !HELPER(implementation).needDriveSummary; -} - - -bool DeviceGroup::updateService() -{ - HELPER(implementation).update(); - return true; -} - - -DeviceGroup::~DeviceGroup() -{ - if (implementation!=nullptr) { - delete &HELPER(implementation); - implementation = nullptr; - } -} diff --git a/src/devices/DeviceGroup/DeviceGroup.h b/src/devices/DeviceGroup/DeviceGroup.h deleted file mode 100644 index 0a00a648746..00000000000 --- a/src/devices/DeviceGroup/DeviceGroup.h +++ /dev/null @@ -1,61 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_DEVICEGROUP_H -#define YARP_DEV_DEVICEGROUP_H - -#include -#include - -/** - * @ingroup dev_impl_other - * - * \brief `group`: Lets you make a bunch of devices as a group. - */ -class DeviceGroup : - public yarp::dev::DeviceDriver, - public yarp::dev::IService -{ -public: - DeviceGroup() = default; - DeviceGroup(const DeviceGroup&) = delete; - DeviceGroup(DeviceGroup&&) = delete; - DeviceGroup& operator=(const DeviceGroup&) = delete; - DeviceGroup& operator=(DeviceGroup&&) = delete; - ~DeviceGroup() override; - - bool open(yarp::os::Searchable& config) override; - - bool close() override - { - return closeMain(); - } - - bool startService() override; - - bool stopService() override - { - return close(); - } - - bool updateService() override; - -private: - void* implementation{nullptr}; - - bool closeMain(); - - yarp::dev::PolyDriver source; - yarp::dev::PolyDriver sink; - - bool open(const char *key, - yarp::dev::PolyDriver& poly, - yarp::os::Searchable& config, - const char *comment); -}; - - -#endif // YARP_DEV_DEVICEGROUP_H diff --git a/src/devices/JoypadControlClient/JoypadControlClient.cpp b/src/devices/JoypadControlClient/JoypadControlClient.cpp index 8729553d1d2..027ba028bb1 100644 --- a/src/devices/JoypadControlClient/JoypadControlClient.cpp +++ b/src/devices/JoypadControlClient/JoypadControlClient.cpp @@ -7,7 +7,6 @@ #include #include #include -#include using namespace yarp::dev; using namespace yarp::sig; diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index b2b134a03ab..0ff443be6ec 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -26,7 +26,6 @@ set(YARP_dev_HDRS yarp/dev/ControlBoardPid.h yarp/dev/ControlBoardVocabs.h yarp/dev/DeviceDriver.h - yarp/dev/DriverLinkCreator.h yarp/dev/Drivers.h yarp/dev/GPUInterface.h yarp/dev/GazeControl.h @@ -159,7 +158,6 @@ set(YARP_dev_SRCS yarp/dev/ControlBoardInterfacesImpl.cpp yarp/dev/ControlBoardPid.cpp yarp/dev/DeviceDriver.cpp - yarp/dev/DriverLinkCreator.cpp yarp/dev/Drivers.cpp yarp/dev/GazeControl.cpp yarp/dev/IAnalogSensor.cpp diff --git a/src/libYARP_dev/src/yarp/dev/DriverLinkCreator.cpp b/src/libYARP_dev/src/yarp/dev/DriverLinkCreator.cpp deleted file mode 100644 index efa3fa2443b..00000000000 --- a/src/libYARP_dev/src/yarp/dev/DriverLinkCreator.cpp +++ /dev/null @@ -1,17 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -yarp::dev::DriverLinkCreator::DriverLinkCreator(const std::string& name, PolyDriver& source) : - name(name) -{ - holding.link(source); -} - -yarp::dev::DriverLinkCreator::~DriverLinkCreator() -{ - holding.close(); -} diff --git a/src/libYARP_dev/src/yarp/dev/DriverLinkCreator.h b/src/libYARP_dev/src/yarp/dev/DriverLinkCreator.h deleted file mode 100644 index 2d82a17d7c0..00000000000 --- a/src/libYARP_dev/src/yarp/dev/DriverLinkCreator.h +++ /dev/null @@ -1,70 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_DRIVERLINKCREATOR_H -#define YARP_DEV_DRIVERLINKCREATOR_H - -#include -#include - -namespace yarp::dev { - -/** - * A factory for creating links to a driver that has already been - * created. - */ -class YARP_dev_API DriverLinkCreator : - public DriverCreator -{ -private: - YARP_SUPPRESS_DLL_INTERFACE_WARNING_ARG(std::string) name; - PolyDriver holding; - -public: - DriverLinkCreator(const std::string& name, PolyDriver& source); - virtual ~DriverLinkCreator() override; - - std::string toString() const override - { - return name; - } - - DeviceDriver *create() const override - { - DeviceDriver *internal; - const_cast(holding).view(internal); - return internal; - } - - std::string getName() const override - { - return name; - } - - std::string getWrapper() const override - { - return "(link)"; - } - - std::string getCode() const override - { - return "DriverLinkCreator"; - } - - PolyDriver *owner() override - { - return &holding; - } - - void close() - { - holding.close(); - } -}; - -} // namespace yarp::dev - -#endif // YARP_DEV_DRIVERLINKCREATOR_H diff --git a/src/libYARP_dev/src/yarp/dev/all.h b/src/libYARP_dev/src/yarp/dev/all.h index 6ac95fece2c..0244470f6e2 100644 --- a/src/libYARP_dev/src/yarp/dev/all.h +++ b/src/libYARP_dev/src/yarp/dev/all.h @@ -19,7 +19,6 @@ #include #include #include -#include #include #include #include diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index 8316aa4fd70..d8ea8dc62f4 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -7,7 +7,6 @@ target_sources(harness_dev AnalogWrapperTest.cpp ControlBoardRemapperTest.cpp ControlBoardNwsTest.cpp - GroupDriverTest.cpp MapGrid2DTest.cpp MultipleAnalogSensorsInterfacesTest.cpp PolyDriverTest.cpp diff --git a/tests/libYARP_dev/ControlBoardNwsTest.cpp b/tests/libYARP_dev/ControlBoardNwsTest.cpp index 2148d0987b0..14e2b984508 100644 --- a/tests/libYARP_dev/ControlBoardNwsTest.cpp +++ b/tests/libYARP_dev/ControlBoardNwsTest.cpp @@ -21,7 +21,6 @@ using namespace yarp::dev; TEST_CASE("dev::controlBoard_nws_yarp", "[yarp::dev]") { - YARP_REQUIRE_PLUGIN("group", "device"); YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); YARP_REQUIRE_PLUGIN("remote_controlboard", "device"); diff --git a/tests/libYARP_dev/GroupDriverTest.cpp b/tests/libYARP_dev/GroupDriverTest.cpp deleted file mode 100644 index f6cfb5f3de9..00000000000 --- a/tests/libYARP_dev/GroupDriverTest.cpp +++ /dev/null @@ -1,51 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include -#include - -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; - -TEST_CASE("dev::GroupDriver", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("group", "device"); - YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); - YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); - - Network::setLocalMode(true); - - SECTION("make sure groups of devices can be instantiated correctly") - { - Property p; - p.fromConfig("\ -device group\n\ -\n\ -[part mymotor]\n\ -device fakeMotionControl\n\ -GENERAL (Joints 10)\n\ -\n\ -[part broadcast]\n\ -device controlBoard_nws_yarp\n\ -subdevice mymotor\n\ -name /mymotor\n\ -"); - p.put("verbose",1); - PolyDriver dd(p); - Bottle cmd("get axes"), reply; - Network::write(Contact("/mymotor/rpc:i"), cmd, reply); - CHECK(reply.get(2).asInt32() == 10); // axis count is correct - } - - Network::setLocalMode(false); -} diff --git a/tests/libYARP_dev/TorqueControlTest.cpp b/tests/libYARP_dev/TorqueControlTest.cpp index 1fb01cf8372..bfe75a9515a 100644 --- a/tests/libYARP_dev/TorqueControlTest.cpp +++ b/tests/libYARP_dev/TorqueControlTest.cpp @@ -21,7 +21,6 @@ using namespace yarp::dev; TEST_CASE("dev::TorqueControl", "[yarp::dev]") { - YARP_REQUIRE_PLUGIN("group", "device"); YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); YARP_REQUIRE_PLUGIN("remote_controlboard", "device"); From 4187397695f43a452496463a0e87db21cb24ed9a Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 24 Nov 2022 18:18:10 +0100 Subject: [PATCH 039/267] added tests for: fakeMotionControl, ControlBoardWrapper, ControlBoardRemapper, ControlBoard_nws_yarp --- .../ControlBoardRemapper/CMakeLists.txt | 5 + .../ControlBoardRemapper/tests/CMakeLists.txt | 42 +++++++++ .../tests}/ControlBoardRemapperTest.cpp | 0 .../tests/ControlBoardRemapperTest2.cpp | 74 +++++++++++++++ .../ControlBoardWrapper/CMakeLists.txt | 5 + .../ControlBoardWrapper/tests/CMakeLists.txt | 41 ++++++++ .../tests/ControlBoardWrapperTest.cpp | 48 ++++++++++ .../ControlBoard_nws_yarp/CMakeLists.txt | 5 + .../tests/CMakeLists.txt | 41 ++++++++ .../tests/ControlBoard_nws_yarpTest.cpp | 41 ++++++++ src/devices/RemoteControlBoard/CMakeLists.txt | 5 + .../RemoteControlBoard/tests/CMakeLists.txt | 41 ++++++++ .../tests/RemoteControlBoardTest.cpp | 85 +++++++++++++++++ src/devices/fakeMotionControl/CMakeLists.txt | 5 + .../fakeMotionControl/tests/CMakeLists.txt | 41 ++++++++ .../tests/FakeMotionControlTest.cpp | 56 +++++++++++ src/libYARP_dev/src/CMakeLists.txt | 12 +++ .../src/yarp/dev/tests/IAxisInfoTest.cpp | 6 ++ .../src/yarp/dev/tests/IAxisInfoTest.h | 40 ++++++++ .../yarp/dev/tests/IPositionControlTest.cpp | 6 ++ .../src/yarp/dev/tests/IPositionControlTest.h | 30 ++++++ .../src/yarp/dev/tests/ITorqueControlTest.cpp | 6 ++ .../src/yarp/dev/tests/ITorqueControlTest.h | 54 +++++++++++ tests/libYARP_dev/CMakeLists.txt | 3 - tests/libYARP_dev/ControlBoardNwsTest.cpp | 78 ---------------- tests/libYARP_dev/TorqueControlTest.cpp | 93 ------------------- 26 files changed, 689 insertions(+), 174 deletions(-) create mode 100644 src/devices/ControlBoardRemapper/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/ControlBoardRemapper/tests}/ControlBoardRemapperTest.cpp (100%) create mode 100644 src/devices/ControlBoardRemapper/tests/ControlBoardRemapperTest2.cpp create mode 100644 src/devices/ControlBoardWrapper/tests/CMakeLists.txt create mode 100644 src/devices/ControlBoardWrapper/tests/ControlBoardWrapperTest.cpp create mode 100644 src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt create mode 100644 src/devices/ControlBoard_nws_yarp/tests/ControlBoard_nws_yarpTest.cpp create mode 100644 src/devices/RemoteControlBoard/tests/CMakeLists.txt create mode 100644 src/devices/RemoteControlBoard/tests/RemoteControlBoardTest.cpp create mode 100644 src/devices/fakeMotionControl/tests/CMakeLists.txt create mode 100644 src/devices/fakeMotionControl/tests/FakeMotionControlTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.h create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.h create mode 100644 src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.h delete mode 100644 tests/libYARP_dev/ControlBoardNwsTest.cpp delete mode 100644 tests/libYARP_dev/TorqueControlTest.cpp diff --git a/src/devices/ControlBoardRemapper/CMakeLists.txt b/src/devices/ControlBoardRemapper/CMakeLists.txt index d3c90188ece..a2d33e3fff6 100644 --- a/src/devices/ControlBoardRemapper/CMakeLists.txt +++ b/src/devices/ControlBoardRemapper/CMakeLists.txt @@ -57,4 +57,9 @@ if(NOT SKIP_controlboardremapper OR NOT SKIP_remotecontrolboardremapper) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_controlboardremapper PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/ControlBoardRemapper/tests/CMakeLists.txt b/src/devices/ControlBoardRemapper/tests/CMakeLists.txt new file mode 100644 index 00000000000..8f79a30ec6d --- /dev/null +++ b/src/devices/ControlBoardRemapper/tests/CMakeLists.txt @@ -0,0 +1,42 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_controlBoardRemapper) + +target_sources(harness_dev_controlBoardRemapper + PRIVATE + ControlBoardRemapperTest.cpp + ControlBoardRemapperTest2.cpp +) + +target_link_libraries(harness_dev_controlBoardRemapper + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_controlBoardRemapper PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_controlBoardRemapper) diff --git a/tests/libYARP_dev/ControlBoardRemapperTest.cpp b/src/devices/ControlBoardRemapper/tests/ControlBoardRemapperTest.cpp similarity index 100% rename from tests/libYARP_dev/ControlBoardRemapperTest.cpp rename to src/devices/ControlBoardRemapper/tests/ControlBoardRemapperTest.cpp diff --git a/src/devices/ControlBoardRemapper/tests/ControlBoardRemapperTest2.cpp b/src/devices/ControlBoardRemapper/tests/ControlBoardRemapperTest2.cpp new file mode 100644 index 00000000000..cade261ef67 --- /dev/null +++ b/src/devices/ControlBoardRemapper/tests/ControlBoardRemapperTest2.cpp @@ -0,0 +1,74 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +TEST_CASE("dev::ControlBoardRemapperTest2", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); + YARP_REQUIRE_PLUGIN("controlboardremapper", "device"); + + Network::setLocalMode(true); + + SECTION("Checking controlboardremapper device") + { + PolyDriver ddmc; + PolyDriver ddremapper; + IPositionControl* ipos = nullptr; + ITorqueControl* itrq = nullptr; + IAxisInfo* iinfo = nullptr; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property p_cfg; + p_cfg.put("device", "fakeMotionControl"); + Property& grp = p_cfg.addGroup("GENERAL"); + grp.put("Joints", 2); + REQUIRE(ddmc.open(p_cfg)); + } + { + Property p_cfg; + p_cfg.put("device", "controlboardremapper"); + yarp::os::Value* jlist = yarp::os::Value::makeList("joint0 joint1"); + p_cfg.put("axesNames", jlist); + REQUIRE(ddremapper.open(p_cfg)); + } + { + yarp::dev::IMultipleWrapper* ww_nws; ddremapper.view(ww_nws); + yarp::dev::PolyDriverList pdlist; pdlist.push(&ddmc,"fakeboard1"); + bool result_att = ww_nws->attachAll(pdlist); + REQUIRE(result_att); + } + + ddremapper.view(ipos); + ddremapper.view(itrq); + ddremapper.view(iinfo); + yarp::dev::tests::exec_iPositionControl_test_1(ipos); + yarp::dev::tests::exec_iTorqueControl_test_1(itrq); + yarp::dev::tests::exec_iAxisInfo_test_1(iinfo); + + //"Close all polydrivers and check" + { + CHECK(ddremapper.close()); + CHECK(ddmc.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/ControlBoardWrapper/CMakeLists.txt b/src/devices/ControlBoardWrapper/CMakeLists.txt index 56221cc6662..c63b0d52d7a 100644 --- a/src/devices/ControlBoardWrapper/CMakeLists.txt +++ b/src/devices/ControlBoardWrapper/CMakeLists.txt @@ -103,4 +103,9 @@ if(NOT SKIP_controlboardwrapper2) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_controlboardwrapper2 PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/ControlBoardWrapper/tests/CMakeLists.txt b/src/devices/ControlBoardWrapper/tests/CMakeLists.txt new file mode 100644 index 00000000000..54fd84ea872 --- /dev/null +++ b/src/devices/ControlBoardWrapper/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_controlBoardWrapper) + +target_sources(harness_dev_controlBoardWrapper + PRIVATE + ControlBoardWrapperTest.cpp +) + +target_link_libraries(harness_dev_controlBoardWrapper + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_controlBoardWrapper PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_controlBoardWrapper) diff --git a/src/devices/ControlBoardWrapper/tests/ControlBoardWrapperTest.cpp b/src/devices/ControlBoardWrapper/tests/ControlBoardWrapperTest.cpp new file mode 100644 index 00000000000..376a3dcd96c --- /dev/null +++ b/src/devices/ControlBoardWrapper/tests/ControlBoardWrapperTest.cpp @@ -0,0 +1,48 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Map2DnwsTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("map2D_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking map2D_nws_yarp device") + { + PolyDriver ddmapserver; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property pmapserver_cfg; + pmapserver_cfg.put("device", "map2D_nws_yarp"); + REQUIRE(ddmapserver.open(pmapserver_cfg)); + } + + //"Close all polydrivers and check" + { + CHECK(ddmapserver.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/ControlBoard_nws_yarp/CMakeLists.txt b/src/devices/ControlBoard_nws_yarp/CMakeLists.txt index 5941d8abc52..891f965b2f5 100644 --- a/src/devices/ControlBoard_nws_yarp/CMakeLists.txt +++ b/src/devices/ControlBoard_nws_yarp/CMakeLists.txt @@ -55,4 +55,9 @@ if(NOT SKIP_controlBoard_nws_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_controlBoard_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt b/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..06c7216f550 --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_controlBoard_nws_yarp) + +target_sources(harness_dev_controlBoard_nws_yarp + PRIVATE + ControlBoard_nws_yarpTest.cpp +) + +target_link_libraries(harness_dev_controlBoard_nws_yarp + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_controlBoard_nws_yarp PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_controlBoard_nws_yarp) diff --git a/src/devices/ControlBoard_nws_yarp/tests/ControlBoard_nws_yarpTest.cpp b/src/devices/ControlBoard_nws_yarp/tests/ControlBoard_nws_yarpTest.cpp new file mode 100644 index 00000000000..7f48497e17b --- /dev/null +++ b/src/devices/ControlBoard_nws_yarp/tests/ControlBoard_nws_yarpTest.cpp @@ -0,0 +1,41 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +TEST_CASE("dev::controlBoard_nws_yarp", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking controlBoard_nws_yarp device") + { + PolyDriver ddnws; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property pcfg; + pcfg.put("device", "controlBoard_nws_yarp"); + pcfg.put("name", "/controlboard"); + REQUIRE(ddnws.open(pcfg)); + } + + //"Close all polydrivers and check" + { + CHECK(ddnws.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/RemoteControlBoard/CMakeLists.txt b/src/devices/RemoteControlBoard/CMakeLists.txt index 76120225c86..796779346dc 100644 --- a/src/devices/RemoteControlBoard/CMakeLists.txt +++ b/src/devices/RemoteControlBoard/CMakeLists.txt @@ -47,4 +47,9 @@ if(NOT SKIP_remote_controlboard) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_remote_controlboard PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/RemoteControlBoard/tests/CMakeLists.txt b/src/devices/RemoteControlBoard/tests/CMakeLists.txt new file mode 100644 index 00000000000..8931bfe8f55 --- /dev/null +++ b/src/devices/RemoteControlBoard/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_RemoteControlBoard) + +target_sources(harness_dev_RemoteControlBoard + PRIVATE + RemoteControlBoardTest.cpp +) + +target_link_libraries(harness_dev_RemoteControlBoard + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_RemoteControlBoard PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_RemoteControlBoard) diff --git a/src/devices/RemoteControlBoard/tests/RemoteControlBoardTest.cpp b/src/devices/RemoteControlBoard/tests/RemoteControlBoardTest.cpp new file mode 100644 index 00000000000..5831aa5b337 --- /dev/null +++ b/src/devices/RemoteControlBoard/tests/RemoteControlBoardTest.cpp @@ -0,0 +1,85 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +TEST_CASE("dev::RemoteControlBoardTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); + YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); + YARP_REQUIRE_PLUGIN("remote_controlboard", "device"); + + Network::setLocalMode(true); + + SECTION("Checking remote_controlboard device") + { + PolyDriver ddmc; + PolyDriver ddnws; + PolyDriver ddnwc; + + IPositionControl* ipos = nullptr; + ITorqueControl* itrq = nullptr; + IAxisInfo* iinfo = nullptr; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property p_cfg; + p_cfg.put("device", "fakeMotionControl"); + Property& grp = p_cfg.addGroup("GENERAL"); + grp.put("Joints", 2); + REQUIRE(ddmc.open(p_cfg)); + } + yarp::os::Time::delay(0.1); + { + Property p_cfg; + p_cfg.put("device", "controlBoard_nws_yarp"); + p_cfg.put("name", "/controlboardserver"); + REQUIRE(ddnws.open(p_cfg)); + } + { + yarp::dev::WrapperSingle* ww_nws; ddnws.view(ww_nws); + bool result_att = ww_nws->attach(&ddmc); + REQUIRE(result_att); + } + yarp::os::Time::delay(0.1); + { + Property p_cfg; + p_cfg.put("device", "remote_controlboard"); + p_cfg.put("local", "/local_controlboard"); + p_cfg.put("remote", "/controlboardserver"); + REQUIRE(ddnwc.open(p_cfg)); + } + + ddnwc.view(ipos); + ddnwc.view(itrq); + ddnwc.view(iinfo); + yarp::dev::tests::exec_iPositionControl_test_1(ipos); + yarp::dev::tests::exec_iTorqueControl_test_1(itrq); + yarp::dev::tests::exec_iAxisInfo_test_1(iinfo); + + //"Close all polydrivers and check" + { + CHECK(ddnwc.close()); + CHECK(ddnws.close()); + CHECK(ddmc.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/fakeMotionControl/CMakeLists.txt b/src/devices/fakeMotionControl/CMakeLists.txt index c5e3fe9c948..eb8900a2cad 100644 --- a/src/devices/fakeMotionControl/CMakeLists.txt +++ b/src/devices/fakeMotionControl/CMakeLists.txt @@ -44,4 +44,9 @@ if(NOT SKIP_fakeMotionControl) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeMotionControl PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeMotionControl/tests/CMakeLists.txt b/src/devices/fakeMotionControl/tests/CMakeLists.txt new file mode 100644 index 00000000000..84df140d627 --- /dev/null +++ b/src/devices/fakeMotionControl/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeMotionControl) + +target_sources(harness_dev_fakeMotionControl + PRIVATE + FakeMotionControlTest.cpp +) + +target_link_libraries(harness_dev_fakeMotionControl + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_fakeMotionControl PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeMotionControl) diff --git a/src/devices/fakeMotionControl/tests/FakeMotionControlTest.cpp b/src/devices/fakeMotionControl/tests/FakeMotionControlTest.cpp new file mode 100644 index 00000000000..34d6c3d537d --- /dev/null +++ b/src/devices/fakeMotionControl/tests/FakeMotionControlTest.cpp @@ -0,0 +1,56 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +TEST_CASE("dev::fakeMotionControl", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); + + Network::setLocalMode(true); + + SECTION("Checking map2D_nws_yarp device") + { + PolyDriver ddmc; + IPositionControl* ipos=nullptr; + ITorqueControl* itrq=nullptr; + IAxisInfo* iaxis = nullptr; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property p_cfg; + p_cfg.put("device", "fakeMotionControl"); + REQUIRE(ddmc.open(p_cfg)); + } + + ddmc.view(ipos); + ddmc.view(itrq); + ddmc.view(iaxis); + yarp::dev::tests::exec_iPositionControl_test_1(ipos); + yarp::dev::tests::exec_iTorqueControl_test_1(itrq); + yarp::dev::tests::exec_iAxisInfo_test_1(iaxis); + + //"Close all polydrivers and check" + { + CHECK(ddmc.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index 0c5c862aa06..e42a7a5314d 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -410,12 +410,24 @@ target_sources(YARP_dev_tests yarp/dev/tests/IDummyTest.h yarp/dev/tests/IRangefinder2DTest.cpp yarp/dev/tests/IRangefinder2DTest.h + yarp/dev/tests/IPositionControlTest.cpp + yarp/dev/tests/IPositionControlTest.h + yarp/dev/tests/ITorqueControlTest.cpp + yarp/dev/tests/ITorqueControlTest.h + yarp/dev/tests/IAxisInfoTest.cpp + yarp/dev/tests/IAxisInfoTest.h ) else() target_sources(YARP_dev_tests PRIVATE yarp/dev/tests/IDummyTest.cpp yarp/dev/tests/IDummyTest.h + yarp/dev/tests/IPositionControlTest.cpp + yarp/dev/tests/IPositionControlTest.h + yarp/dev/tests/ITorqueControlTest.cpp + yarp/dev/tests/ITorqueControlTest.h + yarp/dev/tests/IAxisInfoTest.cpp + yarp/dev/tests/IAxisInfoTest.h ) endif() diff --git a/src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.cpp new file mode 100644 index 00000000000..ff66f3109e0 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IAxisInfoTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.h b/src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.h new file mode 100644 index 00000000000..33cd2ead1e9 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IAxisInfoTest.h @@ -0,0 +1,40 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IAXISINFOTEST_H +#define IAXISINFOTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void exec_iAxisInfo_test_1(IAxisInfo* iinfo) + { + REQUIRE(iinfo !=nullptr); + + bool b; + + int ax; + b = iinfo->getAxes(&ax); + CHECK(b); + CHECK(ax != 0); + + std::string name; + b = iinfo->getAxisName(0,name); + CHECK(b); + CHECK(name == std::string("joint0")); + + yarp::dev::JointTypeEnum type; + b = iinfo->getJointType(0, type); + CHECK(b); + CHECK(type == yarp::dev::JointTypeEnum::VOCAB_JOINTTYPE_REVOLUTE); + } +} + +#endif diff --git a/src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.cpp new file mode 100644 index 00000000000..c67f4de4ad0 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IPositionControlTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.h b/src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.h new file mode 100644 index 00000000000..50869f2e191 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IPositionControlTest.h @@ -0,0 +1,30 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IPOSITIONCONTROLTEST_H +#define IPOSITIONCONTROLTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void exec_iPositionControl_test_1(IPositionControl* ipos) + { + REQUIRE(ipos!=nullptr); + + bool b; + + int ax; + b = ipos->getAxes(&ax); + CHECK(b); + CHECK(ax != 0); + } +} + +#endif diff --git a/src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.cpp new file mode 100644 index 00000000000..c18e135883c --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "ITorqueControlTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.h b/src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.h new file mode 100644 index 00000000000..b30b8bd405c --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/ITorqueControlTest.h @@ -0,0 +1,54 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef ITORQUECONTROLTEST_H +#define ITORQUECONTROLTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void exec_iTorqueControl_test_1(ITorqueControl* itrq) + { + REQUIRE(itrq != nullptr); + + bool b; + + int ax; + b = itrq->getAxes(&ax); + CHECK(b); + CHECK(ax != 0); + + yarp::dev::MotorTorqueParameters params; + //params.bemf = 0.1; + //params.bemf_scale = 0.2; + //params.ktau = 0.3; + //params.ktau_scale = 0.4; + params.viscousPos = 0.5; + params.viscousNeg = 0.6; + params.coulombPos = 0.7; + params.coulombNeg = 0.8; + b= itrq->setMotorTorqueParams(0, params); + CHECK(b); + + yarp::dev::MotorTorqueParameters res; + b= itrq->getMotorTorqueParams(0, &res); + CHECK(b); + //CHECK(res.bemf == 0.1); // interface seems functional + //CHECK(res.bemf_scale == 0.2); // interface seems functional + //CHECK(res.ktau == 0.3); // interface seems functional + //CHECK(res.ktau_scale == 0.4); // interface seems functional + CHECK(res.viscousPos == 0.5); // interface seems functional + CHECK(res.viscousNeg == 0.6); // interface seems functional + CHECK(res.coulombPos == 0.7); // interface seems functional + CHECK(res.coulombNeg == 0.8); // interface seems functional + } +} + +#endif diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index d8ea8dc62f4..349d2c5a8ff 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -5,8 +5,6 @@ add_executable(harness_dev) target_sources(harness_dev PRIVATE AnalogWrapperTest.cpp - ControlBoardRemapperTest.cpp - ControlBoardNwsTest.cpp MapGrid2DTest.cpp MultipleAnalogSensorsInterfacesTest.cpp PolyDriverTest.cpp @@ -15,7 +13,6 @@ target_sources(harness_dev frameGrabberCropperTest.cpp frameGrabber_nws_yarpTest.cpp grabberDualTest.cpp - TorqueControlTest.cpp ) target_link_libraries(harness_dev diff --git a/tests/libYARP_dev/ControlBoardNwsTest.cpp b/tests/libYARP_dev/ControlBoardNwsTest.cpp deleted file mode 100644 index 14e2b984508..00000000000 --- a/tests/libYARP_dev/ControlBoardNwsTest.cpp +++ /dev/null @@ -1,78 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include -#include -#include -#include - -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; - -TEST_CASE("dev::controlBoard_nws_yarp", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); - YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); - YARP_REQUIRE_PLUGIN("remote_controlboard", "device"); - - Network::setLocalMode(true); - - SECTION("test the controlBoard_nws_yarp device") - { - PolyDriver dd_nws; - Property p_nws; - p_nws.put("device", "controlBoard_nws_yarp"); - p_nws.put("name", "/motor"); - bool result_nws = dd_nws.open(p_nws); - REQUIRE(result_nws); - - PolyDriver dd_dev; - Property p_dev; - p_dev.put("device", "fakeMotionControl"); - auto& pg = p_dev.addGroup("GENERAL"); - pg.put("Joints", 16); - bool result_dev = dd_dev.open(p_dev); - REQUIRE(result_dev); - - yarp::dev::WrapperSingle* ww_nws; - dd_nws.view(ww_nws); - bool result_att = ww_nws->attach(&dd_dev); - REQUIRE(result_att); - - // Check if IMultipleWrapper interface is correctly found - yarp::dev::IMultipleWrapper * i_mwrapper=nullptr; - bool result_imw = dd_nws.view(i_mwrapper); - REQUIRE(result_imw); // IMultipleWrapper view reported successful - REQUIRE(i_mwrapper != nullptr); // IMultipleWrapper pointer not null - - PolyDriver dd2; - Property p2; - p2.put("device","remote_controlboard"); - p2.put("remote","/motor"); - p2.put("local","/motor/client"); - p2.put("carrier","tcp"); - p2.put("ignoreProtocolCheck","true"); - bool result = dd2.open(p2); - REQUIRE(result); // remote_controlboard open reported successful - - IPositionControl *pos = nullptr; - result = dd2.view(pos); - REQUIRE(result); // interface reported - int axes = 0; - pos->getAxes(&axes); - CHECK(axes == 16); // interface seems functional - CHECK(dd_nws.close()); // close dd reported successful - CHECK(dd_dev.close()); // close dd reported successful - CHECK(dd2.close()); // close dd2 reported successful - } -} diff --git a/tests/libYARP_dev/TorqueControlTest.cpp b/tests/libYARP_dev/TorqueControlTest.cpp deleted file mode 100644 index bfe75a9515a..00000000000 --- a/tests/libYARP_dev/TorqueControlTest.cpp +++ /dev/null @@ -1,93 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include -#include -#include - -#include - -#include -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; - -TEST_CASE("dev::TorqueControl", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("fakeMotionControl", "device"); - YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); - YARP_REQUIRE_PLUGIN("remote_controlboard", "device"); - - Network::setLocalMode(true); - - SECTION("test the controlBoard_nws_yarp device") - { - PolyDriver dd_nws; - Property p_nws; - p_nws.put("device","controlBoard_nws_yarp"); - p_nws.put("name", "/motor"); - bool result_nws = dd_nws.open(p_nws); - REQUIRE(result_nws); - - PolyDriver dd_dev; - Property p_dev; - p_dev.put("device", "fakeMotionControl"); - auto& pg = p_dev.addGroup("GENERAL"); - pg.put("Joints", 1); - bool result_dev = dd_dev.open(p_dev); - REQUIRE(result_dev); - - yarp::dev::WrapperSingle* ww_nws; - dd_nws.view(ww_nws); - bool result_att = ww_nws->attach(&dd_dev); - REQUIRE(result_att); // controlboard_nws_yarp open reported successful - - PolyDriver dd2; - Property p2; - p2.put("device","remote_controlboard"); - p2.put("remote","/motor"); - p2.put("local","/motor/client"); - p2.put("carrier","tcp"); - p2.put("ignoreProtocolCheck","true"); - bool result = dd2.open(p2); - REQUIRE(result); // remote_controlboard open reported successful - - ITorqueControl *trq = nullptr; - result = dd2.view(trq); - REQUIRE(result); // interface reported - - yarp::dev::MotorTorqueParameters params; - yarp::dev::MotorTorqueParameters res; - - //params.bemf = 0.1; - //params.bemf_scale = 0.2; - //params.ktau = 0.3; - //params.ktau_scale = 0.4; - params.viscousPos = 0.5; - params.viscousNeg = 0.6; - params.coulombPos = 0.7; - params.coulombNeg = 0.8; - - trq->setMotorTorqueParams(0, params); - trq->getMotorTorqueParams(0, &res); - - //CHECK(res.bemf == 0.1); // interface seems functional - //CHECK(res.bemf_scale == 0.2); // interface seems functional - //CHECK(res.ktau == 0.3); // interface seems functional - //CHECK(res.ktau_scale == 0.4); // interface seems functional - CHECK(res.viscousPos == 0.5); // interface seems functional - CHECK(res.viscousNeg == 0.6); // interface seems functional - CHECK(res.coulombPos == 0.7); // interface seems functional - CHECK(res.coulombNeg == 0.8); // interface seems functional - CHECK(dd_nws.close()); // close dd_nws reported successful - CHECK(dd_dev.close()); // close dd_dev reported successful - CHECK(dd2.close()); // close dd2 reported successful - } -} From 76f5f2c43bd392692c0eb331c878d9cf5d721103 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 25 Nov 2022 13:14:43 +0100 Subject: [PATCH 040/267] Removed test for `AnalogWrapper` device --- tests/libYARP_dev/AnalogWrapperTest.cpp | 138 ------------------------ tests/libYARP_dev/CMakeLists.txt | 1 - 2 files changed, 139 deletions(-) delete mode 100644 tests/libYARP_dev/AnalogWrapperTest.cpp diff --git a/tests/libYARP_dev/AnalogWrapperTest.cpp b/tests/libYARP_dev/AnalogWrapperTest.cpp deleted file mode 100644 index 5dbabf1a910..00000000000 --- a/tests/libYARP_dev/AnalogWrapperTest.cpp +++ /dev/null @@ -1,138 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; - - -TEST_CASE("dev::AnalogWrapperTest", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("fakeAnalogSensor", "device"); - YARP_REQUIRE_PLUGIN("analogServer", "device"); - - Network::setLocalMode(true); - - SECTION("Analogwrapper Test (test 1)") - { - // First test: Try to make it open a single port and I check its - // existence and of the relative rpc port - Property p; - p.put("device","analogServer"); - p.put("name","/testAnalogWrapper"); - p.put("period",20); - p.put("channels",10); - p.put("subdevice","fakeAnalogSensor"); - - PolyDriver dd; - REQUIRE(dd.open(p)); - - Network::sync("/testAnalogWrapper/rpc:i"); - Network::sync("/testAnalogWrapper"); - - CHECK(Network::exists("/testAnalogWrapper/rpc:i")); // /testAnalogWrapper/rpc:i port created succefully - CHECK(Network::exists("/testAnalogWrapper")); // /testAnalogWrapper port created succefully - CHECK(dd.close()); // close reported successful - } - - SECTION("Analogwrapper Test (test 2)") - { - // Second test: Try to open a device after opening the same port that it - // will open - BufferedPort portrpc; - CHECK(portrpc.open("/testAnalogWrapper/rpc:i")); // open reported successful - Network::sync("/testAnalogWrapper/rpc:i"); - - BufferedPort port; - CHECK(port.open("/testAnalogWrapper")); // open reported successful - Network::sync("/testAnalogWrapper"); - - Property p; - p.put("device","analogServer"); - p.put("name","/testAnalogWrapper"); - p.put("period",20); - p.put("channels",10); - p.put("subdevice","fakeAnalogSensor"); - - PolyDriver dd; - CHECK_FALSE(dd.open(p)); // Open of AnalogWrapper2 with one port open failed as expected (address conflict) - CHECK_FALSE(dd.isValid()); // isValid() of AnalogWrapper2 with one port failed as expected open (address conflict) - - portrpc.close(); - port.close(); - CHECK(dd.close()); // close reported successful - } - - SECTION("Analogwrapper Test (test 3)") - { - //Third test: The same of before but with multiple ports - Property p; - p.put("device","analogServer"); - p.put("name","/testAnalogWrapperMultip"); - p.put("period",20); - p.put("channels",3); - p.put("subdevice","fakeAnalogSensor"); - p.fromString("(ports (left_hand left_forearm left_arm)) (left_hand 0 0 0 0) (left_forearm 0 0 0 0) (left_arm 0 0 0 0)", false); - - PolyDriver dd; - REQUIRE(dd.open(p)); // Open of AnalogWrapper with multiple port open reported successful - - Network::sync("/testAnalogWrapperMultip/left_hand"); - Network::sync("/testAnalogWrapperMultip/left_hand/rpc:i"); - Network::sync("/testAnalogWrapperMultip/left_forearm"); - Network::sync("/testAnalogWrapperMultip/left_forearm/rpc:i"); - Network::sync("/testAnalogWrapperMultip/left_arm"); - Network::sync("/testAnalogWrapperMultip/left_arm/rpc:i"); - - CHECK(dd.isValid()); // isValid of AnalogWrapper with multiple port open reported successful - CHECK_FALSE(Network::exists("/rpc:i")); // /rpc:i has not been opened - CHECK_FALSE(Network::exists("/rpc:o")); // /rpc:o has not been opened - - CHECK(Network::exists("/testAnalogWrapperMultip/left_hand")); // /testAnalogWrapperMultip/left_hand port opened succesfully - CHECK(Network::exists("/testAnalogWrapperMultip/left_hand/rpc:i")); // /testAnalogWrapperMultip/left_hand/rpc:i port opened succesfully - CHECK(Network::exists("/testAnalogWrapperMultip/left_forearm")); // /testAnalogWrapperMultip/left_forearm port opened succesfully - CHECK(Network::exists("/testAnalogWrapperMultip/left_forearm/rpc:i"));// /testAnalogWrapperMultip/left_forearm/rpc:i port opened succesfully - CHECK(Network::exists("/testAnalogWrapperMultip/left_arm"));// /testAnalogWrapperMultip/left_arm port opened succesfully - CHECK(Network::exists("/testAnalogWrapperMultip/left_arm/rpc:i"));// /testAnalogWrapperMultip/left_arm/rpc:i port opened succesfully - - CHECK(dd.close()); // close reported successful - } - - - SECTION("Analogwrapper Test (test 4)") - { - //Fourth test: test for address confict with multiple ports - Property p; - p.put("device","analogServer"); - p.put("name","/testAnalogWrapperMultip"); - p.put("period",20); - p.put("channels",3); - p.put("subdevice","fakeAnalogSensor"); - p.fromString("(ports (left_hand left_forearm left_arm)) (left_hand 0 0 0 0) (left_forearm 0 0 0 0) (left_arm 0 0 0 0)", false); - - BufferedPort port; - port.open("/testAnalogWrapperMultip/left_hand"); - Network::sync("/testAnalogWrapperMultip/left_hand"); - - BufferedPort portrpc; - portrpc.open("/testAnalogWrapperMultip/left_forearm/rpc:i"); - Network::sync("/testAnalogWrapperMultip/left_forearm/rpc:i"); - - PolyDriver dd; - CHECK_FALSE(dd.open(p)); // Open of AnalogWrapper2 with multiple ports open failed as expected (address conflict) - CHECK_FALSE(dd.isValid()); // isValid() of AnalogWrapper2 with multiple ports failed as expected open (address conflict) - - portrpc.close(); - port.close(); - CHECK(dd.close()); // close reported successful - } - - Network::setLocalMode(false); -}; diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index 349d2c5a8ff..1122dd1ab3c 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -4,7 +4,6 @@ add_executable(harness_dev) target_sources(harness_dev PRIVATE - AnalogWrapperTest.cpp MapGrid2DTest.cpp MultipleAnalogSensorsInterfacesTest.cpp PolyDriverTest.cpp From a7d16ae7c3f5bcee2029984b2dc3dd2b2449ddc3 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 25 Nov 2022 15:02:15 +0100 Subject: [PATCH 041/267] added tests: fakeIMU, multipleanalogsensorsclient, multipleanalogsensorsserver --- src/devices/fakeIMU/CMakeLists.txt | 5 ++ src/devices/fakeIMU/tests/CMakeLists.txt | 41 +++++++++ src/devices/fakeIMU/tests/FakeImuTest.cpp | 47 ++++++++++ .../CMakeLists.txt | 5 ++ .../tests/CMakeLists.txt | 41 +++++++++ .../tests/MultipleAnalogSensorsClientTest.cpp | 63 ++----------- .../CMakeLists.txt | 5 ++ .../tests/CMakeLists.txt | 41 +++++++++ .../tests/MultipleAnalogSensorsServerTest.cpp | 89 +++++++++++++++++++ src/libYARP_dev/src/CMakeLists.txt | 2 + .../dev/tests/IOrientationSensorsTest.cpp | 6 ++ .../yarp/dev/tests/IOrientationSensorsTest.h | 43 +++++++++ tests/libYARP_dev/CMakeLists.txt | 1 - 13 files changed, 330 insertions(+), 59 deletions(-) create mode 100644 src/devices/fakeIMU/tests/CMakeLists.txt create mode 100644 src/devices/fakeIMU/tests/FakeImuTest.cpp create mode 100644 src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt rename tests/libYARP_dev/MultipleAnalogSensorsInterfacesTest.cpp => src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp (50%) create mode 100644 src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt create mode 100644 src/devices/multipleanalogsensorsserver/tests/MultipleAnalogSensorsServerTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.h diff --git a/src/devices/fakeIMU/CMakeLists.txt b/src/devices/fakeIMU/CMakeLists.txt index bb73bc4ff41..bd5727ec59b 100644 --- a/src/devices/fakeIMU/CMakeLists.txt +++ b/src/devices/fakeIMU/CMakeLists.txt @@ -45,4 +45,9 @@ if(NOT SKIP_fakeIMU) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeIMU PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeIMU/tests/CMakeLists.txt b/src/devices/fakeIMU/tests/CMakeLists.txt new file mode 100644 index 00000000000..7ba26b0df06 --- /dev/null +++ b/src/devices/fakeIMU/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeImu) + +target_sources(harness_dev_fakeImu + PRIVATE + FakeImuTest.cpp +) + +target_link_libraries(harness_dev_fakeImu + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_fakeImu PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeImu) diff --git a/src/devices/fakeIMU/tests/FakeImuTest.cpp b/src/devices/fakeIMU/tests/FakeImuTest.cpp new file mode 100644 index 00000000000..88a6021d463 --- /dev/null +++ b/src/devices/fakeIMU/tests/FakeImuTest.cpp @@ -0,0 +1,47 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +TEST_CASE("dev::fakeImu", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeImu", "device"); + + Network::setLocalMode(true); + + SECTION("Checking map2D_nws_yarp device") + { + PolyDriver ddmc; + yarp::dev::IOrientationSensors* iimu=nullptr; + + ////////"Checking opening map2DServer and map2DClient polydrivers" + { + Property p_cfg; + p_cfg.put("device", "fakeMotionControl"); + p_cfg.put("constantValue", 1); + REQUIRE(ddmc.open(p_cfg)); + } + + ddmc.view(iimu); + yarp::dev::tests::exec_IOrientationSensors_test_1(iimu); + + //"Close all polydrivers and check" + { + CHECK(ddmc.close()); + } + } + + Network::setLocalMode(false); +} diff --git a/src/devices/multipleanalogsensorsclient/CMakeLists.txt b/src/devices/multipleanalogsensorsclient/CMakeLists.txt index c3ffff41028..c5bc077202c 100644 --- a/src/devices/multipleanalogsensorsclient/CMakeLists.txt +++ b/src/devices/multipleanalogsensorsclient/CMakeLists.txt @@ -44,4 +44,9 @@ if(ENABLE_multipleanalogsensorsclient) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_multipleanalogsensorsclient PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt b/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt new file mode 100644 index 00000000000..96b22f15d2f --- /dev/null +++ b/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_multipleanalogsensorsclient) + +target_sources(harness_dev_multipleanalogsensorsclient + PRIVATE + MultipleAnalogSensorsClientTest.cpp +) + +target_link_libraries(harness_dev_multipleanalogsensorsclient + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_multipleanalogsensorsclient PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_multipleanalogsensorsclient) diff --git a/tests/libYARP_dev/MultipleAnalogSensorsInterfacesTest.cpp b/src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp similarity index 50% rename from tests/libYARP_dev/MultipleAnalogSensorsInterfacesTest.cpp rename to src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp index a94d8dde8a3..6bd6ef99737 100644 --- a/tests/libYARP_dev/MultipleAnalogSensorsInterfacesTest.cpp +++ b/src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp @@ -3,6 +3,7 @@ * SPDX-License-Identifier: BSD-3-Clause */ +#include #include #include @@ -27,9 +28,9 @@ TEST_CASE("dev::MultipleAnalogSensorsInterfacesTest", "[yarp::dev]") YARP_REQUIRE_PLUGIN("multipleanalogsensorsserver", "device"); YARP_REQUIRE_PLUGIN("multipleanalogsensorsclient", "device"); -#if defined(DISABLE_FAILING_TESTS) - YARP_SKIP_TEST("Skipping failing tests") -#endif +//#if defined(DISABLE_FAILING_TESTS) +// YARP_SKIP_TEST("Skipping failing tests") +//#endif Network::setLocalMode(true); @@ -81,25 +82,8 @@ TEST_CASE("dev::MultipleAnalogSensorsInterfacesTest", "[yarp::dev]") // Compare the readings of actual device and client device yarp::dev::IOrientationSensors* clientOrientSens; REQUIRE(client.view(clientOrientSens)); // IOrientationSensors of multipleanalogsensorsclient correctly opened - nrOfSensors = clientOrientSens->getNrOfOrientationSensors(); - CHECK(nrOfSensors == 1); // getNrOfOrientationSensors of multipleanalogsensorsclient works correctly - yarp::sig::Vector sensorMeasure(3, 0.0), clientMeasure(3, 0.0); - double timestamp{0.0}, clientTimestamp{0.0}; - - MAS_status status = clientOrientSens->getOrientationSensorStatus(0); - CHECK(status == MAS_status::MAS_OK); // multipleanalogsensorsclient getOrientationSensorStatus return value is MAS_OK - - bool result = orientSens->getOrientationSensorMeasureAsRollPitchYaw(0, sensorMeasure, timestamp); - bool resultClient = clientOrientSens->getOrientationSensorMeasureAsRollPitchYaw(0, clientMeasure, clientTimestamp); - - CHECK(result == resultClient); // getOrientationSensorMeasureAsRollPitchYaw return value is consistent between sensor and client - - for(int i=0; i < 3; i++) { - CHECK(sensorMeasure[i] == Approx(clientMeasure[i])); // getOrientationSensorMeasureAsRollPitchYaw measure is consistent between sensor and client - } - - CHECK(std::abs(timestamp-clientTimestamp) < 0.2); // getOrientationSensorMeasureAsRollPitchYaw measure is consistent between sensor and client (up to 200 ms) + yarp::dev::tests::exec_IOrientationSensors_test_1(clientOrientSens); // Close devices client.close(); @@ -108,42 +92,5 @@ TEST_CASE("dev::MultipleAnalogSensorsInterfacesTest", "[yarp::dev]") imuSensor.close(); } - SECTION("Test the multiple analog sensors device on a single IMU (wrapped subdevice)") - { - PolyDriver wrapper; - Property pWrapper; - pWrapper.put("device", "multipleanalogsensorsserver"); - pWrapper.put("subdevice", "fakeIMU"); // wrapped subdevice - std::string serverPrefix = "/test/mas/server"; - pWrapper.put("name", serverPrefix); - pWrapper.put("period", 10); - pWrapper.put("constantValue", 1); // subdevice-specific - REQUIRE(wrapper.open(pWrapper)); // multipleanalogsensorsserver open reported successful - - // Open the client - Property pClient; - pClient.put("device", "multipleanalogsensorsclient"); - pClient.put("remote", serverPrefix); - pClient.put("local", "/test/mas/client"); - // Increase timeout time because we don't know the load of the machine on which the test will run - pClient.put("timeout", 1.0); - - PolyDriver client; - REQUIRE(client.open(pClient)); // multipleanalogsensorsclient open reported successful - - // Let make sure that the data get read by the client - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - - // Check the readings of the client device - yarp::dev::IOrientationSensors* clientOrientSens; - REQUIRE(client.view(clientOrientSens)); // IOrientationSensors of multipleanalogsensorsclient correctly opened - int nrOfSensors = clientOrientSens->getNrOfOrientationSensors(); - CHECK(nrOfSensors == 1); // getNrOfOrientationSensors of multipleanalogsensorsclient works correctly - - // Close devices - client.close(); - wrapper.close(); - } - Network::setLocalMode(false); } diff --git a/src/devices/multipleanalogsensorsserver/CMakeLists.txt b/src/devices/multipleanalogsensorsserver/CMakeLists.txt index f55dddb3485..603eaecc86d 100644 --- a/src/devices/multipleanalogsensorsserver/CMakeLists.txt +++ b/src/devices/multipleanalogsensorsserver/CMakeLists.txt @@ -46,4 +46,9 @@ if(ENABLE_multipleanalogsensorsserver) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_multipleanalogsensorsserver PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt b/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt new file mode 100644 index 00000000000..62d5b6d5c1f --- /dev/null +++ b/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_multipleanalogsensorsserver) + +target_sources(harness_dev_multipleanalogsensorsserver + PRIVATE + MultipleAnalogSensorsServerTest.cpp +) + +target_link_libraries(harness_dev_multipleanalogsensorsserver + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_multipleanalogsensorsserver PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_multipleanalogsensorsserver) diff --git a/src/devices/multipleanalogsensorsserver/tests/MultipleAnalogSensorsServerTest.cpp b/src/devices/multipleanalogsensorsserver/tests/MultipleAnalogSensorsServerTest.cpp new file mode 100644 index 00000000000..6463a93eb2b --- /dev/null +++ b/src/devices/multipleanalogsensorsserver/tests/MultipleAnalogSensorsServerTest.cpp @@ -0,0 +1,89 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; + + +TEST_CASE("dev::MultipleAnalogSensorsServerTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeIMU", "device"); + YARP_REQUIRE_PLUGIN("multipleanalogsensorsserver", "device"); + +//#if defined(DISABLE_FAILING_TESTS) +// YARP_SKIP_TEST("Skipping failing tests") +//#endif + + Network::setLocalMode(true); + + SECTION("Test the nws alone") + { + PolyDriver wrapper; + + Property pWrapper; + pWrapper.put("device", "multipleanalogsensorsserver"); + std::string serverPrefix = "/test/mas/server"; + pWrapper.put("name", serverPrefix); + pWrapper.put("period", 10); + REQUIRE(wrapper.open(pWrapper)); // multipleanalogsensorsserver open reported successful + + // Close devices + wrapper.close(); + } + + SECTION("Test the multiple analog sensors device on a single IMU (deferred attach)") + { + // We first allocate a single fakeImu + PolyDriver imuSensor; + PolyDriver wrapper; + + Property p; + p.put("device", "fakeIMU"); + p.put("constantValue", 1); + + REQUIRE(imuSensor.open(p)); // sensor open reported successful + + yarp::dev::IOrientationSensors* orientSens; + REQUIRE(imuSensor.view(orientSens)); // IOrientationSensors of fakeIMU correctly opened + int nrOfSensors = orientSens->getNrOfOrientationSensors(); + CHECK(nrOfSensors == 1); // getNrOfOrientationSensors of fakeIMU works correctly + + Property pWrapper; + pWrapper.put("device", "multipleanalogsensorsserver"); + std::string serverPrefix = "/test/mas/server"; + pWrapper.put("name", serverPrefix); + pWrapper.put("period", 10); + REQUIRE(wrapper.open(pWrapper)); // multipleanalogsensorsserver open reported successful + + yarp::dev::IMultipleWrapper *iwrap = nullptr; + REQUIRE(wrapper.view(iwrap)); // IMultipleWrapper interface correctly opened for the multipleanalogsensorsserver + + PolyDriverList pdList; + pdList.push(&imuSensor, "pdlist_key"); + REQUIRE(iwrap->attachAll(pdList)); // multipleanalogsensorsserver attached successfully to the device + + // Close devices + iwrap->detachAll(); + wrapper.close(); + imuSensor.close(); + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index e42a7a5314d..d4e99d8dd6d 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -416,6 +416,8 @@ target_sources(YARP_dev_tests yarp/dev/tests/ITorqueControlTest.h yarp/dev/tests/IAxisInfoTest.cpp yarp/dev/tests/IAxisInfoTest.h + yarp/dev/tests/IOrientationSensorsTest.cpp + yarp/dev/tests/IOrientationSensorsTest.h ) else() target_sources(YARP_dev_tests diff --git a/src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.cpp new file mode 100644 index 00000000000..cc54f6fe5ee --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IOrientationSensorsTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.h b/src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.h new file mode 100644 index 00000000000..560d5a8f853 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IOrientationSensorsTest.h @@ -0,0 +1,43 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IORIENTATIONSENSOTSTEST_H +#define IORIENTATIONSENSOTSTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void exec_IOrientationSensors_test_1(IOrientationSensors* ios) + { + REQUIRE(ios != nullptr); + + int nrOfSensors = ios->getNrOfOrientationSensors(); + CHECK(nrOfSensors == 1); // getNrOfOrientationSensors of multipleanalogsensorsclient works correctly + + yarp::sig::Vector sensorMeasure(3, 0.0), clientMeasure(3, 0.0); + double timestamp{ 0.0 }, clientTimestamp{ 0.0 }; + + MAS_status status = ios->getOrientationSensorStatus(0); + CHECK(status == MAS_status::MAS_OK); // multipleanalogsensorsclient getOrientationSensorStatus return value is MAS_OK + + bool result = ios->getOrientationSensorMeasureAsRollPitchYaw(0, sensorMeasure, timestamp); + bool resultClient = ios->getOrientationSensorMeasureAsRollPitchYaw(0, clientMeasure, clientTimestamp); + + CHECK(result == resultClient); // getOrientationSensorMeasureAsRollPitchYaw return value is consistent between sensor and client + + for (int i = 0; i < 3; i++) { + CHECK(sensorMeasure[i] == Approx(clientMeasure[i])); // getOrientationSensorMeasureAsRollPitchYaw measure is consistent between sensor and client + } + + CHECK(std::abs(timestamp - clientTimestamp) < 0.2); // getOrientationSensorMeasureAsRollPitchYaw measure is consistent between sensor and client (up to 200 ms) + } +} + +#endif diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index 1122dd1ab3c..c4e8af8254e 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -5,7 +5,6 @@ add_executable(harness_dev) target_sources(harness_dev PRIVATE MapGrid2DTest.cpp - MultipleAnalogSensorsInterfacesTest.cpp PolyDriverTest.cpp robotDescriptionTest.cpp fakeFrameGrabberTest.cpp From c8421253538e8d78ba84429c13abb352f837ea3f Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 25 Nov 2022 15:37:29 +0100 Subject: [PATCH 042/267] Added new tests: robotDescriptionClient, robotDescriptionServer. The implementation is incomplete because it is not using the nws/nwc architecture. These devices will be probably refactored in the future. --- .../RobotDescriptionClient/CMakeLists.txt | 5 ++ .../tests/CMakeLists.txt | 41 ++++++++++ .../tests/robotDescriptionClientTest.cpp | 4 +- .../RobotDescriptionServer/CMakeLists.txt | 5 ++ .../tests/CMakeLists.txt | 41 ++++++++++ .../tests/robotDescriptionServerTest.cpp | 82 +++++++++++++++++++ tests/libYARP_dev/CMakeLists.txt | 1 - 7 files changed, 176 insertions(+), 3 deletions(-) create mode 100644 src/devices/RobotDescriptionClient/tests/CMakeLists.txt rename tests/libYARP_dev/robotDescriptionTest.cpp => src/devices/RobotDescriptionClient/tests/robotDescriptionClientTest.cpp (96%) create mode 100644 src/devices/RobotDescriptionServer/tests/CMakeLists.txt create mode 100644 src/devices/RobotDescriptionServer/tests/robotDescriptionServerTest.cpp diff --git a/src/devices/RobotDescriptionClient/CMakeLists.txt b/src/devices/RobotDescriptionClient/CMakeLists.txt index a8d498c0f5e..719970892b9 100644 --- a/src/devices/RobotDescriptionClient/CMakeLists.txt +++ b/src/devices/RobotDescriptionClient/CMakeLists.txt @@ -41,4 +41,9 @@ if(NOT SKIP_robotDescriptionClient) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_robotDescriptionClient PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/RobotDescriptionClient/tests/CMakeLists.txt b/src/devices/RobotDescriptionClient/tests/CMakeLists.txt new file mode 100644 index 00000000000..960783d133d --- /dev/null +++ b/src/devices/RobotDescriptionClient/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_robotDescriptionClient) + +target_sources(harness_dev_robotDescriptionClient + PRIVATE + robotDescriptionClientTest.cpp +) + +target_link_libraries(harness_dev_robotDescriptionClient + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_robotDescriptionClient PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_robotDescriptionClient) diff --git a/tests/libYARP_dev/robotDescriptionTest.cpp b/src/devices/RobotDescriptionClient/tests/robotDescriptionClientTest.cpp similarity index 96% rename from tests/libYARP_dev/robotDescriptionTest.cpp rename to src/devices/RobotDescriptionClient/tests/robotDescriptionClientTest.cpp index 8ce6acc218b..e9619b3d327 100644 --- a/tests/libYARP_dev/robotDescriptionTest.cpp +++ b/src/devices/RobotDescriptionClient/tests/robotDescriptionClientTest.cpp @@ -19,7 +19,7 @@ using namespace yarp::os; using namespace yarp::dev; -TEST_CASE("dev::robotDescriptionTest", "[yarp::dev]") +TEST_CASE("dev::robotDescriptionClientTest", "[yarp::dev]") { YARP_REQUIRE_PLUGIN("robotDescriptionServer", "device"); YARP_REQUIRE_PLUGIN("robotDescriptionClient", "device"); @@ -27,7 +27,7 @@ TEST_CASE("dev::robotDescriptionTest", "[yarp::dev]") Network::setLocalMode(true); - SECTION("Test the RobotDescription client/server") + SECTION("Test the robotDescriptionClient device") { PolyDriver ddserver; Property pserver_cfg; diff --git a/src/devices/RobotDescriptionServer/CMakeLists.txt b/src/devices/RobotDescriptionServer/CMakeLists.txt index 186a11a5ffa..7165bfa7055 100644 --- a/src/devices/RobotDescriptionServer/CMakeLists.txt +++ b/src/devices/RobotDescriptionServer/CMakeLists.txt @@ -41,4 +41,9 @@ if(NOT SKIP_robotDescriptionServer) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_robotDescriptionServer PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/RobotDescriptionServer/tests/CMakeLists.txt b/src/devices/RobotDescriptionServer/tests/CMakeLists.txt new file mode 100644 index 00000000000..25d1faa9c5f --- /dev/null +++ b/src/devices/RobotDescriptionServer/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_robotDescriptionServer) + +target_sources(harness_dev_robotDescriptionServer + PRIVATE + robotDescriptionServerTest.cpp +) + +target_link_libraries(harness_dev_robotDescriptionServer + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_robotDescriptionServer PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_robotDescriptionServer) diff --git a/src/devices/RobotDescriptionServer/tests/robotDescriptionServerTest.cpp b/src/devices/RobotDescriptionServer/tests/robotDescriptionServerTest.cpp new file mode 100644 index 00000000000..78750ac1a6d --- /dev/null +++ b/src/devices/RobotDescriptionServer/tests/robotDescriptionServerTest.cpp @@ -0,0 +1,82 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + + +#include + +#include +#include +#include + +#include +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; + +TEST_CASE("dev::robotDescriptionServerTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("robotDescriptionServer", "device"); + YARP_REQUIRE_PLUGIN("robotDescriptionClient", "device"); + YARP_REQUIRE_PLUGIN("controlBoard_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Test the RobotDescriptionServer device") + { + PolyDriver ddserver; + Property pserver_cfg; + pserver_cfg.put("device", "robotDescriptionServer"); + pserver_cfg.put("local", "/robotDescriptionServerPort"); + REQUIRE(ddserver.open(pserver_cfg)); // robotDescriptionServer open reported successful + + IRobotDescription* idesc = nullptr; + PolyDriver ddclient; + Property pclient_cfg; + pclient_cfg.put("device", "robotDescriptionClient"); + pclient_cfg.put("local", "/robotDescriptionClientPort"); + pclient_cfg.put("remote", "/robotDescriptionServerPort"); + REQUIRE(ddclient.open(pclient_cfg)); // robotDescriptionClient open reported successful + + REQUIRE(ddclient.view(idesc)); // IRobotDescription interface open reported successful + + DeviceDescription dev1; dev1.device_name = "/icubTest/left_arm"; dev1.device_type = "controlBoard_nws_yarp"; + DeviceDescription dev2; dev2.device_name = "/icubTest/left_leg"; dev2.device_type = "controlBoard_nws_yarp"; + DeviceDescription dev3; dev3.device_name = "/icubTest/test"; dev3.device_type = "testDevice"; + idesc->registerDevice(dev1); + idesc->registerDevice(dev2); + idesc->registerDevice(dev3); + std::vector list1; + std::vector list2; + + idesc->getAllDevices(list1); + CHECK(list1.size() == 3); + CHECK(std::find(list1.begin(), list1.end(), dev1) != list1.end()); + CHECK(std::find(list1.begin(), list1.end(), dev2) != list1.end()); + CHECK(std::find(list1.begin(), list1.end(), dev3) != list1.end()); + // IRobotDescription::getAllDevices() successfully tested + + idesc->getAllDevicesByType("controlBoard_nws_yarp", list2); + CHECK(list2.size() == 2); + CHECK(std::find(list2.begin(), list2.end(), dev1) != list2.end()); + CHECK(std::find(list2.begin(), list2.end(), dev2) != list2.end()); + CHECK_FALSE(std::find(list2.begin(), list2.end(), dev3) != list2.end()); + // IRobotDescription::getControlBoardWrapperDevices() successfully tested + + // Test unregister device + idesc->unregisterDevice("/icubTest/test"); + idesc->getAllDevicesByType("testDevice", list2); + CHECK(list2.size() == 0); // IRobotDescription::unregisterDevice() successfully tested + + // Close devices + CHECK(ddclient.close()); // robotDescriptionClient successfully closed + CHECK(ddserver.close()); // robotDescriptionServer successfully closed + } + + Network::setLocalMode(false); +} diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index c4e8af8254e..e1580e74a0b 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -6,7 +6,6 @@ target_sources(harness_dev PRIVATE MapGrid2DTest.cpp PolyDriverTest.cpp - robotDescriptionTest.cpp fakeFrameGrabberTest.cpp frameGrabberCropperTest.cpp frameGrabber_nws_yarpTest.cpp From 4b9bf655f05b2210b08d5c42701a6450eaf1aff8 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 1 Aug 2022 11:05:35 +0200 Subject: [PATCH 043/267] added new device FakeLaserWithMotor --- src/devices/CMakeLists.txt | 1 + src/devices/fakeLaserWithMotor/CMakeLists.txt | 47 ++ .../fakeLaserWithMotor/fakeLaserWithMotor.cpp | 482 +++++++++++++ .../fakeLaserWithMotor/fakeLaserWithMotor.h | 252 +++++++ .../fakeLaserWithMotor_motors.cpp | 642 ++++++++++++++++++ .../fakeLaserWithMotor_utils.cpp | 281 ++++++++ .../robotinterface_xml/ros.xml | 41 ++ .../robotinterface_xml/yarp.xml | 39 ++ 8 files changed, 1785 insertions(+) create mode 100644 src/devices/fakeLaserWithMotor/CMakeLists.txt create mode 100644 src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp create mode 100644 src/devices/fakeLaserWithMotor/fakeLaserWithMotor.h create mode 100644 src/devices/fakeLaserWithMotor/fakeLaserWithMotor_motors.cpp create mode 100644 src/devices/fakeLaserWithMotor/fakeLaserWithMotor_utils.cpp create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/ros.xml create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/yarp.xml diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index 62d52af3e59..b0784e65803 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -47,6 +47,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(IOdometry2DMsgs) add_subdirectory(DynamixelAX12Ftdi) add_subdirectory(fakeLaser) + add_subdirectory(fakeLaserWithMotor) add_subdirectory(fakeMicrophone) add_subdirectory(fakeSpeaker) add_subdirectory(laserFromDepth) diff --git a/src/devices/fakeLaserWithMotor/CMakeLists.txt b/src/devices/fakeLaserWithMotor/CMakeLists.txt new file mode 100644 index 00000000000..a9d6bd7b4e2 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/CMakeLists.txt @@ -0,0 +1,47 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +yarp_prepare_plugin(fakeLaserWithMotor + CATEGORY device + TYPE FakeLaserWithMotor + INCLUDE fakeLaserWithMotor.h + DEPENDS "TARGET YARP::YARP_math") + +if(NOT SKIP_fakeLaserWithMotor) + yarp_add_plugin(yarp_fakeLaserWithMotor) + + target_sources(yarp_fakeLaserWithMotor + PRIVATE + fakeLaserWithMotor.h + fakeLaserWithMotor.cpp + fakeLaserWithMotor_motors.cpp + fakeLaserWithMotor_utils.cpp + ) + + target_link_libraries(yarp_fakeLaserWithMotor + PRIVATE + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_math + ) + list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS + YARP_os + YARP_sig + YARP_dev + YARP_math + ) + + yarp_install( + TARGETS yarp_fakeLaserWithMotor + EXPORT YARP_${YARP_PLUGIN_MASTER} + COMPONENT ${YARP_PLUGIN_MASTER} + LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} + ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} + YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} + ) + + set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) + + set_property(TARGET yarp_fakeLaserWithMotor PROPERTY FOLDER "Plugins/Device/Fake") +endif() diff --git a/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp new file mode 100644 index 00000000000..32be820673d --- /dev/null +++ b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp @@ -0,0 +1,482 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#define _USE_MATH_DEFINES + +#include "fakeLaserWithMotor.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//#define LASER_DEBUG +#ifndef DEG2RAD +#define DEG2RAD M_PI/180.0 +#endif + +YARP_LOG_COMPONENT(FAKE_LASER, "yarp.devices.fakeLaserWithMotor") + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; + +// see FakeLaser.h for device documentation + +bool FakeLaserWithMotor::open(yarp::os::Searchable& config) +{ + m_info = "Fake Laser device for test/debugging"; + m_device_status = DEVICE_OK_STANBY; + +#ifdef LASER_DEBUG + yCDebug(FAKE_LASER) << "%s\n", config.toString().c_str()); +#endif + + if (config.check("help")) + { + yCInfo(FAKE_LASER,"Some examples:"); + yCInfo(FAKE_LASER,"yarpdev --device fakeLaser --help"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test no_obstacles"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_pattern"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5 --SENSOR::resolution 0.5 --SKIP::min 0 50 --SKIP::max 10 60"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_server /localizationServer"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localizationServer"); + yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_context context --map_file mymap.map"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localization2D_nws_yarp --localization_device localization2D_nwc_yarp"); + return false; + } + + bool br = config.check("GENERAL"); + if (br != false) + { + yarp::os::Searchable& general_config = config.findGroup("GENERAL"); + m_period = general_config.check("period", Value(0.02), "Period of the sampling thread in s").asFloat64(); + this->setPeriod(m_period); + } + + std::string string_test_mode = config.check("test", Value(std::string("use_pattern")), "string to select test mode").asString(); + if (string_test_mode == "no_obstacles") { m_test_mode = NO_OBSTACLES; } + else if (string_test_mode == "use_pattern") { m_test_mode = USE_PATTERN; } + else if (string_test_mode == "use_mapfile") { m_test_mode = USE_MAPFILE; } + else if (string_test_mode == "use_constant") { m_test_mode = USE_CONSTANT_VALUE; } + else if (string_test_mode == "use_square_trap") { m_test_mode = USE_SQUARE_TRAP; } + else { yCError(FAKE_LASER) << "invalid/unknown value for param 'test'"; return false; } + + //parse all the parameters related to the linear/angular range of the sensor + if (this->parseConfiguration(config) == false) + { + yCError(FAKE_LASER) << ": error parsing parameters"; + return false; + } + + //the different fake laser modalities + else if (m_test_mode == USE_CONSTANT_VALUE) + { + if (config.check("const_distance")) + { + m_const_value = config.check("const_distance", Value(1.0), "default constant distance").asFloat64(); + } + } + else if (m_test_mode == USE_SQUARE_TRAP) + { + m_robot_loc_x = 0; + m_robot_loc_y = 0; + m_robot_loc_t = 0; + m_map.m_map_name = "test_map_10x10m"; + m_map.m_resolution = 0.01; //m/pixel + m_map.m_origin.setOrigin(-5,-5,0); //m + m_map.setSize_in_meters(10,10); + for (size_t y = 0; y < m_map.m_height; y++) + { + for (size_t x = 0; x < m_map.m_width; x++) + { + m_map.setOccupancyData(yarp::dev::Nav2D::XYCell(x, y),0); + m_map.setMapFlag(yarp::dev::Nav2D::XYCell(x, y), MapGrid2D::map_flags::MAP_CELL_FREE); + } + } + m_originally_loaded_map = m_map; + trap_the_robot(3); //3m + MapGrid2D::map_flags vv; + m_map.saveToFile("mio1"); + } + else if (m_test_mode == USE_MAPFILE) + { + std::string map_file; + if (config.check("map_context") && config.check("map_file")) + { + yarp::os::ResourceFinder rf; + std::string tmp_filename = config.find("map_file").asString(); + std::string tmp_contextname = config.find("map_context").asString(); + rf.setDefaultContext(tmp_contextname); + rf.setDefaultConfigFile(tmp_filename); + bool b = rf.configure(0, nullptr); + if (b) + { + map_file = rf.findFile(tmp_filename); + if (map_file == "") + { + yCWarning(FAKE_LASER, "Unable to find file: %s from context: %s\n", tmp_filename.c_str(), tmp_contextname.c_str()); + } + } + else + { + yCWarning(FAKE_LASER, "Unable to find file: %s from context: %s\n", tmp_filename.c_str(), tmp_contextname.c_str()); + } + } + else if (config.check("map_file")) + { + map_file = config.check("map_file", Value(std::string("map.yaml")), "map filename").asString(); + } + else + { + yCError(FAKE_LASER) << "Missing `map_file` or `map_context`+`map_file` parameters"; + return false; + } + + if (map_file=="") + { + yCError(FAKE_LASER) << "File not found"; + return false; + } + bool ret = m_originally_loaded_map.loadFromFile(map_file); + if (ret == false) + { + yCError(FAKE_LASER) << "A problem occurred while opening:" << map_file; + return false; + } + m_map = m_originally_loaded_map; + m_robot_loc_x=0; + m_robot_loc_y=0; + m_robot_loc_t=0; + } + + yCInfo(FAKE_LASER) << "Starting debug mode"; + yCInfo(FAKE_LASER) << "test mode:"<< m_test_mode << " i.e. " << string_test_mode; + + // INIT ALL INTERFACES + std::vector tmpZeros; tmpZeros.resize(m_njoints, 0.0); + std::vector tmpOnes; tmpOnes.resize(m_njoints, 1.0); + std::vector axisMap; axisMap.resize(m_njoints, 1.0); + axisMap[0] = 0; + axisMap[1] = 1; + axisMap[2] = 2; + ImplementEncodersTimed::initialize(m_njoints, axisMap.data(), tmpOnes.data(), nullptr); + ImplementPositionControl::initialize(m_njoints, axisMap.data(), tmpOnes.data(), nullptr); + ImplementControlMode::initialize(m_njoints, axisMap.data()); + ImplementVelocityControl::initialize(m_njoints, axisMap.data(), tmpOnes.data(), nullptr); + ImplementInteractionMode::initialize(m_njoints, axisMap.data(), tmpOnes.data(), nullptr); + ImplementAxisInfo::initialize(m_njoints, axisMap.data()); + if (!alloc(m_njoints)) + { + yCError(FAKE_LASER) << "Malloc failed"; + return false; + } + _jointType[0] = VOCAB_JOINTTYPE_PRISMATIC; + _jointType[1] = VOCAB_JOINTTYPE_PRISMATIC; + _jointType[2] = VOCAB_JOINTTYPE_REVOLUTE; + _axisName[0] = "joint_x"; + _axisName[1] = "joint_y"; + _axisName[2] = "joint_t"; + _controlModes[0] = VOCAB_CM_IDLE; + _controlModes[1] = VOCAB_CM_IDLE; + _controlModes[2] = VOCAB_CM_IDLE; + + if (!m_rpcPort.open("/fakeLaser/rpc:i")) + { + yCError(FAKE_LASER, "Failed to open port %s", "/fakeLaser/rpc:i"); + return false; + } + m_rpcPort.setReader(*this); + + return PeriodicThread::start(); +} + +bool FakeLaserWithMotor::close() +{ + PeriodicThread::stop(); + + driver.close(); + + return true; +} + +bool FakeLaserWithMotor::setDistanceRange(double min, double max) +{ + m_mutex.lock(); + m_min_distance = min; + m_max_distance = max; + m_mutex.unlock(); + return true; +} + +bool FakeLaserWithMotor::setScanLimits(double min, double max) +{ + m_mutex.lock(); + m_min_angle = min; + m_max_angle = max; + m_mutex.unlock(); + return true; +} + +bool FakeLaserWithMotor::setHorizontalResolution(double step) +{ + m_mutex.lock(); + m_resolution = step; + m_mutex.unlock(); + return true; +} + +bool FakeLaserWithMotor::setScanRate(double rate) +{ + m_mutex.lock(); + m_period = (1.0 / rate); + m_mutex.unlock(); + return false; +} + +bool FakeLaserWithMotor::threadInit() +{ +#ifdef LASER_DEBUG + yCDebug(FAKE_LASER)<<"thread initialising...\n"); + yCDebug(FAKE_LASER)<<"... done!\n"); +#endif + + return true; +} + +bool FakeLaserWithMotor::acquireDataFromHW() +{ + m_laser_data.clear(); + double t = yarp::os::Time::now(); + static double t_orig = yarp::os::Time::now(); + double size = (t - (t_orig)); + + static int test_count = 0; + static int test = 0; + + if (m_test_mode == USE_PATTERN) + { + for (size_t i = 0; i < m_sensorsNum; i++) + { + double value = 0; + if (test == 0) + { + value = i / 100.0; + } + else if (test == 1) + { + value = size * 2; + } + else if (test == 2) + { + if (i <= 10) { value = 1.0 + i / 20.0; } + else if (i >= 90 && i <= 100) { value = 2.0 + (i - 90) / 20.0; } + else { value = m_min_distance; } + } + m_laser_data.push_back(value); + } + + test_count++; + if (test_count == 60) + { + test_count = 0; test++; if (test > 2) { test = 0; } + t_orig = yarp::os::Time::now(); + } + } + else if (m_test_mode == NO_OBSTACLES) + { + for (size_t i = 0; i < m_sensorsNum; i++) + { + m_laser_data.push_back(std::numeric_limits::infinity()); + } + } + else if (m_test_mode == USE_CONSTANT_VALUE) + { + for (size_t i = 0; i < m_sensorsNum; i++) + { + m_laser_data.push_back(m_const_value); + } + } + else if (m_test_mode == USE_MAPFILE || + m_test_mode == USE_SQUARE_TRAP) + { + m_robot_loc_x = _encoders[0];//loc.x; + m_robot_loc_y = _encoders[1];//loc.y; + m_robot_loc_t = _encoders[2];//loc.theta; + + for (size_t i = 0; i < m_sensorsNum; i++) + { + //compute the ray in the robot reference frame + double ray_angle = i * m_resolution + m_min_angle; + double ray_target_x = m_max_distance * cos(ray_angle * DEG2RAD); + double ray_target_y = m_max_distance * sin(ray_angle * DEG2RAD); + + //transforms the ray from the robot to the world reference frame + XYWorld ray_world; + ray_world.x = ray_target_x * cos(m_robot_loc_t * DEG2RAD) - ray_target_y * sin(m_robot_loc_t * DEG2RAD) + m_robot_loc_x; + ray_world.y = ray_target_x * sin(m_robot_loc_t * DEG2RAD) + ray_target_y * cos(m_robot_loc_t * DEG2RAD) + m_robot_loc_y; + XYCell src = m_map.world2Cell(XYWorld(m_robot_loc_x, m_robot_loc_y)); + + //beware! src is the robot position and it is always inside the image. + //dst is the end of the ray, and it can be out of the image! + //for this reason i am not going to call world2Cell() on dst, because that functions clips the point to the border without + //knowing the angular coefficient of the ray. I thus need the unclipped value, and run the LiangBarsky algorithm + //(which knows the angular coefficient of the ray) on it. + XYWorld ray_world_rot; + XYCell_unbounded dst; + ray_world_rot.x = ray_world.x * m_map.m_origin.get_ca() - ray_world.y * m_map.m_origin.get_sa(); + ray_world_rot.y = ray_world.x * m_map.m_origin.get_sa() + ray_world.y * m_map.m_origin.get_ca(); + dst.x = int((+ray_world_rot.x - this->m_map.m_origin.get_x()) / this->m_map.m_resolution) + 0; + dst.y = int((-ray_world_rot.y + this->m_map.m_origin.get_y()) / this->m_map.m_resolution) + (int)m_map.m_height - 1; + + XYCell newsrc; + XYCell newdst; + double distance; + if (LiangBarsky_clip(0, (int)m_map.width(), 0, (int)m_map.height(), + XYCell_unbounded(src.x, src.y), dst, newsrc, newdst)) + { + distance = checkStraightLine(src, newdst); + double simulated_noise = (*m_dis)(*m_gen); + m_laser_data.push_back(distance + simulated_noise); + } + else + { + //This should never happen, unless the robot is outside the map! + yDebug() << "Robot is outside the map?!"; + m_laser_data.push_back(std::numeric_limits::infinity()); + } + + } + } + + //set the device status + m_device_status = yarp::dev::IRangefinder2D::DEVICE_OK_IN_USE; + + return true; +} + +void FakeLaserWithMotor::run() +{ + for (size_t i=0; ib) + { + _posCtrl_references[i] = _posCtrl_references[i] + _command_speeds[i] / m_period * 1000; + if (b > a) _posCtrl_references[i] =a; + } + else if (b a) _posCtrl_references[i] = a; + } +*/ + } + } + m_mutex.lock(); + updateLidarData(); + m_mutex.unlock(); + return; +} + +bool FakeLaserWithMotor::read(yarp::os::ConnectionReader& connection) +{ + yarp::os::Bottle command; + yarp::os::Bottle reply; + bool ok = command.read(connection); + if (!ok) { + return false; + } + reply.clear(); + + if (command.get(0).asString() == "trap") + { + if (command.size() == 1) + { + trap_the_robot(); + reply.addVocab32(VOCAB_OK); + } + else if (command.size() == 2) + { + trap_the_robot(command.get(1).asFloat64()); + reply.addVocab32(VOCAB_OK); + } + else + { + reply.addVocab32(VOCAB_ERR); + } + } + else if (command.get(0).asString() == "wall") + { + if (command.size() == 1) + { + wall_the_robot(1.0, 1.0); + wall_the_robot(1.0, 1.05); + reply.addVocab32(VOCAB_OK); + } + else if (command.size() == 2) + { + wall_the_robot(command.get(1).asFloat64(), 1.0); + wall_the_robot(command.get(1).asFloat64(), 1.05); + reply.addVocab32(VOCAB_OK); + } + else if (command.size() == 3) + { + wall_the_robot(command.get(1).asFloat64(), command.get(2).asFloat64()); + wall_the_robot(command.get(1).asFloat64(), command.get(2).asFloat64()+0.05); + reply.addVocab32(VOCAB_OK); + } + else + { + reply.addVocab32(VOCAB_ERR); + } + } + else if (command.get(0).asString() == "free") + { + free_the_robot(); + reply.addVocab32(VOCAB_OK); + } + else if (command.get(0).asString() == "help") + { + reply.addVocab32("many"); + reply.addString("wall : creates a wall in front of the robot"); + reply.addString("trap : traps the robot in a box obstacle"); + reply.addString("free: removes all generated obstacles"); + } + else + { + yCError(FAKE_LASER) << "Invalid command"; + reply.addVocab32(VOCAB_ERR); + } + + yarp::os::ConnectionWriter* returnToSender = connection.getWriter(); + if (returnToSender != nullptr) + { + reply.write(*returnToSender); + } + return true; +} + +void FakeLaserWithMotor::threadRelease() +{ +#ifdef LASER_DEBUG + yCDebug(FAKE_LASER) << "FakeLaser Thread releasing..."); + yCDebug(FAKE_LASER) << "... done."); +#endif +} diff --git a/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.h b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.h new file mode 100644 index 00000000000..7ee8c2a5b33 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.h @@ -0,0 +1,252 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef FAKE_LASER_WITH_MOTOR_H +#define FAKE_LASER_WITH_MOTOR_H + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +/** +* @ingroup dev_impl_fake dev_impl_lidar +* +* @brief `fakeLaserWithMotor` : fake sensor device driver for testing purposes and reference for IRangefinder2D devices. +* +* | YARP device name | +* |:-----------------:| +* | `fakeLaserWithMotor` | +* +* \section fakeLaser_device_parameters Description of input parameters +* +* Parameters accepted in the config argument of the open method: +* | Parameter name | Type | Units | Default Value | Required | Description | Notes | +* |:-------------------:|:------:|:-----:|:-------------:|:--------:|:-----------:|:-----:| +* | test | string | - | - | Yes | Choose the modality | It can be one of the following: no_obstacles, use_pattern, use_mapfile | +* | map_file | string | - | - | No | Full path to a .map file | Mandatory if --test use_mapfile option has been set | +* | clip_max | double | m | 3.5 | No | Maximum detectable distance for an obstacle | - | +* | clip_min | double | m | 0.1 | No | Minimum detectable distance for an obstacle | - | +* | max_angle | double | deg | 360 | No | Angular range of the sensor | - | +* | min_angle | double | deg | 0 | No | Angular range of the sensor | - | +* | resolution | double | deg | 1.0 | No | Device resolution | - | +* +* \section Usage examples: +* yarpdev --device fakeLaser --help +* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test no_obstacles +* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_pattern +* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map +* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map +* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map +*/ + +class FakeLaserWithMotor : public yarp::os::PeriodicThread, + public yarp::dev::Lidar2DDeviceBase, + public yarp::dev::DeviceDriver, + public yarp::os::PortReader, + public yarp::dev::IEncodersTimedRaw, + public yarp::dev::IPositionControlRaw, + public yarp::dev::IVelocityControlRaw, + public yarp::dev::IControlModeRaw, + public yarp::dev::IAxisInfoRaw, + // public yarp::dev::StubImplTorqueControlRaw, + public yarp::dev::StubImplInteractionModeRaw, + public yarp::dev::ImplementPositionControl, + public yarp::dev::ImplementVelocityControl, + public yarp::dev::ImplementControlMode, + public yarp::dev::ImplementInteractionMode, + public yarp::dev::ImplementEncodersTimed, + public yarp::dev::ImplementAxisInfo +{ +protected: + enum test_mode_t { NO_OBSTACLES = 0, USE_PATTERN =1, USE_MAPFILE =2, USE_CONSTANT_VALUE =3, USE_SQUARE_TRAP }; + + yarp::dev::PolyDriver driver; + test_mode_t m_test_mode; + + double m_period; + yarp::dev::Nav2D::MapGrid2D m_originally_loaded_map; + yarp::dev::Nav2D::MapGrid2D m_map; + + //motor stuff + size_t m_njoints=3; + + //this is the position of the localized robot in the map + double m_robot_loc_x=0; + double m_robot_loc_y=0; + double m_robot_loc_t=0; + + std::random_device* m_rd; + std::mt19937* m_gen; + std::uniform_real_distribution<>* m_dis; + double m_const_value=1; + + yarp::os::Port m_rpcPort; + +public: + FakeLaserWithMotor(double period = 0.02) : PeriodicThread(period), + m_period(period), + m_test_mode(test_mode_t::NO_OBSTACLES), + ImplementPositionControl(this), + ImplementVelocityControl(this), + ImplementEncodersTimed(this), + ImplementControlMode(this), + ImplementInteractionMode(this), + ImplementAxisInfo(this) + { + //default parameters + m_min_distance = 0.1; //m + m_max_distance = 8.0; //m + m_min_angle = 0; //degrees + m_max_angle = 360; //degrees + m_resolution = 1.0; //degrees + + //noise generator + m_rd = new std::random_device; + m_gen = new std::mt19937((*m_rd)()); + m_dis = new std::uniform_real_distribution<>(0, 0.01); + } + + ~FakeLaserWithMotor() + { + delete m_rd; + delete m_gen; + delete m_dis; + m_rd = 0; + m_gen = 0; + m_dis = 0; + } + + bool open(yarp::os::Searchable& config) override; + bool close() override; + bool threadInit() override; + void threadRelease() override; + void run() override; + +private: + void drawStraightLine(yarp::dev::Nav2D::XYCell src, yarp::dev::Nav2D::XYCell dst); + void wall_the_robot(double siz = 1.0, double dist = 1.0); + void obst_the_robot(double siz = 1.0, double dist = 1.0); + void trap_the_robot(double siz = 1.0); + void free_the_robot(); + + double checkStraightLine(yarp::dev::Nav2D::XYCell src, yarp::dev::Nav2D::XYCell dst); + bool LiangBarsky_clip(int edgeLeft, int edgeRight, int edgeTop, int edgeBottom, + yarp::dev::Nav2D::XYCell_unbounded src, yarp::dev::Nav2D::XYCell_unbounded dst, + yarp::dev::Nav2D::XYCell& src_clipped, yarp::dev::Nav2D::XYCell& dst_clipped); + +public: + //IRangefinder2D interface + bool setDistanceRange (double min, double max) override; + bool setScanLimits (double min, double max) override; + bool setHorizontalResolution (double step) override; + bool setScanRate (double rate) override; + +public: + // internal stuff + std::string* _axisName = nullptr; // axis name + yarp::dev::JointTypeEnum* _jointType = nullptr; // axis type + int* _controlModes = nullptr; + double* _encoders = nullptr; // encoders + double* _posCtrl_references = nullptr; // used for position control. + double* _ref_speeds = nullptr; // used for position control. + double* _command_speeds = nullptr; // used for velocity control. + double* _ref_accs = nullptr; // used for velocity control. + + bool alloc(int njoints); + bool dealloc(); + +public: + //motor interfaces + bool resetEncoderRaw(int j) override; + bool resetEncodersRaw() override; + bool setEncoderRaw(int j, double val) override; + bool setEncodersRaw(const double* vals) override; + bool getEncoderRaw(int j, double* v) override; + bool getEncodersRaw(double* encs) override; + bool getEncoderSpeedRaw(int j, double* sp) override; + bool getEncoderSpeedsRaw(double* spds) override; + bool getEncoderAccelerationRaw(int j, double* spds) override; + bool getEncoderAccelerationsRaw(double* accs) override; + + bool getEncodersTimedRaw(double* encs, double* stamps) override; + bool getEncoderTimedRaw(int j, double* encs, double* stamp) override; + + // POSITION CONTROL INTERFACE RAW + bool getAxes(int* ax) override; + bool positionMoveRaw(int j, double ref) override; + bool positionMoveRaw(const double* refs) override; + bool relativeMoveRaw(int j, double delta) override; + bool relativeMoveRaw(const double* deltas) override; + bool checkMotionDoneRaw(bool* flag) override; + bool checkMotionDoneRaw(int j, bool* flag) override; + bool setRefSpeedRaw(int j, double sp) override; + bool setRefSpeedsRaw(const double* spds) override; + bool setRefAccelerationRaw(int j, double acc) override; + bool setRefAccelerationsRaw(const double* accs) override; + bool getRefSpeedRaw(int j, double* ref) override; + bool getRefSpeedsRaw(double* spds) override; + bool getRefAccelerationRaw(int j, double* acc) override; + bool getRefAccelerationsRaw(double* accs) override; + bool stopRaw(int j) override; + bool stopRaw() override; + + bool positionMoveRaw(const int n_joint, const int* joints, const double* refs) override; + bool relativeMoveRaw(const int n_joint, const int* joints, const double* deltas) override; + bool checkMotionDoneRaw(const int n_joint, const int* joints, bool* flags) override; + bool setRefSpeedsRaw(const int n_joint, const int* joints, const double* spds) override; + bool setRefAccelerationsRaw(const int n_joint, const int* joints, const double* accs) override; + bool getRefSpeedsRaw(const int n_joint, const int* joints, double* spds) override; + bool getRefAccelerationsRaw(const int n_joint, const int* joints, double* accs) override; + bool stopRaw(const int n_joint, const int* joints) override; + bool getTargetPositionRaw(const int joint, double* ref) override; + bool getTargetPositionsRaw(double* refs) override; + bool getTargetPositionsRaw(const int n_joint, const int* joints, double* refs) override; + + //IControlMode + bool getControlModeRaw(int j, int* v) override; + bool getControlModesRaw(int* v) override; + bool getControlModesRaw(const int n_joint, const int* joints, int* modes) override; + bool setControlModeRaw(const int j, const int mode) override; + bool setControlModesRaw(const int n_joint, const int* joints, int* modes) override; + bool setControlModesRaw(int* modes) override; + + //IVelocityControl + bool velocityMoveRaw(int j, double sp) override; + bool velocityMoveRaw(const double* sp) override; + bool velocityMoveRaw(const int n_joint, const int* joints, const double* spds) override; + bool getRefVelocityRaw(const int joint, double* ref) override; + bool getRefVelocitiesRaw(double* refs) override; + bool getRefVelocitiesRaw(const int n_joint, const int* joints, double* refs) override; + + bool getAxisNameRaw(int axis, std::string& name) override; + bool getJointTypeRaw(int axis, yarp::dev::JointTypeEnum& type) override; +public: + //Lidar2DDeviceBase + bool acquireDataFromHW() override final; + +public: + bool read(yarp::os::ConnectionReader& connection) override; +}; + +#endif diff --git a/src/devices/fakeLaserWithMotor/fakeLaserWithMotor_motors.cpp b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor_motors.cpp new file mode 100644 index 00000000000..a60d1f64a45 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor_motors.cpp @@ -0,0 +1,642 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#define _USE_MATH_DEFINES + +#include "fakeLaserWithMotor.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//#define LASER_DEBUG +#ifndef DEG2RAD +#define DEG2RAD M_PI/180.0 +#endif + +YARP_LOG_COMPONENT(FAKE_LASER_MOTORS, "yarp.devices.fakeLaserWithMotor.motors") + +using namespace yarp::os; +using namespace yarp::dev; + +template ::value, int> = 0> + T* allocAndCheck(int size) +{ + T* t = new T[size]; + yAssert(t != 0); + memset(t, 0, sizeof(T) * size); + return t; +} + +template ::value, int> = 0> + T* allocAndCheck(int size) +{ + T* t = new T[size]; + yAssert(t != 0); + return t; +} + +template +void checkAndDestroy(T*& p) { + if (p != 0) { + delete[] p; + p = 0; + } +} + + +//Motor interfaces +bool FakeLaserWithMotor::getEncodersTimedRaw(double* encs, double* stamps) +{ + bool ret = getEncodersRaw(encs); + m_mutex.lock(); + for (int i = 0; i < m_njoints; i++) { + stamps[i] = m_timestamp.getTime(); + } + m_mutex.unlock(); + return ret; +} + +bool FakeLaserWithMotor::getEncoderTimedRaw(int j, double* encs, double* stamp) +{ + bool ret = getEncoderRaw(j, encs); + m_mutex.lock(); + *stamp = m_timestamp.getTime(); + m_mutex.unlock(); + + return ret; +} + +bool FakeLaserWithMotor::getAxes(int* ax) +{ + *ax = m_njoints; + return true; +} + +bool FakeLaserWithMotor::positionMoveRaw(int j, double ref) +{ + int mode = 0; + getControlModeRaw(j, &mode); + if ((mode != VOCAB_CM_POSITION) && + (mode != VOCAB_CM_MIXED) && + (mode != VOCAB_CM_IMPEDANCE_POS) && + (mode != VOCAB_CM_IDLE)) + { + yCError(FAKE_LASER_MOTORS) << "positionMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode"; + } + _posCtrl_references[j] = ref; + return true; +} + +bool FakeLaserWithMotor::positionMoveRaw(const double* refs) +{ + bool ret = true; + for (int j = 0, index = 0; j < m_njoints; j++, index++) + { + ret &= positionMoveRaw(j, refs[index]); + } + return ret; +} + +bool FakeLaserWithMotor::relativeMoveRaw(int j, double delta) +{ + int mode = 0; + getControlModeRaw(j, &mode); + if ((mode != VOCAB_CM_POSITION) && + (mode != VOCAB_CM_MIXED) && + (mode != VOCAB_CM_IMPEDANCE_POS) && + (mode != VOCAB_CM_IDLE)) + { + yCError(FAKE_LASER_MOTORS) << "relativeMoveRaw: skipping command because joint " << j << " is not in VOCAB_CM_POSITION mode"; + } + _posCtrl_references[j] += delta; + return false; +} + +bool FakeLaserWithMotor::relativeMoveRaw(const double* deltas) +{ + bool ret = true; + for (int j = 0, index = 0; j < m_njoints; j++, index++) + { + ret &= relativeMoveRaw(j, deltas[index]); + } + return ret; +} + + +bool FakeLaserWithMotor::checkMotionDoneRaw(int j, bool* flag) +{ + *flag = false; + return false; +} + +bool FakeLaserWithMotor::checkMotionDoneRaw(bool* flag) +{ + bool ret = true; + bool val, tot_res = true; + + for (int j = 0, index = 0; j < m_njoints; j++, index++) + { + ret &= checkMotionDoneRaw(&val); + tot_res &= val; + } + *flag = tot_res; + return ret; +} + +bool FakeLaserWithMotor::setRefSpeedRaw(int j, double sp) +{ + // Velocity is expressed in iDegrees/s + // save internally the new value of speed; it'll be used in the positionMove + int index = j; + _ref_speeds[index] = sp; + return true; +} + +bool FakeLaserWithMotor::setRefSpeedsRaw(const double* spds) +{ + // Velocity is expressed in iDegrees/s + // save internally the new value of speed; it'll be used in the positionMove + for (int j = 0, index = 0; j < m_njoints; j++, index++) + { + _ref_speeds[index] = spds[index]; + } + return true; +} + +bool FakeLaserWithMotor::setRefAccelerationRaw(int j, double acc) +{ + // Acceleration is expressed in iDegrees/s^2 + // save internally the new value of the acceleration; it'll be used in the velocityMove command + + if (acc > 1e6) + { + _ref_accs[j] = 1e6; + } + else if (acc < -1e6) + { + _ref_accs[j] = -1e6; + } + else + { + _ref_accs[j] = acc; + } + + return true; +} + +bool FakeLaserWithMotor::setRefAccelerationsRaw(const double* accs) +{ + // Acceleration is expressed in iDegrees/s^2 + // save internally the new value of the acceleration; it'll be used in the velocityMove command + for (int j = 0, index = 0; j < m_njoints; j++, index++) + { + if (accs[j] > 1e6) + { + _ref_accs[index] = 1e6; + } + else if (accs[j] < -1e6) + { + _ref_accs[index] = -1e6; + } + else + { + _ref_accs[index] = accs[j]; + } + } + return true; +} + +bool FakeLaserWithMotor::getRefSpeedRaw(int j, double* spd) +{ + *spd = _ref_speeds[j]; + return true; +} + +bool FakeLaserWithMotor::getRefSpeedsRaw(double* spds) +{ + memcpy(spds, _ref_speeds, sizeof(double) * m_njoints); + return true; +} + +bool FakeLaserWithMotor::getRefAccelerationRaw(int j, double* acc) +{ + *acc = _ref_accs[j]; + return true; +} + +bool FakeLaserWithMotor::getRefAccelerationsRaw(double* accs) +{ + memcpy(accs, _ref_accs, sizeof(double) * m_njoints); + return true; +} + +bool FakeLaserWithMotor::stopRaw(int j) +{ + return false; +} + +bool FakeLaserWithMotor::stopRaw() +{ + bool ret = true; + for (int j = 0; j < m_njoints; j++) + { + ret &= stopRaw(j); + } + return ret; +} +///////////// END Position Control INTERFACE ////////////////// + +bool FakeLaserWithMotor::getControlModeRaw(int j, int* v) +{ + *v = _controlModes[j]; + return true; +} + +// IControl Mode 2 +bool FakeLaserWithMotor::getControlModesRaw(int* v) +{ + bool ret = true; + for (int j = 0; j < m_njoints; j++) + { + ret = ret && getControlModeRaw(j, &v[j]); + } + return ret; +} + +bool FakeLaserWithMotor::getControlModesRaw(const int n_joint, const int* joints, int* modes) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && getControlModeRaw(joints[j], &modes[j]); + } + return ret; +} + + + +bool FakeLaserWithMotor::setControlModeRaw(const int j, const int _mode) +{ + if (_mode == VOCAB_CM_FORCE_IDLE) + { + _controlModes[j] = VOCAB_CM_IDLE; + } + else + { + _controlModes[j] = _mode; + } + return true; +} + + +bool FakeLaserWithMotor::setControlModesRaw(const int n_joint, const int* joints, int* modes) +{ + bool ret = true; + for (int i = 0; i < n_joint; i++) + { + ret &= setControlModeRaw(joints[i], modes[i]); + } + return ret; +} + +bool FakeLaserWithMotor::setControlModesRaw(int* modes) +{ + bool ret = true; + for (int i = 0; i < m_njoints; i++) + { + ret &= setControlModeRaw(i, modes[i]); + } + return ret; +} + +bool FakeLaserWithMotor::alloc(int nj) +{ + _controlModes = allocAndCheck(nj); + _encoders = allocAndCheck(nj); + _axisName = new std::string[nj]; + _jointType = new JointTypeEnum[nj]; + + // Reserve space for data stored locally. values are initialized to 0 + _posCtrl_references = allocAndCheck(nj); + _command_speeds = allocAndCheck(nj); + _ref_speeds = allocAndCheck(nj); + _ref_accs = allocAndCheck(nj); + + //resizeBuffers(); + + return true; +} + +bool FakeLaserWithMotor::dealloc() +{ + checkAndDestroy(_controlModes); + checkAndDestroy(_encoders); + checkAndDestroy(_posCtrl_references); + checkAndDestroy(_command_speeds); + checkAndDestroy(_ref_speeds); + checkAndDestroy(_ref_accs); + checkAndDestroy(_axisName); + checkAndDestroy(_jointType); + return true; +} + + +bool FakeLaserWithMotor::setEncoderRaw(int j, double val) +{ + return NOT_YET_IMPLEMENTED("setEncoder"); +} + +bool FakeLaserWithMotor::setEncodersRaw(const double* vals) +{ + return NOT_YET_IMPLEMENTED("setEncoders"); +} + +bool FakeLaserWithMotor::resetEncoderRaw(int j) +{ + return NOT_YET_IMPLEMENTED("resetEncoder"); +} + +bool FakeLaserWithMotor::resetEncodersRaw() +{ + return NOT_YET_IMPLEMENTED("resetEncoders"); +} + +bool FakeLaserWithMotor::getEncoderRaw(int j, double* value) +{ + bool ret = true; + + *value = _encoders[j]; + + return ret; +} + +bool FakeLaserWithMotor::getEncodersRaw(double* encs) +{ + bool ret = true; + for (int j = 0; j < m_njoints; j++) + { + bool ok = getEncoderRaw(j, &encs[j]); + ret = ret && ok; + + } + return ret; +} + +bool FakeLaserWithMotor::getEncoderSpeedRaw(int j, double* sp) +{ + // To avoid returning uninitialized memory, we set the encoder speed to 0 + *sp = 0.0; + return true; +} + +bool FakeLaserWithMotor::getEncoderSpeedsRaw(double* spds) +{ + bool ret = true; + for (int j = 0; j < m_njoints; j++) + { + ret &= getEncoderSpeedRaw(j, &spds[j]); + } + return ret; +} + +bool FakeLaserWithMotor::getEncoderAccelerationRaw(int j, double* acc) +{ + // To avoid returning uninitialized memory, we set the encoder acc to 0 + *acc = 0.0; + + return true; +} + +bool FakeLaserWithMotor::getEncoderAccelerationsRaw(double* accs) +{ + bool ret = true; + for (int j = 0; j < m_njoints; j++) + { + ret &= getEncoderAccelerationRaw(j, &accs[j]); + } + return ret; +} + +bool FakeLaserWithMotor::setRefAccelerationsRaw(const int n_joint, const int* joints, const double* accs) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && setRefAccelerationRaw(joints[j], accs[j]); + } + return ret; +} + +bool FakeLaserWithMotor::getRefSpeedsRaw(const int n_joint, const int* joints, double* spds) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && getRefSpeedRaw(joints[j], &spds[j]); + } + return ret; +} + +bool FakeLaserWithMotor::getRefAccelerationsRaw(const int n_joint, const int* joints, double* accs) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && getRefAccelerationRaw(joints[j], &accs[j]); + } + return ret; +} + +bool FakeLaserWithMotor::stopRaw(const int n_joint, const int* joints) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && stopRaw(joints[j]); + } + return ret; +} + +bool FakeLaserWithMotor::positionMoveRaw(const int n_joint, const int* joints, const double* refs) +{ + for (int j = 0; j < n_joint; j++) + { + yCDebug(FAKE_LASER_MOTORS, "j: %d; ref %f;\n", joints[j], refs[j]); fflush(stdout); + } + + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && positionMoveRaw(joints[j], refs[j]); + } + return ret; +} + +bool FakeLaserWithMotor::relativeMoveRaw(const int n_joint, const int* joints, const double* deltas) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && relativeMoveRaw(joints[j], deltas[j]); + } + return ret; +} + +bool FakeLaserWithMotor::checkMotionDoneRaw(const int n_joint, const int* joints, bool* flag) +{ + bool ret = true; + bool val = true; + bool tot_val = true; + + for (int j = 0; j < n_joint; j++) + { + ret = ret && checkMotionDoneRaw(joints[j], &val); + tot_val &= val; + } + *flag = tot_val; + return ret; +} + +bool FakeLaserWithMotor::setRefSpeedsRaw(const int n_joint, const int* joints, const double* spds) +{ + bool ret = true; + for (int j = 0; j < n_joint; j++) + { + ret = ret && setRefSpeedRaw(joints[j], spds[j]); + } + return ret; +} + +bool FakeLaserWithMotor::getTargetPositionRaw(int axis, double* ref) +{ + int mode = 0; + getControlModeRaw(axis, &mode); + if ((mode != VOCAB_CM_POSITION) && + (mode != VOCAB_CM_MIXED) && + (mode != VOCAB_CM_IMPEDANCE_POS)) + { + yCWarning(FAKE_LASER_MOTORS) << "getTargetPosition: Joint " << axis << " is not in POSITION mode, therefore the value returned by " << + "this call is for reference only and may not reflect the actual behaviour of the motor/firmware."; + } + *ref = _posCtrl_references[axis]; + return true; +} + +bool FakeLaserWithMotor::getTargetPositionsRaw(double* refs) +{ + bool ret = true; + for (int i = 0; i < m_njoints; i++) { + ret &= getTargetPositionRaw(i, &refs[i]); + } + return ret; +} + +bool FakeLaserWithMotor::getTargetPositionsRaw(int nj, const int* jnts, double* refs) +{ + bool ret = true; + for (int i = 0; i < nj; i++) + { + ret &= getTargetPositionRaw(jnts[i], &refs[i]); + } + return ret; +} + +bool FakeLaserWithMotor::velocityMoveRaw(int j, double sp) +{ + int mode = 0; + getControlModeRaw(j, &mode); + if ((mode != VOCAB_CM_VELOCITY) && + (mode != VOCAB_CM_MIXED) && + (mode != VOCAB_CM_IMPEDANCE_VEL) && + (mode != VOCAB_CM_IDLE)) + { + yCError(FAKE_LASER_MOTORS) << "velocityMoveRaw: skipping command because board " << " joint " << j << " is not in VOCAB_CM_VELOCITY mode"; + } + _command_speeds[j] = sp; + //last_velocity_command[j] = yarp::os::Time::now(); + return true; +} + +bool FakeLaserWithMotor::velocityMoveRaw(const double* sp) +{ + bool ret = true; + for (int i = 0; i < m_njoints; i++) { + ret &= velocityMoveRaw(i, sp[i]); + } + return ret; +} +bool FakeLaserWithMotor::velocityMoveRaw(const int n_joint, const int* joints, const double* spds) +{ + bool ret = true; + for (int i = 0; i < n_joint; i++) + { + ret &= velocityMoveRaw(joints[i], spds[i]); + } + return ret; +} + +bool FakeLaserWithMotor::getRefVelocityRaw(int axis, double* ref) +{ + *ref = _command_speeds[axis]; + return true; +} + +bool FakeLaserWithMotor::getRefVelocitiesRaw(double* refs) +{ + bool ret = true; + for (int i = 0; i < m_njoints; i++) + { + ret &= getRefVelocityRaw(i, &refs[i]); + } + return ret; +} + +bool FakeLaserWithMotor::getRefVelocitiesRaw(int nj, const int* jnts, double* refs) +{ + bool ret = true; + for (int i = 0; i < nj; i++) + { + ret &= getRefVelocityRaw(jnts[i], &refs[i]); + } + return ret; +} + + +bool FakeLaserWithMotor::getAxisNameRaw(int axis, std::string& name) +{ + if (axis >= 0 && axis < m_njoints) + { + name = _axisName[axis]; + return true; + } + else + { + name = "ERROR"; + return false; + } +} + +bool FakeLaserWithMotor::getJointTypeRaw(int axis, yarp::dev::JointTypeEnum& type) +{ + if (axis >= 0 && axis < m_njoints) + { + type = _jointType[axis]; + return true; + } + else + { + return false; + } +} diff --git a/src/devices/fakeLaserWithMotor/fakeLaserWithMotor_utils.cpp b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor_utils.cpp new file mode 100644 index 00000000000..c26ca4024a0 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor_utils.cpp @@ -0,0 +1,281 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#define _USE_MATH_DEFINES + +#include "fakeLaserWithMotor.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//#define LASER_DEBUG +#ifndef DEG2RAD +#define DEG2RAD M_PI/180.0 +#endif + +YARP_LOG_COMPONENT(FAKE_LASER_UTILS, "yarp.devices.fakeLaserWithMotor.Utils") + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; + +void FakeLaserWithMotor::wall_the_robot(double siz, double dist) +{ + //double res; + //m_map.getResolution(res); + //size_t siz_cell = siz / res; + //size_t dist_cell = dist / res; + XYCell robot = m_map.world2Cell(XYWorld(m_robot_loc_x, m_robot_loc_y)); + + XYWorld ray_start; + XYWorld start (0+dist, 0 - siz); + ray_start.x = start.x * cos(m_robot_loc_t * DEG2RAD) - start.y * sin(m_robot_loc_t * DEG2RAD) + m_robot_loc_x; + ray_start.y = start.x * sin(m_robot_loc_t * DEG2RAD) + start.y * cos(m_robot_loc_t * DEG2RAD) + m_robot_loc_y; + XYCell start_cell = m_map.world2Cell(ray_start); + + XYWorld ray_end; + XYWorld end(0 + dist, 0 + siz); + ray_end.x = end.x * cos(m_robot_loc_t * DEG2RAD) - end.y * sin(m_robot_loc_t * DEG2RAD) + m_robot_loc_x; + ray_end.y = end.x * sin(m_robot_loc_t * DEG2RAD) + end.y * cos(m_robot_loc_t * DEG2RAD) + m_robot_loc_y; + XYCell end_cell = m_map.world2Cell(ray_end); + + drawStraightLine(start_cell,end_cell); +} + +void FakeLaserWithMotor::obst_the_robot(double siz, double dist) +{ + //NOT YET IMPLEMENTED + /*double res; + m_map.getResolution(res); + size_t siz_cell = size_t(siz / res); + size_t dist_cell = size_t(dist / res); + XYCell robot = m_map.world2Cell(XYWorld(m_robot_loc_x, m_robot_loc_y));*/ +} + +void FakeLaserWithMotor::trap_the_robot(double siz) +{ + double res; + m_map.getResolution(res); + size_t siz_cell = size_t(siz / res); + size_t x=0; + size_t y=0; + XYCell robot = m_map.world2Cell(XYWorld (m_robot_loc_x, m_robot_loc_y)); + + y = robot.y - siz_cell; + for (x= robot.x- siz_cell; x< robot.x + siz_cell; x++) + { + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + } + + y = robot.y + siz_cell; + for (x = robot.x - siz_cell; x < robot.x + siz_cell; x++) + { + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + } + + x = robot.x - siz_cell; + for (y = robot.y - siz_cell; y < robot.y + siz_cell; y++) + { + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + } + + x = robot.x + siz_cell; + for (y = robot.y - siz_cell; y < robot.y + siz_cell; y++) + { + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + } +} + +void FakeLaserWithMotor::free_the_robot() +{ + m_map=m_originally_loaded_map; +} + +void FakeLaserWithMotor::drawStraightLine(XYCell src, XYCell dst) +{ + long int x, y; + long int dx, dy, dx1, dy1, px, py, xe, ye, i; + dx = (long int)dst.x - (long int)src.x; + dy = (long int)dst.y - (long int)src.y; + dx1 = abs(dx); + dy1 = abs(dy); + px = 2 * dy1 - dx1; + py = 2 * dx1 - dy1; + if (dy1 <= dx1) + { + if (dx >= 0) + { + x = (long int)src.x; + y = (long int)src.y; + xe = (long int)dst.x; + } + else + { + x = (long int)dst.x; + y = (long int)dst.y; + xe = (long int)src.x; + } + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + for (i = 0; x < xe; i++) + { + x = x + 1; + if (px < 0) + { + px = px + 2 * dy1; + } + else + { + if ((dx < 0 && dy < 0) || (dx > 0 && dy > 0)) + { + y = y + 1; + } + else + { + y = y - 1; + } + px = px + 2 * (dy1 - dx1); + } + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + } + } + else + { + if (dy >= 0) + { + x = (long int)src.x; + y = (long int)src.y; + ye = (long int)dst.y; + } + else + { + x = (long int)dst.x; + y = (long int)dst.y; + ye = (long int)src.y; + } + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + for (i = 0; y < ye; i++) + { + y = y + 1; + if (py <= 0) + { + py = py + 2 * dx1; + } + else + { + if ((dx < 0 && dy < 0) || (dx > 0 && dy > 0)) + { + x = x + 1; + } + else + { + x = x - 1; + } + py = py + 2 * (dx1 - dy1); + } + m_map.setMapFlag(XYCell(x, y), yarp::dev::Nav2D::MapGrid2D::map_flags::MAP_CELL_WALL); + } + } +} + +double FakeLaserWithMotor::checkStraightLine(XYCell src, XYCell dst) +{ + //BEWARE: src and dest must be already clipped and >0 in this function + XYCell test_point; + test_point.x = src.x; + test_point.y = src.y; + + //here using the fast Bresenham algorithm + int dx = abs(int(dst.x - src.x)); + int dy = abs(int(dst.y - src.y)); + int err = dx - dy; + + int sx; + int sy; + if (src.x < dst.x) { sx = 1; } else { sx = -1; } + if (src.y < dst.y) { sy = 1; } else { sy = -1; } + + while (true) + { + //the test point is going to move from src until it reaches dst OR + //if it reaches the boundaries of the image + if (test_point.x==0 || test_point.y ==0 || test_point.x>=m_map.width() || test_point.y>=m_map.height()) + { + break; + } + + //if (m_map.isFree(src) == false) + if (m_map.isWall(XYCell(test_point.x,test_point.y))) + { + XYWorld world_start = m_map.cell2World(src); + XYWorld world_end = m_map.cell2World(XYCell(test_point.x, test_point.y)); + double dist = sqrt(pow(world_start.x - world_end.x, 2) + pow(world_start.y - world_end.y, 2)); + return dist; + } + + if (test_point.x == dst.x && test_point.y == dst.y) + { + break; + } + + int e2 = err * 2; + if (e2 > -dy) + { + err = err - dy; + test_point.x += sx; + } + if (e2 < dx) + { + err = err + dx; + test_point.y += sy; + } + } + return std::numeric_limits::infinity(); +} + +bool FakeLaserWithMotor::LiangBarsky_clip(int edgeLeft, int edgeRight, int edgeTop, int edgeBottom, + XYCell_unbounded src, XYCell_unbounded dst, + XYCell& src_clipped, XYCell& dst_clipped) +{ + double t0 = 0.0; double t1 = 1.0; + double xdelta = double(dst.x - src.x); + double ydelta = double(dst.y - src.y); + double p, q, r; + + for (int edge = 0; edge < 4; edge++) + { + if (edge == 0) { p = -xdelta; q = -(edgeLeft - src.x); } + if (edge == 1) { p = xdelta; q = (edgeRight - src.x); } + if (edge == 2) { p = -ydelta; q = -(edgeTop - src.y); } + if (edge == 3) { p = ydelta; q = (edgeBottom - src.y); } + r = q / p; + if (p == 0 && q < 0) { return false; } //line is outside (parallel) + + if (p < 0) + { + if (r > t1) { return false; } //line is outside. + else if (r > t0) { t0 = r; } //line is clipped + } + else if (p > 0) + { + if (r < t0) { return false; } //line is outside. + else if (r < t1) { t1 = r; } //line is clipped + } + } + + src_clipped.x = size_t(double(src.x) + t0 * xdelta); + src_clipped.y = size_t(double(src.y) + t0 * ydelta); + dst_clipped.x = size_t(double(src.x) + t1 * xdelta); + dst_clipped.y = size_t(double(src.y) + t1 * ydelta); + + return true; //line is clipped +} diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/ros.xml b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros.xml new file mode 100644 index 00000000000..e40b026ccf1 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros.xml @@ -0,0 +1,41 @@ + + + + + + + + + + /robot/motor + /robot/motor + /robot/motor + 0.01 + + + lidarmotor + + + + + + + /robot/motor + /robot/motor + 0.01 + + + lidarmotor + + + + + + + use_square_trap + + + diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/yarp.xml b/src/devices/fakeLaserWithMotor/robotinterface_xml/yarp.xml new file mode 100644 index 00000000000..102e224922e --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/yarp.xml @@ -0,0 +1,39 @@ + + + + + + + + + + /lidar + /lidar2 + 0.01 + + + lidarmotor + + + + + + + /robot/motor + 0.01 + + + lidarmotor + + + + + + + use_square_trap + + + From 8346ef5099987216fd253ceb40ec62d6d6f3da8f Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Mon, 1 Aug 2022 14:19:36 +0200 Subject: [PATCH 044/267] ros2 test added --- .../robotinterface_xml/robot.urdf | 37 +++++++++ .../robotinterface_xml/robot_state_pub.launch | 9 +++ .../robotinterface_xml/robot_state_pub2.py | 27 +++++++ .../robotinterface_xml/ros2.xml | 64 +++++++++++++++ .../robotinterface_xml/ros2b.xml | 78 +++++++++++++++++++ 5 files changed, 215 insertions(+) create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub.launch create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub2.py create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/ros2.xml create mode 100644 src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf new file mode 100644 index 00000000000..c6f00528851 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub.launch b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub.launch new file mode 100644 index 00000000000..bb18e993c8d --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub2.py b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub2.py new file mode 100644 index 00000000000..5d854982673 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot_state_pub2.py @@ -0,0 +1,27 @@ +import os +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + + use_sim_time = LaunchConfiguration('use_sim_time', default='false') + + urdf = os.path.abspath("./robot.urdf") + with open(urdf, 'r') as infp: + robot_desc = infp.read() + + return LaunchDescription([ + DeclareLaunchArgument( + 'use_sim_time', + default_value='false', + description='Use simulation (Gazebo) clock if true'), + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[{'use_sim_time': use_sim_time, 'robot_description': robot_desc, 'publish_frequency': 200.0}], + arguments=[urdf]) + ]) diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2.xml b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2.xml new file mode 100644 index 00000000000..4775272ee47 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2.xml @@ -0,0 +1,64 @@ + + + + + + + + + + /lidar + /lidar2 + 0.01 + + + lidarmotor + + + + + + + /robot/motor + 0.01 + + + lidarmotor + + + + + + + ldnode + /robot_lidar + lidar_link + 0.01 + + + lidarmotor + + + + + + + rmnode + /joint_states + 0.01 + + + lidarmotor + + + + + + + use_square_trap + + + diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml new file mode 100644 index 00000000000..fe7cb678eb3 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml @@ -0,0 +1,78 @@ + + + + + + + + + + /lidar + /lidar2 + 0.01 + + + lidarmotor + + + + + + + /robot/motor + 0.01 + + + lidarmotor + + + + + + + + rmnode + /robot_lidar + /joint_states + lidar_link + 0.01 + + + lidarmotor + + + + + + + use_square_trap + + + From 23b1185b6cbac67ae6df031cd90224de8ec72fe7 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 16 Sep 2022 17:22:41 +0200 Subject: [PATCH 045/267] added folders to skip to check_license script --- .../robotinterface_xml/robot.urdf | 9 ++-- .../robotinterface_xml/ros2b.xml | 2 +- tests/misc/check_license.pl | 47 ++++++++++++++----- tests/misc/check_license_skip.txt | 1 + 4 files changed, 41 insertions(+), 18 deletions(-) diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf index c6f00528851..eaa1cadbf80 100644 --- a/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/robot.urdf @@ -5,7 +5,7 @@ - + @@ -19,7 +19,7 @@ - + @@ -27,11 +27,10 @@ - + - +
- diff --git a/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml index fe7cb678eb3..1e3f8f1ad4b 100644 --- a/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml +++ b/src/devices/fakeLaserWithMotor/robotinterface_xml/ros2b.xml @@ -70,7 +70,7 @@ - + use_square_trap diff --git a/tests/misc/check_license.pl b/tests/misc/check_license.pl index 6bf22ca03cd..f4b6f3b2d90 100755 --- a/tests/misc/check_license.pl +++ b/tests/misc/check_license.pl @@ -170,21 +170,43 @@ END my $skip = 0; my $errors = 0; my $known = 0; +my $number_files_marked_to_skip = scalar(@skip_files); +foreach my $skipline (@skip_files) { + if (substr ($skipline, -1) eq '/') { + $number_files_marked_to_skip--; } +} + +use File::Spec; foreach my $filename (@files) { $files++; - # For now skip files known to have a broken license - my $match = 0; + my $match_filename = 0; + my $match_dir = 0; for (@skip_files) { + # skip files known to have a broken license if ("$filename" eq "$_") { - $match = 1; + $match_filename = 1; + last; + } + # skip directories known to contain files which have a broken license + my($vol,$dir,$file) = File::Spec->splitpath($filename); + my($vol2,$dir2,$file2) = File::Spec->splitpath($_); + # print "testing $dir $dir2 \n"; + if ("$dir" eq "$_") { + $match_dir = 1; + $number_files_marked_to_skip++; last; } } - if( $match ) { - print_if_verbose "[SKIP (known)] $filename\n"; + if( $match_filename ) { + print "[SKIP (known file)] $filename\n"; + $known++; + next; + } + elsif( $match_dir ) { + print "[SKIP (known dir)] $filename\n"; $known++; next; } @@ -444,28 +466,29 @@ END print_if_verbose "FILES: $files\n"; print_if_verbose "OK: $ok\n"; print_if_verbose "SKIP: $skip\n"; -print_if_verbose "KNOWN: $known\n"; +print_if_verbose "KNOWN (COUNTED): $known\n"; +print_if_verbose "KNOWN (DECLARED FROM FILE): $number_files_marked_to_skip\n"; print_if_verbose "ERRORS: $errors\n"; print_if_verbose "---\n"; print_if_verbose "\n"; if ($ok + $skip + $known + $errors != $files) { - print_if_verbose "[ERROR: Some file was not counted]\n\n"; + print "[ERROR: Some file was not counted]\n\n"; exit 1; } -if ($known < scalar(@skip_files)) { - print_if_verbose "[ERROR: Some known file was not found and the skip file was not updated]\n\n"; +if ($known < $number_files_marked_to_skip) { + print "[ERROR: Some known file was not found and the skip file was not updated]\n\n"; exit 1; } -if ($known > scalar(@skip_files)) { - print_if_verbose "[ERROR: Some new known file was added and the skip file was not updated]\n\n"; +if ($known > $number_files_marked_to_skip) { + print "[ERROR: Some new known file was added and the skip file was not updated]\n\n"; exit 1; } if ($errors != 0) { - print_if_verbose "[ERROR: Some file has an invalid license]\n\n"; + print "[ERROR: Some file has an invalid license]\n\n"; exit 1; } diff --git a/tests/misc/check_license_skip.txt b/tests/misc/check_license_skip.txt index 9fa428f74cb..f0f3e42aa69 100644 --- a/tests/misc/check_license_skip.txt +++ b/tests/misc/check_license_skip.txt @@ -1,3 +1,4 @@ bindings/lua/argcargv.i src/devices/opencv/OpenCVGrabber.cpp src/devices/opencv/OpenCVGrabber.h +src/devices/fakeLaserWithMotor/robotinterface_xml/ From a84cc191e65a4434444e4a6628e03abc3048f04a Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 25 Nov 2022 18:08:27 +0100 Subject: [PATCH 046/267] added tests for device fakeLaserWithMotor --- src/devices/fakeLaserWithMotor/CMakeLists.txt | 5 ++ .../fakeLaserWithMotor/tests/CMakeLists.txt | 53 +++++++++++++++++++ .../tests/fakeLaserWithMotorTest.cpp | 48 +++++++++++++++++ 3 files changed, 106 insertions(+) create mode 100644 src/devices/fakeLaserWithMotor/tests/CMakeLists.txt create mode 100644 src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp diff --git a/src/devices/fakeLaserWithMotor/CMakeLists.txt b/src/devices/fakeLaserWithMotor/CMakeLists.txt index a9d6bd7b4e2..cca3bbeaa26 100644 --- a/src/devices/fakeLaserWithMotor/CMakeLists.txt +++ b/src/devices/fakeLaserWithMotor/CMakeLists.txt @@ -44,4 +44,9 @@ if(NOT SKIP_fakeLaserWithMotor) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeLaserWithMotor PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt b/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt new file mode 100644 index 00000000000..b4c4da9d10a --- /dev/null +++ b/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeLaserWithMotor) + +target_sources(harness_dev_fakeLaserWithMotor + PRIVATE + fakeLaserWithMotorTest.cpp +) + +target_link_libraries(harness_dev_fakeLaserWithMotor + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_fakeLaserWithMotor + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + fakeLaserWithMotorTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_fakeLaserWithMotor PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeLaserWithMotor) diff --git a/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp b/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp new file mode 100644 index 00000000000..a3f29dcc6d5 --- /dev/null +++ b/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp @@ -0,0 +1,48 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::FakeLaserTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeLaser", "device"); + + Network::setLocalMode(true); + + SECTION("Checking FakeLaserTest device") + { + PolyDriver fakelaserdev; + IRangefinder2D* irng = nullptr; + + ////////"Checking opening polydriver" + { + Property las_cfg; + las_cfg.put("device", "fakeLaser"); + las_cfg.put("test", "use_constant"); + las_cfg.put("const_distance", 0.5); + REQUIRE(fakelaserdev.open(las_cfg)); + REQUIRE(fakelaserdev.view(irng)); + } + + //execute tests + yarp::dev::tests::exec_iRangefinder2D_test_1(irng); + + //"Close all polydrivers and check" + CHECK(fakelaserdev.close()); + } + + Network::setLocalMode(false); +} From 8d5fe3cf46dbd6031bcc3223395041c569e1cf7d Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 25 Nov 2022 19:55:45 +0100 Subject: [PATCH 047/267] improved test of device fakeLaserWithMotor several cleanups to laser-related devices --- .ci/initial-cache.gh.linux.cmake | 2 +- src/devices/fakeLaser/fakeLaser.cpp | 20 +- src/devices/fakeLaser/fakeLaser.h | 11 +- src/devices/fakeLaser/info/readme.txt | 10 +- src/devices/fakeLaserWithMotor/CMakeLists.txt | 1 + .../fakeLaserWithMotor/fakeLaserWithMotor.cpp | 171 ++--------------- .../fakeLaserWithMotor/fakeLaserWithMotor.h | 14 +- .../fakeLaserWithMotor_laser.cpp | 175 ++++++++++++++++++ .../tests/fakeLaserWithMotorTest.cpp | 11 +- .../laserFromExternalPort.cpp | 8 +- .../laserFromPointCloud.cpp | 4 +- .../src/yarp/dev/tests/IRangefinder2DTest.h | 2 + 12 files changed, 230 insertions(+), 199 deletions(-) create mode 100644 src/devices/fakeLaserWithMotor/fakeLaserWithMotor_laser.cpp diff --git a/.ci/initial-cache.gh.linux.cmake b/.ci/initial-cache.gh.linux.cmake index 35f79fc5a4a..b1cf74d92f4 100644 --- a/.ci/initial-cache.gh.linux.cmake +++ b/.ci/initial-cache.gh.linux.cmake @@ -63,7 +63,7 @@ set(ENABLE_yarpmod_SDLJoypad ON CACHE BOOL "") set(ENABLE_yarpmod_batteryClient ON CACHE BOOL "") set(ENABLE_yarpmod_batteryWrapper ON CACHE BOOL "") set(ENABLE_yarpmod_upowerBattery ON CACHE BOOL "") -set(ENABLE_yarpmod_Rangefinder2DWrapper ON CACHE BOOL "") +set(ENABLE_yarpmod_rangefinder2D_nws_yarp ON CACHE BOOL "") set(ENABLE_yarpmod_multipleanalogsensorsserver ON CACHE BOOL "") set(ENABLE_yarpmod_multipleanalogsensorsclient ON CACHE BOOL "") set(ENABLE_yarpmod_multipleanalogsensorsremapper ON CACHE BOOL "") diff --git a/src/devices/fakeLaser/fakeLaser.cpp b/src/devices/fakeLaser/fakeLaser.cpp index d9feb592127..3e9a44c0600 100644 --- a/src/devices/fakeLaser/fakeLaser.cpp +++ b/src/devices/fakeLaser/fakeLaser.cpp @@ -44,15 +44,15 @@ bool FakeLaser::open(yarp::os::Searchable& config) { yCInfo(FAKE_LASER,"Some examples:"); yCInfo(FAKE_LASER,"yarpdev --device fakeLaser --help"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test no_obstacles"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_pattern"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5 --SENSOR::resolution 0.5 --SKIP::min 0 50 --SKIP::max 10 60"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_server /localizationServer"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localizationServer"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_context context --map_file mymap.map"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test no_obstacles"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_pattern"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5 --SENSOR::resolution 0.5 --SKIP::min 0 50 --SKIP::max 10 60"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_server /localizationServer"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localizationServer"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_context context --map_file mymap.map"); yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localization2D_nws_yarp --localization_device localization2D_nwc_yarp"); return false; } @@ -196,8 +196,6 @@ bool FakeLaser::close() { PeriodicThread::stop(); - driver.close(); - if (m_loc_port) { m_loc_port->interrupt(); diff --git a/src/devices/fakeLaser/fakeLaser.h b/src/devices/fakeLaser/fakeLaser.h index d4f1ea737f8..7f620233f71 100644 --- a/src/devices/fakeLaser/fakeLaser.h +++ b/src/devices/fakeLaser/fakeLaser.h @@ -49,11 +49,11 @@ * * \section Usage examples: * yarpdev --device fakeLaser --help -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test no_obstacles -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_pattern -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test no_obstacles +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_pattern +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient * yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_device localization2D_nwc_yarp */ @@ -66,7 +66,6 @@ class FakeLaser : public yarp::os::PeriodicThread, enum test_mode_t { NO_OBSTACLES = 0, USE_PATTERN =1, USE_MAPFILE =2, USE_CONSTANT_VALUE =3 }; enum localization_mode_t { LOC_NOT_SET=0, LOC_FROM_PORT = 1, LOC_FROM_CLIENT = 2 }; - yarp::dev::PolyDriver driver; test_mode_t m_test_mode; localization_mode_t m_loc_mode; diff --git a/src/devices/fakeLaser/info/readme.txt b/src/devices/fakeLaser/info/readme.txt index 2ec3d452b9f..17eb708de4b 100644 --- a/src/devices/fakeLaser/info/readme.txt +++ b/src/devices/fakeLaser/info/readme.txt @@ -1,18 +1,18 @@ Some examples: -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test no_obstacles +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test no_obstacles All measurements obtained from laser device will be inf. -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_pattern +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_pattern The output should be similar to the one shown in these pictures: ex1.jpg x axis is pointing upward (N), y axis is pointg leftward (W) ex2.jpg laser data are increasing counterclockwise -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map A map is loaded. Laser data are generated assuming robot position is in 0,0,0 -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i A map is loaded. Laser data are generated, with robot position obtained from a yarp port -* yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient +* yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /ikart/laser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient A map is loaded. Laser data are generated, with robot position obtained from a localization client diff --git a/src/devices/fakeLaserWithMotor/CMakeLists.txt b/src/devices/fakeLaserWithMotor/CMakeLists.txt index cca3bbeaa26..ada28f90303 100644 --- a/src/devices/fakeLaserWithMotor/CMakeLists.txt +++ b/src/devices/fakeLaserWithMotor/CMakeLists.txt @@ -14,6 +14,7 @@ if(NOT SKIP_fakeLaserWithMotor) PRIVATE fakeLaserWithMotor.h fakeLaserWithMotor.cpp + fakeLaserWithMotor_laser.cpp fakeLaserWithMotor_motors.cpp fakeLaserWithMotor_utils.cpp ) diff --git a/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp index 32be820673d..758843bebed 100644 --- a/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp +++ b/src/devices/fakeLaserWithMotor/fakeLaserWithMotor.cpp @@ -29,8 +29,6 @@ using namespace yarp::os; using namespace yarp::dev; using namespace yarp::dev::Nav2D; -// see FakeLaser.h for device documentation - bool FakeLaserWithMotor::open(yarp::os::Searchable& config) { m_info = "Fake Laser device for test/debugging"; @@ -43,17 +41,17 @@ bool FakeLaserWithMotor::open(yarp::os::Searchable& config) if (config.check("help")) { yCInfo(FAKE_LASER,"Some examples:"); - yCInfo(FAKE_LASER,"yarpdev --device fakeLaser --help"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test no_obstacles"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_pattern"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_constant --const_distance 0.5 --SENSOR::resolution 0.5 --SKIP::min 0 50 --SKIP::max 10 60"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_server /localizationServer"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localizationServer"); - yCInfo(FAKE_LASER,"yarpdev --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /fakeLaser:o --test use_mapfile --map_context context --map_file mymap.map"); - yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaser --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localization2D_nws_yarp --localization_device localization2D_nwc_yarp"); + yCInfo(FAKE_LASER,"yarpdev --device fakeLaserWithMotor --help"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test no_obstacles"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_pattern"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_constant --const_distance 0.5"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_constant --const_distance 0.5 --SENSOR::resolution 0.5 --SKIP::min 0 50 --SKIP::max 10 60"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_port /fakeLaser/location:i"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_server /localizationServer"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localizationServer"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_mapfile --map_context context --map_file mymap.map"); + yCInfo(FAKE_LASER,"yarpdev --device rangefinder2D_nws_yarp --subdevice fakeLaserWithMotor --period 0.01 --name /fakeLaser:o --test use_mapfile --map_file mymap.map --localization_client /fakeLaser/localizationClient --localization_server /localization2D_nws_yarp --localization_device localization2D_nwc_yarp"); return false; } @@ -206,45 +204,9 @@ bool FakeLaserWithMotor::close() { PeriodicThread::stop(); - driver.close(); - - return true; -} - -bool FakeLaserWithMotor::setDistanceRange(double min, double max) -{ - m_mutex.lock(); - m_min_distance = min; - m_max_distance = max; - m_mutex.unlock(); - return true; -} - -bool FakeLaserWithMotor::setScanLimits(double min, double max) -{ - m_mutex.lock(); - m_min_angle = min; - m_max_angle = max; - m_mutex.unlock(); return true; } -bool FakeLaserWithMotor::setHorizontalResolution(double step) -{ - m_mutex.lock(); - m_resolution = step; - m_mutex.unlock(); - return true; -} - -bool FakeLaserWithMotor::setScanRate(double rate) -{ - m_mutex.lock(); - m_period = (1.0 / rate); - m_mutex.unlock(); - return false; -} - bool FakeLaserWithMotor::threadInit() { #ifdef LASER_DEBUG @@ -255,117 +217,6 @@ bool FakeLaserWithMotor::threadInit() return true; } -bool FakeLaserWithMotor::acquireDataFromHW() -{ - m_laser_data.clear(); - double t = yarp::os::Time::now(); - static double t_orig = yarp::os::Time::now(); - double size = (t - (t_orig)); - - static int test_count = 0; - static int test = 0; - - if (m_test_mode == USE_PATTERN) - { - for (size_t i = 0; i < m_sensorsNum; i++) - { - double value = 0; - if (test == 0) - { - value = i / 100.0; - } - else if (test == 1) - { - value = size * 2; - } - else if (test == 2) - { - if (i <= 10) { value = 1.0 + i / 20.0; } - else if (i >= 90 && i <= 100) { value = 2.0 + (i - 90) / 20.0; } - else { value = m_min_distance; } - } - m_laser_data.push_back(value); - } - - test_count++; - if (test_count == 60) - { - test_count = 0; test++; if (test > 2) { test = 0; } - t_orig = yarp::os::Time::now(); - } - } - else if (m_test_mode == NO_OBSTACLES) - { - for (size_t i = 0; i < m_sensorsNum; i++) - { - m_laser_data.push_back(std::numeric_limits::infinity()); - } - } - else if (m_test_mode == USE_CONSTANT_VALUE) - { - for (size_t i = 0; i < m_sensorsNum; i++) - { - m_laser_data.push_back(m_const_value); - } - } - else if (m_test_mode == USE_MAPFILE || - m_test_mode == USE_SQUARE_TRAP) - { - m_robot_loc_x = _encoders[0];//loc.x; - m_robot_loc_y = _encoders[1];//loc.y; - m_robot_loc_t = _encoders[2];//loc.theta; - - for (size_t i = 0; i < m_sensorsNum; i++) - { - //compute the ray in the robot reference frame - double ray_angle = i * m_resolution + m_min_angle; - double ray_target_x = m_max_distance * cos(ray_angle * DEG2RAD); - double ray_target_y = m_max_distance * sin(ray_angle * DEG2RAD); - - //transforms the ray from the robot to the world reference frame - XYWorld ray_world; - ray_world.x = ray_target_x * cos(m_robot_loc_t * DEG2RAD) - ray_target_y * sin(m_robot_loc_t * DEG2RAD) + m_robot_loc_x; - ray_world.y = ray_target_x * sin(m_robot_loc_t * DEG2RAD) + ray_target_y * cos(m_robot_loc_t * DEG2RAD) + m_robot_loc_y; - XYCell src = m_map.world2Cell(XYWorld(m_robot_loc_x, m_robot_loc_y)); - - //beware! src is the robot position and it is always inside the image. - //dst is the end of the ray, and it can be out of the image! - //for this reason i am not going to call world2Cell() on dst, because that functions clips the point to the border without - //knowing the angular coefficient of the ray. I thus need the unclipped value, and run the LiangBarsky algorithm - //(which knows the angular coefficient of the ray) on it. - XYWorld ray_world_rot; - XYCell_unbounded dst; - ray_world_rot.x = ray_world.x * m_map.m_origin.get_ca() - ray_world.y * m_map.m_origin.get_sa(); - ray_world_rot.y = ray_world.x * m_map.m_origin.get_sa() + ray_world.y * m_map.m_origin.get_ca(); - dst.x = int((+ray_world_rot.x - this->m_map.m_origin.get_x()) / this->m_map.m_resolution) + 0; - dst.y = int((-ray_world_rot.y + this->m_map.m_origin.get_y()) / this->m_map.m_resolution) + (int)m_map.m_height - 1; - - XYCell newsrc; - XYCell newdst; - double distance; - if (LiangBarsky_clip(0, (int)m_map.width(), 0, (int)m_map.height(), - XYCell_unbounded(src.x, src.y), dst, newsrc, newdst)) - { - distance = checkStraightLine(src, newdst); - double simulated_noise = (*m_dis)(*m_gen); - m_laser_data.push_back(distance + simulated_noise); - } - else - { - //This should never happen, unless the robot is outside the map! - yDebug() << "Robot is outside the map?!"; - m_laser_data.push_back(std::numeric_limits::infinity()); - } - - } - } - - //set the device status - m_device_status = yarp::dev::IRangefinder2D::DEVICE_OK_IN_USE; - - return true; -} - void FakeLaserWithMotor::run() { for (size_t i=0; i +#include +#include +#include +#include +#include +#include +#include +#include +#include + + //#define LASER_DEBUG +#ifndef DEG2RAD +#define DEG2RAD M_PI/180.0 +#endif + +YARP_LOG_COMPONENT(FAKE_LASER_LASER, "yarp.devices.fakeLaserWithMotor") + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::dev::Nav2D; + +bool FakeLaserWithMotor::setDistanceRange(double min, double max) +{ + m_mutex.lock(); + m_min_distance = min; + m_max_distance = max; + m_mutex.unlock(); + return true; +} + +bool FakeLaserWithMotor::setScanLimits(double min, double max) +{ + m_mutex.lock(); + m_min_angle = min; + m_max_angle = max; + m_mutex.unlock(); + return true; +} + +bool FakeLaserWithMotor::setHorizontalResolution(double step) +{ + m_mutex.lock(); + m_resolution = step; + m_mutex.unlock(); + return true; +} + +bool FakeLaserWithMotor::setScanRate(double rate) +{ + m_mutex.lock(); + m_period = (1.0 / rate); + m_mutex.unlock(); + return false; +} + +bool FakeLaserWithMotor::acquireDataFromHW() +{ + m_laser_data.clear(); + double t = yarp::os::Time::now(); + static double t_orig = yarp::os::Time::now(); + double size = (t - (t_orig)); + + static int test_count = 0; + static int test = 0; + + if (m_test_mode == USE_PATTERN) + { + for (size_t i = 0; i < m_sensorsNum; i++) + { + double value = 0; + if (test == 0) + { + value = i / 100.0; + } + else if (test == 1) + { + value = size * 2; + } + else if (test == 2) + { + if (i <= 10) { value = 1.0 + i / 20.0; } + else if (i >= 90 && i <= 100) { value = 2.0 + (i - 90) / 20.0; } + else { value = m_min_distance; } + } + m_laser_data.push_back(value); + } + + test_count++; + if (test_count == 60) + { + test_count = 0; test++; if (test > 2) { test = 0; } + t_orig = yarp::os::Time::now(); + } + } + else if (m_test_mode == NO_OBSTACLES) + { + for (size_t i = 0; i < m_sensorsNum; i++) + { + m_laser_data.push_back(std::numeric_limits::infinity()); + } + } + else if (m_test_mode == USE_CONSTANT_VALUE) + { + for (size_t i = 0; i < m_sensorsNum; i++) + { + m_laser_data.push_back(m_const_value); + } + } + else if (m_test_mode == USE_MAPFILE || + m_test_mode == USE_SQUARE_TRAP) + { + m_robot_loc_x = _encoders[0];//loc.x; + m_robot_loc_y = _encoders[1];//loc.y; + m_robot_loc_t = _encoders[2];//loc.theta; + + for (size_t i = 0; i < m_sensorsNum; i++) + { + //compute the ray in the robot reference frame + double ray_angle = i * m_resolution + m_min_angle; + double ray_target_x = m_max_distance * cos(ray_angle * DEG2RAD); + double ray_target_y = m_max_distance * sin(ray_angle * DEG2RAD); + + //transforms the ray from the robot to the world reference frame + XYWorld ray_world; + ray_world.x = ray_target_x * cos(m_robot_loc_t * DEG2RAD) - ray_target_y * sin(m_robot_loc_t * DEG2RAD) + m_robot_loc_x; + ray_world.y = ray_target_x * sin(m_robot_loc_t * DEG2RAD) + ray_target_y * cos(m_robot_loc_t * DEG2RAD) + m_robot_loc_y; + XYCell src = m_map.world2Cell(XYWorld(m_robot_loc_x, m_robot_loc_y)); + + //beware! src is the robot position and it is always inside the image. + //dst is the end of the ray, and it can be out of the image! + //for this reason i am not going to call world2Cell() on dst, because that functions clips the point to the border without + //knowing the angular coefficient of the ray. I thus need the unclipped value, and run the LiangBarsky algorithm + //(which knows the angular coefficient of the ray) on it. + XYWorld ray_world_rot; + XYCell_unbounded dst; + ray_world_rot.x = ray_world.x * m_map.m_origin.get_ca() - ray_world.y * m_map.m_origin.get_sa(); + ray_world_rot.y = ray_world.x * m_map.m_origin.get_sa() + ray_world.y * m_map.m_origin.get_ca(); + dst.x = int((+ray_world_rot.x - this->m_map.m_origin.get_x()) / this->m_map.m_resolution) + 0; + dst.y = int((-ray_world_rot.y + this->m_map.m_origin.get_y()) / this->m_map.m_resolution) + (int)m_map.m_height - 1; + + XYCell newsrc; + XYCell newdst; + double distance; + if (LiangBarsky_clip(0, (int)m_map.width(), 0, (int)m_map.height(), + XYCell_unbounded(src.x, src.y), dst, newsrc, newdst)) + { + distance = checkStraightLine(src, newdst); + double simulated_noise = (*m_dis)(*m_gen); + m_laser_data.push_back(distance + simulated_noise); + } + else + { + //This should never happen, unless the robot is outside the map! + yDebug() << "Robot is outside the map?!"; + m_laser_data.push_back(std::numeric_limits::infinity()); + } + + } + } + + //set the device status + m_device_status = yarp::dev::IRangefinder2D::DEVICE_OK_IN_USE; + + return true; +} diff --git a/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp b/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp index a3f29dcc6d5..20e53aae535 100644 --- a/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp +++ b/src/devices/fakeLaserWithMotor/tests/fakeLaserWithMotorTest.cpp @@ -4,10 +4,12 @@ */ #include +#include #include #include #include #include +#include #include #include @@ -16,9 +18,9 @@ using namespace yarp::dev; using namespace yarp::sig; using namespace yarp::os; -TEST_CASE("dev::FakeLaserTest", "[yarp::dev]") +TEST_CASE("dev::FakeLaserWithMotorTest", "[yarp::dev]") { - YARP_REQUIRE_PLUGIN("fakeLaser", "device"); + YARP_REQUIRE_PLUGIN("fakeLaserWithMotor", "device"); Network::setLocalMode(true); @@ -26,19 +28,22 @@ TEST_CASE("dev::FakeLaserTest", "[yarp::dev]") { PolyDriver fakelaserdev; IRangefinder2D* irng = nullptr; + IPositionControl* ipos = nullptr; ////////"Checking opening polydriver" { Property las_cfg; - las_cfg.put("device", "fakeLaser"); + las_cfg.put("device", "fakeLaserWithMotor"); las_cfg.put("test", "use_constant"); las_cfg.put("const_distance", 0.5); REQUIRE(fakelaserdev.open(las_cfg)); REQUIRE(fakelaserdev.view(irng)); + REQUIRE(fakelaserdev.view(ipos)); } //execute tests yarp::dev::tests::exec_iRangefinder2D_test_1(irng); + yarp::dev::tests::exec_iPositionControl_test_1(ipos); //"Close all polydrivers and check" CHECK(fakelaserdev.close()); diff --git a/src/devices/laserFromExternalPort/laserFromExternalPort.cpp b/src/devices/laserFromExternalPort/laserFromExternalPort.cpp index 519a5c21e61..37d8f5f1b94 100644 --- a/src/devices/laserFromExternalPort/laserFromExternalPort.cpp +++ b/src/devices/laserFromExternalPort/laserFromExternalPort.cpp @@ -34,16 +34,16 @@ using namespace yarp::dev; YARP_LOG_COMPONENT(LASER_FROM_EXTERNAL_PORT, "yarp.devices.laserFromExternalPort") /* -yarpdev --device Rangefinder2DWrapper --subdevice laserFromExternalPort \ +yarpdev --device rangefinder2D_nws_yarp --subdevice laserFromExternalPort \ --SENSOR::input_ports_name "(/port1 /port2)" \ --TRANSFORM_CLIENT::local /LaserFromExternalPort/tfClient \ --TRANSFORM_CLIENT::remote /transformServer \ --TRANSFORMS::src_frames "(/frame1 /frame2)" \ --TRANSFORMS::dst_frame /output_frame ---period 10 \ +--period 0.01 \ --name /outlaser:o -yarpdev --device Rangefinder2DWrapper --subdevice laserFromExternalPort \ +yarpdev --device rangefinder2D_nws_yarp --subdevice laserFromExternalPort \ --SENSOR::min_angle 0 --SENSOR::max_angle 360 --SENSOR::resolution 0.5 @@ -52,7 +52,7 @@ yarpdev --device Rangefinder2DWrapper --subdevice laserFromExternalPort \ --TRANSFORM_CLIENT::remote /transformServer \ --TRANSFORMS::src_frames "(/frame1 /frame2)" \ --TRANSFORMS::dst_frame /output_frame ---period 10 \ +--period 0.01 \ --name /outlaser:o */ diff --git a/src/devices/laserFromPointCloud/laserFromPointCloud.cpp b/src/devices/laserFromPointCloud/laserFromPointCloud.cpp index fc01be07a6c..07f9d5e9d68 100644 --- a/src/devices/laserFromPointCloud/laserFromPointCloud.cpp +++ b/src/devices/laserFromPointCloud/laserFromPointCloud.cpp @@ -33,7 +33,7 @@ YARP_LOG_COMPONENT(LASER_FROM_POINTCLOUD, "yarp.devices.laserFromPointCloud") /* -yarpdev --device Rangefinder2DWrapper --subdevice laserFromPointCloud \ +yarpdev --device rangefinder2D_nws_yarp --subdevice laserFromPointCloud \ --ROS::useROS true --ROS::ROS_nodeName /cer-laserFront \ --ROS::ROS_topicName /laserDepth --ROS::frame_id /mobile_base_lidar_F \ --SENSOR \ @@ -50,7 +50,7 @@ yarpdev --device Rangefinder2DWrapper --subdevice laserFromPointCloud \ --Z_CLIPPING_PLANES::camera_frame_id depth_center \ --Z_CLIPPING_PLANES::ground_frame_id ground_link \ --publish_ROS_pointcloud \ - --period 10 \ + --period 0.10 \ --name /outlaser:o */ diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h index 965c1af725e..c77d1f39a47 100644 --- a/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h +++ b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h @@ -17,6 +17,8 @@ namespace yarp::dev::tests { inline void exec_iRangefinder2D_test_1(IRangefinder2D* irf) { + REQUIRE(irf != nullptr); + bool b; std::string info; From 8bed4fe0021bc04ddb1ff10d66ddef4a279e2f87 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 25 Nov 2022 20:05:42 +0100 Subject: [PATCH 048/267] added Changelog --- doc/release/master/fakeLaserWithMotor.md | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 doc/release/master/fakeLaserWithMotor.md diff --git a/doc/release/master/fakeLaserWithMotor.md b/doc/release/master/fakeLaserWithMotor.md new file mode 100644 index 00000000000..6cd3893abbe --- /dev/null +++ b/doc/release/master/fakeLaserWithMotor.md @@ -0,0 +1,6 @@ +fakeLaserWithMotor {#master} +----------- + +### `devices` + +* added new device `fakeLaserWithMotor` From 950c95949427aa8753f3a111c20cbdd9a65200dd Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 23 Nov 2022 21:06:49 +0100 Subject: [PATCH 049/267] addes tests for: FakeFrameGrabber, frameGrabberCropper, frameGrabber_nws_yarp, frameGrabber_nwc_yarp, grabberDual --- .../ServerFrameGrabberDual/CMakeLists.txt | 5 + .../tests/CMakeLists.txt | 41 ++++ .../tests}/grabberDualTest.cpp | 0 src/devices/fakeFrameGrabber/CMakeLists.txt | 5 + .../fakeFrameGrabber/tests/CMakeLists.txt | 41 ++++ .../tests/fakeFrameGrabberTest.cpp | 74 +++++++ .../frameGrabberCropper/CMakeLists.txt | 5 + .../frameGrabberCropper/tests/CMakeLists.txt | 41 ++++ .../tests}/frameGrabberCropperTest.cpp | 0 .../frameGrabber_nws_yarp/CMakeLists.txt | 5 + .../tests/CMakeLists.txt | 41 ++++ .../tests/frameGrabber_nws_yarpTest.cpp | 115 +++++++++++ src/libYARP_dev/src/CMakeLists.txt | 4 + .../yarp/dev/tests/IFrameGrabberImageTest.cpp | 6 + .../yarp/dev/tests/IFrameGrabberImageTest.h | 63 ++++++ .../yarp/dev/tests/IRgbVisualParamsTest.cpp | 6 + .../src/yarp/dev/tests/IRgbVisualParamsTest.h | 105 ++++++++++ tests/libYARP_dev/CMakeLists.txt | 4 - tests/libYARP_dev/fakeFrameGrabberTest.cpp | 177 ----------------- .../libYARP_dev/frameGrabber_nws_yarpTest.cpp | 182 ------------------ 20 files changed, 557 insertions(+), 363 deletions(-) create mode 100644 src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/ServerFrameGrabberDual/tests}/grabberDualTest.cpp (100%) create mode 100644 src/devices/fakeFrameGrabber/tests/CMakeLists.txt create mode 100644 src/devices/fakeFrameGrabber/tests/fakeFrameGrabberTest.cpp create mode 100644 src/devices/frameGrabberCropper/tests/CMakeLists.txt rename {tests/libYARP_dev => src/devices/frameGrabberCropper/tests}/frameGrabberCropperTest.cpp (100%) create mode 100644 src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt create mode 100644 src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.h create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.h delete mode 100644 tests/libYARP_dev/fakeFrameGrabberTest.cpp delete mode 100644 tests/libYARP_dev/frameGrabber_nws_yarpTest.cpp diff --git a/src/devices/ServerFrameGrabberDual/CMakeLists.txt b/src/devices/ServerFrameGrabberDual/CMakeLists.txt index 273bcc2018d..b5c91e805f6 100644 --- a/src/devices/ServerFrameGrabberDual/CMakeLists.txt +++ b/src/devices/ServerFrameGrabberDual/CMakeLists.txt @@ -47,4 +47,9 @@ if(NOT SKIP_grabberDual) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_grabberDual PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt b/src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt new file mode 100644 index 00000000000..8cd6b0dbd66 --- /dev/null +++ b/src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_grabberDual) + +target_sources(harness_dev_grabberDual + PRIVATE + grabberDualTest.cpp +) + +target_link_libraries(harness_dev_grabberDual + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_grabberDual PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_grabberDual) diff --git a/tests/libYARP_dev/grabberDualTest.cpp b/src/devices/ServerFrameGrabberDual/tests/grabberDualTest.cpp similarity index 100% rename from tests/libYARP_dev/grabberDualTest.cpp rename to src/devices/ServerFrameGrabberDual/tests/grabberDualTest.cpp diff --git a/src/devices/fakeFrameGrabber/CMakeLists.txt b/src/devices/fakeFrameGrabber/CMakeLists.txt index 1d10c8237ec..446414a74a0 100644 --- a/src/devices/fakeFrameGrabber/CMakeLists.txt +++ b/src/devices/fakeFrameGrabber/CMakeLists.txt @@ -52,4 +52,9 @@ if(ENABLE_fakeFrameGrabber) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeFrameGrabber PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeFrameGrabber/tests/CMakeLists.txt b/src/devices/fakeFrameGrabber/tests/CMakeLists.txt new file mode 100644 index 00000000000..f964d31234e --- /dev/null +++ b/src/devices/fakeFrameGrabber/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeFrameGrabber) + +target_sources(harness_dev_fakeFrameGrabber + PRIVATE + fakeFrameGrabberTest.cpp +) + +target_link_libraries(harness_dev_fakeFrameGrabber + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_fakeFrameGrabber PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeFrameGrabber) diff --git a/src/devices/fakeFrameGrabber/tests/fakeFrameGrabberTest.cpp b/src/devices/fakeFrameGrabber/tests/fakeFrameGrabberTest.cpp new file mode 100644 index 00000000000..1ee24f08fd5 --- /dev/null +++ b/src/devices/fakeFrameGrabber/tests/fakeFrameGrabberTest.cpp @@ -0,0 +1,74 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::sig; + + +TEST_CASE("dev::fakeFrameGrabberTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); + + Network::setLocalMode(true); + + SECTION("Test the IFrameGrabberImage interface") + { + // Open the device + PolyDriver dd; + Property p; + p.put("device", "fakeFrameGrabber"); + REQUIRE(dd.open(p)); + + // Get the IFrameGrabberImage interface + IFrameGrabberImage* iFrameGrabberImage = nullptr; + REQUIRE(dd.view(iFrameGrabberImage)); + + yarp::dev::tests::exec_IFrameGrabberImage_test_1(iFrameGrabberImage); + + // Close the device + CHECK(dd.close()); + } + + + SECTION("Test the IRgbVisualParams interface") + { + // Open the device + PolyDriver dd; + Property p; + p.put("device","fakeFrameGrabber"); + REQUIRE(dd.open(p)); + + // Get the IRgbVisualParams interface + IRgbVisualParams* rgbParams = nullptr; + REQUIRE(dd.view(rgbParams)); + + yarp::dev::tests::exec_IRgbVisualParams_test_1(rgbParams); + + // Close the device + CHECK(dd.close()); // client close reported successful + } + + // TODO Add tests for the other interfaces + + Network::setLocalMode(false); +} diff --git a/src/devices/frameGrabberCropper/CMakeLists.txt b/src/devices/frameGrabberCropper/CMakeLists.txt index e8726779051..32ed7ea6119 100644 --- a/src/devices/frameGrabberCropper/CMakeLists.txt +++ b/src/devices/frameGrabberCropper/CMakeLists.txt @@ -43,4 +43,9 @@ if(NOT SKIP_frameGrabberCropper) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_frameGrabberCropper PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/frameGrabberCropper/tests/CMakeLists.txt b/src/devices/frameGrabberCropper/tests/CMakeLists.txt new file mode 100644 index 00000000000..2c56727fbfd --- /dev/null +++ b/src/devices/frameGrabberCropper/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_frameGrabberCropper) + +target_sources(harness_dev_frameGrabberCropper + PRIVATE + frameGrabberCropperTest.cpp +) + +target_link_libraries(harness_dev_frameGrabberCropper + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_frameGrabberCropper PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_frameGrabberCropper) diff --git a/tests/libYARP_dev/frameGrabberCropperTest.cpp b/src/devices/frameGrabberCropper/tests/frameGrabberCropperTest.cpp similarity index 100% rename from tests/libYARP_dev/frameGrabberCropperTest.cpp rename to src/devices/frameGrabberCropper/tests/frameGrabberCropperTest.cpp diff --git a/src/devices/frameGrabber_nws_yarp/CMakeLists.txt b/src/devices/frameGrabber_nws_yarp/CMakeLists.txt index d797b3dd7d0..10411af280e 100644 --- a/src/devices/frameGrabber_nws_yarp/CMakeLists.txt +++ b/src/devices/frameGrabber_nws_yarp/CMakeLists.txt @@ -46,4 +46,9 @@ if(NOT SKIP_frameGrabber_nws_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_frameGrabber_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt b/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..657f7f3b284 --- /dev/null +++ b/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_frameGrabber_nws_yarp) + +target_sources(harness_dev_frameGrabber_nws_yarp + PRIVATE + frameGrabber_nws_yarpTest.cpp +) + +target_link_libraries(harness_dev_frameGrabber_nws_yarp + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_frameGrabber_nws_yarp PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_frameGrabber_nws_yarp) diff --git a/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp b/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp new file mode 100644 index 00000000000..5dbd23adb06 --- /dev/null +++ b/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp @@ -0,0 +1,115 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::sig; + + +TEST_CASE("dev::frameGrabber_nws_yarpTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); + YARP_REQUIRE_PLUGIN("frameGrabber_nwc_yarp", "device"); + YARP_REQUIRE_PLUGIN("frameGrabber_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Test the grabber wrapper") + { + PolyDriver dd; + PolyDriver dd2; + Property p; + Property p2; + p.put("device","frameGrabber_nwc_yarp"); + p.put("remote","/grabber"); + p.put("local","/grabber/client"); + + p2.put("device","frameGrabber_nws_yarp"); + p2.put("subdevice","fakeFrameGrabber"); + + REQUIRE(dd2.open(p2)); // server open reported successful + REQUIRE(dd.open(p)); // client open reported successful + + IFrameGrabberImage *grabber = nullptr; + REQUIRE(dd.view(grabber)); // interface reported + + yarp::os::SystemClock::delaySystem(0.5); + + ImageOf img; + grabber->getImage(img); + CHECK(img.width() > 0); // interface seems functional + CHECK(dd2.close()); // server close reported successful + CHECK(dd.close()); // client close reported successful + } + + SECTION("Test the IRgbVisualParams interface") + { + // Try to open a FakeFrameGrabber and I check all the parameters + PolyDriver dd; + PolyDriver dd2; + Property p; + Property p2; + Property intrinsics; + Bottle* retM = nullptr; + + p.put("device","frameGrabber_nwc_yarp"); + p.put("remote","/grabber"); + p.put("local","/grabber/client"); + p.put("no_stream", 1); + + p2.put("device","frameGrabber_nws_yarp"); + p2.put("subdevice","fakeFrameGrabber"); + + REQUIRE(dd2.open(p2)); // server open reported successful + REQUIRE(dd.open(p)); // client open reported successful + + IFrameGrabberImage* igrabber = nullptr; + IRgbVisualParams* irgbParams = nullptr; + REQUIRE(dd.view(igrabber)); // interface rgb params reported + REQUIRE(dd.view(irgbParams)); // interface rgb params reported + + yarp::dev::tests::exec_IFrameGrabberImage_test_1(igrabber); + yarp::dev::tests::exec_IRgbVisualParams_test_1(irgbParams); + + // Test the crop function - must work. + IFrameGrabberImage *grabber = nullptr; + REQUIRE(dd.view(grabber)); + ImageOf img; + ImageOf crop; + grabber->getImage(img); + + yarp::sig::VectorOf> vertices; + vertices.resize(2); + vertices[0] = std::pair (0, 0); + vertices[1] = std::pair (10, 10); // Configure a doable crop. + + // check crop function + CHECK(grabber->getImageCrop(YARP_CROP_RECT, vertices, crop)); + CHECK(crop.width() > 0); + CHECK(crop.height() > 0); + + CHECK(dd2.close()); // server close reported successful + CHECK(dd.close()); // client close reported successful + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index d4e99d8dd6d..8af4eec60c3 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -400,6 +400,10 @@ add_library(YARP::YARP_dev_tests ALIAS YARP_dev_tests) if(TARGET YARP::YARP_math) target_sources(YARP_dev_tests PRIVATE + yarp/dev/tests/IFrameGrabberImageTest.cpp + yarp/dev/tests/IFrameGrabberImageTest.h + yarp/dev/tests/IRgbVisualParamsTest.cpp + yarp/dev/tests/IRgbVisualParamsTest.h yarp/dev/tests/IFrameTransformTest.cpp yarp/dev/tests/IFrameTransformTest.h yarp/dev/tests/IMap2DTest.cpp diff --git a/src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.cpp new file mode 100644 index 00000000000..a5426725560 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IFrameGrabberImageTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.h b/src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.h new file mode 100644 index 00000000000..49b2019e6db --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IFrameGrabberImageTest.h @@ -0,0 +1,63 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IFRAMEGRABBERIMAGETEST_H +#define IFRAMEGRABBERIMAGETEST_H + +#include +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + constexpr int default_height = 240; + constexpr int default_width = 320; + constexpr double default_hfov = 1.0; + constexpr double default_vfov = 2.0; + constexpr double default_physFocalLength = 3.0; + constexpr double default_focalLengthX = 4.0; + constexpr double default_focalLengthY = 5.0; + constexpr double default_principalPointX = 6.0; + constexpr double default_principalPointY = 7.0; + constexpr double default_k1 = 8.0; + constexpr double default_k2 = 9.0; + constexpr double default_k3 = 10.0; + constexpr double default_t1 = 11.0; + constexpr double default_t2 = 12.0; + const std::string default_distortionModel = "FishEye"; + constexpr std::array default_rectificationMatrix = { 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 }; + + constexpr size_t crop_h = 24; + constexpr size_t crop_w = 32; + + const yarp::sig::VectorOf> vertices{ {0, 0}, {crop_w - 1, crop_h - 1} }; + + inline void exec_IFrameGrabberImage_test_1(IFrameGrabberImage* iframe) + { + // Check width() + CHECK(iframe->width() == default_width); + + // Check height() + CHECK(iframe->height() == default_height); + + // Check getImage() + ImageOf img; + iframe->getImage(img); + CHECK(img.width() == default_width); + CHECK(img.height() == default_height); + + // Check getImageCrop() + ImageOf crop; + CHECK(iframe->getImageCrop(YARP_CROP_RECT, vertices, crop)); + CHECK(crop.width() == crop_w); + CHECK(crop.height() == crop_h); + } +} + +#endif diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.cpp new file mode 100644 index 00000000000..9bcb9c56c9e --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IRgbVisualParamsTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.h b/src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.h new file mode 100644 index 00000000000..58cdd151f5a --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IRgbVisualParamsTest.h @@ -0,0 +1,105 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IRGBVISUALPARAMSTEST_H +#define IRGBVISUALPARAMSTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + const std::vector default_configurations = { + { 128, 128, 60.0, VOCAB_PIXEL_RGB }, + { 256, 256, 30.0, VOCAB_PIXEL_BGR }, + { 512, 512, 15.0, VOCAB_PIXEL_MONO } + }; + + inline void exec_IRgbVisualParams_test_1(IRgbVisualParams* irgb) + { + // check the default parameters + + // checking fov + double hfov = 0.0; + double vfov = 0.0; + irgb->getRgbFOV(hfov, vfov); + CHECK(hfov == 1.0); + CHECK(vfov == 2.0); + + // checking height + CHECK(irgb->getRgbHeight() == 240); + + // checking width + CHECK(irgb->getRgbWidth() == 320); + + // checking mirroring + bool rgbMirroring; + irgb->getRgbMirroring(rgbMirroring); + CHECK_FALSE(rgbMirroring); + + // checking intrinsics + yarp::os::Property intrinsics; + irgb->getRgbIntrinsicParam(intrinsics); + CHECK(intrinsics.find("focalLengthX").asFloat64() == 4.0); // checking focalLength X + CHECK(intrinsics.find("focalLengthY").asFloat64() == 5.0); // checking focalLength Y + CHECK(intrinsics.find("principalPointX").asFloat64() == 6.0); // checking principalPoint X + CHECK(intrinsics.find("principalPointY").asFloat64() == 7.0); // checking principalPoint Y + CHECK(intrinsics.find("k1").asFloat64() == 8.0); // checking k1 + CHECK(intrinsics.find("k2").asFloat64() == 9.0); // checking k2 + CHECK(intrinsics.find("k3").asFloat64() == 10.0); // checking k3 + CHECK(intrinsics.find("t1").asFloat64() == 11.0); // checking t1 + CHECK(intrinsics.find("t2").asFloat64() == 12.0); // checking t2 + CHECK(intrinsics.find("distortionModel").asString() == "FishEye"); // checking distorionModel + + // checking the rectificationMatrix + yarp::os::Bottle* retM = nullptr; + retM = intrinsics.find("rectificationMatrix").asList(); + double data[9] = { 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 }; + Vector v(9, data); + Vector v2; + Portable::copyPortable(*retM, v2); + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + CHECK(retM->get(i * 3 + j).asFloat64() == v(i * 3 + j)); + CHECK(v2(i * 3 + j) == v(i * 3 + j)); + } + } + + // checking getRgbResolution + int height, width; + irgb->getRgbResolution(width, height); + CHECK(width == 320); + CHECK(height == 240); + + // checking configurations size + VectorOf configurations; + CHECK(irgb->getRgbSupportedConfigurations(configurations)); + CHECK(configurations.size() == 3); + + // checking first supported configuration + CHECK(configurations[0].height == 128); + CHECK(configurations[0].width == 128); + CHECK(configurations[0].framerate == 60.0); + CHECK(configurations[0].pixelCoding == VOCAB_PIXEL_RGB); + + // checking second supported configuration + CHECK(configurations[1].height == 256); + CHECK(configurations[1].width == 256); + CHECK(configurations[1].framerate == 30.0); + CHECK(configurations[1].pixelCoding == VOCAB_PIXEL_BGR); + + // checking third supported configuration + CHECK(configurations[2].height == 512); + CHECK(configurations[2].width == 512); + CHECK(configurations[2].framerate == 15.0); + CHECK(configurations[2].pixelCoding == VOCAB_PIXEL_MONO); + } +} + +#endif diff --git a/tests/libYARP_dev/CMakeLists.txt b/tests/libYARP_dev/CMakeLists.txt index e1580e74a0b..23a4acc66c9 100644 --- a/tests/libYARP_dev/CMakeLists.txt +++ b/tests/libYARP_dev/CMakeLists.txt @@ -6,10 +6,6 @@ target_sources(harness_dev PRIVATE MapGrid2DTest.cpp PolyDriverTest.cpp - fakeFrameGrabberTest.cpp - frameGrabberCropperTest.cpp - frameGrabber_nws_yarpTest.cpp - grabberDualTest.cpp ) target_link_libraries(harness_dev diff --git a/tests/libYARP_dev/fakeFrameGrabberTest.cpp b/tests/libYARP_dev/fakeFrameGrabberTest.cpp deleted file mode 100644 index 1d6a721e280..00000000000 --- a/tests/libYARP_dev/fakeFrameGrabberTest.cpp +++ /dev/null @@ -1,177 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include - -#include -#include -#include -#include -#include - -#include -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - - -TEST_CASE("dev::fakeFrameGrabberTest", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); - - Network::setLocalMode(true); - - constexpr int default_height = 240; - constexpr int default_width = 320; - constexpr double default_hfov = 1.0; - constexpr double default_vfov = 2.0; - constexpr double default_physFocalLength = 3.0; - constexpr double default_focalLengthX = 4.0; - constexpr double default_focalLengthY = 5.0; - constexpr double default_principalPointX = 6.0; - constexpr double default_principalPointY = 7.0; - constexpr double default_k1 = 8.0; - constexpr double default_k2 = 9.0; - constexpr double default_k3 = 10.0; - constexpr double default_t1 = 11.0; - constexpr double default_t2 = 12.0; - const std::string default_distortionModel = "FishEye"; - constexpr std::array default_rectificationMatrix = {1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0}; - const std::vector default_configurations = { - { 128, 128, 60.0, VOCAB_PIXEL_RGB }, - { 256, 256, 30.0, VOCAB_PIXEL_BGR }, - { 512, 512, 15.0, VOCAB_PIXEL_MONO } - }; - - constexpr size_t crop_h = 24; - constexpr size_t crop_w = 32; - - const yarp::sig::VectorOf> vertices {{0, 0}, {crop_w - 1, crop_h - 1}}; - - SECTION("Test the IFrameGrabberImage interface") - { - // Open the device - PolyDriver dd; - Property p; - p.put("device", "fakeFrameGrabber"); - REQUIRE(dd.open(p)); - - // Get the IFrameGrabberImage interface - IFrameGrabberImage* iFrameGrabberImage = nullptr; - REQUIRE(dd.view(iFrameGrabberImage)); - - // Check width() - CHECK(iFrameGrabberImage->width() == default_width); - - // Check height() - CHECK(iFrameGrabberImage->height() == default_height); - - // Check getImage() - ImageOf img; - iFrameGrabberImage->getImage(img); - CHECK(img.width() == default_width); - CHECK(img.height() == default_height); - - // Check getImageCrop() - ImageOf crop; - CHECK(iFrameGrabberImage->getImageCrop(YARP_CROP_RECT, vertices, crop)); - CHECK(crop.width() == crop_w); - CHECK(crop.height() == crop_h); - - // Close the device - CHECK(dd.close()); - } - - - SECTION("Test the IRgbVisualParams interface") - { - // Open the device - PolyDriver dd; - Property p; - p.put("device","fakeFrameGrabber"); - REQUIRE(dd.open(p)); - - // Get the IRgbVisualParams interface - IRgbVisualParams* rgbParams = nullptr; - REQUIRE(dd.view(rgbParams)); - - // Check getRgbFOV() - double hfov; - double vfov; - rgbParams->getRgbFOV(hfov, vfov); - CHECK(hfov == default_hfov); - CHECK(vfov == default_vfov); - - // Check getRgbHeight() and getRgbWidth() - CHECK(rgbParams->getRgbWidth() == default_width); - CHECK(rgbParams->getRgbHeight() == default_height); - - // Check getRgbMirroring() - bool rgbMirroring; - rgbParams->getRgbMirroring(rgbMirroring); - CHECK_FALSE(rgbMirroring); - - // Check getRgbIntrinsicParam() - Property intrinsics; - rgbParams->getRgbIntrinsicParam(intrinsics); - CHECK(intrinsics.find("physFocalLength").asFloat64() == default_physFocalLength); - CHECK(intrinsics.find("focalLengthX").asFloat64() == default_focalLengthX); - CHECK(intrinsics.find("focalLengthY").asFloat64() == default_focalLengthY); - CHECK(intrinsics.find("principalPointX").asFloat64() == default_principalPointX); - CHECK(intrinsics.find("principalPointY").asFloat64() == default_principalPointY); - CHECK(intrinsics.find("k1").asFloat64() == default_k1); - CHECK(intrinsics.find("k2").asFloat64() == default_k2); - CHECK(intrinsics.find("k3").asFloat64() == default_k3); - CHECK(intrinsics.find("t1").asFloat64() == default_t1); - CHECK(intrinsics.find("t2").asFloat64() == default_t2); - CHECK(intrinsics.find("distortionModel").asString() == default_distortionModel); - Bottle* retMat = intrinsics.find("rectificationMatrix").asList(); - for(int i=0; i<3; i++) { - for(int j=0; j<3; j++) { - CHECK(retMat->get(i*3+j).asFloat64() == default_rectificationMatrix[i*3+j]); - } - } - - // Checking getRgbResolution() - int height; - int width; - rgbParams->getRgbResolution(width,height); - CHECK(width == default_width); - CHECK(height == default_height); - - // Check getRgbSupportedConfigurations() - VectorOf configurations; - CHECK(rgbParams->getRgbSupportedConfigurations(configurations)); - CHECK(configurations.size() == 3); - // checking first supported configuration - CHECK(configurations[0].height == default_configurations[0].height); - CHECK(configurations[0].width == default_configurations[0].width); - CHECK(configurations[0].framerate == default_configurations[0].framerate); - CHECK(configurations[0].pixelCoding == default_configurations[0].pixelCoding); - // checking second supported configuration - CHECK(configurations[1].height == default_configurations[1].height); - CHECK(configurations[1].width == default_configurations[1].width); - CHECK(configurations[1].framerate == default_configurations[1].framerate); - CHECK(configurations[1].pixelCoding == default_configurations[1].pixelCoding); - // checking third supported configuration - CHECK(configurations[2].height == default_configurations[2].height); - CHECK(configurations[2].width == default_configurations[2].width); - CHECK(configurations[2].framerate == default_configurations[2].framerate); - CHECK(configurations[2].pixelCoding == default_configurations[2].pixelCoding); - - // Close the device - CHECK(dd.close()); // client close reported successful - } - - // TODO Add tests for the other interfaces - - Network::setLocalMode(false); -} diff --git a/tests/libYARP_dev/frameGrabber_nws_yarpTest.cpp b/tests/libYARP_dev/frameGrabber_nws_yarpTest.cpp deleted file mode 100644 index 2253a33baa1..00000000000 --- a/tests/libYARP_dev/frameGrabber_nws_yarpTest.cpp +++ /dev/null @@ -1,182 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include - -#include -#include -#include -#include -#include - -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - - -TEST_CASE("dev::frameGrabber_nws_yarpTest", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); - YARP_REQUIRE_PLUGIN("frameGrabber_nwc_yarp", "device"); - YARP_REQUIRE_PLUGIN("frameGrabber_nws_yarp", "device"); - - Network::setLocalMode(true); - - SECTION("Test the grabber wrapper") - { - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - p.put("device","frameGrabber_nwc_yarp"); - p.put("remote","/grabber"); - p.put("local","/grabber/client"); - - p2.put("device","frameGrabber_nws_yarp"); - p2.put("subdevice","fakeFrameGrabber"); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); // interface reported - - yarp::os::SystemClock::delaySystem(0.5); - - ImageOf img; - grabber->getImage(img); - CHECK(img.width() > 0); // interface seems functional - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } - - SECTION("Test the IRgbVisualParams interface") - { - // Try to open a FakeFrameGrabber and I check all the parameters - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - Property intrinsics; - Bottle* retM = nullptr; - - p.put("device","frameGrabber_nwc_yarp"); - p.put("remote","/grabber"); - p.put("local","/grabber/client"); - p.put("no_stream", 1); - - p2.put("device","frameGrabber_nws_yarp"); - p2.put("subdevice","fakeFrameGrabber"); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IRgbVisualParams* rgbParams = nullptr; - REQUIRE(dd.view(rgbParams)); // interface rgb params reported - - // check the default parameters - - // checking fov - double hfov=0.0; - double vfov=0.0; - rgbParams->getRgbFOV(hfov,vfov); - CHECK(hfov == 1.0); - CHECK(vfov == 2.0); - - // checking height - CHECK(rgbParams->getRgbHeight() == 240); - - // checking width - CHECK(rgbParams->getRgbWidth() == 320); - - // checking mirroring - bool rgbMirroring; - rgbParams->getRgbMirroring(rgbMirroring); - CHECK_FALSE(rgbMirroring); - - // checking intrinsics - rgbParams->getRgbIntrinsicParam(intrinsics); - CHECK(intrinsics.find("focalLengthX").asFloat64() == 4.0); // checking focalLength X - CHECK(intrinsics.find("focalLengthY").asFloat64() == 5.0); // checking focalLength Y - CHECK(intrinsics.find("principalPointX").asFloat64() == 6.0); // checking principalPoint X - CHECK(intrinsics.find("principalPointY").asFloat64() == 7.0); // checking principalPoint Y - CHECK(intrinsics.find("k1").asFloat64() == 8.0); // checking k1 - CHECK(intrinsics.find("k2").asFloat64() == 9.0); // checking k2 - CHECK(intrinsics.find("k3").asFloat64() == 10.0); // checking k3 - CHECK(intrinsics.find("t1").asFloat64() == 11.0); // checking t1 - CHECK(intrinsics.find("t2").asFloat64() == 12.0); // checking t2 - CHECK(intrinsics.find("distortionModel").asString() == "FishEye"); // checking distorionModel - - // checking the rectificationMatrix - retM = intrinsics.find("rectificationMatrix").asList(); - double data[9]= {1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0}; - Vector v(9,data); - Vector v2; - Portable::copyPortable(*retM,v2); - for(int i=0; i<3; i++) { - for(int j=0; j<3; j++) { - CHECK(retM->get(i*3+j).asFloat64() == v(i*3+j)); - CHECK(v2(i*3+j) == v(i*3+j)); - } - } - - // checking getRgbResolution - int height, width; - rgbParams->getRgbResolution(width,height); - CHECK(width==320); - CHECK(height==240); - - // checking configurations size - VectorOf configurations; - CHECK(rgbParams->getRgbSupportedConfigurations(configurations)); - CHECK(configurations.size() == 3); - - // checking first supported configuration - CHECK(configurations[0].height == 128); - CHECK(configurations[0].width == 128); - CHECK(configurations[0].framerate == 60.0); - CHECK(configurations[0].pixelCoding == VOCAB_PIXEL_RGB); - - // checking second supported configuration - CHECK(configurations[1].height == 256); - CHECK(configurations[1].width == 256); - CHECK(configurations[1].framerate == 30.0); - CHECK(configurations[1].pixelCoding == VOCAB_PIXEL_BGR); - - // checking third supported configuration - CHECK(configurations[2].height == 512); - CHECK(configurations[2].width == 512); - CHECK(configurations[2].framerate == 15.0); - CHECK(configurations[2].pixelCoding == VOCAB_PIXEL_MONO); - - // Test the crop function - must work. - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); - ImageOf img; - ImageOf crop; - grabber->getImage(img); - - yarp::sig::VectorOf> vertices; - vertices.resize(2); - vertices[0] = std::pair (0, 0); - vertices[1] = std::pair (10, 10); // Configure a doable crop. - - // check crop function - CHECK(grabber->getImageCrop(YARP_CROP_RECT, vertices, crop)); - CHECK(crop.width() > 0); - CHECK(crop.height() > 0); - - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } - - Network::setLocalMode(false); -} From fceb27ea0eae3b76f038a49465dd7de658d4a55a Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 16:32:27 +0100 Subject: [PATCH 050/267] The following devices `grabberDual` and `remote_grabber`, previously deprecated, have been removed from yarp. --- src/devices/CMakeLists.txt | 2 - src/devices/RemoteFrameGrabber/CMakeLists.txt | 50 - .../RemoteFrameGrabber/RemoteFrameGrabber.cpp | 20 - .../RemoteFrameGrabber/RemoteFrameGrabber.h | 322 ----- .../ServerFrameGrabberDual/CMakeLists.txt | 55 - .../ServerFrameGrabberDual.cpp | 1248 ----------------- .../ServerFrameGrabberDual.h | 277 ---- .../tests/grabberDualTest.cpp | 402 ------ 8 files changed, 2376 deletions(-) delete mode 100644 src/devices/RemoteFrameGrabber/CMakeLists.txt delete mode 100644 src/devices/RemoteFrameGrabber/RemoteFrameGrabber.cpp delete mode 100644 src/devices/RemoteFrameGrabber/RemoteFrameGrabber.h delete mode 100644 src/devices/ServerFrameGrabberDual/CMakeLists.txt delete mode 100644 src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.cpp delete mode 100644 src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.h delete mode 100644 src/devices/ServerFrameGrabberDual/tests/grabberDualTest.cpp diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index b0784e65803..0c4d1a8b79c 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -81,7 +81,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(fakeLocalizerDevice) add_subdirectory(fakeNavigationDevice) add_subdirectory(ServerSerial) - add_subdirectory(RemoteFrameGrabber) add_subdirectory(RemoteControlBoard) add_subdirectory(AnalogSensorClient) add_subdirectory(AnalogWrapper) @@ -93,7 +92,6 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(ControlBoardRemapper) add_subdirectory(RobotDescriptionClient) add_subdirectory(RobotDescriptionServer) - add_subdirectory(ServerFrameGrabberDual) add_subdirectory(JoypadControlNetUtils) add_subdirectory(JoypadControlClient) add_subdirectory(JoypadControlServer) diff --git a/src/devices/RemoteFrameGrabber/CMakeLists.txt b/src/devices/RemoteFrameGrabber/CMakeLists.txt deleted file mode 100644 index 616f7e42d1f..00000000000 --- a/src/devices/RemoteFrameGrabber/CMakeLists.txt +++ /dev/null @@ -1,50 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(remote_grabber - CATEGORY device - TYPE RemoteFrameGrabber - INCLUDE RemoteFrameGrabber.h - EXTRA_CONFIG - WRAPPER=grabber - DEFAULT ON -) - -if(NOT SKIP_remote_grabber) - yarp_add_plugin(yarp_remote_grabber) - - target_sources(yarp_remote_grabber - PRIVATE - RemoteFrameGrabber.cpp - RemoteFrameGrabber.h - ) - - target_sources(yarp_remote_grabber PRIVATE $) - target_include_directories(yarp_remote_grabber PRIVATE $) - - target_link_libraries(yarp_remote_grabber - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_remote_grabber - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_remote_grabber PROPERTY FOLDER "Plugins/Device") -endif() diff --git a/src/devices/RemoteFrameGrabber/RemoteFrameGrabber.cpp b/src/devices/RemoteFrameGrabber/RemoteFrameGrabber.cpp deleted file mode 100644 index 710718cc1c5..00000000000 --- a/src/devices/RemoteFrameGrabber/RemoteFrameGrabber.cpp +++ /dev/null @@ -1,20 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "RemoteFrameGrabber.h" - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - -YARP_LOG_COMPONENT(REMOTEFRAMEGRABBER, "yarp.devices.RemoteFrameGrabber") - -RemoteFrameGrabber::RemoteFrameGrabber() : - FrameGrabberControls_Forwarder(port), - FrameGrabberControlsDC1394_Forwarder(port), - RgbVisualParams_Forwarder(port) -{ -} diff --git a/src/devices/RemoteFrameGrabber/RemoteFrameGrabber.h b/src/devices/RemoteFrameGrabber/RemoteFrameGrabber.h deleted file mode 100644 index c32acdd6c61..00000000000 --- a/src/devices/RemoteFrameGrabber/RemoteFrameGrabber.h +++ /dev/null @@ -1,322 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_REMOTEFRAMEGRABBER_H -#define YARP_DEV_REMOTEFRAMEGRABBER_H - -#include // for memcpy - -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include - -YARP_DECLARE_LOG_COMPONENT(REMOTEFRAMEGRABBER) - -/** - * @ingroup dev_impl_network_clients - * - * \section remoteFrameGrabber - * - * \brief `remote_grabber`: Connect to a ServerFrameGrabber. See ServerFrameGrabber for - * the network protocol used. - */ -class RemoteFrameGrabber : - public yarp::dev::DeviceDriver, - public yarp::dev::IFrameGrabberImage, - public yarp::proto::framegrabber::FrameGrabberControls_Forwarder, - public yarp::proto::framegrabber::FrameGrabberControlsDC1394_Forwarder, - public yarp::proto::framegrabber::RgbVisualParams_Forwarder -{ -public: - RemoteFrameGrabber(); - RemoteFrameGrabber(const RemoteFrameGrabber&) = delete; - RemoteFrameGrabber(RemoteFrameGrabber&&) = delete; - RemoteFrameGrabber& operator=(const RemoteFrameGrabber&) = delete; - RemoteFrameGrabber& operator=(RemoteFrameGrabber&&) = delete; - ~RemoteFrameGrabber() override = default; - - - bool getImage(yarp::sig::ImageOf& image) override - { - mutex.lock(); - if(no_stream == true) - { - image.zero(); - mutex.unlock(); - return false; - } - - if (reader.read(true)!=nullptr) { - image = *(reader.lastRead()); - lastHeight = image.height(); - lastWidth = image.width(); - mutex.unlock(); - return true; - } - mutex.unlock(); - return false; - } - - bool getImageCrop(cropType_id_t cropType, yarp::sig::VectorOf > vertices, yarp::sig::ImageOf& image) override - { - yarp::os::Bottle cmd; - yarp::os::Bottle response; - cmd.addVocab32(VOCAB_FRAMEGRABBER_IMAGE); - cmd.addVocab32(VOCAB_GET); - cmd.addVocab32(VOCAB_CROP); - cmd.addInt32(cropType); - yarp::os::Bottle & list = cmd.addList(); - for(size_t i=0; i - * local Port name of this client. - * remote Port name of server to connect to. - * - * - * @param config The options to use - * @return true iff the object could be configured. - */ - bool open(yarp::os::Searchable& config) override - { - yCTrace(REMOTEFRAMEGRABBER); - yCDebug(REMOTEFRAMEGRABBER) << "config is " << config.toString(); - - remote = config.check("remote",yarp::os::Value(""), - "port name of real grabber").asString(); - local = config.check("local",yarp::os::Value("..."), - "port name to use locally").asString(); - std::string carrier = - config.check("stream",yarp::os::Value("tcp"), - "carrier to use for streaming").asString(); - port.open(local); - if (remote!="") { - yCInfo(REMOTEFRAMEGRABBER) << "connecting " << local << " to " << remote; - - if(!config.check("no_stream") ) - { - no_stream = false; - if (!yarp::os::Network::connect(remote, local, carrier)) { - yCError(REMOTEFRAMEGRABBER) << "cannot connect " << local << " to " << remote; - } - } else { - no_stream = true; - } - - // reverse connection for RPC - // could choose to do this only on need - - yarp::os::Network::connect(local,remote); - } - reader.attach(port); - return true; - } - - bool close() override - { - port.close(); -// mutex.lock(); // why does it need this? - return true; - } - -#ifndef YARP_NO_DEPRECATED // Since YARP 3.0.0 - bool setBrightness(double v) override - { - return setCommand(VOCAB_BRIGHTNESS, v); - } - double getBrightness() override - { - return getCommand(VOCAB_BRIGHTNESS); - } - bool setExposure(double v) override - { - return setCommand(VOCAB_EXPOSURE, v); - } - double getExposure() override - { - return getCommand(VOCAB_EXPOSURE); - } - - bool setSharpness(double v) override - { - return setCommand(VOCAB_SHARPNESS, v); - } - double getSharpness() override - { - return getCommand(VOCAB_SHARPNESS); - } - - bool setWhiteBalance(double blue, double red) override - { - return setCommand(VOCAB_WHITE, blue, red); - } - bool getWhiteBalance(double &blue, double &red) override - { - return getCommand(VOCAB_WHITE, blue, red); - } - - bool setHue(double v) override - { - return setCommand(VOCAB_HUE,v); - } - double getHue() override - { - return getCommand(VOCAB_HUE); - } - - bool setSaturation(double v) override - { - return setCommand(VOCAB_SATURATION,v); - } - double getSaturation() override - { - return getCommand(VOCAB_SATURATION); - } - - bool setGamma(double v) override - { - return setCommand(VOCAB_GAMMA,v); - } - double getGamma() override - { - return getCommand(VOCAB_GAMMA); - } - - bool setShutter(double v) override - { - return setCommand(VOCAB_SHUTTER,v); - } - double getShutter() override - { - return getCommand(VOCAB_SHUTTER); - } - - bool setGain(double v) override - { - return setCommand(VOCAB_GAIN,v); - } - double getGain() override - { - return getCommand(VOCAB_GAIN); - } - - bool setIris(double v) override - { - return setCommand(VOCAB_IRIS,v); - } - double getIris() override - { - return getCommand(VOCAB_IRIS); - } -#endif - -private: - yarp::os::PortReaderBuffer > reader; - yarp::os::Port port; - std::string remote; - std::string local; - std::mutex mutex; - int lastHeight{0}; - int lastWidth{0}; - bool no_stream{false}; - -protected: - - IFrameGrabberControlsDC1394 *Ifirewire{nullptr}; - - bool setCommand(int code, double v) - { - yarp::os::Bottle cmd, response; - cmd.addVocab32(VOCAB_FRAMEGRABBER_CONTROL); - cmd.addVocab32(VOCAB_SET); - cmd.addVocab32(code); - cmd.addFloat64(v); - port.write(cmd,response); - return true; - } - - bool setCommand(int code, double b, double r) - { - yarp::os::Bottle cmd, response; - cmd.addVocab32(VOCAB_FRAMEGRABBER_CONTROL); - cmd.addVocab32(VOCAB_SET); - cmd.addVocab32(code); - cmd.addFloat64(b); - cmd.addFloat64(r); - port.write(cmd,response); - return true; - } - - double getCommand(int code) const - { - yarp::os::Bottle cmd, response; - cmd.addVocab32(VOCAB_FRAMEGRABBER_CONTROL); - cmd.addVocab32(VOCAB_GET); - cmd.addVocab32(code); - port.write(cmd,response); - // response should be [cmd] [name] value - return response.get(2).asFloat64(); - } - - bool getCommand(int code, double &b, double &r) const - { - yarp::os::Bottle cmd, response; - cmd.addVocab32(VOCAB_FRAMEGRABBER_CONTROL); - cmd.addVocab32(VOCAB_GET); - cmd.addVocab32(code); - port.write(cmd,response); - // response should be [cmd] [name] value - b=response.get(2).asFloat64(); - r=response.get(3).asFloat64(); - return true; - } -}; - -#endif // YARP_DEV_REMOTEFRAMEGRABBER_H diff --git a/src/devices/ServerFrameGrabberDual/CMakeLists.txt b/src/devices/ServerFrameGrabberDual/CMakeLists.txt deleted file mode 100644 index b5c91e805f6..00000000000 --- a/src/devices/ServerFrameGrabberDual/CMakeLists.txt +++ /dev/null @@ -1,55 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - - -yarp_prepare_plugin(grabberDual - CATEGORY device - TYPE ServerGrabber - INCLUDE ServerFrameGrabberDual.h - EXTRA_CONFIG - WRAPPER=grabberDual - DEFAULT ON -) - -if(NOT SKIP_grabberDual) - yarp_add_plugin(yarp_grabberDual) - - target_sources(yarp_grabberDual - PRIVATE - ServerFrameGrabberDual.cpp - ServerFrameGrabberDual.h - ) - - target_sources(yarp_grabberDual PRIVATE $) - target_include_directories(yarp_grabberDual PRIVATE $) - - target_link_libraries(yarp_grabberDual - PRIVATE - YARP::YARP_os - YARP::YARP_sig - YARP::YARP_dev - ) - list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS - YARP_os - YARP_sig - YARP_dev - ) - - yarp_install( - TARGETS yarp_grabberDual - EXPORT YARP_${YARP_PLUGIN_MASTER} - COMPONENT ${YARP_PLUGIN_MASTER} - LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} - ARCHIVE DESTINATION ${YARP_STATIC_PLUGINS_INSTALL_DIR} - YARP_INI DESTINATION ${YARP_PLUGIN_MANIFESTS_INSTALL_DIR} - ) - - set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - - set_property(TARGET yarp_grabberDual PROPERTY FOLDER "Plugins/Device") - - if(YARP_COMPILE_TESTS) - add_subdirectory(tests) - endif() - -endif() diff --git a/src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.cpp b/src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.cpp deleted file mode 100644 index 9bfb7847c3f..00000000000 --- a/src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.cpp +++ /dev/null @@ -1,1248 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "ServerFrameGrabberDual.h" - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include -#include // std::for_each - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - -namespace { -YARP_LOG_COMPONENT(SERVERGRABBER, "yarp.device.grabberDual") -} - - -// **********ServerGrabberResponder********** - -ServerGrabberResponder::ServerGrabberResponder(bool _left) : - left(_left) -{ -} - -bool ServerGrabberResponder::configure(ServerGrabber* _server) -{ - if(_server) - { - server=_server; - return true; - } - yCError(SERVERGRABBER) << "ServerGrabberResponder: invalid server pointer"; - return false; -} - -bool ServerGrabberResponder::respond(const yarp::os::Bottle &command, yarp::os::Bottle &reply){ - if(server) - { - if(server->respond(command,reply,left,false)) - { - return true; - } - else - { - return DeviceResponder::respond(command, reply); - } - } else { - return false; - } -} - -// **********ServerGrabber********** - -ServerGrabber::ServerGrabber() : - PeriodicThread(DEFAULT_THREAD_PERIOD) -{ -} - -ServerGrabber::~ServerGrabber() -{ - if (param.active) { - close(); - } -} - -bool ServerGrabber::close() { - if (!param.active) { - return false; - } - stopThread(); - - param.active = false; - pImg.interrupt(); - pImg.close(); - rpcPort.interrupt(); - rpcPort.close(); - - if(responder){ - delete responder; - responder=nullptr; - } - - if(param.split) - { - pImg2.interrupt(); - pImg2.close(); - } - - - if(param.twoCameras) - { - rpcPort2.interrupt(); - rpcPort2.close(); - } - - cleanUp(); - if(poly) - { - poly->close(); - delete poly; - poly=nullptr; - } - - if(responder2) - { - delete responder2; - responder2=nullptr; - } - - if(isSubdeviceOwned && poly2) - { - poly2->close(); - delete poly2; - poly2=nullptr; - } - isSubdeviceOwned=false; - if (p2!=nullptr) { - delete p2; - p2 =nullptr; - } - return true; -} - -bool ServerGrabber::open(yarp::os::Searchable& config) { - yCIWarning(SERVERGRABBER, id()) << config.toString(); - yCIWarning(SERVERGRABBER, id()) << "The 'grabberDual' device is deprecated in favour of 'frameGrabber_nws_yarp' (and eventually 'frameGrabberCropper')."; - yCIWarning(SERVERGRABBER, id()) << "The old device is no longer supported, and it will be deprecated in YARP 3.7 and removed in YARP 4."; - yCIWarning(SERVERGRABBER, id()) << "Please update your scripts."; - - if (param.active) { - yCIError(SERVERGRABBER, id(), "Did you just try to open the same ServerGrabber twice?"); - return false; - } - - if(!fromConfig(config)) - { - yCIError(SERVERGRABBER, id()) << "Device ServerGrabber failed to open, check previous log for error messages."; - return false; - } - - if(!initialize_YARP(config)) - { - yCIError(SERVERGRABBER, id()) <<"Error initializing YARP ports"; - return false; - } - - if(isSubdeviceOwned){ - if(! openAndAttachSubDevice(config)) - { - yCIError(SERVERGRABBER, id(), "Error while opening subdevice"); - return false; - } - } - else - { - yCIInfo(SERVERGRABBER, id()) << "Running, waiting for attach..."; - if (!openDeferredAttach(config)) { - return false; - } - } - - - param.active = true; -// //ASK/TODO update usage and see if we need to add DeviceResponder as dependency -// DeviceResponder::makeUsage(); -// addUsage("[set] [bri] $fBrightness", "set brightness"); -// addUsage("[set] [expo] $fExposure", "set exposure"); -// addUsage("[set] [shar] $fSharpness", "set sharpness"); -// addUsage("[set] [whit] $fBlue $fRed", "set white balance"); -// addUsage("[set] [hue] $fHue", "set hue"); -// addUsage("[set] [satu] $fSaturation", "set saturation"); -// addUsage("[set] [gamm] $fGamma", "set gamma"); -// addUsage("[set] [shut] $fShutter", "set shutter"); -// addUsage("[set] [gain] $fGain", "set gain"); -// addUsage("[set] [iris] $fIris", "set iris"); - -// addUsage("[get] [bri]", "get brightness"); -// addUsage("[get] [expo]", "get exposure"); -// addUsage("[get] [shar]", "get sharpness"); -// addUsage("[get] [whit]", "get white balance"); -// addUsage("[get] [hue]", "get hue"); -// addUsage("[get] [satu]", "get saturation"); -// addUsage("[get] [gamm]", "get gamma"); -// addUsage("[get] [shut]", "get shutter"); -// addUsage("[get] [gain]", "get gain"); -// addUsage("[get] [iris]", "get iris"); - -// addUsage("[get] [w]", "get width of image"); -// addUsage("[get] [h]", "get height of image"); - - - return true; -} - -bool ServerGrabber::fromConfig(yarp::os::Searchable &config) -{ - if (config.check("period", "refresh period(in ms) of the broadcasted values through yarp ports") - && config.find("period").isInt32()) { - period = config.find("period").asInt32() / 1000.0; - } else { - yCIInfo(SERVERGRABBER, id()) << "Period parameter not found, using default of" << DEFAULT_THREAD_PERIOD << "s"; - } - if((config.check("subdevice")) && (config.check("left_config") || config.check("right_config"))) - { - yCIError(SERVERGRABBER, id()) << "Found both 'subdevice' and 'left_config/right_config' parameters..."; - return false; - } - if (!config.check("subdevice", "name of the subdevice to use as a data source") - && config.check("left_config", "name of the ini file containing the configuration of one of two subdevices to use as a data source") - && config.check("right_config", "name of the ini file containing the configuration of one of two subdevices to use as a data source")) { - param.twoCameras = true; - } - if (config.check("twoCameras", "if true ServerGrabber will open and handle two devices, if false only one")) { //extra conf parameter for the yarprobotinterface - param.twoCameras = config.find("twoCameras").asBool(); - } - if (config.check("split", "set 'true' to split the streaming on two different ports")) { - param.split = config.find("split").asBool(); - } - if(config.check("capabilities","two capabilities supported, COLOR and RAW respectively for rgb and raw streaming")) - { - if (config.find("capabilities").asString() == "COLOR") { - param.cap=COLOR; - } else if (config.find("capabilities").asString() == "RAW") { - param.cap = RAW; - } - } else { - yCIWarning(SERVERGRABBER, id()) << "'capabilities' parameter not found or misspelled, the option available are COLOR(default) and RAW, using default"; - } - param.canDrop = !config.check("no_drop","if present, use strict policy for sending data"); - param.addStamp = config.check("stamp","if present, add timestamps to data"); - - param.singleThreaded = - config.check("single_threaded", - "if present, operate in single threaded mode"); - //TODO audio part - std::string rootName; - rootName = config.check("name",Value("/grabber"), - "name of port to send data on").asString(); - if (!param.twoCameras && param.split) { - param.splitterMode = true; - } - - responder = new ServerGrabberResponder(true); - if (!responder->configure(this)) { - return false; - } - if(param.twoCameras) - { - responder2 = new ServerGrabberResponder(false); - if (!responder2->configure(this)) { - return false; - } - - rpcPort_Name = rootName + "/left/rpc"; - rpcPort2_Name = rootName + "/right/rpc"; - if(param.split) - { - pImg_Name = rootName + "/left"; - pImg2_Name = rootName + "/right"; - } else { - pImg_Name = rootName; - } - - // check if we need to create subdevice or if they are - // passed later on thorugh attachAll() - if(config.check("left_config") && config.check("right_config")) - { - isSubdeviceOwned=true; - } - else - { - isSubdeviceOwned=false; - } - } - else - { - if(param.split) - { - responder2 = new ServerGrabberResponder(false); - if (!responder2->configure(this)) { - return false; - } - pImg_Name = rootName + "/left"; - pImg2_Name = rootName + "/right"; - } - else - { - pImg_Name = rootName; - } - rpcPort_Name = rootName + "/rpc"; - if(config.check("subdevice")) - { - isSubdeviceOwned=true; - } - else - { - isSubdeviceOwned=false; - } - } - - - return true; -} - -bool ServerGrabber::initialize_YARP(yarp::os::Searchable ¶ms) -{ - // Open ports - bool bRet; - bRet = true; - if(!rpcPort.open(rpcPort_Name)) - { - yCIError(SERVERGRABBER, id()) << "Unable to open rpc Port" << rpcPort_Name.c_str(); - bRet = false; - } - rpcPort.setReader(*responder); - - pImg.promiseType(Type::byName("yarp/image")); - pImg.setWriteOnly(); - if(!pImg.open(pImg_Name)) - { - yCIError(SERVERGRABBER, id()) << "Unable to open image streaming Port" << pImg_Name.c_str(); - bRet = false; - } - pImg.setReader(*responder); - - if(param.twoCameras) - { - if(!rpcPort2.open(rpcPort2_Name)) - { - yCIError(SERVERGRABBER, id()) << "Unable to open rpc Port" << rpcPort2_Name.c_str(); - bRet = false; - } - rpcPort2.setReader(*responder2); - } - if(param.split) - { - pImg2.promiseType(Type::byName("yarp/image")); - pImg2.setWriteOnly(); - - if(!pImg2.open(pImg2_Name)) - { - yCIError(SERVERGRABBER, id()) << "Unable to open image streaming Port" << pImg2_Name.c_str(); - bRet = false; - } - pImg2.setReader(*responder2); - } - - return bRet; -} - -bool ServerGrabber::respond(const yarp::os::Bottle& cmd, - yarp::os::Bottle& response, bool left, bool both=false) { - int code = cmd.get(0).asVocab32(); - Bottle response2; - switch (code) - { - case VOCAB_FRAMEGRABBER_IMAGE: - { - switch (cmd.get(1).asVocab32()) - { - case VOCAB_GET: - { - switch (cmd.get(2).asVocab32()) - { - case VOCAB_CROP: - { - response.clear(); - // If the device driver support it, use the device implementation, because it may be more efficient. - // If not, acquire the whole image and crop it here before sending it. - - Bottle *list = cmd.get(4).asList(); - int nPoints = list->size() /2; // divided by 2 because each pixel is identified by 2 numbers (u,v) - - yarp::sig::VectorOf > vertices; - vertices.resize(nPoints); - - for(int i=0; iget(i*2).asInt32(); - vertices[i].second = list->get(i*2 +1).asInt32(); - } - - ImageOf< PixelRgb > cropped; - - // Choose the interface and eventual offset depending on case. - - /* HW/SW configurations here: (1a, 1b, 2a, 2b), for each one the user can request a crop on left or right image - * 1) single HW camera as a source - * 1a) split false: a single image to handle - * 1b) split true : 2 images, I have to handle left or right image. If user request a crop in the right side, - * of the image, then add an offset - * - * 2) two HW sources - * 2a) split true: choose appropriate image source based on left/right request - * 2b) split false: choose appropriate image source based on crop position. Crop request have to belong to a - * single frame, either left or right. Example: 2 cameras with 320x240 pixels each placed - * one after the other, generates a single stitched image of 640x240. - * Anyway a crop request like (200,100)(400,200) shall be rejected, even if it could be - * considered as a part of the image resulting from the stitch. - * Right now the decision is took based on the first point of vector 'vertices', since all - * points are expected to belong to the same frame (left/right) - * - */ - - // Default values here are valid for cases 1a and `left` side of 2a - IFrameGrabberImage *imageInterface = fgImage; - - if(param.twoCameras == false) // a single HW source of images - { - imageInterface = fgImage; - if(left == false) // if left is false, implicitly split is true - { - std::for_each(vertices.begin(), vertices.end(), [=](auto &pt) { pt.first += imageInterface->width() / 2; }); // 1b - } - - } - else - { - if(param.split) // 2a, right image - { - if(left == false) - { - imageInterface = fgImage2; - // no offset - } - } - else - { - if(vertices[0].first >= fgImage->width()) // 2b, right image - { - imageInterface = fgImage2; - std::for_each(vertices.begin(), vertices.end(), [=](auto &pt) { pt.first -= fgImage->width(); }); - } - } - - } - - if(imageInterface != nullptr) - { - if(imageInterface->getImageCrop((cropType_id_t) cmd.get(3).asVocab32(), vertices, cropped) ) - { - // use the device output - } - else - { - // In case the device has not yet implemented this feature, do it here (less efficient) - if(cmd.get(3).asVocab32() == YARP_CROP_RECT) - { - if(nPoints != 2) - { - response.addString("GetImageCrop failed: RECT mode requires 2 vertices."); - yCIError(SERVERGRABBER, id()) << "GetImageCrop failed: RECT mode requires 2 vertices, got " << nPoints; - return false; - } - ImageOf< PixelRgb > full; - imageInterface->getImage(full); - - if(!utils::cropRect(full, vertices[0], vertices[1], cropped)) - { - response.addString("GetImageCrop failed: utils::cropRect error."); - yCIError(SERVERGRABBER, id(), "GetImageCrop failed: utils::cropRect error: (%d, %d) (%d, %d)", - vertices[0].first, - vertices[0].second, - vertices[1].first, - vertices[1].second); - return false; - } - } - else if(cmd.get(3).asVocab32() == YARP_CROP_LIST) - { - response.addString("List type not yet implemented"); - } - else - { - response.addString("Crop type unknown"); - } - } - } - - response.addVocab32(VOCAB_CROP); - response.addVocab32(VOCAB_IS); - response.addInt32(cropped.width()); // Actual width of image in pixels, to check everything is ok - response.addInt32(cropped.height()); // Actual height of image in pixels, to check everything is ok - - response.add(Value(cropped.getRawImage(), cropped.getRawImageSize())); - return true; - } break; - } break; - - } break; - - case VOCAB_SET: // Nothing to do here yet - default: - { - yCIError(SERVERGRABBER, id()) << "FrameGrabberImage interface received an unknown command " << cmd.toString(); - } break; - - } - - } break; - - // first check if requests are coming from new iFrameGrabberControl2 interface and process them - case VOCAB_FRAMEGRABBER_CONTROL: - { - if(param.twoCameras) - { - bool ret; - if(both){ - ret=ifgCtrl_Responder.respond(cmd, response); - ret&=ifgCtrl2_Responder.respond(cmd, response2); - if(!ret || (response!=response2)) - { - response.clear(); - response.addVocab32(VOCAB_FAILED); - ret=false; - yCIWarning(SERVERGRABBER, id()) << "Response different among cameras or failed"; - } - } - else - { - if(left) - { - ret=ifgCtrl_Responder.respond(cmd, response); - } - else - { - ret=ifgCtrl2_Responder.respond(cmd, response); - } - } - return ret; - } else { - return ifgCtrl_Responder.respond(cmd, response); - } - } break; - - case VOCAB_RGB_VISUAL_PARAMS: - { - if(param.twoCameras) - { - bool ret; - ret=rgbParser.respond(cmd,response); - ret&=rgbParser2.respond(cmd,response2); - if(ret) - { - switch (cmd.get(2).asVocab32()) - { - //Only the intrinsic parameters are allowed to be different among the two cameras - // so we give both responses appending one to the other. - case VOCAB_INTRINSIC_PARAM: - { - Bottle& newResponse = response.addList(); - newResponse.append(*response2.get(3).asList()); - break; - } - //In general if the two response are different we send a FAIL vocab - default: - { - if(response!=response2) - { - response.clear(); - response.addVocab32(VOCAB_FAILED); - ret=false; - yCIWarning(SERVERGRABBER, id()) << "Response different among cameras or failed"; - } - break; - } - } - } - - return ret; - } else { - return rgbParser.respond(cmd, response); - } - } break; - ////////////////// - // DC1394 COMMANDS - ////////////////// - case VOCAB_FRAMEGRABBER_CONTROL_DC1394: - { - if(param.twoCameras) - { - bool ret; - if(both) - { - ret=ifgCtrl_DC1394_Responder.respond(cmd, response); - ret&=ifgCtrl2_DC1394_Responder.respond(cmd, response2); - if(!ret || (response!=response2)) - { - response.clear(); - response.addString("command not recognized"); - ret=false; - yCIWarning(SERVERGRABBER, id()) << "Responses different among cameras or failed"; - - } - } - else - { - if(left) - { - ret=ifgCtrl_DC1394_Responder.respond(cmd, response); - } - else - { - ret=ifgCtrl2_DC1394_Responder.respond(cmd, response); - } - } - return ret; - } else { - return ifgCtrl_DC1394_Responder.respond(cmd, response); - } - } break; - } - yCIError(SERVERGRABBER, id()) << "Command not recognized" << cmd.toString(); - return false; -} - -bool ServerGrabber::attachAll(const PolyDriverList &device2attach) -{ - bool ret=false; - if(param.twoCameras) - { - bool leftDone=false;//for avoiding double left - bool rightDone=false;//for avoiding double right - if (device2attach.size() != 2) - { - yCIError(SERVERGRABBER, id(), "Expected two devices to be attached"); - return false; - } - for(int i=0;ipoly; - if (!Idevice2attach->isValid()) - { - yCIError(SERVERGRABBER, id()) << "Device " << device2attach[i]->key << " to attach to is not valid ... cannot proceed"; - return false; - } - if(device2attach[i]->key == "LEFT" && !leftDone) - { - leftDone |= Idevice2attach->view(rgbVis_p); - leftDone |= Idevice2attach->view(fgImage); - leftDone |= Idevice2attach->view(fgImageRaw); - leftDone |= Idevice2attach->view(fgCtrl); - leftDone |= Idevice2attach->view(fgCtrl_DC1394); - } - else if(device2attach[i]->key == "RIGHT" && !rightDone) - { - rightDone |= Idevice2attach->view(rgbVis_p2); - rightDone |= Idevice2attach->view(fgImage2); - rightDone |= Idevice2attach->view(fgImageRaw2); - rightDone |= Idevice2attach->view(fgCtrl2); - rightDone |= Idevice2attach->view(fgCtrl2_DC1394); - } - else - { - yCIError(SERVERGRABBER, id()) << "Failed to attach. The two targets must be LEFT RIGHT and devices must implement" - " either IFrameGrabberImage or IFrameGrabberImageRaw"; - return false; - - } - } - switch(param.cap) - { - case COLOR : - { - if((fgImage==nullptr) || (fgImage2==nullptr)) - { - yCIError(SERVERGRABBER, id()) << "Capability \"COLOR\" required not supported"; - return false; - } - } - break; - case RAW : - { - if((fgImageRaw==nullptr) || (fgImageRaw2==nullptr)) - { - yCIError(SERVERGRABBER, id()) << "Capability \"RAW\" required not supported"; - return false; - } - } - } - if((rgbVis_p == nullptr) || (rgbVis_p2 == nullptr)) - { - yCIWarning(SERVERGRABBER, id()) << "Targets has not IVisualParamInterface, some features cannot be available"; - } - //Configuring parsers - if(rgbVis_p != nullptr && rgbVis_p2 != nullptr) - { - if(!(rgbParser.configure(rgbVis_p)) || !(rgbParser2.configure(rgbVis_p2))) - { - yCIError(SERVERGRABBER, id()) << "Error configuring interfaces for parsers"; - return false; - } - } - if(fgCtrl != nullptr && fgCtrl2 != nullptr) - { - if(!(ifgCtrl_Responder.configure(fgCtrl)) || !(ifgCtrl2_Responder.configure(fgCtrl2))) - { - yCIError(SERVERGRABBER, id()) << "Error configuring interfaces for parsers"; - return false; - } - } - if(fgCtrl_DC1394 != nullptr && fgCtrl2_DC1394 != nullptr) - { - if(!(ifgCtrl_DC1394_Responder.configure(fgCtrl_DC1394)) || !(ifgCtrl2_DC1394_Responder.configure(fgCtrl2_DC1394))) - { - yCIError(SERVERGRABBER, id()) << "Error configuring interfaces for parsers"; - return false; - } - } - } - else{ - if (device2attach.size() != 1) - { - yCIError(SERVERGRABBER, id(), "Expected one device to be attached"); - return false; - } - yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly; - Idevice2attach->view(rgbVis_p); - Idevice2attach->view(fgImage); - Idevice2attach->view(fgImageRaw); - Idevice2attach->view(fgCtrl); - Idevice2attach->view(fgCtrl_DC1394); - switch(param.cap){ - case COLOR : - { - if(fgImage==nullptr) - { - yCIError(SERVERGRABBER, id()) << "Capability \"COLOR\" required not supported"; - return false; - } - } - break; - case RAW : - { - if(fgImageRaw==nullptr) - { - yCIError(SERVERGRABBER, id()) << "Capability \"RAW\" required not supported"; - return false; - } - } - } - - if (!Idevice2attach->isValid()) - { - yCIError(SERVERGRABBER, id()) << "Device " << device2attach[0]->key << " to attach to is not valid ... cannot proceed"; - return false; - } - - if(rgbVis_p == nullptr) - { - yCIWarning(SERVERGRABBER, id()) << "Targets has not IVisualParamInterface, some features cannot be available"; - } - - //Configuring parsers - if(rgbVis_p != nullptr) - { - if(!(rgbParser.configure(rgbVis_p))) - { - yCIError(SERVERGRABBER, id()) << "Error configuring interfaces for parsers"; - return false; - } - } - if(fgCtrl != nullptr) - { - if(!(ifgCtrl_Responder.configure(fgCtrl))) - { - yCIError(SERVERGRABBER, id()) << "Error configuring interfaces for parsers"; - return false; - } - } - - if(fgCtrl_DC1394 != nullptr) - { - if(!(ifgCtrl_DC1394_Responder.configure(fgCtrl_DC1394))) - { - yCIError(SERVERGRABBER, id()) << "Error configuring interfaces for parsers"; - return false; - } - } - } - - PeriodicThread::setPeriod(period); - ret = PeriodicThread::start(); - - return ret; -} -bool ServerGrabber::detachAll() -{ - //check if we already instantiated a subdevice previously - if (isSubdeviceOwned) { - return false; - } - stopThread(); - return true; - -} -void ServerGrabber::stopThread() -{ - if (yarp::os::PeriodicThread::isRunning()) { - yarp::os::PeriodicThread::stop(); - } - - rgbVis_p = nullptr; - rgbVis_p2 = nullptr; - fgImage = nullptr; - fgImage2 = nullptr; - fgImageRaw = nullptr; - fgImageRaw2 = nullptr; - fgCtrl = nullptr; - fgCtrl2 = nullptr; - fgCtrl_DC1394 = nullptr; - fgCtrl2_DC1394 = nullptr; -} - -void ServerGrabber::setupFlexImage(const Image &_img, FlexImage &flex_i) -{ - flex_i.setPixelCode(_img.getPixelCode()); - flex_i.setQuantum(_img.getQuantum()); - flex_i.setTopIsLowIndex(_img.topIsLowIndex()); - flex_i.setExternal(_img.getRawImage(), _img.width(),_img.height()); - -} - -bool ServerGrabber::attach(PolyDriver *poly) -{ - if(param.twoCameras) - { - yCIError(SERVERGRABBER, id()) << "Server grabber configured for two cameras, but only one provided"; - return false; - } - PolyDriverList plist; - if(poly) - { - PolyDriverDescriptor p(poly,"poly"); - plist.push(p); - return attachAll(plist); - } - else - { - yCIError(SERVERGRABBER, id()) << "Invalid device to be attached"; - return false; - } - return true; -} -bool ServerGrabber::detach() -{ - return detachAll(); -} - -bool ServerGrabber::openDeferredAttach(Searchable &prop){ - // I dunno what to do here now... - isSubdeviceOwned = false; - return true; -} - -bool ServerGrabber::openAndAttachSubDevice(Searchable &prop){ - PolyDriverList plist; - if(param.twoCameras){ - Property p,p2; - poly = new PolyDriver; - poly2 = new PolyDriver; - std::string file, file2; - if(!prop.check("left_config") || !prop.check("right_config")) - { - yCIError(SERVERGRABBER, id()) << "Missing 'left_config' or 'right_config' filename... "; - return false; - } - ResourceFinder rf, rf2; - if(prop.check("context")) - { - rf.setDefaultContext(prop.find("context").asString().c_str()); - rf2.setDefaultContext(prop.find("context").asString().c_str()); - } - file=prop.find("left_config").toString(); - file2=prop.find("right_config").toString(); - p.fromConfigFile(rf.findFileByName(file)); - p2.fromConfigFile(rf2.findFileByName(file2)); - if(p.isNull() || p2.isNull()) - { - yCIError(SERVERGRABBER, id()) << "Unable to find files specified in 'left_config' and/or 'right_config'"; - return false; - } -// p.fromString(prop.findGroup("LEFT").toString().c_str()); -// p2.fromString(prop.findGroup("RIGHT").toString().c_str()); - if(param.cap==COLOR){ - p.put("pixelType", VOCAB_PIXEL_RGB); - p2.put("pixelType", VOCAB_PIXEL_RGB); - } - else - { - p.put("pixelType", VOCAB_PIXEL_MONO); - p2.put("pixelType", VOCAB_PIXEL_MONO); - } - if(p.find("height").asInt32() != p2.find("height").asInt32() || - p.find("width").asInt32() != p2.find("width").asInt32()) - { - yCIError(SERVERGRABBER, id()) << "Error in the configuration file, the two images have to have the same dimensions"; - return false; - } - //COSA FA? Serve? Guardarci - //p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring - // if errors occurred during open, quit here. - poly->open(p); - poly2->open(p2); - - if (!(poly->isValid()) || !(poly2->isValid())) - { - yCIError(SERVERGRABBER, id(), "Opening devices... FAILED"); - return false; - } - PolyDriverDescriptor pd(poly,"LEFT"); - PolyDriverDescriptor pd2(poly2,"RIGHT"); - plist.push(pd); - plist.push(pd2); - //The thread is started by attachAll() - if (!attachAll(plist)) { - return false; - } - } - else - { - Property p; - poly = new PolyDriver; - p.fromString(prop.toString()); - if(param.cap==COLOR){ - p.put("pixelType", VOCAB_PIXEL_RGB); - } - else - { - p.put("pixelType", VOCAB_PIXEL_MONO); - } - p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring - p.unput("device"); - p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before - - // if errors occurred during open, quit here. - poly->open(p); - - if (!(poly->isValid())) - { - yCIError(SERVERGRABBER, id(), "opening subdevice... FAILED"); - return false; - } - PolyDriverDescriptor pd(poly,"poly"); - plist.push(pd); - //The thread is started by attachAll() - if (!attachAll(plist)) { - return false; - } - } - isSubdeviceOwned = true; - return true; -} - -bool ServerGrabber::threadInit() -{ - if(param.twoCameras) - { - if(param.cap==COLOR) - { - img= new ImageOf; - img->resize(fgImage->width(),fgImage->height()); - img2= new ImageOf; - img2->resize(fgImage2->width(),fgImage2->height()); - } - else - { - img_Raw= new ImageOf; - img_Raw->resize(fgImageRaw->width(),fgImageRaw->height()); - img2_Raw= new ImageOf; - img2_Raw->resize(fgImageRaw2->width(),fgImageRaw2->height()); - } - } - else - { - if(param.cap==COLOR) - { - img= new ImageOf; - if(param.splitterMode) - { - img->resize(fgImage->width()/2,fgImage->height()); - - img2= new ImageOf; - img2->resize(fgImage->width()/2,fgImage->height()); - } - else - { - img->resize(fgImage->width(),fgImage->height()); - } - } - else - { - img_Raw= new ImageOf; - if(param.splitterMode) - { - img_Raw->resize(fgImageRaw->width()/2,fgImageRaw->height()); - - img2_Raw= new ImageOf; - img2_Raw->resize(fgImageRaw->width()/2,fgImageRaw->height()); - } - else - { - img_Raw->resize(fgImageRaw->width(), fgImageRaw->height()); - } - } - } - return true; -} - -void ServerGrabber::threadRelease(){ - - - -} - -void ServerGrabber::run() -{ - if(param.twoCameras) - { - if(param.split) - { - FlexImage& flex_i=pImg.prepare(); - FlexImage& flex_i2=pImg2.prepare(); - if(param.cap==COLOR) - { - if(fgImage!=nullptr && fgImage2 !=nullptr) - { - fgImage->getImage(*img); - setupFlexImage(*img,flex_i); - fgImage2->getImage(*img2); - setupFlexImage(*img2,flex_i2); - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - if(param.cap==RAW) - { - if(fgImageRaw!=nullptr && fgImageRaw2 !=nullptr) - { - fgImageRaw->getImage(*img_Raw); - setupFlexImage(*img_Raw,flex_i); - fgImageRaw2->getImage(*img2_Raw); - setupFlexImage(*img2_Raw,flex_i2); - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - Stamp s = Stamp(count,Time::now()); - pImg.setStrict(!param.canDrop); - pImg.setEnvelope(s); - pImg.write(); - pImg2.setStrict(!param.canDrop); - Stamp s2 = Stamp(count2,Time::now()); - pImg2.setEnvelope(s2); - pImg2.write(); - count++; - count2++; - - } - else - { - FlexImage& flex_i=pImg.prepare(); - if(param.cap==COLOR) - { - if(fgImage!=nullptr && fgImage2 !=nullptr) - { - flex_i.setPixelCode(VOCAB_PIXEL_RGB); - flex_i.resize(fgImage->width()*2,fgImage->height()); - fgImage->getImage(*img); - fgImage2->getImage(*img2); - - bool ok = utils::horzConcat(*img, *img2, flex_i); - if (!ok) - { - yCIError(SERVERGRABBER, id()) << "Failed to concatenate images"; - return; - } - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - if(param.cap==RAW) - { - if(fgImageRaw!=nullptr && fgImageRaw2 !=nullptr) - { - flex_i.setPixelCode(VOCAB_PIXEL_MONO); - flex_i.resize(fgImageRaw->width()*2,fgImageRaw->height()); - fgImageRaw->getImage(*img_Raw); - fgImageRaw2->getImage(*img2_Raw); - bool ok = utils::horzConcat(*img_Raw, *img2_Raw, flex_i); - if (!ok) - { - yCIError(SERVERGRABBER, id()) << "Failed to concatenate images"; - return; - } - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - - Stamp s = Stamp(count,Time::now()); - pImg.setStrict(!param.canDrop); - pImg.setEnvelope(s); - pImg.write(); - count++; - } - } - else - { - if(param.splitterMode) - { - FlexImage& flex_i=pImg.prepare(); - FlexImage& flex_i2=pImg2.prepare(); - - if(param.cap==COLOR) - { - if(fgImage!=nullptr) - { - yarp::sig::ImageOf inputImage; - fgImage->getImage(inputImage); - - bool ok = utils::vertSplit(inputImage,*img,*img2); - if (!ok) - { - yCIError(SERVERGRABBER, id()) << "Failed to split the image"; - return; - } - - setupFlexImage(*img,flex_i); - setupFlexImage(*img2,flex_i2); - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - if(param.cap==RAW) - { - if(fgImageRaw!=nullptr) - { - yarp::sig::ImageOf inputImage; - fgImageRaw->getImage(inputImage); - - bool ok = utils::vertSplit(inputImage,*img_Raw,*img2_Raw); - if (!ok) - { - yCIError(SERVERGRABBER, id()) << "Failed to split the image"; - return; - } - - setupFlexImage(*img_Raw,flex_i); - setupFlexImage(*img2_Raw,flex_i2); - - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - Stamp s = Stamp(count,Time::now()); - pImg.setStrict(!param.canDrop); - pImg.setEnvelope(s); - pImg.write(); - pImg2.setStrict(!param.canDrop); - Stamp s2 = Stamp(count2,Time::now()); - pImg2.setEnvelope(s2); - pImg2.write(); - count++; - count2++; - } - else - { - FlexImage& flex_i=pImg.prepare(); - - if(param.cap==COLOR) - { - if(fgImage!=nullptr) - { - fgImage->getImage(*img); - setupFlexImage(*img,flex_i); - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - if(param.cap==RAW) - { - if(fgImageRaw!=nullptr) - { - fgImageRaw->getImage(*img_Raw); - setupFlexImage(*img_Raw,flex_i); - } else { - yCIError(SERVERGRABBER, id()) << "Image not captured.. check hardware configuration"; - } - } - Stamp s = Stamp(count,Time::now()); - pImg.setStrict(!param.canDrop); - pImg.setEnvelope(s); - pImg.write(); - count++; - } - } -} - -void ServerGrabber::shallowCopyImages(const yarp::sig::FlexImage& src, yarp::sig::FlexImage& dest) -{ - dest.setPixelCode(src.getPixelCode()); - dest.setQuantum(src.getQuantum()); - dest.setTopIsLowIndex(src.topIsLowIndex()); - dest.setExternal(src.getRawImage(), src.width(), src.height()); -} -void ServerGrabber::cleanUp() -{ - if(param.cap==COLOR) - { - if(img!=nullptr) - { - delete img; - img=nullptr; - } - if(img2!=nullptr) - { - delete img2; - img2=nullptr; - } - } - else - { - if(img_Raw!=nullptr) - { - delete img_Raw; - img_Raw=nullptr; - } - if(img2_Raw!=nullptr) - { - delete img2_Raw; - img2_Raw=nullptr; - } - } -} diff --git a/src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.h b/src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.h deleted file mode 100644 index 879062c199e..00000000000 --- a/src/devices/ServerFrameGrabberDual/ServerFrameGrabberDual.h +++ /dev/null @@ -1,277 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#ifndef YARP_DEV_SERVERGRABBER_H -#define YARP_DEV_SERVERGRABBER_H - -#include - - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -class ServerGrabber; - - -class ServerGrabberResponder : - public yarp::dev::DeviceResponder -{ -private: - bool left{false}; - ServerGrabber* server{nullptr}; -public: - ServerGrabberResponder(bool _left = false); - ~ServerGrabberResponder() override = default; - bool configure(ServerGrabber* _server); - bool respond(const yarp::os::Bottle &command, yarp::os::Bottle &reply) override; -}; - - -enum Capabilities -{ -// AV, - COLOR, - RAW, -}; - - -struct Configuration -{ - bool spoke{false}; // location of this variable tickles bug on Solaris/gcc3.2 - bool canDrop{true}; - bool addStamp{false}; - bool active{false}; - bool singleThreaded{false}; - bool twoCameras{false}; - bool split{false}; - bool splitterMode{false}; - bool hasAudio{false}; - Capabilities cap{COLOR}; -}; - - -#define DEFAULT_THREAD_PERIOD 0.03 //s - - -/** - * @ingroup dev_impl_wrapper dev_impl_deprecated - * - * \brief `grabberDual` *deprecated*: A Network grabber for camera devices. - * - * In base of the configuration this device can handle one or two cameras.\n - * In case of two cameras, the RGB or RAW streaming will be produced on two separated ports or on a single port with the two images - * stitched horizontally.\n - * Moreover it has two rpc ports that have the same name of the streaming ports + "/rpc" suffix.\n - * The inheritance from yarp::dev::IWrapper and yarp::dev::IMultipleWrapper allows to be instantiated also through yarprobotinterface. - * See their documentation for more details about each interface. - * - * This device is paired with its client called RemoteFrameGrabber to receive the data streams and perform remote operations. - * - * \section grabberDual_device_parameters Description of input parameters - * - * Parameters required by this device are: - * | Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes | - * |:--------------:|:-----------------------:|:-------:|:--------------:|:-------------:|:-----------------------------------------------------------------------------------------------------------------------------------------:|:------------------------------------------------------------------------------------------------------------:|:-----:| - * | period | - | int | ms | 30 | No | refresh period(in ms) of the broadcasted values through yarp ports | default 30ms | - * | name | - | string | - | /grabber | No | Prefix name of the ports opened by the ServerGrabber | Required suffix like '/rpc' will be added by the device | - * | capabilities | - | string | - | COLOR | No | two capabilities supported, COLOR and RAW respectively for rgb and raw streaming | - | - * | twoCameras | - | bool | - | - | required only for instantiating this device with the yarprobotinterface | if true ServerGrabber will open and handle two devices, if false only one | =true it makes required left_config and right_config parameters, =false subdevice parameter becomes required| - * | split | - | bool | - | false | No | set 'true' to split the streaming of the input camera/s on two different ports | Useful in case of dual cameras, the image will be split vertically in the 2 output ports 'left' and 'right' | - * | subdevice | - | string | - | - | used for opening and handling a single device, alternative to 'attach' action | name of the subdevice to use as a data source | when used, parameters for the subdevice must be provided as well | - * | left_config | - | string | - | - | used for opening and handling two devices, required if right_config present and/or twoCameras set to true | name of the ini file containing the configuration of one of two subdevices to use as a data source | when used, parameters for the subdevice must be provided in the file specified. This parameter is not admitted if the device is configured for working with one device. | - * | right_config | - | string | - | - | used for opening and handling two devices, required if left_config present and/or twoCameras set to true | name of the ini file containing the configuration of one of two subdevices to use as a data source | when used, parameters for the subdevice must be provided in the file specified. This parameter is not admitted if the device is configured for working with one device. | - * | context | - | string | - | - | No | name of context where the yarp::os::ResourceFinder will search the ini files specified in left_config and right_config | - | - * - * Some example of configuration files: - * - * Example of configuration file using .ini format, for handling two cameras. - * - * \code{.unparsed} - * device grabberDual - * capabilities RAW - * split false - * period 30 - * twoCameras true - * left_config left_config.ini #name of the config file containing the parameters for the camera device - * right_config right_config.ini #name of the config file containing the parameters for the camera device - * \endcode - * - * Example of configuration file using .ini format, for handling one camera. - * - * \code{.unparsed} - * device grabberDual - * capabilities COLOR # not necessary to specify 'COLOR', this is the default value if capabilities is omitted - * period 30 - * subdevice fakeFrameGrabber - * \endcode - * - * Example of configuration file using .xml format, for handling two cameras. - * - * \code{.xml} - * - * 30 - * /grabber - * RGB - * false - * true - * - * - * - * testCamera_left - * testCamera_right - * - * - * - * - * \endcode - * - * Example of configuration file using .xml format, for handling one camera. - * - * \code{.xml} - * - * 30 - * /grabber - * RGB - * false - * true - * - * - * - * usbCamera_left_single - * - * - * - * - * \endcode - * - */ -class ServerGrabber : - public yarp::dev::DeviceDriver, - public yarp::dev::IWrapper, - public yarp::dev::IMultipleWrapper, - public yarp::os::PeriodicThread -{ -private: - double period{DEFAULT_THREAD_PERIOD}; - int count{0}; - int count2{0}; - ServerGrabberResponder* responder{nullptr}; - ServerGrabberResponder* responder2{nullptr}; - yarp::proto::framegrabber::RgbVisualParams_Responder rgbParser; - yarp::proto::framegrabber::RgbVisualParams_Responder rgbParser2; - yarp::dev::IRgbVisualParams* rgbVis_p{nullptr}; - yarp::dev::IRgbVisualParams* rgbVis_p2{nullptr}; - std::string rpcPort_Name; - std::string rpcPort2_Name; - yarp::os::Port rpcPort; - yarp::os::Port rpcPort2; - std::string pImg_Name; - std::string pImg2_Name; - yarp::os::BufferedPort pImg; - yarp::os::BufferedPort pImg2; - yarp::os::Port *p2{nullptr};//audio - yarp::dev::PolyDriver* poly{nullptr}; //subDeviceOwned convert to pointer - yarp::dev::PolyDriver* poly2{nullptr}; - yarp::dev::IFrameGrabberImage *fgImage{nullptr}; - yarp::dev::IFrameGrabberImage *fgImage2{nullptr}; - yarp::dev::IFrameGrabberImageRaw *fgImageRaw{nullptr}; - yarp::dev::IFrameGrabberImageRaw *fgImageRaw2{nullptr}; - //yarp::sig::FlexImage doubleImage, doubleImage2; -// IAudioVisualGrabber *fgAv{nullptr}; //TODO: manage the AV - yarp::dev::IFrameGrabberControls *fgCtrl{nullptr}; - yarp::dev::IFrameGrabberControls *fgCtrl2{nullptr}; - yarp::dev::IFrameGrabberControlsDC1394* fgCtrl_DC1394{nullptr}; - yarp::dev::IFrameGrabberControlsDC1394* fgCtrl2_DC1394{nullptr}; - yarp::dev::IPreciselyTimed *fgTimed{nullptr}; - yarp::proto::framegrabber::FrameGrabberControls_Responder ifgCtrl_Responder; - yarp::proto::framegrabber::FrameGrabberControls_Responder ifgCtrl2_Responder; - yarp::proto::framegrabber::FrameGrabberControlsDC1394_Responder ifgCtrl_DC1394_Responder; - yarp::proto::framegrabber::FrameGrabberControlsDC1394_Responder ifgCtrl2_DC1394_Responder; - Configuration param; - yarp::sig::ImageOf* img{nullptr}; - yarp::sig::ImageOf* img2{nullptr}; - yarp::sig::ImageOf* img_Raw{nullptr}; - yarp::sig::ImageOf* img2_Raw{nullptr}; - - // Open the wrapper only, the attach method needs to be called before using it - // Typical usage: yarprobotinterface - bool openDeferredAttach(yarp::os::Searchable& prop); - - // If a subdevice parameter is given, the wrapper will open it(or them) and attach to immediately. - // Typical usage: simulator or command line - bool isSubdeviceOwned{false}; - bool openAndAttachSubDevice(yarp::os::Searchable& prop); - -public: - ServerGrabber(); - ServerGrabber(const ServerGrabber&) = delete; - ServerGrabber(ServerGrabber&&) = delete; - ServerGrabber& operator=(const ServerGrabber&) = delete; - ServerGrabber& operator=(ServerGrabber&&) = delete; - ~ServerGrabber() override; - - //DeviceDriver - bool close() override; - /** - * Configure with a set of options. - * @param config The options to use - * @return true iff the object could be configured. - */ - bool open(yarp::os::Searchable& config) override; - - //bool read(ConnectionReader& connection) override; - - //DeviceResponder - bool respond(const yarp::os::Bottle& command, - yarp::os::Bottle& reply, bool left, bool both); - // IMultipleWrapper interface - bool attachAll(const yarp::dev::PolyDriverList &device2attach) override; - - bool detachAll() override; - - // IWrapper interface - bool attach(yarp::dev::PolyDriver *poly) override; - - bool detach() override; - - //RateThread - bool threadInit() override; - - void threadRelease() override; - - void run() override; -protected: - - bool fromConfig(yarp::os::Searchable &config); - - bool initialize_YARP(yarp::os::Searchable ¶ms); - - void stopThread(); - - void setupFlexImage(const yarp::sig::Image& img, yarp::sig::FlexImage& flex_i); - - void shallowCopyImages(const yarp::sig::FlexImage& src, yarp::sig::FlexImage& dest); - - void cleanUp(); -}; - -#endif // YARP_DEV_SERVERGRABBER_H diff --git a/src/devices/ServerFrameGrabberDual/tests/grabberDualTest.cpp b/src/devices/ServerFrameGrabberDual/tests/grabberDualTest.cpp deleted file mode 100644 index a3f7c760bbd..00000000000 --- a/src/devices/ServerFrameGrabberDual/tests/grabberDualTest.cpp +++ /dev/null @@ -1,402 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include - -#include -#include -#include -#include -#include - -#include - -#include -#include - -using namespace yarp::os; -using namespace yarp::dev; -using namespace yarp::sig; - - -TEST_CASE("dev::grabberDualTest", "[yarp::dev]") -{ - YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); - YARP_REQUIRE_PLUGIN("remote_grabber", "device"); - YARP_REQUIRE_PLUGIN("grabberDual", "device"); - - Network::setLocalMode(true); - - SECTION("Test the grabber wrapper") - { - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - p.put("device","remote_grabber"); - p.put("remote","/grabber"); - p.put("local","/grabber/client"); - - p2.put("device","grabberDual"); - p2.put("subdevice","fakeFrameGrabber"); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); // interface reported - - yarp::os::SystemClock::delaySystem(0.5); - - ImageOf img; - grabber->getImage(img); - CHECK(img.width() > 0); // interface seems functional - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } - - SECTION("Test the IRgbVisualParams interface") - { - // Try to open a FakeFrameGrabber and I check all the parameters - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - Property intrinsics; - Bottle* retM = nullptr; - - p.put("device","remote_grabber"); - p.put("remote","/grabber"); - p.put("local","/grabber/client"); - p.put("no_stream", 1); - - p2.put("device","grabberDual"); - p2.put("subdevice","fakeFrameGrabber"); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IRgbVisualParams* rgbParams = nullptr; - REQUIRE(dd.view(rgbParams)); // interface rgb params reported - - // check the default parameters - - // checking fov - double hfov=0.0; - double vfov=0.0; - rgbParams->getRgbFOV(hfov,vfov); - CHECK(hfov == 1.0); - CHECK(vfov == 2.0); - - // checking height - CHECK(rgbParams->getRgbHeight() == 240); - - // checking width - CHECK(rgbParams->getRgbWidth() == 320); - - // checking mirroring - bool rgbMirroring; - rgbParams->getRgbMirroring(rgbMirroring); - CHECK_FALSE(rgbMirroring); - - // checking intrinsics - rgbParams->getRgbIntrinsicParam(intrinsics); - CHECK(intrinsics.find("focalLengthX").asFloat64() == 4.0); // checking focalLength X - CHECK(intrinsics.find("focalLengthY").asFloat64() == 5.0); // checking focalLength Y - CHECK(intrinsics.find("principalPointX").asFloat64() == 6.0); // checking principalPoint X - CHECK(intrinsics.find("principalPointY").asFloat64() == 7.0); // checking principalPoint Y - CHECK(intrinsics.find("k1").asFloat64() == 8.0); // checking k1 - CHECK(intrinsics.find("k2").asFloat64() == 9.0); // checking k2 - CHECK(intrinsics.find("k3").asFloat64() == 10.0); // checking k3 - CHECK(intrinsics.find("t1").asFloat64() == 11.0); // checking t1 - CHECK(intrinsics.find("t2").asFloat64() == 12.0); // checking t2 - CHECK(intrinsics.find("distortionModel").asString() == "FishEye"); // checking distorionModel - - // checking the rectificationMatrix - retM = intrinsics.find("rectificationMatrix").asList(); - double data[9]= {1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0}; - Vector v(9,data); - Vector v2; - Portable::copyPortable(*retM,v2); - for(int i=0; i<3; i++) { - for(int j=0; j<3; j++) { - CHECK(retM->get(i*3+j).asFloat64() == v(i*3+j)); - CHECK(v2(i*3+j) == v(i*3+j)); - } - } - - // checking getRgbResolution - int height, width; - rgbParams->getRgbResolution(width,height); - CHECK(width==320); - CHECK(height==240); - - // checking configurations size - VectorOf configurations; - CHECK(rgbParams->getRgbSupportedConfigurations(configurations)); - CHECK(configurations.size() == 3); - - // checking first supported configuration - CHECK(configurations[0].height == 128); - CHECK(configurations[0].width == 128); - CHECK(configurations[0].framerate == 60.0); - CHECK(configurations[0].pixelCoding == VOCAB_PIXEL_RGB); - - // checking second supported configuration - CHECK(configurations[1].height == 256); - CHECK(configurations[1].width == 256); - CHECK(configurations[1].framerate == 30.0); - CHECK(configurations[1].pixelCoding == VOCAB_PIXEL_BGR); - - // checking third supported configuration - CHECK(configurations[2].height == 512); - CHECK(configurations[2].width == 512); - CHECK(configurations[2].framerate == 15.0); - CHECK(configurations[2].pixelCoding == VOCAB_PIXEL_MONO); - - // Test the crop function - must work. - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); - ImageOf img; - ImageOf crop; - grabber->getImage(img); - - yarp::sig::VectorOf> vertices; - vertices.resize(2); - vertices[0] = std::pair (0, 0); - vertices[1] = std::pair (10, 10); // Configure a doable crop. - - // check crop function - CHECK(grabber->getImageCrop(YARP_CROP_RECT, vertices, crop)); - CHECK(crop.width() > 0); - CHECK(crop.height() > 0); - - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } - - SECTION("Test the IRgbVisualParams interface") - { - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - Property intrinsics; - Bottle* retM = nullptr; - - p.put("device","remote_grabber"); - p.put("remote","/grabber/left/rpc"); - p.put("local","/grabber/client"); - - p2.put("device","grabberDual"); - p2.put("context","fakeFrameGrabberTest"); - p2.put("left_config","left_test.ini"); - p2.put("right_config","right_test.ini"); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IRgbVisualParams* rgbParams = nullptr; - REQUIRE(dd.view(rgbParams)); // interface rgb params reported - - // check the default parameters - - // checking fov - double hfov=0.0; - double vfov=0.0; - rgbParams->getRgbFOV(hfov,vfov); - CHECK(hfov == 1.0); - CHECK(vfov == 2.0); - - // checking height - CHECK(rgbParams->getRgbHeight() == 240); - - // checking width - CHECK(rgbParams->getRgbWidth() == 320); - - // checking mirroring - bool rgbMirroring; - rgbParams->getRgbMirroring(rgbMirroring); - CHECK_FALSE(rgbMirroring); - - // checking intrinsics - rgbParams->getRgbIntrinsicParam(intrinsics); - CHECK(intrinsics.find("focalLengthX").asFloat64() == 4.0); // checking focalLength X - CHECK(intrinsics.find("focalLengthY").asFloat64() == 5.0); // checking focalLength Y - CHECK(intrinsics.find("principalPointX").asFloat64() == 6.0); // checking principalPoint X - CHECK(intrinsics.find("principalPointY").asFloat64() == 7.0); // checking principalPoint Y - CHECK(intrinsics.find("k1").asFloat64() == 8.0); // checking k1 - CHECK(intrinsics.find("k2").asFloat64() == 9.0); // checking k2 - CHECK(intrinsics.find("k3").asFloat64() == 10.0); // checking k3 - CHECK(intrinsics.find("t1").asFloat64() == 11.0); // checking t1 - CHECK(intrinsics.find("t2").asFloat64() == 12.0); // checking t2 - CHECK(intrinsics.find("distortionModel").asString() == "FishEye"); // checking distorionModel - - // checking the rectificationMatrix - retM = intrinsics.find("rectificationMatrix").asList(); - double data[9]= {1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0}; - Vector v(9,data); - Vector v2; - Portable::copyPortable(*retM, v2); - for(int i=0; i<3; i++) { - for(int j=0; j<3; j++) { - CHECK(retM->get(i*3+j).asFloat64() == v(i*3+j)); - CHECK(v2(i*3+j) == v(i*3+j)); - } - } - - Bottle bt = intrinsics.findGroup("right"); - CHECK_FALSE(bt.isNull()); //checking second intrinsics - - CHECK(bt.find("focalLengthX").asFloat64() == 4.0); // checking focalLength X - CHECK(bt.find("focalLengthY").asFloat64() == 5.0); // checking focalLength Y - CHECK(bt.find("principalPointX").asFloat64() == 6.0); // checking principalPoint X - CHECK(bt.find("principalPointY").asFloat64() == 7.0); // checking principalPoint Y - CHECK(bt.find("k1").asFloat64() == 8.0); // checking k1 - CHECK(bt.find("k2").asFloat64() == 9.0); // checking k2 - CHECK(bt.find("k3").asFloat64() == 10.0); // checking k3 - CHECK(bt.find("t1").asFloat64() == 11.0); // checking t1 - CHECK(bt.find("t2").asFloat64() == 12.0); // checking t2 - CHECK(bt.find("distortionModel").asString() == "FishEye"); // checking distorionModel - - // checking if all the ports have been opened correctly - CHECK(Network::exists("/grabber")); - CHECK(Network::exists("/grabber/left/rpc")); - CHECK(Network::exists("/grabber/right/rpc")); - - // checking the rectificationMatrix - retM = bt.find("rectificationMatrix").asList(); - Portable::copyPortable(*retM,v2); - for(int i=0; i<3; i++) { - for(int j=0; j<3; j++) { - CHECK(retM->get(i*3+j).asFloat64() == v(i*3+j)); - CHECK(v2(i*3+j) == v(i*3+j)); - } - } - - CHECK(dd.close()); // client close reported successful - - yarp::os::SystemClock::delaySystem(0.5); - - p.unput("remote"); - p.put("remote","/grabber/right/rpc"); - - REQUIRE(dd.open(p)); // checking opening client - - rgbParams = nullptr; - REQUIRE(dd.view(rgbParams)); // interface rgb params reported - - // check the default parameters - - // checking fov - rgbParams->getRgbFOV(hfov,vfov); - CHECK(hfov == 1.0); - CHECK(vfov == 2.0); - - // checking height - CHECK(rgbParams->getRgbHeight() == 240); - - // checking width - CHECK(rgbParams->getRgbWidth() == 320); - - // checking mirroring - rgbParams->getRgbMirroring(rgbMirroring); - CHECK_FALSE(rgbMirroring); - - // checking intrinsics - rgbParams->getRgbIntrinsicParam(intrinsics); - CHECK(intrinsics.find("focalLengthX").asFloat64() == 4.0); // checking focalLength X - CHECK(intrinsics.find("focalLengthY").asFloat64() == 5.0); // checking focalLength Y - CHECK(intrinsics.find("principalPointX").asFloat64() == 6.0); // checking principalPoint X - CHECK(intrinsics.find("principalPointY").asFloat64() == 7.0); // checking principalPoint Y - CHECK(intrinsics.find("k1").asFloat64() == 8.0); // checking k1 - CHECK(intrinsics.find("k2").asFloat64() == 9.0); // checking k2 - CHECK(intrinsics.find("k3").asFloat64() == 10.0); // checking k3 - CHECK(intrinsics.find("t1").asFloat64() == 11.0); // checking t1 - CHECK(intrinsics.find("t2").asFloat64() == 12.0); // checking t2 - CHECK(intrinsics.find("distortionModel").asString() == "FishEye"); // checking distorionModel - - // checking the rectificationMatrix - retM = intrinsics.find("rectificationMatrix").asList(); - - Portable::copyPortable(*retM, v2); - for(int i=0; i<3; i++) { - for(int j=0; j<3; j++) { - CHECK(retM->get(i*3+j).asFloat64() == v(i*3+j)); - CHECK(v2(i*3+j) == v(i*3+j)); - } - } - - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } - - SECTION("test the splitter mode") - { - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - - p.put("device","remote_grabber"); - p.put("remote","/grabber/left"); - p.put("local","/grabber/client"); - - p2.put("device","grabberDual"); - p2.put("subdevice","fakeFrameGrabber"); - size_t width = 320; - p2.put("width", (int)width); - p2.put("split", true); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); // interface reported - - ImageOf img; - grabber->getImage(img); - CHECK(img.width() > 0); // interface seems functional - - // checking if all the ports have been opened correctly - CHECK(Network::exists("/grabber/rpc")); - CHECK(Network::exists("/grabber/left")); - CHECK(Network::exists("/grabber/right")); - - yarp::os::BufferedPort> pLeft, pRight; - CHECK(pLeft.open("/pLeft")); // checking if /pLeft was opened correctly - CHECK(pRight.open("/pRight")); // checking if /pRight was opened correctly - - // checking the connections - CHECK(Network::connect("/grabber/left", pLeft.getName())); - CHECK(Network::connect("/grabber/right", pRight.getName())); - - ImageOf* imgL = pLeft.read(); - ImageOf* imgR = pRight.read(); - REQUIRE(imgL != nullptr); - REQUIRE(imgR != nullptr); - - // checking imgL and imgR dimensions - CHECK(imgL->width() == width/2); - CHECK(imgR->width() == width/2); - - // Test the crop function - must work - ImageOf crop; - - // Configure a doable crop. - const yarp::sig::VectorOf> vertices {{0,0}, {10, 10}}; - - // check crop function - CHECK(grabber->getImageCrop(YARP_CROP_RECT, vertices, crop)); - CHECK(crop.width() > 0); - CHECK(crop.height() > 0); - - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } - - Network::setLocalMode(false); -} From 606723e179efdb84d128a4e4a8c6533fa1a1140a Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 16:38:28 +0100 Subject: [PATCH 051/267] completed tests for frameGrabber_nwc_yarp, frameGrabber_nws_yarp, frameGrabberCropper --- .../tests/frameGrabberCropperTest.cpp | 2 + .../frameGrabber_nwc_yarp/CMakeLists.txt | 5 + .../tests/CMakeLists.txt | 12 +-- .../tests/frameGrabber_nwc_yarpTest.cpp | 97 +++++++++++++++++++ .../tests/frameGrabber_nws_yarpTest.cpp | 88 ++++------------- 5 files changed, 128 insertions(+), 76 deletions(-) rename src/devices/{ServerFrameGrabberDual => frameGrabber_nwc_yarp}/tests/CMakeLists.txt (74%) create mode 100644 src/devices/frameGrabber_nwc_yarp/tests/frameGrabber_nwc_yarpTest.cpp diff --git a/src/devices/frameGrabberCropper/tests/frameGrabberCropperTest.cpp b/src/devices/frameGrabberCropper/tests/frameGrabberCropperTest.cpp index b8ae3a483e9..4df92b6f44d 100644 --- a/src/devices/frameGrabberCropper/tests/frameGrabberCropperTest.cpp +++ b/src/devices/frameGrabberCropper/tests/frameGrabberCropperTest.cpp @@ -49,6 +49,7 @@ TEST_CASE("dev::frameGrabberCropperTest", "[yarp::dev]") // Attach frameGrabberCropper left yarp::dev::IWrapper* wl = nullptr; REQUIRE(ddl.view(wl)); + REQUIRE(wl); REQUIRE(wl->attach(&dd)); // Check IFrameGrabberImage on frameGrabberCropper left @@ -74,6 +75,7 @@ TEST_CASE("dev::frameGrabberCropperTest", "[yarp::dev]") // Attach frameGrabberCropper right yarp::dev::IWrapper* wr = nullptr; REQUIRE(ddr.view(wr)); + REQUIRE(wr); REQUIRE(wr->attach(&dd)); // Check IFrameGrabberImage on frameGrabberCropper right diff --git a/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt b/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt index eb288a59ead..ddee458891b 100644 --- a/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt +++ b/src/devices/frameGrabber_nwc_yarp/CMakeLists.txt @@ -46,4 +46,9 @@ if(NOT SKIP_frameGrabber_nwc_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_frameGrabber_nwc_yarp PROPERTY FOLDER "Plugins/Device/NWC") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt b/src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt similarity index 74% rename from src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt rename to src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt index 8cd6b0dbd66..da7942f0229 100644 --- a/src/devices/ServerFrameGrabberDual/tests/CMakeLists.txt +++ b/src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt @@ -20,14 +20,14 @@ endfunction() find_package(YARP::YARP_dev_tests) -add_executable(harness_dev_grabberDual) +add_executable(harness_dev_frameGrabber_nwc_yarp) -target_sources(harness_dev_grabberDual +target_sources(harness_dev_frameGrabber_nwc_yarp PRIVATE - grabberDualTest.cpp + frameGrabber_nwc_yarpTest.cpp ) -target_link_libraries(harness_dev_grabberDual +target_link_libraries(harness_dev_frameGrabber_nwc_yarp PRIVATE YARP_harness YARP::YARP_os @@ -36,6 +36,6 @@ target_link_libraries(harness_dev_grabberDual YARP::YARP_dev_tests ) -set_property(TARGET harness_dev_grabberDual PROPERTY FOLDER "Test") +set_property(TARGET harness_dev_frameGrabber_nwc_yarp PROPERTY FOLDER "Test") -yarp_catch_discover_tests(harness_dev_grabberDual) +yarp_catch_discover_tests(harness_dev_frameGrabber_nwc_yarp) diff --git a/src/devices/frameGrabber_nwc_yarp/tests/frameGrabber_nwc_yarpTest.cpp b/src/devices/frameGrabber_nwc_yarp/tests/frameGrabber_nwc_yarpTest.cpp new file mode 100644 index 00000000000..8919160b487 --- /dev/null +++ b/src/devices/frameGrabber_nwc_yarp/tests/frameGrabber_nwc_yarpTest.cpp @@ -0,0 +1,97 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::sig; + + +TEST_CASE("dev::frameGrabber_nwc_yarpTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); + YARP_REQUIRE_PLUGIN("frameGrabber_nwc_yarp", "device"); + YARP_REQUIRE_PLUGIN("frameGrabber_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Test the frameGrabber_nwc_yarp device with a frameGrabber_nws_yarp device") + { + PolyDriver dd_fake; + PolyDriver dd_nws; + PolyDriver dd_nwc; + Property p_fake; + Property p_nws; + Property p_nwc; + + p_nws.put("device","frameGrabber_nws_yarp"); + p_fake.put("device","fakeFrameGrabber"); + REQUIRE(dd_fake.open(p_fake)); + REQUIRE(dd_nws.open(p_nws)); + yarp::os::SystemClock::delaySystem(0.5); + + {yarp::dev::WrapperSingle* ww_nws; dd_nws.view(ww_nws); + REQUIRE(ww_nws); + bool result_att = ww_nws->attach(&dd_fake); + REQUIRE(result_att); } + + p_nwc.put("device", "frameGrabber_nwc_yarp"); + p_nwc.put("remote", "/grabber"); + p_nwc.put("local", "/grabber/client"); + p_nwc.put("no_stream", 1); + REQUIRE(dd_nwc.open(p_nwc)); + + IFrameGrabberImage* igrabber = nullptr; + IRgbVisualParams* irgbParams = nullptr; + REQUIRE(dd_nwc.view(igrabber)); + REQUIRE(dd_nwc.view(irgbParams)); + + yarp::os::SystemClock::delaySystem(0.5); + + { + ImageOf img; + igrabber->getImage(img); + CHECK(img.width() > 0); + } + { + ImageOf crop; + yarp::sig::VectorOf> vertices; + vertices.resize(2); + vertices[0] = std::pair (0, 0); + vertices[1] = std::pair (10, 10); // Configure a doable crop. + CHECK(igrabber->getImageCrop(YARP_CROP_RECT, vertices, crop)); + CHECK(crop.width() > 0); + CHECK(crop.height() > 0); + } + + yarp::dev::tests::exec_IFrameGrabberImage_test_1(igrabber); + yarp::dev::tests::exec_IRgbVisualParams_test_1(irgbParams); + + yarp::os::SystemClock::delaySystem(0.5); + + CHECK(dd_nwc.close()); + CHECK(dd_nws.close()); + CHECK(dd_fake.close()); + } + + Network::setLocalMode(false); +} diff --git a/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp b/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp index 5dbd23adb06..f93d10cac3a 100644 --- a/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp +++ b/src/devices/frameGrabber_nws_yarp/tests/frameGrabber_nws_yarpTest.cpp @@ -14,6 +14,7 @@ #include #include #include +#include #include @@ -28,87 +29,34 @@ using namespace yarp::sig; TEST_CASE("dev::frameGrabber_nws_yarpTest", "[yarp::dev]") { YARP_REQUIRE_PLUGIN("fakeFrameGrabber", "device"); - YARP_REQUIRE_PLUGIN("frameGrabber_nwc_yarp", "device"); YARP_REQUIRE_PLUGIN("frameGrabber_nws_yarp", "device"); Network::setLocalMode(true); - SECTION("Test the grabber wrapper") + SECTION("Test the frameGrabber_nws_yarp device") { - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - p.put("device","frameGrabber_nwc_yarp"); - p.put("remote","/grabber"); - p.put("local","/grabber/client"); + PolyDriver dd_fake; + PolyDriver dd_nws; + Property p_fake; + Property p_nws; - p2.put("device","frameGrabber_nws_yarp"); - p2.put("subdevice","fakeFrameGrabber"); + p_nws.put("device", "frameGrabber_nws_yarp"); - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); // interface reported + p_fake.put("device", "fakeFrameGrabber"); + REQUIRE(dd_fake.open(p_fake)); + REQUIRE(dd_nws.open(p_nws)); yarp::os::SystemClock::delaySystem(0.5); - ImageOf img; - grabber->getImage(img); - CHECK(img.width() > 0); // interface seems functional - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful - } + {yarp::dev::WrapperSingle* ww_nws; dd_nws.view(ww_nws); + REQUIRE(ww_nws); + bool result_att = ww_nws->attach(&dd_fake); + REQUIRE(result_att); } - SECTION("Test the IRgbVisualParams interface") - { - // Try to open a FakeFrameGrabber and I check all the parameters - PolyDriver dd; - PolyDriver dd2; - Property p; - Property p2; - Property intrinsics; - Bottle* retM = nullptr; - - p.put("device","frameGrabber_nwc_yarp"); - p.put("remote","/grabber"); - p.put("local","/grabber/client"); - p.put("no_stream", 1); - - p2.put("device","frameGrabber_nws_yarp"); - p2.put("subdevice","fakeFrameGrabber"); - - REQUIRE(dd2.open(p2)); // server open reported successful - REQUIRE(dd.open(p)); // client open reported successful - - IFrameGrabberImage* igrabber = nullptr; - IRgbVisualParams* irgbParams = nullptr; - REQUIRE(dd.view(igrabber)); // interface rgb params reported - REQUIRE(dd.view(irgbParams)); // interface rgb params reported - - yarp::dev::tests::exec_IFrameGrabberImage_test_1(igrabber); - yarp::dev::tests::exec_IRgbVisualParams_test_1(irgbParams); - - // Test the crop function - must work. - IFrameGrabberImage *grabber = nullptr; - REQUIRE(dd.view(grabber)); - ImageOf img; - ImageOf crop; - grabber->getImage(img); - - yarp::sig::VectorOf> vertices; - vertices.resize(2); - vertices[0] = std::pair (0, 0); - vertices[1] = std::pair (10, 10); // Configure a doable crop. - - // check crop function - CHECK(grabber->getImageCrop(YARP_CROP_RECT, vertices, crop)); - CHECK(crop.width() > 0); - CHECK(crop.height() > 0); - - CHECK(dd2.close()); // server close reported successful - CHECK(dd.close()); // client close reported successful + yarp::os::SystemClock::delaySystem(0.5); + + CHECK(dd_nws.close()); + CHECK(dd_fake.close()); } Network::setLocalMode(false); From 67ea163e22933fcd74410080971a6a585983c1a0 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 16:49:56 +0100 Subject: [PATCH 052/267] removed examples related to deprecated device `grabberDual` --- example/dev/CMakeLists.txt | 3 - example/dev/double_server/CMakeLists.txt | 21 -- example/dev/double_server/double_server.cpp | 50 --- example/dev/fake_grabber/CMakeLists.txt | 64 ---- example/dev/fake_grabber/FakeFrameGrabber.h | 71 ----- example/dev/fake_grabber/FakeFrameGrabber2.h | 301 ------------------ example/dev/fake_grabber/fake_grabber.cpp | 69 ---- example/dev/fake_grabber/fake_grabber_net.cpp | 55 ---- .../dev/fake_grabber/fake_grabber_net2.cpp | 54 ---- example/dev/file_grabber/CMakeLists.txt | 37 --- example/dev/file_grabber/FileFrameGrabber.h | 99 ------ example/dev/file_grabber/file_grabber.cpp | 67 ---- example/dev/file_grabber/file_grabber_net.cpp | 55 ---- example/dev/file_grabber/image/README.TXT | 8 - example/dev/file_grabber/image/img0250.ppm | 18 -- example/dev/file_grabber/image/img0251.ppm | 16 - example/dev/file_grabber/image/img0252.ppm | 16 - example/dev/file_grabber/image/img0253.ppm | 25 -- example/dev/file_grabber/image/img0254.ppm | 25 -- example/dev/file_grabber/image/img0255.ppm | 15 - example/dev/file_grabber/image/img0256.ppm | 14 - example/dev/file_grabber/image/img0257.ppm | 20 -- example/dev/file_grabber/image/img0258.ppm | 14 - example/dev/file_grabber/image/img0259.ppm | 21 -- 24 files changed, 1138 deletions(-) delete mode 100644 example/dev/double_server/CMakeLists.txt delete mode 100644 example/dev/double_server/double_server.cpp delete mode 100644 example/dev/fake_grabber/CMakeLists.txt delete mode 100644 example/dev/fake_grabber/FakeFrameGrabber.h delete mode 100644 example/dev/fake_grabber/FakeFrameGrabber2.h delete mode 100644 example/dev/fake_grabber/fake_grabber.cpp delete mode 100644 example/dev/fake_grabber/fake_grabber_net.cpp delete mode 100644 example/dev/fake_grabber/fake_grabber_net2.cpp delete mode 100644 example/dev/file_grabber/CMakeLists.txt delete mode 100644 example/dev/file_grabber/FileFrameGrabber.h delete mode 100644 example/dev/file_grabber/file_grabber.cpp delete mode 100644 example/dev/file_grabber/file_grabber_net.cpp delete mode 100644 example/dev/file_grabber/image/README.TXT delete mode 100644 example/dev/file_grabber/image/img0250.ppm delete mode 100644 example/dev/file_grabber/image/img0251.ppm delete mode 100644 example/dev/file_grabber/image/img0252.ppm delete mode 100644 example/dev/file_grabber/image/img0253.ppm delete mode 100644 example/dev/file_grabber/image/img0254.ppm delete mode 100644 example/dev/file_grabber/image/img0255.ppm delete mode 100644 example/dev/file_grabber/image/img0256.ppm delete mode 100644 example/dev/file_grabber/image/img0257.ppm delete mode 100644 example/dev/file_grabber/image/img0258.ppm delete mode 100644 example/dev/file_grabber/image/img0259.ppm diff --git a/example/dev/CMakeLists.txt b/example/dev/CMakeLists.txt index c7513f1bc4f..2012117ae50 100644 --- a/example/dev/CMakeLists.txt +++ b/example/dev/CMakeLists.txt @@ -8,10 +8,7 @@ foreach(example_name attachable audio_test - double_server - fake_grabber fake_motor - file_grabber grabber_client grabber_crop motorcontrol diff --git a/example/dev/double_server/CMakeLists.txt b/example/dev/double_server/CMakeLists.txt deleted file mode 100644 index b1cf9eed1e1..00000000000 --- a/example/dev/double_server/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -if(NOT DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - cmake_minimum_required(VERSION 3.16) - project(double_server) - find_package(YARP REQUIRED COMPONENTS os dev) -endif() - -add_executable(double_server) -target_sources(double_server PRIVATE double_server.cpp) -target_link_libraries(double_server - PRIVATE - YARP::YARP_os - YARP::YARP_init - YARP::YARP_dev -) - -if(DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - set_property(TARGET double_server PROPERTY FOLDER "Examples/dev") -endif() diff --git a/example/dev/double_server/double_server.cpp b/example/dev/double_server/double_server.cpp deleted file mode 100644 index a05774a78dd..00000000000 --- a/example/dev/double_server/double_server.cpp +++ /dev/null @@ -1,50 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#include -#include - -#include - -#include - -using yarp::dev::PolyDriver; -using yarp::os::Network; -using yarp::os::Property; - -int main(int argc, char* argv[]) -{ - YARP_UNUSED(argc); - YARP_UNUSED(argv); - - Network yarp; - - Property config; - config.fromString("(device grabberDual) (subdevice ffmpeg_grabber) (name /dev1/image) (name2 /dev1/sound)"); - - PolyDriver dd(config); - if (!dd.isValid()) { - printf("Failed to create and configure device 1\n"); - return 1; - } - - Property config2; - config2.fromString("(device grabberDual) (subdevice ffmpeg_grabber) (name /dev2/image) (name2 /dev2/sound)"); - - PolyDriver dd2(config2); - if (!dd2.isValid()) { - printf("Failed to create and configure device 2\n"); - return 1; - } - - while (true) { - printf("Sending data..."); - yarp::os::Time::delay(5); - } - - return 0; -} diff --git a/example/dev/fake_grabber/CMakeLists.txt b/example/dev/fake_grabber/CMakeLists.txt deleted file mode 100644 index c0a8ddc5107..00000000000 --- a/example/dev/fake_grabber/CMakeLists.txt +++ /dev/null @@ -1,64 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -if(NOT DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - cmake_minimum_required(VERSION 3.16) - project(fake_grabber) - find_package(YARP REQUIRED COMPONENTS os sig dev) -endif() - -add_executable(fake_grabber) -target_sources(fake_grabber - PRIVATE - fake_grabber.cpp - FakeFrameGrabber.h -) -target_link_libraries(fake_grabber - PRIVATE - YARP::YARP_os - YARP::YARP_init - YARP::YARP_sig - YARP::YARP_dev -) - -if(DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - set_property(TARGET fake_grabber PROPERTY FOLDER "Examples/dev") -endif() - - -add_executable(fake_grabber_net) -target_sources(fake_grabber_net - PRIVATE - fake_grabber_net.cpp - FakeFrameGrabber.h -) -target_link_libraries(fake_grabber_net - PRIVATE - YARP::YARP_os - YARP::YARP_init - YARP::YARP_sig - YARP::YARP_dev -) - -if(DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - set_property(TARGET fake_grabber_net PROPERTY FOLDER "Examples/dev") -endif() - - -add_executable(fake_grabber_net2) -target_sources(fake_grabber_net2 - PRIVATE - fake_grabber_net2.cpp - FakeFrameGrabber2.h -) -target_link_libraries(fake_grabber_net2 - PRIVATE - YARP::YARP_os - YARP::YARP_init - YARP::YARP_sig - YARP::YARP_dev -) - -if(DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - set_property(TARGET fake_grabber_net2 PROPERTY FOLDER "Examples/dev") -endif() diff --git a/example/dev/fake_grabber/FakeFrameGrabber.h b/example/dev/fake_grabber/FakeFrameGrabber.h deleted file mode 100644 index 375dd61b1b8..00000000000 --- a/example/dev/fake_grabber/FakeFrameGrabber.h +++ /dev/null @@ -1,71 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include - -#include -#include - -class FakeFrameGrabber : - public yarp::dev::IFrameGrabberImage, - public yarp::dev::DeviceDriver -{ -private: - int w, h; - int ct; - yarp::sig::PixelRgb circlePixel; - -public: - FakeFrameGrabber() - { - h = w = 0; - ct = 0; - circlePixel = yarp::sig::PixelRgb{255, 0, 0}; - } - - bool open(int w, int h) - { - this->w = w; - this->h = h; - return w > 0 && h > 0; - } - - bool open(yarp::os::Searchable& config) override - { - // extract width and height configuration, if present - // otherwise use 128x128 - int desiredWidth = config.check("w", yarp::os::Value(128)).asInt32(); - int desiredHeight = config.check("h", yarp::os::Value(128)).asInt32(); - return open(desiredWidth, desiredHeight); - } - - bool close() override - { - return true; // easy - } - - bool getImage(yarp::sig::ImageOf& image) override - { - yarp::os::Time::delay(0.1); // simulate waiting for hardware to report - image.resize(w, h); - image.zero(); - yarp::sig::draw::addCrossHair(image, circlePixel, ct, h / 2, h / 8); - ct = (ct + 4) % w; - return true; - } - - int height() const override - { - return h; - } - - int width() const override - { - return w; - } -}; diff --git a/example/dev/fake_grabber/FakeFrameGrabber2.h b/example/dev/fake_grabber/FakeFrameGrabber2.h deleted file mode 100644 index 061514f123c..00000000000 --- a/example/dev/fake_grabber/FakeFrameGrabber2.h +++ /dev/null @@ -1,301 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include - -#include - -class FakeFrameGrabber : - public yarp::dev::IFrameGrabberImage, - public yarp::dev::IFrameGrabberControls, - public yarp::dev::DeviceDriver -{ -private: - int w, h; - int ct; - yarp::sig::PixelRgb circlePixel; - double brightness; - -public: - FakeFrameGrabber() - { - h = w = 0; - ct = 0; - circlePixel = yarp::sig::PixelRgb{255, 0, 0}; - brightness = 1; - } - - bool open(int w, int h) - { - this->w = w; - this->h = h; - return w > 0 && h > 0; - } - - bool open(yarp::os::Searchable& config) override - { - // extract width and height configuration, if present - // otherwise use 128x128 - int desiredWidth = config.check("w", yarp::os::Value(128)).asInt32(); - int desiredHeight = config.check("h", yarp::os::Value(128)).asInt32(); - return open(desiredWidth, desiredHeight); - } - - bool close() override - { - return true; // easy - } - - bool getImage(yarp::sig::ImageOf& image) override - { - yarp::os::Time::delay(0.1); // simulate waiting for hardware to report - image.resize(w, h); - image.zero(); - yarp::sig::draw::addCrossHair(image, circlePixel, ct, h / 2, h / 8); - ct = (ct + 4) % w; - return true; - } - - int height() const override - { - return h; - } - - int width() const override - { - return w; - } - -#ifndef YARP_NO_DEPRECATED // Since YARP 3.0.0 - bool setBrightness(double v) override - { - if (v > 1) { - v = 1; - } - if (v < 0) { - v = 0; - } - circlePixel = yarp::sig::PixelRgb{static_cast(255 * v), 0, 0}; - brightness = v; - return true; - } - - bool setShutter(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setGain(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setWhiteBalance(double red, double green) override - { - YARP_UNUSED(red); - YARP_UNUSED(green); - return false; - } - - bool getWhiteBalance(double& red, double& green) - override - { - red = 0; - green = 0; - return false; - } - - double getBrightness() override - { - return brightness; - } - - double getShutter() override - { - return 0; - } - - double getGain() override - { - return 0; - } - - bool setExposure(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setSharpness(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setHue(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setSaturation(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setGamma(double v) override - { - YARP_UNUSED(v); - return false; - } - - bool setIris(double v) override - { - YARP_UNUSED(v); - return false; - } - - double getExposure() override - { - return 0.0; - } - - double getSharpness() override - { - return 0.0; - } - - double getHue() override - { - return 0.0; - } - - double getSaturation() override - { - return 0.0; - } - - double getGamma() override - { - return 0.0; - } - - double getIris() override - { - return 0.0; - } -#endif - - bool getCameraDescription(CameraDescriptor* camera) override - { - YARP_UNUSED(camera); - return false; - } - - bool hasFeature(int feature, bool* hasFeature) override - { - YARP_UNUSED(feature); - YARP_UNUSED(hasFeature); - return false; - } - - bool setFeature(int feature, double value) override - { - YARP_UNUSED(feature); - YARP_UNUSED(value); - return false; - } - - bool getFeature(int feature, double* value) override - { - YARP_UNUSED(feature); - YARP_UNUSED(value); - return false; - } - - bool setFeature(int feature, double value1, double value2) override - { - YARP_UNUSED(feature); - YARP_UNUSED(value1); - YARP_UNUSED(value2); - return false; - } - - bool getFeature(int feature, double* value1, double* value2) override - { - YARP_UNUSED(feature); - YARP_UNUSED(value1); - YARP_UNUSED(value2); - return false; - } - - bool hasOnOff(int feature, bool* HasOnOff) override - { - YARP_UNUSED(feature); - YARP_UNUSED(HasOnOff); - return false; - } - - bool setActive(int feature, bool onoff) override - { - YARP_UNUSED(feature); - YARP_UNUSED(onoff); - return false; - } - - bool getActive(int feature, bool* isActive) override - { - YARP_UNUSED(feature); - YARP_UNUSED(isActive); - return false; - } - - bool hasAuto(int feature, bool* hasAuto) override - { - YARP_UNUSED(feature); - YARP_UNUSED(hasAuto); - return false; - } - - bool hasManual(int feature, bool* hasManual) override - { - YARP_UNUSED(feature); - YARP_UNUSED(hasManual); - return false; - } - - bool hasOnePush(int feature, bool* hasOnePush) override - { - YARP_UNUSED(feature); - YARP_UNUSED(hasOnePush); - return false; - } - - bool setMode(int feature, FeatureMode mode) override - { - YARP_UNUSED(feature); - YARP_UNUSED(mode); - return false; - } - - bool getMode(int feature, FeatureMode* mode) override - { - YARP_UNUSED(feature); - YARP_UNUSED(mode); - return false; - } - - bool setOnePush(int feature) override - { - YARP_UNUSED(feature); - return false; - } -}; diff --git a/example/dev/fake_grabber/fake_grabber.cpp b/example/dev/fake_grabber/fake_grabber.cpp deleted file mode 100644 index 0c55dcde7cf..00000000000 --- a/example/dev/fake_grabber/fake_grabber.cpp +++ /dev/null @@ -1,69 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - - -#include -#include - -#include - -#include -#include -#include - -#include "FakeFrameGrabber.h" -#include - -using yarp::dev::DriverCreator; -using yarp::dev::DriverCreatorOf; -using yarp::dev::Drivers; -using yarp::dev::IFrameGrabberImage; -using yarp::dev::PolyDriver; -using yarp::os::Network; -using yarp::os::Property; -using yarp::sig::ImageOf; -using yarp::sig::PixelRgb; - -int main(int argc, char* argv[]) -{ - Network yarp; - - // give YARP a factory for creating instances of FakeFrameGrabber - DriverCreator* fakey_factory = new DriverCreatorOf("fakey", - "grabber", - "FakeFrameGrabber"); - Drivers::factory().add(fakey_factory); // hand factory over to YARP - - // use YARP to create and configure an instance of FakeFrameGrabber - Property config; - if (argc == 1) { - // no arguments, use a default - config.fromString("(device fakey) (w 640) (h 480)"); - } else { - // expect something like "--device fakey --w 640 --h 480" - // or "--device dragonfly" - // or "--device fakeFrameGrabber --period 0.5 --mode [ball]" - config.fromCommand(argc, argv); - } - PolyDriver dd(config); - if (!dd.isValid()) { - printf("Failed to create and configure a device\n"); - return 1; - } - IFrameGrabberImage* grabberInterface; - if (!dd.view(grabberInterface)) { - printf("Failed to view device through IFrameGrabberImage interface\n"); - return 1; - } - - ImageOf img; - grabberInterface->getImage(img); - printf("Got a %zux%zu image\n", img.width(), img.height()); - - dd.close(); - - return 0; -} diff --git a/example/dev/fake_grabber/fake_grabber_net.cpp b/example/dev/fake_grabber/fake_grabber_net.cpp deleted file mode 100644 index 084a54804d5..00000000000 --- a/example/dev/fake_grabber/fake_grabber_net.cpp +++ /dev/null @@ -1,55 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "FakeFrameGrabber.h" - -#include -#include -#include - -#include -#include - -#include - -using yarp::dev::DriverCreator; -using yarp::dev::DriverCreatorOf; -using yarp::dev::Drivers; -using yarp::dev::PolyDriver; -using yarp::os::Network; -using yarp::os::Property; - - -int main(int argc, char* argv[]) -{ - YARP_UNUSED(argc); - YARP_UNUSED(argv); - - Network yarp; - - // give YARP a factory for creating instances of FakeFrameGrabber - DriverCreator* fakey_factory = new DriverCreatorOf("fakey", - "grabberDual", - "FakeFrameGrabber"); - Drivers::factory().add(fakey_factory); // hand factory over to YARP - - // use YARP to create and configure a networked of FakeFrameGrabber - Property config; - config.fromString("(device grabberDual) (name /fakey) (subdevice fakey) (w 200) (h 200)"); - PolyDriver dd(config); - if (!dd.isValid()) { - printf("Failed to create and configure a device\n"); - return 1; - } - - // snooze while the network device operates - while (true) { - printf("Network device is active...\n"); - yarp::os::Time::delay(5); - } - - return 0; -} diff --git a/example/dev/fake_grabber/fake_grabber_net2.cpp b/example/dev/fake_grabber/fake_grabber_net2.cpp deleted file mode 100644 index 9dc8cd70d0f..00000000000 --- a/example/dev/fake_grabber/fake_grabber_net2.cpp +++ /dev/null @@ -1,54 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include -#include - -#include -#include - -#include "FakeFrameGrabber2.h" -#include - -using yarp::dev::DriverCreator; -using yarp::dev::DriverCreatorOf; -using yarp::dev::Drivers; -using yarp::dev::PolyDriver; -using yarp::os::Network; -using yarp::os::Property; - - -int main(int argc, char* argv[]) -{ - YARP_UNUSED(argc); - YARP_UNUSED(argv); - - Network yarp; - - // give YARP a factory for creating instances of FakeFrameGrabber - DriverCreator* fakey_factory = new DriverCreatorOf("fakey", - "grabberDual", - "FakeFrameGrabber"); - Drivers::factory().add(fakey_factory); // hand factory over to YARP - - // use YARP to create and configure a networked of FakeFrameGrabber - Property config; - config.fromString("(device grabberDual) (name /fakey) (subdevice fakey) (w 200) (h 200)"); - PolyDriver dd(config); - if (!dd.isValid()) { - printf("Failed to create and configure a device\n"); - return 1; - } - - // snooze while the network device operates - while (true) { - printf("Network device is active...\n"); - yarp::os::Time::delay(5); - } - - return 0; -} diff --git a/example/dev/file_grabber/CMakeLists.txt b/example/dev/file_grabber/CMakeLists.txt deleted file mode 100644 index 6ea5ceb67c6..00000000000 --- a/example/dev/file_grabber/CMakeLists.txt +++ /dev/null @@ -1,37 +0,0 @@ -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-License-Identifier: BSD-3-Clause - -if(NOT DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - cmake_minimum_required(VERSION 3.16) - project(file_grabber) - find_package(YARP REQUIRED COMPONENTS os sig dev) -endif() - -add_executable(file_grabber) -target_sources(file_grabber PRIVATE file_grabber.cpp) -target_link_libraries(file_grabber - PRIVATE - YARP::YARP_os - YARP::YARP_init - YARP::YARP_sig - YARP::YARP_dev -) - -if(DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - set_property(TARGET file_grabber PROPERTY FOLDER "Examples/dev") -endif() - - -add_executable(file_grabber_net) -target_sources(file_grabber_net PRIVATE file_grabber_net.cpp) -target_link_libraries(file_grabber_net - PRIVATE - YARP::YARP_os - YARP::YARP_init - YARP::YARP_sig - YARP::YARP_dev -) - -if(DEFINED CMAKE_MINIMUM_REQUIRED_VERSION) - set_property(TARGET file_grabber_net PROPERTY FOLDER "Examples/dev") -endif() diff --git a/example/dev/file_grabber/FileFrameGrabber.h b/example/dev/file_grabber/FileFrameGrabber.h deleted file mode 100644 index 50adf7e24ea..00000000000 --- a/example/dev/file_grabber/FileFrameGrabber.h +++ /dev/null @@ -1,99 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include - -#include -#include - -class FileFrameGrabber : - public yarp::dev::IFrameGrabberImage, - public yarp::dev::DeviceDriver -{ -private: - std::string pattern{"%d.ppm"}; - std::string lastLoad; - int first{-1}; - int last{-1}; - int at{-1}; - int h{0}; - int w{0}; - - bool findImage(yarp::sig::ImageOf& image) - { - bool triedFirst = false; - char buf[1000]; - sprintf(buf, pattern.c_str(), at); - while (!yarp::sig::file::read(image, buf)) { - if (at == first) { - if (triedFirst) { - return false; - } - triedFirst = true; - } - if (last == -1) { - at = first; - } else { - at++; - if (at > last) { - at = first; - } - } - sprintf(buf, pattern.c_str(), at); - } - lastLoad = buf; - h = image.height(); - w = image.width(); - return true; - } - -public: - bool open(const char* pattern, int first, int last) - { - this->pattern = pattern; - this->first = first; - this->last = last; - at = first; - yarp::sig::ImageOf dummy; - return findImage(dummy); - } - - bool open(yarp::os::Searchable& config) override - { - std::string pattern = config.check("pattern", yarp::os::Value("%d.ppm")).asString(); - int first = config.check("first", yarp::os::Value(0)).asInt32(); - int last = config.check("last", yarp::os::Value(-1)).asInt32(); - return open(pattern.c_str(), first, last); - } - - bool close() override - { - return true; // easy - } - - bool getImage(yarp::sig::ImageOf& image) override - { - bool ok = findImage(image); - if (ok) { - printf("showing image %s\n", lastLoad.c_str()); - at++; - if (last != -1 && at > last) { - at = first; - } - } - return ok; - } - - int height() const override - { - return h; - } - - int width() const override - { - return w; - } -}; diff --git a/example/dev/file_grabber/file_grabber.cpp b/example/dev/file_grabber/file_grabber.cpp deleted file mode 100644 index f4e2c98e297..00000000000 --- a/example/dev/file_grabber/file_grabber.cpp +++ /dev/null @@ -1,67 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include -#include -#include -#include -#include -#include - -#include "FileFrameGrabber.h" - -#include - -using yarp::os::Network; -using yarp::os::Property; -using yarp::dev::DriverCreator; -using yarp::dev::DriverCreatorOf; -using yarp::dev::Drivers; -using yarp::dev::PolyDriver; -using yarp::dev::IFrameGrabberImage; -using yarp::sig::ImageOf; -using yarp::sig::PixelRgb; - -int main(int argc, char* argv[]) -{ - Network yarp; - - // give YARP a factory for creating instances of FileFrameGrabber - DriverCreator* file_grabber_factory = new DriverCreatorOf("file_grabber", - "grabber", - "FileFrameGrabber"); - Drivers::factory().add(file_grabber_factory); // hand factory over to YARP - - // use YARP to create and configure an instance of FileFrameGrabber - Property config; - if (argc == 1) { - // no arguments, use a default - config.fromString("(device file_grabber) (pattern \"image/%03d.ppm\")"); - } else { - // expect something like '--device file_grabber --pattern "image/%03d.ppm"' - // or '--device dragonfly' - // or '--device fakeFrameGrabber --period 0.5 --mode [ball]' - config.fromCommand(argc, argv); - } - PolyDriver dd(config); - if (!dd.isValid()) { - printf("Failed to create and configure a device\n"); - return 1; - } - IFrameGrabberImage* grabberInterface; - if (!dd.view(grabberInterface)) { - printf("Failed to view device through IFrameGrabberImage interface\n"); - return 1; - } - - ImageOf img; - grabberInterface->getImage(img); - printf("Got a %zux%zu image\n", img.width(), img.height()); - - dd.close(); - - return 0; -} diff --git a/example/dev/file_grabber/file_grabber_net.cpp b/example/dev/file_grabber/file_grabber_net.cpp deleted file mode 100644 index 40ed2482e40..00000000000 --- a/example/dev/file_grabber/file_grabber_net.cpp +++ /dev/null @@ -1,55 +0,0 @@ -/* - * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) - * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium - * SPDX-License-Identifier: BSD-3-Clause - */ - -#include "FileFrameGrabber.h" - -#include -#include -#include - -#include -#include - -#include - -using yarp::dev::DriverCreator; -using yarp::dev::DriverCreatorOf; -using yarp::dev::Drivers; -using yarp::dev::PolyDriver; -using yarp::os::Network; -using yarp::os::Property; - -int main(int argc, char* argv[]) -{ - YARP_UNUSED(argc); - YARP_UNUSED(argv); - - Network yarp; - - // give YARP a factory for creating instances of FileFrameGrabber - DriverCreator* file_grabber_factory = new DriverCreatorOf("file_grabber", - "grabberDual", - "FileFrameGrabber"); - Drivers::factory().add(file_grabber_factory); // hand factory over to YARP - - // use YARP to create and configure a networked of FakeFrameGrabber - Property config; - // You may have to tweak the "image" path to match where your executable is - config.fromString("(device grabberDual) (name /file) (subdevice file_grabber) (pattern \"image/img%04d.ppm\") (first 250)"); - PolyDriver dd(config); - if (!dd.isValid()) { - printf("Failed to create and configure a device\n"); - return 1; - } - - // snooze while the network device operates - while (true) { - printf("Network device is active...\n"); - yarp::os::Time::delay(5); - } - - return 0; -} diff --git a/example/dev/file_grabber/image/README.TXT b/example/dev/file_grabber/image/README.TXT deleted file mode 100644 index 8bbfde39c5f..00000000000 --- a/example/dev/file_grabber/image/README.TXT +++ /dev/null @@ -1,8 +0,0 @@ -The images in this directory are: - -# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) -# SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium -# SPDX-License-Identifier: BSD-3-Clause - -# At your option, you may alternatively use the images under the Creative -# Commons Attribution license, see http://creativecommons.org/licenses/by/3.0/ diff --git a/example/dev/file_grabber/image/img0250.ppm b/example/dev/file_grabber/image/img0250.ppm deleted file mode 100644 index 913779608cd..00000000000 --- a/example/dev/file_grabber/image/img0250.ppm +++ /dev/null @@ -1,18 +0,0 @@ -P6 -128 128 -255 -brƒcs‚iyˆjv‚ls~wy}¯ªª‡tzˆso|Œo}ˆtƒ‰p‹ar]n}t…”‘£¯¢³½£µ¼¨·¿®¼Ç¹ÇÔºË×ÂÓßÊÜãÌÛßÙäååììèìïñóùòôøññóôôö÷÷ùùüýöøüøúþôóøþþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúùþóñûäêï×åçÑäéÊâêÅÝåÌáêÃÛå½Ôã¿ØæºÓá¹Ôæ·Òè³Íè°Éé·ÌéºÊä°ÆÚ¯ÈØ®Ç×°ÆÚ³Éß°ÂÞµËã¸Ðå¸ÐåµÍä¬ÇÝ©Ãܤ¾×«ÂÞ³Êä³Éá«ÃÚ¥¿Ø©ÃÜ«ÂÞ¬ÄÛ¥½Ò¤¼Ï­Ãר¾Ò¦¼Ð§¾Ï§»Ë¢³ÄªºÍ¯ÀÓ¬½Ð¨¹Ì¨¸Î§»Í¢¹È§ºÏ¢²Ì¥µËªºÍ§·È °Áž¯»©·Â®½Å›ª²š©±™¥±–¤± ¯‰š©…–§€‘¢{Œwˆ—qƒk|hxŽ[q…Vq…Sk~Rh|Uiy\m|Oaf_pewfy~k{|pxzy}u¯«œ‚u|…n{‚m|„p‡v…k}‡bv„_psƒ’Šœ¨˜ª´œ¯¶¥¸¿±Ä˵ÇηÍÓ½ÕÝÆÙàÑàèÙæëÜçèãìëêïïêíîñðõíïóñóùûýÿóò÷ññóòòôûûýÿÿÿýýýùùùôôöÿýÿöõüôóúðòøçêòâïöÎáèÅÞãÀÝãÀÝãÉãìÀ×æ½ÐåµÍâ­Çà²É㩾ٱÃß±À߶Èä½Óë·Òä·Ôá¯ËݯÉâ¸Ðç¹Ïç¸Ðç¯Æà­ÅÜ­ÅÚºÐæ²ÅܱÄÙ¹Ìá°Æܦ½×¦ÀÛ¨ÁߨÂݬÃߪÁÛ©¾Ù¤¼Ï¨ÁÍ©½Ë©¹Ê©ºÍ¤·Î¤´Ê©¸Î©¸Î©¸Î«»Ñ¡´ÉžµÆžµÆ ·È§ºÏ¦¹Î£¶Íš®Àž¯¾Ÿ¯¾ ­¿™¦¸˜¥¹•¥¶ ¯ˆœ¬‡š¯‚–¦}Žwˆ”t‚uƒly‹du†]qƒZn€Vj|Ym}TetKZ`_pm~iyˆlz…jw~v{w·µ¦ƒˆ„q{ƒl{ƒm~ˆqƒŠu„Œq‚Žev‰bv†q…“”Ÿ•§±¯»ª»Ê°ÄÒ²ÉÖ¹ÎÙÇÙåÉÛåÈÙãÐÝäÜãêßæíàçðÞæêäêíëñôéíðíðñóóõòòôûûýøøúÿþÿùøýø÷üðïôòñøñó÷íñôæìñåêô×éðÈâéÂÜãÂÚäÂÙæ»ÏáµÉÛ²ÅÚµÈݼÏäÀÖê´Ìß·Òæ°Êã¯Æà­ÂݹÑä·Óà²ÎÝ´Ìß³Îâ±Ëä¬ÈÞ¯Ëß±Íã°Êå¯Êå±Ìç°Ëæ°Êå«ÇÝ®ÊÜ¥ÀÒ±ÉÞ°Ëß©ÅÛ°Ë߬ÄÙ®ÆÙ¬ÂÖ®ÄØ£¶Ë§ºÏ§ºÏ¤´Ê§³Ì¥±ÈµÁØ­½Õ¡¶Ñ³ËŸµË ¸Ëš²Å¶Æ¡¸ÉŸ°Ã ¬Ãœ¬½™ª¶”¥±”¡±‹œ¦‘£ª’ ­Š•ªƒ¤‚£ sƒ’k|‹k|‹cw…]qYmXk‚SgyQbs?NRao|_o~ct…m{ˆox…uzx¼»®„Šƒt|€mzƒiv†m}Žo€“l}Žm~au…m„“}‘Ÿ’¢±®º¦·Ã­¾Ê®¿Ë®¿É»ÌÖÇØâÉÚäÉÛàÖåéÒååØëëÔççÚêëãñóçîõëó÷èîóïóøûúÿòñöùøýúùþðïô÷ùýó÷úíõùâìòàíòØåìÌÞåËÝç¿ÔßÀÔâ»Òã¸ÐåÁÚêÄÝëºÖå½Øê¯ÊÞ¬ÇݲÌå±Èä¦ÀÙ°Êã¯Êà±Ìà³Ïã±Íá°Ìâ¬Æá­Çâ¬Åã¬Æä©Ãã±Ìç²Íæ±Íã´Ïå«ÃÚ­ÃÛ¨¾Ö´Æâ«Áק½Ñ›¶È›·Ë£¾Ð¬ÄתÆÕ©ÅÔ¨ÄÓ¥¾Î¡¹Ì¦¼Ò¨¿Ð¶ÍÜ¥¼ÉžµÂ±ÃŸ¯Ç£³Ëœ¬Æ˜§¿Ÿ«Ä¬Âž¯Â›¬¿˜¨¾˜¬¾£µ•¦µ•¦²•¦²ŽŸ«…•¦†•­‚’¨r…šn‚”hyŒh|ŽdzŽZm‚TdzUdzQ]tE]n[k~an‚lu„kp|vyv¾¼­ŒŒt{„nw„u€‘u‚”s–o|Žs€l|‹pxˆ›Š–±—¦À¡±Ë©ºÍ«»Ê²ÃÔ³Ä×·ËݸËà¸ËàÆÖìÄÕèÆ×èÑãïÎáèÐâçÞëòàïõÓâèÔæëÖèíÊÜß¼ÌÍËÖ×ÝãæèîñòøûéñõæíöÏÙãÔàìÌÝé¾ÒâºÑàÀ×èÆàéÒíñÀØâ¹ÍÝ°ÇغÒç·Òä¹ÕçÇã÷³Íæ«Æá°Êè«Åà±ÈäªÄݪÄÝ´ÏåºÕë¿Úð¶Îå¯Äᮿ⮿୿ݯÁݧºÓ¬ÄÛ¨ÂÛ°Ê奻ڱӦ·Ü£´Õ¦¸Ö ²Ð¯Í¦¸Ô¤·Ð°É¨¸Ò¤´Îž­Ê“¥Á›­É¢µÎ¬¼Ô£¶Í ³Ê¡±Ç¥´Êž­Å¤°Ë˜§½ž®¿œ­¾š«¼–ªºŠž®£µ‚•ªƒ–«‚•ª|¤|¦{Ž£t‡œtƒ™q{•bn‡jy‘ct‡du„r‚‘Vcu2AIUfwZkz_petzemoptnÀ»±ŒŽ’tyŽmx‹s€’t•s}•mzŽiyŠn~t„—zŠ †–® ¶Ÿ¯Å¡±ÇªºÐ²ÃÖ±ÂÕ·ÈÛ¿ÐãÀÐæºÊäÆÚìÊßêÑæñËÝéÈÙèÁÑäºÊÝ¿ÎäÏàêâòóç÷øêøúÛëìÔãçÚèêÝèéàìêìøöå÷üÆÚêÅÜëÈßðÇàîÍéöÈàó¾Ôì¾Ôì¶Éâ²ÈàµÌæ®Åß²Éå±Ìå­Ëã®Éâ¶Íé¶Íç´Ëå³Ëâ¶Îã¯Éâ¯Éç±Ëä¶Îå¶Îå»Òì±Èâ±Èâ°Êã¶Ðë¯ÉäªÄߟ¹Ò£¾Ô±ÉÞ¯ÅÙ¥»Ñ¬ÂÚ©¿Õ¤ºÐ¦¹Ð¤´Ì¥µÍ­ÅŸ¯Ç¦¶Ð›±Å›·Æ¸Ê˜³É³Ë£³Í¢²Ì¬É˜«ÄŸ²É­Ãž­ÃšªÀ­Ã•©»§¶Šž®Ÿ²…•¨‚‘§€¥¦yˆ r‚šl|”r™l|”hx’eu^n„`pS`p(28\gxVgs]o{Ykp_mmpvo¹¶ª‹q}‹o|Œs€”s€”p}‘gwˆhyŠm~‘q—wŠŸƒ–­‹ž³‹Ÿ±“ª»¡·Ë­Ã×±ÄÛ±ÄÛ¸Ëä¼Ïä¹Íß¿Óå¸Ëà¾Òä¾ÒäÃ×åØêöÑãïÍÞíÎâðÉÝë¿ÔÝÌâèÊßêÂÓæÇØçÑãíÊßêÇÛé¿ØäÅáî¿ØæÉàñÇßòÂÚï»Öì¸Òë³Îâ²ÊݲÊá³Çç´Ëç­Çâ¬Çâ¨ÃÞ°Ëæ¯Éç°Ëæ®Éâ¬Æß´Ëå¬ÃÝ­ÂßµÍä²Êߨ¾ÔµÈá²Êá±ËäªÅÞ©Äߥ¾Ü ´Ö¡µÕ©»Ù«½Ù²Äà±Ãᤵ֩ºÛ¨¹Ú ²Î¢µÎ£¶Ë¦·Ê¥µË¡±É¤·Î¤·Ð¨»Ò¤·Ìœ¯Ä›®Ãš­Ä–¨Ä˜¨ÀŸ¯Â ¯Ç’ ½‘ ºž¸”£¹±‹›®ž±†–¬‚‘©†•«ƒ“¦¥t‡žp„”r‡’oƒ‘j{Žev‰_pƒ[kzSal5?Elv€YgrVgs`ny_luoux¼º¶Œ‘‘v€ˆo}ˆl}Œj{Œfv‰hyŒp€–o—r‚œv‰ }¥Š›®–£µ›¨¼ ¬Å©¸Ð©¹Ñ¨·Ô°½á­¼Ù´ÇܵÌݺÑâ¼Óä¹Ïã¾ÒäÇØë»Ïá·Íá¹ÒâÂÛéÀÜéÁÝê¾ÚçÆßíÉàïÄØêÇÛíÂÕêÉÝïÊÞðÀÓèÂÒì¼Ïè¶Ëæ¹Ñè·Òè´Ïå¾Øñ¬Æá®Äã´Êé·ËëµÌè´ÎçÀÛô·Òí²ÌåÃØó±Ëä®Éâ­Çà®Åá¬Æ߶Ñç³Ëâ­ÂÝ°Åà¯Äá­Ãâ²Èé¨Áß©ÂॿگÆ⧾ثÃÚ®ÄÜ«½Ùª½Ö­½×¨»Ò§ºÑ­ÀÙ«ºÙ¤·ÎžµÆ¡¸É±Ã˜«À™¬Å™¬Å™«Çš¬Ê•¦Ç–¨Ä’¥¼“¦»“£¹“§¹‘¥µž¯‘ž²‡–¬‡—¯‘§‡˜«„•¨†–¬‰™¯xˆ l|’l|oƒ•d}hxŽfpŒckGL_),8|€ƒgru`ouanuakspty³¯µˆ—p|Šly‰iyŒk{Œeu†`t„d{Œd}j‚•p†š{Ž£„˜ª£µŽ¢´”§¼´ÅŸ¶Å©½Ï¬¼Ôª½Ô­ÀÙµÈá´Çà­ÃÛ®ÅßµÊå¹Ëç½Ìé¹Çä¶ÉâÃÙï¾Ôè¾ÔèÁÙîÂÚñ¼ÔëºÑë¹Ïç½ÐéÀÖì½Óé¿ÒéºÊâ·Íã¹Ñæ¹Ôê®Éä¬Çâ³Îé³ÍèºÐï¸Ñï³Ìê±ËæªÄݬÇݪÅÛ¯Éä±Çè¯Èæ¬Æá¾ÙïÂÝï¶ÑåµÍä´Ìá¼Òè¿ÖðªÃ㣾ٷÒë«ÆߪÅÞªÄÝ«Âܧ¾Ú­Ãâ«ÂÞ¤»×¥ºÕ©¹Ó¢²Ê¥µÍ¢µÌ³Éœ´É¸Ì¡¹Î¢µÎ£¶Ï›«ÅŸ²É¡´É ³Ê ³Ì™¬Å•§Ã™¬Á—¨·¤±ˆ¤¯ˆ¡±‡š³‡—±” »ˆ—¯„”ª‚’¨…”ª~Ž¡w„˜z†wƒžr›q›o™dtŽZf};@W&-8yywx~ƒen{]gq^eplpsªª¨ˆ–mzŒdt‡ds‹bs†^o€[lbq‡dtŠk{‘r†˜u‰›yŸƒš©’¦¸˜§½–¦¼›®Ã¡´Ë¥´Ñ¨¸Ð¨¹Ì°ÄÔ¿ÓáµËß³Èã®ÆݱÌâ¯ÇܺÐæ´ÊâºÏì´Éä·Íå¹ÑèÁÙð½Øî¹Ôê½Øì¿×ìÁÜò¿Ùò³Íæ²Éå¶Îå·Íá±ÊÚ´Ð߶Ñå»Òî´Îç²Ìå¶Ðë²Èé²Ëé±Ëé±Ìç²Ìç´Îç¯Éâ©ÅÛªÉÜ´ÔâÃàíÅâñ®ÊÞ®ÊÜ©ÄÖ¶Ñå¨Àפ»×§½Þ¦¿Ý£¾Ù£¾×«Æ߬ÃÝ«½Û¥º×¢·Ô¤¼Ó¤¿Ó¤¼Ñ¦¹Ò ³Ì¢µÎ¡³Ï¨ºØ«½Û£µÓ¡³Ï£µÑ°Ç¯¿ÕŸµË¸Î¢½Ñ—¯Ä˜®Äœ¯Æ™¬Ã¢»¦¾‹¡¹…›±ƒ–­…™«ˆ™ª’££{’¡|•£y’¢u‹Ÿl‚˜m€™h{ct‡N^q4AU:AL\_^xnvz^hnWdkmqt¬§§ˆŽ“gu‚[l{]qXl|Wh{Vfy_l€_o‚izk•j‚—x§„™´¢»•¥½”§¾š°Æ¦¹Ò¦µÒ£²Ï¦µÒ°¿Ü°¿Þ¬ÁÜ®Åß©ÃܶÐé´Ìá´ÈÚ­Ã×½Óë³Ëà¯ÊÜ°Ëß³Íæ·Òë³Îé¶Ñê³Îç´Îç³Êä­ÈÞ¯Ëá¸Ôè½ØêºÖå»Ôä´Ìß²Êß³Îä³Íæ³Îâ±ÉÜ°Ëá¬Åã«Äâ­Ãâ²Éã·Íå¸ÏéºÔï³Íæ²Êá²Íá¯ÊÞ³Îà²ÊÝ­ÄÞ¨¾á¥¾ÜªÅà«ÆܬÄÙ«ÆÜ£½Ø¦Áפ¿Ó¨Ãס¼Ð¤¼Ó¥º×£»Ò¤¼Ñ ¸Íš²Éš°È¯Ë¢¸Ð¢¸Ð§ºÑ¡±É™¬Å¨½Ø˜°Ã“¯¼–¯¿–¬À‘§½•¨Á•¨¿¢·Žž´‘ ¸‰™±ƒ–­ƒ–«‡—­†—¨Š›ª{Œw‡r…šn„˜i“j}’hyˆes~Wdtq{“~Š˜GIMgim{zlrwYdggnl¥¦¡‰’gp}XdrWdtUevVfyPatUh}_u‰i“oˆ˜pŒ›vŽ¡€“ªˆ›°•¨½¤¼Ñ›¶Ì–±Åž¶É¤¼Ó ¶ÕªÁݧ¼×®ÃÞ³Èå²Èç¶Ïñ«Æá²Îâ¦ÂϱËÔ²Ë×½Ôå¶Îá¯ÊÞ°Ìà¯Ëß³Ïã·Òè°Ìâ«Æß«ÆÜ«ÃÚ¯Êà¯Êà²Í߸Ôã³Ëâ´Åæ²Èç®Èè¬Æä¶Ðë¶Ñì«Åã«ÅÞªÂÙ¦ÀÙ¨ÃÞ«ÅÞªÁÛ¯ÆàÀÕð°Ëá®ÊÞ§Ã׬ÇÝ«ÆܪÂÙ£¾Ô£¾×¤¿Õ±ÉÞ³Ê䧽ܪÀߦ¼Û ·ÑªÂ×¥»Ñ¢µÌ­À×®ÁØ¥½Ô•¯ÊšµË¡¼Î™±Ä›±ÇŸ³Å¦·Æ¢³Äž®ÄšªÀ–¦¼–¦¼˜¨¾Ž¡ºŠŸ¼Š¢·©¹Š¡°‹Ÿ¯ŽŸ²…”¬…”¬œ´‚’¨zŠ }£y‰¡v‰žq„™n‚”p’r‡–“|‡Š„œzˆŠ8:0OPKmmmvyxejjmmk¥¡œŒ‘‘blvSalTeqRbqXewTdu]nct…jzr‚˜w‡Ÿv‰ ‚•¬”§¼‘¡·–¦¼šªÂœ¯Æ¡´ÍŸ·Î¸ÎšµÉ¡¹Î³Êä¬ÂáªÃᢼڥÀÙ±Ìâ¥ÀÔ©ÄÖ«ÆÚ®Åß²Éã·Ìç·ÑêµÐé²Îä°Ëß±Ìà©ÄÚ¯Êà·Òè±Ëä²Ìç·Òè¹Ôæ²Íá¯ÊàªÆܧÆÛ¬ÈÞ¯Êà«ÅÞªÃá¬Æá¬Æá¬Åã©Âä°Ëæ·Óé³Îç±Ìç´Ïå®ÆÛ²ÊݨÁÑž¹Ë¥ÀÔ¡»Ô¤½Ý£½Ý¦Ãâ¦ÄÞ©ÄݪÅÞ­ÇâºÕé¯ÈÖ¹Ì᩵Т²Êž´Ê˜³Çš¶Ê—³Ç›¶Ê—¯Â™¯ÃŸµÉ³Ç¢¸Ðœ®Ì–«ÆŽ¦½Œ¢¸¢·ŒŸ´”§¾Ž¡¸“¦¿ ·ˆ›°ƒ™­|’¨|’¦yŒ¡¥€Œ£†•«y‰ŸzŠ yˆžzŠ™w‰ž¨²ÌÎÝ”œ²}ˆ¦uƒ444==;VSRurq|wyvsrŸ™‰’fl|YesSanPapQewOfw]s‡_v‡h|Žs‰Ÿv‹¨u¤vŽ£~™¯©ÄªÀŽ©½«½“«¾š²Ç›°Ë˜®Í§¼âž·×™³Ñ£½Ø®ÃàµÇã°¿Ü­ÂݬÃÝ­ÅܲÈÞ¯ÊܱÍß·Ôã²ÎÝÄÜï³Éß´Ìá´Ìã´Ïã°ËߺÕë­Çà±Ëä¸Ïë²Ìå­Çà«Åà±ÇæªÁÛ²ÈàÀÖî´ÉäªÀß³Èî«Åå¦Çà«Ìå±Îë¯Èæ®ÂâµÊç¼Îê¹Ìå±ÄÝ®ÃÞ¶Êê¨ÂݯÍç°Î褿ڤ¿Ú¬Çâ¦ÄÜ¥ÆݱÐå«ÆÚ¦¾Õ¿Ñí©¾ÙŸ¶ÐµÌ™¯Ç—­Ãš­Ä™°Á—®½—°¼•®º§¶‘¤¹’¥¼Ÿ¼’¥¾¦¾š°Èš­ÆŠŸº‚™µƒ™±“¦½£¹}“«vŒ¤xŠ¦{‹¥{Š¤‘«{‹¥v‰¢s‰¡m‹~ŒŒ½ÃÈ­«·‰›x‰•pƒ666777C@A^[^xtz|yzœš–…‰ŒdnxSal_o~SgwPh{Rj}]uˆ_wŠf~‘m…˜tŒ¡rŠŸvŽ£€˜­¦¼§¼§¾§¾˜°Çœ³Í›°Í±Ó¥¸ßªÀã«Á⩽ݩºÛ­¿Ý°¿Ü¥»Ó¬ÇÝ»Òì­Âß°Ëá©ÅÙ­ÈÜÁÙîºÒç²Èà±Éà½Ôî¹Ðê±Èâ²ÌçµÏí²Íæ°Ìâ«ÇÝ«ÅÞªÄÝ®Åß­ÃÛ­À×¹Ïç½Òí¶Íé¶Ïï°Ëæ¸ÖîÆàþ¹Ïò®Ä秽à®Äå¯Åä«ÀÝ°ÂÞ­ÃÛ¯ÅÝ°Êã«Æá¬Æá«ÁॾެÅç¥Â៿ۧÆÛ©Å׹ȜµÃ•­À´Î µÐ¢±Ðœ¯È›±Ç¤ºÎ¡¸É¤»Ê¡¸Ç™­¿œ¬ÄšªÄ”£À’¥¾’¥¼’¥¼“£»Œ¡¼‰Ÿ¾|‘®†˜´Œ¡¼ˆ¸‘­†•²©‚’¬}¥~Ž¦s‰Ÿh€—m€‡œ–ÏÖÖ¢£¬‹•Ÿ~žzŒ‘>@F24:98?HHJcccwwwˆ…†}€ˆhq€\l}Yo…Rk{RkwQjvVmzdx†k|wŽ{”¢Š¡²~‘¨…›¯¥¹Š ¶–©Â–«Æ˜­Ê¢·Ò¤ºÒœ³Í–¬Ëš¯Ì¦¸Ö­¿Ý¥³Õ¤³Òª¹Ö¥»Ó¥ÀÖ­ÄÞ­Áá«¿ß©½Ý§½Ü®Äã´ËçºÏìÁÖó¾Óð¨¿Ù£½ÖªÅÞ¶ÑêªÄâ¨Áæ¬Ææ§Áß­ÄàµÇå³Êæ«Åà±ËäÁÙð¹Ôè·Òæ°Ëá®Åá¬ÃÝ®ÅßÂÝï·Óà²Íá«Åà¬Åã¬Â㟳ӭ¾ß¬À৽ި¼Þ¤µØ©½ß¨¼à¨¾ß«Áà­Çà©ÄÚž¶É ·Æ¥»Ñ¡¶Óš¬Ê˜¦È›­É®ÁÚ°ÉŸ²Ë’¨¾”ªÀ’¨¼˜¬¾—®¿§º‹£¶’¨¾¥¹‘¤¹Œ¢¶‰¡¶š¬~™«{–¨w’¤|”§…˜­~‘¨yŒ¥rˆžn„˜t‡ v„¦u}‘µ·½ÍÐÜ—˜®ˆ¦¤z†”GP_5:D68>8:@KMShmmz{p{|fu{\mw_pcs„`m[h|^jfu‹l|’tŠžv‘¥tŒ¡yŒ¥†œ°Œ£²“ª»”§¾¢»”¦Â¡³Ñ ±Ô–§Ê¡²×¢·Ô¡·Ï¡¸Ò¦¼Û§¼Ù­¿Û¬Áܤ¹Ö«ÂÞ«ÂÞ«ÂÞ±Èä­Ãâ°Äæ±Èä²Éã´Éæ·Èë±Ãá°ÂÞ±ÄÝ©¼Õ­Âß©½ß­Áá°Ää¯Åä©Ââ«Åã±Ëé®Éä®Éä«Æá­Çâ¬Çà©ÄݬÆá­Ãä¬Æß©Å×¢½Ö«Ä䥿ݨÃÞ¬Çà­Çà­Çा٢¼Õ¥½ÔªÂ׬Âب¾Ô¥»Ó¥½Ô¨ÃÙ¦¾Õ¦¼Ô¨Àצ½×žµÑ¡·Ö´Î§¿Ô¨¾Ò­Ã–©¾“©½©·’«·“ª¹¦ºÌŽ¢²¡±‹¢±Š¡²¤µŽ¡¶‹¡·ƒ™±€–ª‚™¨‰š­„©€ªvˆ¤q„sƒsƒkz—w€ÂÄȶºÉ”˜²Š‘ªƒŠ£{†—CP`DNX:?G59<;;=RWUjqop~€dv}^oyhvƒfv…cs„^o‚\o„ax‰f}Žn‡—p‹n†™yŒ¡„—¬ˆ˜°ŒŸ¶‘¤½¢¹”§¾š°Æ ¶Ì²Íª»Ü ±Ô©¹á¢¶Ú¦¼ß³Ì좻۳ԟ³Õ´ÉäµË᩾ٲÆæ­Âß«½Û¬ÁÜ°ÆÞ®ÄܵÇã°Å੾ۮÆÝ­ÅÚ­ÅÚ¦¾ÕÂÙó¶Íé¨ÂÛ¨ÃÙ±ÌâÁÙðµÍâ´Êà¹Ñè²Ìå²Êá¯ÅÝÃÚô¯Æâ©ÃÞ¬Åã¬Å㤽ݥ¿Ý¨Âà¨Âà¨Áߥ¾Ü¤½Ý©Âà¨Áߢ¼Õ¦ÁשÄÚ«ÂÜŸ·Î©¿Õ­¿Û£±Õ¡³Ñ ²Îš­Æ›®Å­Ã×£¼Ì˜´ÃŸºÌ›¶Ì‘«Æ“©¿¦·Ê°ÆÜŠ¡»‡Ÿ¶¦¼“©½‹ž³Œ°±Šš²„–²—­˜©ˆŸ°~”¨y¡xŒžw‹u‰›q—m|–y‚ÎÑÒŸ¦±Œ–®¦zŠ zˆ“MUWZ__XXZ8;<57;>BGRW_lv|n{‚es~_o€^o‚cs‹[o_sƒbyˆg~o…™nƒžq‰ qŒ¢z•©„œ±Š ´‹ž³¦º‘©¼—¯Â–®Ãš³Á˜²»©ÀÏ°ÃÚž´Êž´Ì£¶ÍªºÒª½Ö¯Ë³Èã«Àݦ½×­ÄÞ§¾Ø¯Æà²Êá®ÄÜ©¾Ù­Áá³Êä¨ÃÙªÂÕ®ÅÖŸºÌ«ÇÝ«ÇÙ¯ËتÂÕ§¼×³ËâºÒç´Ìá³Éá¯Æà°ÉçªÄ߬Ã߯Éä±Ëæ«ÆߪÅÞ¨ÃܦÀÙ¬ÄÙ°ÆÚ¸Ð社٤¾×¦ÀÙœ¶Ï·Ò¢»Ù¢»Û¤½Û¨¾ÝžµÑ¦½×ªÁÛžµÑ´Îš²É—²Ä—³Â™±Æ¡¶Ñ“ªÆ’¨Çž·ÕŽ§Å”®Ì—´Ñ”­Ë’¦Æ›±Ç’©¸¤µ‡š¯ µ‹žµ‚˜°‚™³ƒ›²}“©ƒ™­…›¯w£~‘ª{Ž¥r…šq„›r‚œw„ÍÒÎitw€‘†–¥Ž¢zƒtnixrmke`GHC4977:9BBDZ^aqw|jw€^o~_p]l‚\l‚]p…`vŠf|n„˜t‡žs‰€–ªˆž²—­‚š­‡Ÿ²’«»’©º¥»‘¦Á–¬Ä¥»Ó§ºÑ£³Ë©¾Ù³Ò­Âß±Ãߨ¿Ùž¸Ñ©ÄÚ­ÅÜ®ÆÛªÂÕ«Ãا¾Ø£¼Ú¢»Ý©Ââ¬Å㤽ۤ½Û£¼Ú¨ÁߦÀÛ®Å߬ÇÛ²Íß°Ëß­Çà²Êá¹Ïç·Ìç³ÇçµÌèµÌè³Ê䧼׮ÄÜ®ÄÚ¯Êà©Äݤ½Û§½à¦ÀÛ¨ÃÙ­ÈÞŸ¹Ò ¼Ð¥ÁÓ£¿Ñ¡¼Ð¢¼Õž´Ó•¯Ê¢¼×¦½Ù“¨ÅžµÑœ¶Ñ—±Ê˜°Ç–­Ç²Ïš±Í–¬Ë¥Ä£Ã“ªÄ’ªÁ«¿«¿«½«½‹¡·‘¡»‹¹‡˜¹¤ÁˆŸ¹ƒ›²ƒ›²Œ¢¸€“ª~‘¨{‹£v‰žyŒ¡xˆžs‚šs‚šušsz…ÉÉÉAHSA8BE=@AGGIW[^dkrdr}h|Œn…–n„˜uŒ{¡|’¦‚˜°†œ´¦¾‹¡¹Ž¡º ¹”§À›®Ç¤·Ð”¦Â–¥Ä˜­Ê˜²Íš´Ïš°ÏžµÑ´Î˜°Å¡·Ë³Éߧ¼×³Èå²Ã䧼ש¿Õ¬ÁܦºÜ¤¸Ú«¿á´Êë¸Ñó³ÉèµÊç°Å⩾۫ÂÞ²Éå­ÄÞ®Å߯Äá°¾à¯Áß­ÂÝ«Âܤ¾×£½Ö­Äà°É禿߫ÄâªÀߤºÙ¨¾ß§½Ü§¾Ú­Âß«¹Û¦»ØªÁÛ¦½Ù™­Ï³Ô”­Í”®Ì”®Ì—²Í”¯Ê“©È•¦É”¥Æ’£Ä”©Æ¢¿¤Á”¦ÄŒž¼‹œ½ŠŸºŒ¢¸‹ »†—¸…™»…šÀ—º‚˜¹ŠŸ¼~‘ª~‘¨yŒ£t‡žm€™yŒ¥vˆ¤r„ qƒ¡k™p†œl‚šfx–]rTj‚McyGZoFVl:F_8ISFO^JWgEViGXiIZiJ^nH[pCWiFWjLYkAI]9@K:@CAEH\^bcmudtƒev…v‡˜yŸ|¦€“¨ƒ–«ŒŸ´ŒŸ´…›¯…›¯¦¼–©Â¢²ÊŸ®Ä˜¨ÂŸ®Íž²Òž´×¡·Ø£¹ØŸ¶Ò¤»Õ¡¸Ô¤ºÛ¨¾ßªÀá«Áà¬Àऺ٢»Ù£ºÔ¡·Ï©¿Õ§½Ó«ÂܱÇæ®Ââ²Ãæ¶Êê®Åá¯Æâ³Èå³Êæ¸Òí±Ë椾٣½Ö¨ÂÛ¨ÂÛ¤¾×²ÍãÃÛð©ÄÚ¤¾×­ÈÞ±ÌâªÄÝ«Áàž·Õ¥¾Þ­Äࣶϡ¶ÑŸ³Ó ¶×ž·Ù¡ºØ´Î˜¯ÉŸ´Ï™®É”¦Âš¬È”¦Ä’¨Ç“¬Ì¦Æ‹¡Ä‹¡À¤Á¦Â‹¢¾Œ£¿‡¼‰ º‹£¸ˆ£¹‚œ·…œ¶…—³–¬Ä‚˜°{“ªuŒ¦v§sŠ¦uŒ¦vŽ¥mƒ—k‘dxŠw‹h{’^mŒ]l‰[k…RayQ]tKZpBQiBT^ARaHYjEViHYjN_pN`lVhrN_nP_uJZmGWh?P\9KR9CIFJMU\cbnzgwˆr…žs‰¡u‹£~“®†›¸‰Ÿ·‚•¬Š¶ˆš¶¢»˜«Ä¡¶Ñœ³Ï–¬Ë‘§Èš®Î¬Ë¡²Ó§¸ÝŸ³ÓªÁÛ£ºÖž²Ô¡¸Ò¡¼Ð¥½Ô¦»ÖªÁÝ£¹Ø¥¼Ø«ÀÛ­ÃÛ±ÄÝ­ÃÛ­ÄÞ²ÆæµÅí²Èé²Ëé±Êè²Ëé¬ÇâªÅÞ¬ÄÛ­À׬ÄÛªÄß²Ëé«Áâ´Ëç²ÊáºÔíªÃá®Å᩾ۭ¾ß´Â詺ۣµÓ§¼×¥»Ó¥½Ô¤»Õ¤ºÙ¡µÙ¡µÙ°×—«Ë“©Á³É£¶Í µÐ±ÑŸ°Óž«ÔŽŸÂŠŸ¼‹ »Œžº‹¹Šœº¤Á‰Ÿ¾•µ‚´–²š³~™´}–¶€–·‚–º€”¶~²}‘³{‘´k o„Ÿm›r€Ÿgu’p~›gveqŒ[g‚bn‰ScyNbtOcsO`qPcj>O^CTeFUkN]sN]uM]pO_pP`sKZpIZkM_kH]hDYd;MT6@H?FQ_aplt†y†šxˆ v‹¦z’©z•«ƒš´ˆš¸Š¡»‚œµ‡£·‰¦µ”°Â’®Ä™´Í•¯Ê—±Ê‘«Ä˜¯Éž³Ðš¯Ê¢µÎ§ºÓ¦¸Ô¤¹Ö¡µÕ ·Ñ£»Ò°ÆÞ²ÅÞ¦¸Ô­¿Ýª¼ØªºÔ°Âॹ۳Éè©ÃÞ«Åà±Ëæ°Êå²Éå¬Æß©ÄÚ¨À×¥»ÓªÁÛ¬Ãß©ÃܦÀÙ¦ÀÙ¥¼Ö ·Ñ®Åá«ÅÞ¤ÀÖ¥¿Ø§»Ûª¼Úª¹ÖªºÒ±Á׫¾×¡¶Ó˜²Íœ¶Ô¡¼×ªÄߢ¼×œ³Ï™°Ì¢·ÔŸ¶Ò˜®Í•®Ìš³Ó‰£Ã„ž¾ˆŸ»”¦Â¦À…Ÿº}˜³~™´† ¹ƒš´˜²ƒš´Š¤¿…ž¼|’±‚–¶ˆº€’°‘¯¯tƒ¢q€Ÿm|™q€o~m{fx”_r‹[kƒbq‡Vf|Vi€RezJ]rM`e?NdBQgGVlIZmIZkL]lPapTevUexTdzTd~Ue}Td|JZmBO_5BKHOVfszt†}’z“¡{”¢z‘ …ž®‚š¯ˆ ·‘¨ÄŒ§½‡¢¶‘¬¾›·Æ­ÈÜ·Ò¢¼Õ¤»Õ¡¸Ôš®Îž²Ò¢³Ö¤µÖ¦·Ø¤¹Ô¢¸Ð¢µÎ¤³Ð©¼Õ¯ÅݬÁÜ©¾Û¡¶Ó£´Õ³Âß°¿Ù¯ÂÛ¨½Ø«Á×´ÊÞ³Éá«ÀݨÀ×®ÆÛ«Ãا¿Ö§¿Ö¨¿ÙªÁÛ£ºÔ­ÈÞ­ÈÜ­Çà­Ãâ¯Áß®¼Ûª¼Øž³Î–±Ç”°Äœ¸Êž¹Ë¸Ìž¸Ñš´ÏœµÓ¥¾Ü­Ãâ¦ÀÛ£½Öž¸Óš°Ï›´Ò”®Î•¯Ï‹¥Å‹¥Å‰¢ÄŽ¤ÃŒ¡¾Ž¥¿‰¡¸œ²›´…Ÿ¸ƒ¶ˆž½•¹€‘²‡–µ|°}–¶šµx“¬y“®}“²yŽ©q„q™l{“iyk~“i}duˆ_s…[nƒWmWmTkxRgpQeeBReEVgHYhM^mM]nUfw^o€VjxRjt]r}ZkzZk|Xi|YizQ^p8BL<@EY`iq}‹‘¢yŒ¡Œ¢¸‚š±€š³€™·… »‰¤¿§Àˆ ·“©Á¡±Ëž¶Í ¼ÒµÊ¤·Î¦¹ÒŸ®Ë¡²Ó¤µÚ¥¹Ûš°Ñš´Í¹Ë£¾ÒŸµÍ¦¼Ô¨ºÖ¬Â᤽ߟ¸Ú¤½ß§½à¨¼à³ÊäªÅ×¥ÀÔ¤¼Ó¬Ãß´Èì®Âæ¯Ãç«¿ß°Åà±Ãß±Àß²ÅÞ¯ÅÙ¿Øè´ÍݪÅמ¹Ï“­Æ ¶Õ¥¼Ö§½Õ«ÃÚ¥½Ô¡¶Ñ¦·ØŸ´Ï ¸Í›µÐ–¯Ñ¢»Ûž·Õ¦¿Ý—­Î•«Êž´ÓŸ¹Ò–±Ç£¾Ð¤½Í‘¬Âƒœº‘ªÈ–¬Ë–ªÊ”¥ÈŒ Àˆº†›¸„•¶ˆœ¼}“²~™´…¦½†¤¼q‹¦€š³˜²€—±~“®vŒ¤s‰¡l‚šo‚›m€—p€–p€–euev‰ar]n}^n[l}WhyOafEVgG[kNbrSdwWcz]l‚gvŒ[l}Xlzctƒan€_o€du†iz‰VgsR[jGH\`hzy‰š‚’¨€’®~”¬‚š¯€˜­„š²‘¨Â† »¦À“¨Ã˜ªÆ¤³Ðž´Ì–±Ç–­Ç¤¹Öš¬È¬É¡°Í©¸Õ¦»Ö¦½×ž¹Ï£¿Óœ¸ÊšµÇ ¸ËŸµÉ¥½Ò¨¿Ù«ÂÞ¤ºÙ¬Ã߬Ãß«ÁÙ´ÇÞµËáºÐèµÇã³Á㯽߰¾à±À߸Çæ´Éæ­Äࡸҗ®È›¶Ìž¹Ï¬ÃݵÉé¹Ðì³Ê䨿٧¼Ù§½Õª½Ô§¹Õ¦·Ú¦½×²Íá·Ò˜±Ó—±ÏšµÐš´Í–­Ç‘¨Ä¡·Ö¿Ùô—²Ë—²È—¯Ä•­Â’ªÁ“­Æ˜²Í‘¨Ä¡¿ƒ•±‚”°‹ »Œ¡¼Š¢·ƒ›®z–¬€¡ºv“°u¯pŽ¨q§v’¦|”§u i“o…t†¤hz–k{•k~•[nƒax‡az†^u„^o‚[lXi|NdjIZdM_iShsSdsUex^nZg{]n}`u~_q{es€er‚er†fr‰Zf[j€]nfzŒo…™|“¤ƒš«ƒš«‹Ÿ± ¶” » ºŠ ¸§¾“­Æ”®Ç˜¯Ëš±Í´ÐµÌŸ·Ì´Î±Óš°Ñ£¹ÚªÃá¦À۷О¸Ñœ¸Ê¤ÁÎ¥ÀÒ¡¸Ò¡¸Ò®ÃÞ©¿×¯ÅÝ«ÂÞ¦¼ÝªÁÝŸ·Î ¸Í§½Ó·Íå³Èã¯ÄߨºÖœ®Êª¼Ø±Ãß»Íé²Ìç¨Åä¨ÆÞªÆÚ«ÆÚ¨ÀÕ¢½Ï³Ðß·Ô㡼Μ´É§½Õ³Êä¬Â៹ԛ¶Ñ—µÏš¸Òœ¹Ö¡»Û–¯Í•«ÊŸµÔ™¯Î“­È“­È‘¬Â‘¬À˜¯Ë›¬Ñ˜©Ì˜©Ì’£Æ‘¢Å…š·‚—²}˜¬~š¬›¯{–¬y”ªx’«~—µxŽ±qŠ¨m‡ |”«uˆ¡tŠ rˆžmƒ™i—_u‰[rƒbyŠd{Œbyˆd{Š]p…bqŽYl…Xk„RgpFZhK_mUfuSgwRfxYm{Ynybv„h|ŒfzŒgzau‡_pƒ]nardxŠi•h€—qˆ¢|”«}•ªz’¥ƒš« µ‘ º‘¡»–¦À¥À“­È”¯Ê«Æ—³É™µÇ™µÇœ·Éœ·Ë£»Ò ¶Îª¼Ø¨½Ø§¾Ø¥ÀÔž¹Ë®ÆÛ²Çâ«ÂÞ­ÃâµÌè¶ËæºÑë®Åß«ÃÚ«ÃسÎâ¯ÊÞªÂÕ¤ºÎ§½Ó¯Ä߯ÇÞ¹Ñè¶Íç¶Ëè·Éå½ÍçµÌè©Ãå¥ÀÛ«ÇݾÚð¶ÑçªÄߦ¿á¡»Ù »Ôž¸Ñ ·Ó¡»ÖŸ¹Ôš³Ñ©É©É”±Ò·×©É›´Ò•«Ê•¯ÊšµÐ“­Æ¥À’§Â’¤ÀˆŸ¹©ÄŽ§Å‹¡Â‹¡ÀŽ¤Ã§ÂªÅ€š³…Ÿ¸‚³|”«—®}’­z•«z–¬v’¤o‹št¥xŽ­t«oˆ¦l†Ÿm…šh~–fx”k{•l{•jyfv‰_o…\l„YoƒToVqsK[lIZkWh{XixUgq]oy\nz]u^xcw‡ds‰brŠ^nˆZm„awg}“g}“o…™y£|“¤€”¤‚™¨ƒœ¬ƒœ¬£·§¼Š¡»«Á˜³Çœ·É”°¿Ÿ»Ê¡ºÊŸµÉ§ºÓ¦¸Ô¦´Ö©»Ù«½Ù±Ã߶Èä®Äܨ¾Ö°ÆÚ°ÄÔ´ÈزÆÖ´Ìß³Îä´Ïå±Éà¬ÂزÂÚ­ÅÚªÆܶÕè®ÍÞ©ÈÙ°Ìà©ÄÚ­Âß®ÀÜ´Ãà±ÀݲÁÞ²Äâ®Ââ±Éà±ÉܼÔé·Ìç¬ÃÝ«Åà¨ÂÝ¥»Ú¦ÀÙ§Ãל·Ðž¸Ö›µÓŸ¸Ø£½Ý›µÕŸ¶Ð°ÃØœ®Ê®Ñ—­Î—±Ó–¯Í“ªÆ¤Ä’£Æ’¨ÇŠ£ÁŒ¦¿”¯Ã“®Ä‰ ¼† ¹Œ¨¾‰¥¹ƒž°€›¯œ²„œ³|‘¬x©yª…›±ƒ—©x‹ {‹£z¤sŒœmƒ—r…žg}“bxŒbxŒl‚˜gz‘eu_o‡]m…Xn‚Wp€YrwE\kL`n]m|cuVkt^u„]s‹awat‰]s‡^tˆ]m…_jˆ^mŠasbxŒhn‡“vš|•£…ž®„­ˆ¡±Œ¢¶¢¹ŒŸ¶‘¤½§¼šµÉšµÇ£¼Ì¥½Ð ¸Ï¤¼Ñ¤ºÎ©¿Õ©¿×¦¼Ô¥»Ó­ÀÙ±¿Ü±ÀÖªºË¶ÃÓÄÐÞ¿ÐÜ·È×´ÈÖ¯ÆÓ©ÀÑ©¼Õ¯Äá­Ãä«Äâ²Ìç±ËäµÌæ´ÌáÄÛì®ÆÙ­ÅܯÇÞ°ÆÞ®ÃÞ°Á⧼ٯÆâ¬ÆߨÄÚ«Æ߬ÆáªÄߥ¼ØŸ¸Ö—°Ðž¸Ó±È⢽֖·Ð™·Ï•±Ç™´Í¢½ØŸ¶Ò¢´Òš±Í”­Ë–±ÊŽªÀ–²È§ÀŒ¦ÁŽ§ÅŽ¨Æ“°Ï“°ÍŠ¨ÂªÃŽ¨Á¨¾‰¤º¨¾¨¿Š ¿¢Éšºy”¯s¦qˆ¢„œ³Š ¶x©y®qˆ¤nƒžg|™kŸh}˜i|•bvˆiz‰g{‹bvˆ`t„cw…]q]mƒVktM]pSdu]nfzŠ\p‚\u…Zv…^wƒZr|\p~br…ar\q|bs„kzev‰kr†”uŠ•}‘ŸŠ›®¤µŽ§·ˆž²…˜¯‘§½•­Ä’ªÁ•¬Æ™°Ê µÐ¤ºÐ ¶Ê¨¾Ò®ÁÖ°ÁÔ´Ä׫¿Ñ§½Ñ°ÆÚ¬ÂÖ¦¶Ì§³Ê»Ïá¯ËبÃÕ¬ÄÛ¬ÄÛ±Èâ¸Ïé½Ôð«ÂÞ­Âß«ÀÛµÈá¬ÄÙ¯ÊÞ²ÏÞ·×ã«È×­ÅÚ«ÃرÉàµÍä´Ëå³Ê䨽ڧ½Õ¦¹Î­ÀÙ«¼Ý­Âß ·ÑŸ¶Ðž³ÎŸ·Î¯ÇÜ©ÄÚ¡¼×¥¾Üž´×ž´Õ¥»Ü¡·Ø˜®Ï¶Ô›µÐ•¯Ê¨Æ”®Ç—²Æ“­ÆŽ¤ÃŠ£Ã©Î’¬Ê“­Æ”®Ç“ªÄ•¬È¡ÃŠ ¿‰£¾‚œµ‚™³z‘«z‘­~“®w†£{­y®tŠ©mƒ¤oƒ£n k}›q€Ÿl‚šc~\w‹]uŒe}’^v‰_u‰iyZm‚Xk‚RkpUgqarYi|ct…Zn~Yp[r_pƒ`l…]l‚_n„brˆfyk‚“lƒ’jƒ‘n‡•jƒ“n†™z“¡‚™¦‰ ¯‘¥·‹Ÿ±¢·—¨»›«¾šªÀ˜«Â›±Ç ¶Î§½Ñ®ÅÔ¯Â׸Çä»Êç°¿Ü®ÁÚ²È੼զ¶Ð©¼Õ¡³Ï°ÃÚ½Ñã°ÃضÆÞ´Êà³Ëà¯ÊÞ±Ìâ±Èâ¯Äá³Èã¹Ïç³Ëà¬ÄÙ¯ÇÚ®ÆÙ«ÁÕ³ÃÛµËßÂÞí®ÆÙ¬ÂØ°ÃÜ¥´Ñ«ÁקÀЦ¼Ò«½Û©¾Û¢·Ô¢·Ô¦ºÚ³É襻ڳԣ¸ÞªÃ塺ژ±ÏœµÓ•«Ìœ­Òœ­Îœ®Ê–«Æ“¨Å‘©À£»Î¨ÀÕ’§Â“ªÆ‘ªÊŽ¨Ãˆ¢»§ÀªÅŽªÀŽª¼†¡µ…›³ŠŸºŠ›¼„•¶€‘²ƒ˜µ€—³{­{«y‹©yˆ§w‰¥p‚žn„œl‚šk™bxaw^tŠaw]p‰fy’ds]o‹Ug…ShsRmqYrwTjp\nz]m~`t‚ayƒg‰auƒ_t]r}dy‚t‡ŽpƒŠo‹s„“s‚˜r—z†{Œ„˜¦„›¨¤³‰¢®‹¤°‹¢±–ª¼Ÿ³Ã™­½›²Á ·ÆŸ¶Å©½Ï¥µË§¶Ð£¶Ï§½Õ´Ìß«ÄÔªÃÓ³ÊÛ­ÀÕ°¿×ÅÕï¸Êæ¯ÅÝ­ÅÜ·Ìç¶Çè²Çä¶Íé°Åâ±Ãá³Êä¶Ñê·Òæ´ËÜ°ÇØ´ËܶÌâ±Ãß®ÃÞ¹ÐìµÌæ¸ÏéµËá²ÂØ®ÁÚ°Âà¯Æ⥾ܧ½Ü©½Ý¬Áܨ¾Ö ¸Ïœ·Í“­Ë–¯Ô›´Ô¤¸Øœ³Í˜°Ç•­Ä–¬Ä™®É²Ï£ºÔ—®È“­Æ–°Éœ¶Ï‘¨Ä§Ã‘¨ÄŠ¤½… ¶ª¾… ²‡¢¶‡¡ºˆ¢»ˆŸ¹Ž©¿‚ž´™²€—³~“®x‹¤vŒ vŸ{”¤}–¦z•©o‰¢m„žj|˜iy‘p€“iyŒetŠeu‹at‰f}Šo‰^u‚Uh}SioUptSkuWh{br…`m`p_pp€‘ht‹cs‰at‰i€n‡“o†•w‡wˆ›{‹œt…˜q™‰˜®™°Žž±Š›®¡±Šž¬‘¢µ–¥¿šªÂ”§¾š®¾²½›¯¿£¶Ë£¶Í¯¿Ù¨·Ô«¹Û¯Àᮿà¬ÂÚ²ËÛµÌÝ°ÄÖ¹Ðá²ÉÚ³ÊÛ»Òã¸ÐåµÌæ°Åà®ÀÞµÇå²Áà²ÅܽÔã¿Øæ½Öæ»Ôä»Ñå¶Ìà¶ÌâªÂרÀÕ°Ë߬ÈÞ³ÎâµËá´Êâ±ÃáÂÔð¶Èä­Âݧ¼Ù®ÃிࡳϢµÌ§¿Ô¢¾Ô—³É–°É“¯Á•µÁœ¸ÊšµË•±Ç‘¯Ç—µÍ‘¯É«Æ’©ÅªÅš³Ñ”®Ç‘©À›µÎ©Ä’­Æˆ£¼‡Ÿ´Š²¢¹‹ž·‡žºƒœ¼}—²{•®™°€“¬|¨v‰¢y£r‹›l…“n…”m„•j}’fzŒizhxbqŽ`sŒdwŽj}’bs†Xl|TkzOegZkzTitXmv\qz`u€ar…jx•ds‹kzizcw‰h|Žo‚—oƒ•xŒžo†—sŠ›r‰˜p‡”}‘Ÿ†—¦Œ®‡˜«Šž°…›¯˜«Â˜¨Â–©Âš¬È®Àܧ¹×¤ºÒ¥»Ï«¾Õ¯¿Ù¯Â×±Å׶É૽ٲÊݲÎÙ±Éܨ½Ø¥»Ñ²ÅÚ¶ÍܹÐÝ°ÆÜ­¾ß¹Îë³Èã¯ÂÛ´ÄÞ½ÍåÁÐæºÊà¿Ïå½Íã¸Èà¸Ëà¶ÌàÇÝóÀÒî¾Ðì²Äà°ÆÞ©¿×³Êä³Êæ¯Äá¯Àá¯Äß«ÁÙ¶Ìâ³Éߥ½ÔžµÑž¹Ï£¿Ñ¨ÄÖ˜³Å£¾Ò—¯Æ˜³É”°Æ–²È™µË•±ÅŽª¼ª¾’©Ã‘¨Â¥Â•¬È˜¯Ëœ³Ï“¨Å˜­È’§Â”¦Â‡–µƒ˜µ–²–°|’ª–±|‘®}“²}“´z“±oˆ¦l†¡j„Ÿj„Ÿt‹§u‹£v†žo‚™dwj‚—^y[w†\uƒhŒbs‚Xi|Vf€UfrYe|[l}_s`t‚fzˆev‰kz’izhyŠj{Šj{Šmq…•r†–x‰šrƒ”wˆ›vŠšy›{ŽŸ°‹Ÿ±‹žµ’¥¾‘ ½›ªÄ˜¤¿™¨Âž­ÇŸ¯É˜¨Â¦¶Î³ÃÛ²ÂÚ¬¼Ö¶ÆÜ»Ìß±Á×°ÀÚÂÙê¸Ôß²ÎÛ±ÌÞ´ÍÛÀÔâºÑÞ³ÌدÈدÇܹÏåÁÑëÅÕïÃÒìÁÑé¿ÏçÀÓì½Ïí¿Òé¿Ðã¹Ðá¹Ñä¹Ñè½Òï»Òì²Ìå¸Óé­ÈܬÄÙ´Êâ·Êã°¿Ü´Æâ´Æâ°ÂÞ­¿Ý¨¾Ý›´Ô§Âݤ¿Ø™¸Ë›»Éž»ÊµÈµËßÃÖ횲ɷЕ°Æ«¿µÊ›±ÉŒ¡¼‘¦Ã‹¢¼’©Ã µÒ•¦Ç’¦ÆŠ ¿‰½ž¿ˆŸ»ˆ¢½‡¡º…œ¶˜²–³‚—²~“®~™¯s£s’¥t“¨n‰¢l†¡o† r‡¢wŠ¡n}“v† k|_t\t‰Tj€Ylƒ]p‡Zj„LalXew^n}cs‚ev…fwˆcw‡oƒ“iz‹eu†iyŠk{Œk{ŒmzŽ~‹w„–t„“u†’†—£ˆ™¥ˆš¤”ª°Œ£°‘§»”¤º›§ÀŸ¹™§Ä˜¨Âœ¯È ¶Î¦¼Ô§ºÓ³ÃݲÂعÉÚ±ÁÔ¶ÂÛ¯ÀÓ¯ÃÓ¶ËÖ±ÇÍ´ÆÒ¾Îá¼ÌßÅÑè¹È௾۱ÄÛ­ÀÕ·ËÛÅÙçÔéôÚìøÌÝìËÜí¼ÓâµÎܺÓßÁØåºÑâ¸Ëâ²ÈÜ·Îß¹Ñä²Êß³Îà¯ËÚ´Ìß°ÃÜ°¿Ü­»Ú­¼Û¢°Ò§»Ý¡ºÜ¤½Ý¥¾Þ¢¼×Ÿ¶Ð™°Ì¤¸Ø¡³Ï¤³Í¨¾Ö˜³Éš±Ë ´ÔŸ¶Ò•¬Æ–­Ç˜­È˜®Æš­Æ¤¿¥Ä‘ªÊŒ¥Ç©Ç‰§Áˆ£¾¦Â‹¢¼‹ »Š¡»…Ÿ¸x’«x’­x”ª}™­œ²}”°x«zŽ®t‰¦n€žr„¢p‚ k€›j‚™fyŽp}‘m~au…\o„Xk„Vn…Uq‡Mlm^o€Zn|ax…m‘jzgvŒ_n†]nct…i}‹l„Žm‚o‚” ~›wˆ”}Šš†—£}™„™¤¡¯‹¢¯‘¨·‘¥·‘¡·•¥»•¥½–©À™¯Å°Å¯¿Õ³ÃÙ´ÄÜ®ÄرÉܱÊØ´ËØÂÚâÄÚà½ÏÛ¹ÉܵÅØÀÌã»Çà¿Èç¾Íå¹ÌáÁ×ë¿×êÒéøÏãñ½ÑáÂÖèÇÛíÄÕèÀÔæÅÜí¾ÑæÀÏç¿Ïé½Ìë¿ÎëºÉæÀÒð²Ãä¹Ëé·Æå¸Êæ´Çà­ÃÙ­ÃרÁѬÈצ¾Ó§¼Ù¥»ÓŸµË¦¾Õ›µÐœ¶Ï£½Ö£½Øž´Ó•¬Æ—­ÅŸµÉ ´Æž´Ì•«Ê˜®Í—­Ì•¬È˜­Ê¥Â“§Ç”¨È£ÅŠ ¿§Ã‰ ¼¤Á‹¢¾†Ÿ½‹¥Å„žÀz“³{‘²y’°s¨}•¬…˜¯tŠ tŒ¡s‹ l„™o‡žn…Ÿo† t‹§kƒšh€•ayŽayŽ`wˆ]nVjzcw‰UkoZozXmvfx‚ewƒcs‚ct€ky†m~Šjz‰vˆ”y‹•vˆ”z‹šyŠ›|ŒŸ~ŽŸ€Ÿ’žƒ” žª‹˜¨“¥±¤¯‘¦±˜©¸—¨¹—§½Ÿ¯Å¤³É«»Î´Ä×°ÄÒ®ÆШÀʱÅÓ¼ÐÞºËܶÇرÁÒºËÚ¿ÓáÀÑâºÊÝ·ÇÚ´ÃÙ±ÄÙ´ÊÞ¼Ôç»ÓæÉÝíÈÙåÇÜçÇàì½×àÌäîÅÜéÆÚêÈáïÄàïÂÝï¹Ñæ¼Òè¼Ïè¾Îè¸ÆãºÉæ¾Ðì²Èà³Éß®ÄدÂׯ¿×®½×©¹Ñ±Á×·Í᣾ң¾Ô´Î–­Ç™°Ì¡¸Ôž´Ó™°Êœ´Ë•­ÄŸ·Îž¶Í”ªÂ—¯ÆªÀ”¯Ã‘¬À›¶ÊªÂט³Ç©½ª¾•­Ä§Á‰ ¼„š¹„˜¼„š¹‡žº€š³€›´}˜¬€˜«z•«x’­rŒ¥rŒ¥qˆ¤m¡p†œr†”oƒ‘rƒ”l}Žl}l|p}‘gvŒetŒm~‘^o€TjpZn|_tjˆf{†rƒ’q‚ŽsŽq‚Žj{‡r„r†”tˆ–wˆ™zŠ›„‘£ƒ“¤ƒ“¤¡²Š›¬‹Ÿ¯¤³“ª·“§µ“¨³“¨±“§µ±Ã²ÅÚ¬¼Ö­½Ó¹ÉÚ¸ÉØ´ÆÒ¶ËÖµÊÕ¸ÍؼÐÞ¶ÇÖ¸È×»ÍÙÁÓÝÅ×ãÆÖçÀÐæ»Ëå¿Òé½ÐåÄØèÂÖäÊâìËãëÄÙäÆ×æÀÑâÃÒèÃ×éÁÚêÃÜèÉáéÄÜæÉàíÆ×èÃÏæÁÐè»ÉæºÉæ¹Ëé´Ëç³Íè³Í槿֪ÂÕ¬ÅÕ«ÁÕµÈá«ÃÚ¢½Ó¥¼Ö¢·Ô ±ÒŸ­Ñ¢°Ö¡®×œ®Ì›±Åš°Æ›±ÉŸ·Îœ¶Ï”®Ç”®Ç–±Å–±Ã›¶Ì˜²Í¸Ó©ÇªÃ›·Í›µÎ‘¦Ã¤¿‹¹‚˜°‚š±™®}“©—¬œ²v©z”¯yªtŠ¢rŠ¡k†œo† l€ g~˜k†œrŠŸk~•dxŠiz‹fvŒ^mŠ_r‹^tŒVnvdtƒj{‡o}ˆm~ˆx‰•z‡™pz’s˜p|—p—u„œyŠyŠ›v‡–~œ~œ‚“ŸŠ›¥Šœ£ŠŸ¨‰ ­”­²Ÿµ·–¬²¯»ž¯¾¬¼Í¾Îß®»Í¯ÀѯÃÓ²ÊÔ¹ÑÙ½ÏÙ¼ÈÔ»ÈØ·ÃÚ¹Éß¼Ïä»ÎãÅÕíÄØèÉÞéÇÜåÄÖàÎãìÉÞçËàéÊßêÉÞçÍâëÍàçÚéïÍàåÊàæÏåçÛïïÔçìÎàêÍâíÎâòÅØíÀÓì¾ÑèÃÖí¿Óå¾ÒâºÐæ¶Íé¯Æâ¯Ã㥼֬ÄÛªÂר¾Ô£¶Í©¹Ó¡´Ë¢µÊ¢¸Î¥½Ô˜°Å ¶Ê®ÂÒ©»Ç¤»Ê¥½ÐšµÉ·Ð£¾Ô™±È•°Ä˜³ÅšµÇ‘¬À‡£¹¨Á«Ä©Â©Ä¥Ä¦ÂŒ¡¼Š¢¹‚š¯‚š¯}•ª{“ª}”®{“¨y‘¤u u‹ŸtŒŸu¢p†žqƒŸm€™m€™h~”l‚–ayŒayŒbuŠ`o‡^n†brŠXo|j|ˆp‚Žqp€‘w„˜u‚–pz’u‚–u…˜p€y‡”~ ’§~’¢}Ž~›‚›†—¡‰š¦Ÿ®°’¢³ ­¿˜©¼š­Â¡µÅ§»É¶ÈÒ­¿Æ±ÂÌ´ÄÓ¹ÉÚÅÔê¹ÉÚ¹ÇÔ¾ÏÛÅÖåÂÔàÆ×ãÅÕäÃÐâÇ×èÍÞïÌÜíÊ×éÕæòÐãêÔçìÒäçØèéÛéëÖæç×æêàïó×æêÖèëÎàã×êïÓæíÔêðÉÞçÆ×æÊÖíÆ×èÂÙæÇßéÂ×à¹ÐݾÔèµÈß²ÁÞ´ÇÞ®ÅÖ®ÁÖ±ÁÛ¢¸ÎªÂÕ­Ãר»Ò¢¸Ì™¯Ã˜®Æ µÒ¦¹Ð¢³ÄŸ¶Ã—³¾œ¸ÅšµÇ¸Îš³Ñœ³Í ¶Î›±É™®É“ªÆ˜±Ï‹¦¿¬À‹§¹‡£µˆ£·‰ž¹Š ¸ˆ›´…›³‚™³}•¬—­y‘¨x«uŒ¦yŽ©z¬tˆ¨q‰ qœk‡–h„“a|Ži„˜b}a|Ž\t‰`vŽdzŽZn€Vnvn‚’hŽg~p„”p€sƒ”u‚–x‰˜v‹–w‹™{Ÿx‰šŽ …’¢Š˜¥‰—¢„’ˆ™£ˆ™¥ŽŸ«ž«“¥±“¨³Ÿ°¿¥²Ä¬·Ê¯·Ë°½Ï­½Î±ÂѱÂѶÈÔÄÖàÁÓÝÃÔàÂÏáÊÔìÅÒæÂÒåÇ×æÑßìÑãêÔæë×éìÉÙÚÓãäØçëÜêìàèìçî÷òöÿâéòàëîÛæéáìïÞéêèôòÞîïÔæíÍâëÍåïËãíÂÖäÂÖäÉÝíÊßêÎãìÀÙå½ÙèÆßí½ÑßµÉ×¹ÍÝ´Çܪ¼Ø¡¸Ò¤¾Ù¥¿Ú ¶Õ ·Ñž´Ê›±Ç¡´ËŸ²ÇŸ²Ç ³È›®Ã ¶Ê˜°Å•­Ä—¬É—®Èš²É—¯Ä˜®Ä˜®Æ¥ºÕ–¬ËŒ¡Ç‹ŸÁ‘£Á‘¦Áˆ ·Œ¡¼Ÿ¾ŠŸ¼~—µ–²‚”°|‘¬v©sˆ¥vˆ¦v‹¦|“­vŽ¥rˆžnƒ h| `v•b|—b}“f“\w‰`xf|”_qWowp’q‚•t„œp„–kt†’w†Ž€Ž™|‰™~Ž~žzŠ™Ž {Œ˜†—¡€‘›|—†—£š¬‘ž®˜¥µ–¦µ•¦·¢·Â£¸Á£µ¿«¼È¬½É®»Ë²ÂѸÉظÊÖ¹ËÕÂÔÛÄÓÛÄÒÝÎÜéÈÖáÇÖÞÐÝæÔÝêÑÛãÑØßÜãîÕÙêÝâîàåïÚàåäëëêññîòõîóóòõôðõõêðõìò÷ìï÷ÝäíÚçðØæñÖãóËÜëÁØåÁØåÆÚèÊâêÍæéÂ×âÆÖìÀÓè¿Òé½Ðé½Ìé²Ä⭾ߥ¼Øž¸ÓŸºÐ¡¹Ì¥»Ñ¤¶ÒŸ´Ï“ªÆ—±ÌŸ¸ÖªÄÝš²Ç˜®Ä™¬Å–¬Ä˜°Ç«Á—²È˜°Ç–¬Ä“©¿“¦»“©¿„š²‹£º‰¤º“®Ä¨¿‘¨ÂŽ¥ÁŠ¢¹…²‰ŸµŽ¡¸ƒ–«‚–¨w‹¥~‘¨|Žªn†j…™b}c~l„—g}‘k•r…šgzgzaw‹WmƒYqyt„“sƒ’t„“rƒ’t…–v‡–t…‘z‹•y‡’x‰•|Œ›{‹œ‘¤„•¦‡˜§|™ƒ‘œŠ™¡“¢ª—¥°œ¨¶™§´š¨µŸ¯¾¡²Ã¢²Á®¹Ê½Êܲ¿Ó´ÅÖ·ËÛ»Í×ÇÖÚÅÔÚÈ×ßÅÖàÍÞêÇØäÑßìÔãëÜéîÝèéãêêïöôèíééîîðòøïñõïïñöùúõøùõ÷ûïñ÷öùúéìëëòðæïîÚæâáðëØèé×åðÈÚæÂÖäÓèñÍãéÂ×âÂÓä¿Óå¹Ìã¾ÔêµËá´ËÜÇÞë¶ÊܳÃÛ¨¾Ö¨ÂݪÆÜ¡½Ï¥ÀÒ£»Ð¯ÇÜž¶Í“ªÄš¯Ì µÒ—«Ë“©Áš­Â›«Ã›ªÄ˜¨Â¡°Íš°È–±Å™±Æš°Æ“«Â—±ÊªÀ’ªÁžºÎ„£¶‚ž²Œ§»‡¢¸ƒš¶˜²ƒš´€˜¯y‘¦o…™xŒž{‘§p… r‡¢p… j›v§u‹£h{’n–o•fvfu”cv[n…dy‚z…˜p€‘q‚“u‰™yŸvŠšt…–yŠ›|Œrƒ”{Ÿ€‘ …’¢…“ …“ ’žˆ˜§‹›ª”¡±‘ž®œ§º”¡±•¥´œ­¼ž¯À¤´Ã«¹Æ¬ºÅ´Â͹ÌÓ¹ÏÕ»ÎÓ¿ÑÔÆØÝÆØß¾ÏÙËÙæÑàèÚçîåïõêï÷êðóîóóðòöø÷þöøüùüýöøìÿÿõÿÿòõòóññóóòùñð÷÷öýñõúåìóãîïçóñåò÷ÓáìÏàêÓåñÕçóÓåñÇ×æÉÖèÊÖíÈÔïºÊä»ÑéºÐä¹ÍݹÍ߶ÆÞ¯ÅݬÃß®ÆݨÀÕ¦ÁÕŸºÐœ¶ÏžµÑš²Éž´Ê™¯Ç µÒ™¯Ç˜«À°ÇŸ®Ë™«Ç–«Æ“«Â˜°Ç•­Àš±ÂŒ¤¹•¬Æ’ª¿’ª½•°ÄŒ§½‡¢¸‰¤º“®ÄŽ¥¿€š³‚œ·‡¡º}”®{“¨Š£³y’¢u‹Ÿp†žp…¢t†¤x†¨z‰¨hw”h{”k~—h~–Yn‰]s‹]p‡dy„s€q‚Žn‹rƒ’z‹ž€£¤zŠ~Ž¡€‘¢’£wˆ—|Œ›€‘›‡–žœ¤Œ˜¤Œš¥ž«‘Ÿª›§³š¨µ˜¨¹š¬¶›®³§¹À°¼È±ºÉ»ÀÕºÅÖ½ÊÚÃÔàÅÖàÌÞåÔãéÛééáíéçðïêîóðô÷ðóôùüýóóõùùûþýÿöõúýüÿÿÿöÿÿúÿÿéÿÿëÿÿôÿÿîõõåûø÷ùù÷ùùùòõöîðöäéóäêø×ãïØæñÕåôÊÚíËÜïËßñÅÙëËßñ·ÎݵÎÚ·ÎÝ°ÄÖ¯ÅÙ¯ÇÞ¼Ïè¸Æã±ÁÙ«¾Ó¤ºÎ¢¸Î¢¸Ð¢´Ð¡·Ï¡·Ï²ÉÚ°ÅЗ°À›µÎ•­Äš­ÄµÃй¿Ä©§˜¶©‡²¥ƒ»¬ª¥›£¨´›«ºˆ µ‹£¶Œ¤·‡¢¶ƒ¶‰ ºŸ½‡™µŒžº”ªÀ{“¦{‘¥}¥{Ž¥{©sˆ£r‡¤l†Ÿk†Ÿi…›e€–b}“d•f~“dzcsalŠXlzuuƒs€vƒ“|‡˜xƒ–{†›z…š}„€¡ ~ {ŒŸ~Žˆ–£‰—¢Œš¥Œ›£‘ ¨–¤¯”¢¯š¨µš¨µªº¨µÇ­ºÌ®»Í®»ËÁÎÞ»ÈØÃÎßÉ×âÌÛá×äéÞæêäíìçîìíòðññóööøúöüúúüýýÿþþÿÿÿÿöôðÿÿúÿÿýÿÿúÿÿçÿÿÕÿÿãÿÿâÿÿÞÿÿÛÿÿäÿÿë÷ùëôôôôù÷êññáëñÚæòÑäëÌåêÌâèÏáëÈÚæÇØéÄÛê»ÔâÇÞï¹Ìã³Èã­Áá«ÂÞ¥¼Ø¤¼Ó¢¸Ì›±Å ³È ¹Éœ¸ÇžºÉ–²Á˜±Áš±Â—®¿°Å¦­¶¨££°‹¹t^¯a>¯W'ʼnKëÉ€ÿÿ¹øì«®­™™ ¹•¤¼¦¾£¹ŒŸ¶ŒŸ¶ŒŸ¶Œ¢¸ˆž´‰¡¶|”«|’ªƒ•±~¬xŠ¨y‹§u‡£vˆ¤xŠ¦tŠ¢kƒšf~•f~•k™q€`rŽYn‰Woym‹rƒ’s„•r‚“vƒ—{‹šw‰•y‹•yŠ”|Š•„œš€Ž›ƒ‘žƒ‘žˆ–¡Ž›¤—¤­“ ©›¨˜¥¹›¨º¢¯Á¦³Ã¥³À¯½È´ÂͼËÓÀÏÕÀÏ×ÅÑÝËØáÑÞçßçëïòñíðñîðôðóôõøùûþýùüûþÿþÿÿÿÿÿÿÿÿÿÿÿ÷Á¼¥À½œÿÿçÿÿãÿÿßÿÿòÿÿúÿÿàÿÿÕÿÿÍÿÿÌÿÿÍÿÿÙÿÿìÿÿïîõéàéèØæèÓâêÔãëÏÝèÅÒâÄÑå¾ÏàµÉÙ·Îß´Êà¬ÂÚ©¾ÙªÂ×­ÆÖ«ÄÒ¨¿Ì¤»È›¯½ ¹É¸Î£ºÔ›¬Í ³Ê¢³Â®¶º©¥ Ã•…Òzb¼k;ØŠEÿï¤ÿÿËÿÿÙÿÿêÿÿÛÿÿÍöíÁ½¬¢”˜‰Ÿµ’§Â£ÃŒ£¿ƒš¶š¸{”´˜´ƒ–¯‚•¬}¥y§yŽ«wŒ©r‡¤n„œuˆŸr…špƒ˜k—e}”g–f{–_q]l‹bt€pw‡–r‚•r‚•u˜¢y‰šy‹—zŒ–€‘‚Ÿƒ‘žœ‚“Ÿ€‘Š›§Œš§ž«‹™¦Š˜¥’ ­—©°›­²¢´·¨¸¹²ÂÁ·ÈÄÈÖØÇÎ×ÔÝêÉÔåÐÝæÝçíïõøùùùú÷øûöúÿúÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŠq•§›¡ÿÿúÿÿíÿÿìÿÿðÿÿîÿÿßÿÿåÿÿÜÿÿØÿÿÑÿÿËÿÿÑÿÿÊÿÿÎÿÿÖñôÑÜàÊÔÞÔÔäåÆØßÆÖåÂÔà¿ÑÝÁÒãÄÔì´Âß³½à´Ãà¶Éâ½Ðç³ÃÙ­ÄÕ—³Â£»Î§½Õ¢·Ô˜©Ì›¨º±¹»¹œ‘Í„rÊwQÈj3øÅ„ÿÿÏÿÿäÿÿøÿÿòÿÿîÿÿÛÿÿËÿÿ¿ÿñª·³™Ž™¬‹ž³ƒž´„œ³„™´‡ž¸„›µ„™¶€‘²{«{©yŒ¥v‰¢qˆ¢sŒªuŒ¨vˆ¦o‚›v†žk‚žc}Ÿb{™_t‘bqŽbn‰fw†p€‘t„•y‰š€¡|†žŽ {‹šw‡–~ŽŸ‚’£‚’£‚“¢‚“¢…—¡‡™ž‹¤Œš¥œ¤’¡©•¡­Ÿ¥µ›§µ¡¯¼ ±»©ºÄ¯¾ÆµÂÉÁÏÏÅÔÏÔãÜÑÞÕØàÙñôñüÿþýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿêèäc^VÙÕÆÿÿÿÿÿúÿÿòÿÿðÿÿåÿÿûÿÿÿÿÿüÿÿïÿÿòÿÿçÿÿéÿÿßÿÿ×ÿÿÌÿÿÅÿÿÍþÿÄðò½àâÂÎÐÆÈÑÐÅÓÞÂÔÞÄÙâ±ÅÓªºÐ°ÃÚ¯ÂÛ£»ÐªÅÙ¡¼ÐŸ·Î£ºÔ²Ï¢±Î£¬Ë±Ÿ¬Ø©¤ÎƒrÐjLΓYÿÿ®ÿÿàÿÿúÿÿôÿÿðÿÿèÿÿâÿÿÛÿÿÕÿÿÇÿõšÿ÷¾²¢šš‹Ÿ¯…›¯„œ³—®…šµ†›¶‚”²|Žª}«z¨y‘¨uŒ¦tŠ©vˆ¤€©tƒ iz›h}˜e}”f~‘`y‰ax‰fvŒ]u}l}Žvˆ”x‹’t†’{‹œ¢|ˆŸvƒ•Žž‰”¥‡£ƒŽŸ„‘¡‡˜¢‚”›ŽŸ©›¨‡•¢“¡®˜¦±œ¨´˜¦±˜©³ ±»«¹Æ¬»Ã°¿ÃÂÑÎÛäß×ÞÚáäãíðïõøùüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¶µº+(+d^YÿöíÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûÿÿïÿÿíÿÿåÿÿäÿÿëÿÿÖÿÿÇÿÿÍþÿ¼ÿÿÃÿÿºÿÿÁÿÿÅïôºØݬÂɲ¿ÂʵÁÍ´ÈدÆצ¾Ó¥ÀÒ±ÌÞ¤ÀÏ ¹ÉžµÆš­Â¯«³¼¡ŸÒ†Ýrb¹l?â³jÿÿÙÿÿðÿÿòÿÿôÿÿæÿÿÙÿÿ×ÿÿÕÿÿÕÿÿ×ÿÿÇÿÿ´þè›ÿ峧š†›¦Šž®†¡·‚³€š³‚œ·}“´‚™³€˜­z•«r¦r£rŠ¡sŠ¤nƒ o‡žd“f~‘j}’h|ŽfwŠ^u†d}azp‹vˆ”yŠ™rƒwƒ‘{†—~‰œ|Š—Š˜£†—¡‚“Ÿ€Ž›ƒŽŸ„‘¡†–§¬‹™¦‡˜¤ ¯–§³”¥±–§³«¸¥³¾¦µ½°½Â¹ÁÃÄÐÌÎÚÔßèãæëçêïëôù÷ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿã÷ø¬w}-ÕàŒÿÿäÿÿüÿÿíÿÿìÿÿäÿÿÛÿÿáÿÿüÿÿúÿÿõÿÿôÿÿèÿÿæÿÿäÿÿÔÿÿÌÿÿÄÿÿÁÿÿÄÿÿ¹ÿÿÂÿÿÆÿÿÈúü¹ÒÖ£Æɦ½Æº±½É¯Á˯ÉЧ¿Ç¬¾Ê®´¹²««É™ŒÜ„iÁzHјTÿ÷¼ÿÿèÿÿðÿÿøÿÿðÿÿèÿÿÛÿÿÑÿÿÑÿÿÑÿÿÑÿÿÑÿÿËÿÿÅÿÿ¤ÿð‰ýë´ “Ž‘—œ‰ ±”«¼†™®ˆ›°ˆ˜®…™«ˆœ¬|¤yŒ¥uˆŸq„›t‡œq—k~“pƒ˜l‚šlž`w‘`w‘^v‹_wŠbz‚u…–sƒ’}‹˜sŽu‚’y‡”šzŒ“‰œ£‚•œƒ”ž€—Ž—‹—›…“ †–¥‡˜¤ˆ–£“¡¬’žªŸ¬³§²µ¨³¶©°·»ÈϵÃλÈÏÏ×ÛçéíöñõóóõÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿþÿÿÿÿÿúÿÿöÿÿôÿÿêÿÿØÿÿâÿÿêÿÿèÿÿêÿÿçÿÿãÿÿæÿÿàÿÿÞÿÿÙÿÿÛÿÿÏÿÿÂÿÿ¼ÿÿ´ÿÿ¼ÿÿ²ÿÿ½ÿÿÄÿÿÃâå½ÁŒ³¸—©­—½¼³Ö²£Þ–˃cÂwNñÉ™ÿÿâÿÿöÿÿÿÿÿÿÿÿþÿÿðÿÿâÿÿÑÿÿÃÿÿÃÿÿÃÿÿ¿ÿÿ½ÿÿÁÿÿÇÿÿ½ÿî‹ÿò§øЛ‚Š–±†™²{•®€›­{—¤x‘Ÿz‘ r‰˜yŸrŠmˆžl„›lœr„ yˆ§r tƒ¢ohz–h{”buŒe}‡v‡˜ku‰›r‚“t’zˆ“ƒ’˜Ž•š¤‰–Ÿ„“›|Š•y‡”ƒ‘œ˜‡–œˆ•šŒ–œ’™¢œ¤¨—Ÿ¡™¡¥¤«²©´·®¼¾°¾Àµ¿ÅÃÌËÖÝÙòõôÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿóÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿòÙҥĸ†ÿÿæÿÿñÿÿàÿÿáÿÿìÿÿõÿÿéÿÿèÿÿØÿÿÓÿÿÓÿÿÐÿÿÑÿÿÕÿÿÅÿÿ½ÿÿ¾þÿ¶ÿÿ´ÿÿªÿÿ§ÿÿ±ÿùµÿÉ™çŸr×{SÇUÿõ©ÿÿâÿÿúÿÿÿÿÿÿÿÿÿÿÿþÿÿðÿÿäÿÿÓÿÿÃÿÿ»ÿÿµÿÿµÿÿµÿÿºÿÿÃÿÿ·ÿÿ•ÿð‚ÿøÔ¼™ŽŸ„‡›~‘¨}§|¦—«z¤u‹Ÿ~‘¦yŒ¡uˆŸr…œr…œo‚™t‡ vŒ¤rŠ¡c{’^tŒ`vŽf{–d}‰z‡›t…–j~Žr‚‘zƒ’|‰’ƒ’˜ƒ‘œ‡”¤‹™¦Š–¤‹—~‹”ƒ’šƒ’š…”šˆ•šŽ›¢– ª¤«¡§ª¥­¯š¥¨Ÿ­¯­»½°¾À¸ÅÊÑÜÝãêêõúúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿîÿÿõÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿðÿÿæ÷ÿ·ÿÿ¸ÿÿ×ÿÿòÿÿáÿÿÜÿÿåÿÿãÿÿÜÿÿÙÿÿÞÿÿÙÿÿËÿÿÔÿÿÒÿÿÂÿÿÃÿÿµÿÿ¿ÿÿºÿÿºÿÿ»ÿÿ²ÿÿ­ûÒ‰Ó…O½w>ážgÿÿÌÿÿ×ÿÿèÿÿúÿÿþÿÿÿÿÿþÿÿúÿÿòÿÿìÿÿÙÿÿÉÿÿ½ÿÿ³ÿÿ·ÿÿ»ÿÿÃÿÿËÿÿÁÿÿ¹ÿøŠÿóÿõ±¬œ‹Œ‘}–¦~•¦‚•ª‚•ª|¤v‰ €’®|’ªtŠ u‹¡|¦pƒšpƒœp†š}–¦n†™o…›h~”f|”]usƒ™v†œtƒ™sƒ–vƒ—œ…’›|‹“…”œ„’‚„‘š„Ž–‚”…“•‰™˜…•””¢¢™¤¥¥°³¬¶¼­´»ª¯¹©°·¸ÀĸÀ¾ÇÆÄÉÉááãúúüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùÿÿÿÿÿÿÿÿÿûûùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿöÿÿëÿÿíÿÿåÿÿÖÿÿèÿÿßÿÿÑÿÿÕÿÿÔÿÿÁÿÿÑÿÿÅÿÿ¼ÿÿ»ÿÿÃÿÿ»ÿÿ¸ÿÿºÿÿ»ÿù­á«bÃDËzLÿÓ•ÿÿÍÿÿÞÿÿðÿÿôÿÿøÿÿôÿÿðÿÿðÿÿðÿÿðÿÿòÿÿæÿÿÛÿÿÉÿÿ¹ÿÿ¹ÿÿ¹ÿÿÅÿÿÑÿÿÑÿÿÓÿÿ½ÿó}ÿü ý椚•€¦ª­„“²|‰­w†£}§{‘¥y£s‰Ÿt‡ rŠ¡i„šg”o‚—n‚”m‘lƒ”dzavs‚˜l|t„•t…‘t…~—ƒ’š…“ „¤€Ÿ}›~•{‹Œ{Š~Š˜ˆ” •ž«Ÿ¦±¥ª´¤«²¥°³¢­®®¹º¹ÁÃÂÆËÀÆËÀÅÍÐÔ×ïïïúúüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõÿÿýÿÿ÷ÿÿïÿÿâÿÿæÿÿæÿÿìÿÿôÿÿëÿÿßÿÿÒÿÿÇÿÿÃÿÿ¸ÿÿ¹ÿÿÍÿÿ¼ÿÿ³ÿÿ¹ÿÿÁÿÿµúã‚ÕTÃh9Ù¢gÿÿ¼ÿÿàÿÿîÿÿðÿÿòÿÿìÿÿèÿÿàÿÿÙÿÿÛÿÿàÿÿæÿÿîÿÿêÿÿèÿÿÙÿÿÍÿÿÉÿÿÅÿÿÇÿÿÉÿÿÑÿÿÛÿÿÑÿÿÉúç™ÿð«Å·š~ˆ’‘¢{‘©z¨yŒ¥vŒ¢—­{‘¥y£vŒ¢r‡¢r‡¢lžo…›lƒ’e~Œd}g}‘iy‘f{†m‚l}‰w‚“w„”{ˆ˜~™zŒ“€—ƒ™ƒ’š{”y‹•q‚‘n‹zˆ•’›¨¥ª¶œ¦®Œ›Ÿ“£¤œª¬ž«° ­¶£°·³½Ã¿ÊËÌØÖÕÜØðôìòòòÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿÿÿÿÿÿÿÿÿÿúÿÿÿÿÿÿÿÿÿÿÿþÿÿýÿÿþÿÿúÿÿòÿÿòÿÿñÿÿêÿÿëÿÿèÿÿÖÿÿÜÿÿáÿÿÐÿÿÃÿÿ½ÿÿÉÿÿ¼ÿÿ¿ÿÿ¾ÿýªíÂzÉ~CÀŒBÿäÿÿÍÿÿÛÿÿìÿÿüÿÿðÿÿäÿÿÞÿÿ×ÿÿÕÿÿÓÿÿÓÿÿÓÿÿ×ÿÿÛÿÿâÿÿèÿÿäÿÿâÿÿÛÿÿÕÿÿÏÿÿËÿÿÏÿÿÓÿÿÑÿÿÑÿÿ°ÿí€ÿð·¤’Ž™}©y£z“£}‘£„§€¦~”ª—¯sˆ£q‰ kƒšo‡žo‡ži—fu’ky–it’iz‹rm~ŠyŠ”z‹•wˆ”z‹—…“ †“œ…—}Š“}‹˜z‹—z‹—|Ž•‡–šž«°§­”¢¤“¡£˜¥ª¢¯¶ª±¸¥¨°¨¯¯¬´­¹ÁºÉÏÈÙßÖîòêô÷ôÝÝßÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿôÿÿòÿÿöÿÿúÿÿüÿÿüÿÿøÿÿéÿÿÜÿÿÞÿÿ×ÿÿÎÿÿÍÿÿÒÿÿÏÿÿÒÿÿÙÿÿÁÿÿµÿâæ¡k¼„Gãµtÿÿ¾ÿÿÕÿÿàÿÿêÿÿîÿÿòÿÿæÿÿÙÿÿÏÿÿÅÿÿËÿÿÓÿÿÑÿÿÑÿÿÙÿÿäÿÿêÿÿðÿÿðÿÿðÿÿæÿÿÞÿÿÙÿÿ×ÿÿÕÿÿÓÿÿÑÿÿÑÿÿÃÿþšÿó£ñÑ—›€‰«y…ž|¤z¤|”©|’¦}¥}“©}“«p†žmƒ›rŠ¡oŠ j…›f}—bxi|•]uy…žp€“w‡–yŠ–wˆ’|Ž•‡–žˆ•œ€Š’{ˆ~‹|‹ƒ’˜…“•“žŸ°»¾– ¦¥¯µ›¥­’™¢“˜¢˜›š­ª¢»¸®Ä¿³Ä¾»ÊÂÉÏÏÑÜáßûþûþÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûÿÿíÿÿóÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûÿÿÿÿÿþÿÿöÿÿòÿÿöÿÿ÷ÿÿøÿÿöÿÿðÿÿÞÿÿÚÿÿÕÿÿÜÿÿÚÿÿÛÿÿÇþÿÅÿÿÅÿÿÅÿô¬úŀБR΃JõˇÿÿÌÿÿâÿÿøÿÿòÿÿîÿÿêÿÿèÿÿÞÿÿÕÿÿÏÿÿËÿÿÏÿÿÓÿÿÑÿÿÑÿÿÙÿÿâÿÿìÿÿöÿÿöÿÿöÿÿìÿÿâÿÿâÿÿäÿÿâÿÿàÿÿÞÿÿÞÿÿÓÿÿËÿí£ÿì¦Êµ˜Œ…‘‰Ž£{«wŠ£}¥{¡{ŒŸ‘¤¤yˆ¢r€Ÿr n€žpƒœgzfyŽh{dw|u…˜w‡–p~‹s„Ž|—€—…’™˜v„‘|ˆ–ƒ‰™€†”…“Š™¤¦¬­°¸±´¾¢©´˜¥ˆ•{‚…†´¯¥¾·¬À·ªÅÁ²×ÔÈßÝÎìêÙúûôÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûùÿÿúÿÿéÿÿöÿÿüÿÿÿÿÿÿÿÿüÿÿêÿÿîÿÿëÿÿéÿÿäÿÿåÿÿòÿÿßÿÿáÿÿØÿÿÚÿÿ×ÿÿÎÿÿÌÿÿÖÿÿ×ÿÿÐÿÿÊÿÿËÿÿ¾ÿë“ã«`Õ‚GÕ¡Sÿ÷”ÿÿËÿÿàÿÿìÿÿøÿÿîÿÿæÿÿäÿÿâÿÿÙÿÿÓÿÿÏÿÿËÿÿÍÿÿÏÿÿÓÿÿ×ÿÿäÿÿðÿÿòÿÿöÿÿöÿÿøÿÿôÿÿðÿÿìÿÿèÿÿèÿÿèÿÿâÿÿÛÿÿÑÿÿÉÿÿ¹ÿë’ûãµ Ž‹Ž˜|ˆŸ~Ž¡€‘¤“¥|¤x‹ yŒ£y‹§v„¦p‚ r„ q„fyi|“o—hz†s€sƒ’j{Šr‚‘{ˆš|Š—}Œ”uƒŽw„”~Œ™|ˆ”z‡u‚‹ˆ’œ­´¿§±¹¯¹¿’ …‘†‹Ž‘Ž•”‹³­Ÿµ®£ª£š³­Ÿ¼¶¦Å¿¯êáÒþ÷ìöïèóïìÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿßÿÿàÿÿÔÿÿâÿÿíÿÿìÿÿüÿÿþÿÿÿÿÿùÿÿùÿÿöÿÿìÿÿäÿÿáÿÿçÿÿëÿÿäÿÿèÿÿÖÿÿÇÿÿÂÿÿÆÿÿÄÿÿÚÿÿÑÿÿ³þφތOÀŠAñÕÿÿÅÿÿÙÿÿâÿÿìÿÿæÿÿàÿÿÞÿÿÛÿÿÙÿÿÙÿÿ×ÿÿÕÿÿÓÿÿÑÿÿÕÿÿÙÿÿâÿÿêÿÿþèßàš˜‰ëðÑÿÿøÿÿöÿÿöÿÿøÿÿìÿÿàÿÿàÿÿâÿÿàÿÿÞÿÿÙÿÿ×ÿÿÃÿÿ›ÿô¨ß¿–˜Ž„„‘¥Š—©‚Ÿ}ŽwŽsŠ™y¡rˆœp†žr…žv† r‚šy‰Ÿrƒ–j{Žh}†i~‰qƒl}‰q‚Žsƒ’{Œ–€•v…r€‹˜~‹”}‰•zƒ’ž¥®§­°¨®±­³¸–œŸ„‹‹¨°©¤­Ÿž¡³­©£“£§¢–´®©Áº±¿µ«Âµ¬ÓÁ¼âÔÇïäÏõðäÿÿÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿòÿÿâÿÿÞÿÿÚÿÿïÿÿôÿÿòÿÿöÿÿíÿÿóÿÿòÿÿôÿÿìÿÿíÿÿôÿÿòÿÿðÿÿâÿÿæÿÿÜÿÿÙÿÿÉÿÿ½ÿÿ¼ÿïµÿÕ—ï£aÄ7ÞªSÿùªÿÿ×ÿÿäÿÿðÿÿìÿÿèÿÿàÿÿÙÿÿÕÿÿÓÿÿÕÿÿ×ÿÿÓÿÿÏÿÿÓÿÿ×ÿÿÛÿÿâÿÿøÿôõÓ´ÓݱïàÃ껪½ÿúìÿÿìÿÿòÿÿúÿÿìÿÿÞÿÿÙÿÿÕÿÿÙÿÿÞÿÿÛÿÿÛÿÿÏÿÿÅÿõ¡ÿä–¯œs‡|}ƒ†}™~’¢|¦s‰o…™l„™rŠ¡t‰¤t†¤k™n†›s‰¡gy•e}‡iz‰k|ˆn|‡t€Œy™}‹˜v„s‹x…Ž{ˆ‘Œ“„‘–¨¶¶£¯«­¶µ£§¬Œ•’•§©¯žš¢©¥¢©¥–ŸŒŸŒ¢žª¤”»²¥¹¬£¼³¤¿º§ÍůÚжäÜÆéáÏêàÖóèåõððÿÿÿÿÿÿÿÿÿ÷ûãÿÿíÿÿñÿÿöÿÿîÿÿèÿÿîÿÿóÿÿèÿÿøÿÿôÿÿòÿÿìþÿÏÿÿÓÿÿìÿÿîÿÿéÿÿåÿÿßÿÿØÿÿÛÿÿÔÿÿÅÿߧþ¢|Ç|EÉGùÛŒÿÿÂÿÿÞÿÿôÿÿîÿÿèÿÿäÿÿâÿÿ×ÿÿÏÿÿËÿÿÉÿÿÑÿÿÙÿÿ×ÿÿ×ÿÿÞÿÿæÿÿöÿÿÿæÈâܬîå¸ûÛ±õÉ£äȤäǶÇÿÿúÿÿúÿÿüÿÿìÿÿÞÿÿÕÿÿÏÿÿÓÿÿÙÿÿÛÿÿÞÿÿÛÿÿÛÿÿËüð’ÿù—ÿñÞËšƒWza‚‰‡‚‘•r†”vŽ˜|”žr‹›j‚™k†œe˜ayŽo…™mˆŒcv}fx}o~„tŠzƒx„zˆ“z†’vŽw…u†yˆŒ–ž¬³º¦¬±³ºÃ˜¥†”™  ”•Ž­ªž«¥•£ŸŽ ž¦¢‘®¨˜­¤—´§ ³©Ÿ°©ž¼¶¦ÐÈ´ÝÒ½ÛκÛκÝмÚÑÄîèãüúëþýçÿÿüÿÿüÿÿôÿÿìÿÿáÿÿÐúüÕúùãÿÿÿÿÿÿÿÿøÿÿòÿÿåÿÿàÿÿçÿÿðÿÿèÿÿØÿÿÌÿÿØÿÿÖÿÿËÿÿ¼ÿÖ—ÐX×|QÿÏ‚ÿÿ¤ÿÿÁÿÿÕÿÿæÿÿöÿÿìÿÿâÿÿàÿÿàÿÿÙÿÿÓÿÿÓÿÿÓÿÿÕÿÿÙÿÿÙÿÿÛÿÿæÿÿðÿüñжÊÒ­ÙÒ¢èËå׬õ×®ðΩåÏ»ÔÒÏÇÿÿþÿÿðÿÿæÿÿÞÿÿÙÿÿÕÿÿÕÿÿ×ÿÿÙÿÿÛÿÿÙÿÿÙÿÿÍÿÿ³öì‹ÿû—ÿûÿÿªÿÿ¹óå±¢ž„mqt{ˆuŠ“m„‘m†–kƒ–h€—kƒ˜p†œm‡Žbu|gx‚nzˆrƒr‡t‡ŽyˆŽ|‹“t‚w…y‡”}‰— ¦¶ž«´›ª®™«°‹¤‹š¢§±—š¤š“Ÿ©£ ¥Ÿ§¡‘¥Ÿ‘©£•ª¡”§¡“¥Ÿ‘¬¦˜³ª´¨š»®žÍ½ªÕ­×DZÝ̹áÔÂçÜËæåÁüÿÎÿÿßÿÿÌÿÿÖÿÿñÿÿãÿÿôÿÿôÿÿôÿÿøÿÿúÿÿëÿÿçÿÿâÿÿäÿÿâÿÿÞÿÿÜÿÿãÿÿßÿÿÓÿÿÅÿÿÁÿÙ¥Û}b×—_ÿë—ÿÿÊÿÿÙÿÿàÿÿèÿÿèÿÿèÿÿäÿÿâÿÿÛÿÿ×ÿÿ×ÿÿ×ÿÿÑÿÿÍÿÿÏÿÿÓÿÿÙÿÿàÿÿúñÝäÒ²Øà³øÓ©ðÅŸéÇŸê΢îÏ¥îÒ«óË®çÈ°ßèßàÿÿðÿÿðÿÿðÿÿäÿÿÙÿÿ×ÿÿ×ÿÿ×ÿÿÙÿÿ×ÿÿ×ÿÿÍÿÿÅÿÿ¢ûí‰ÿÿšÿÿ›ÿÿ˜ÿÿÿùžÿî¨ï⦼¶†‚mdiqm{†m‘oƒ“j~f…p{Œr€p‹m€‡q‡w‰“z‹—|—u†qƒˆu„ˆ~‘™¦­“ ©¡ª·™¢¯Œ•¢“£¥§—˜‘¦¢œŽŸšŽ ›˜Ž£ž”ª£š¥ž“¬£–´«žµ¬Ÿ±¨™±¨™µ­›Ã¸¥ÌÁ®×ʺßÒ¾ÙͶÓÌ¡ÿÿÅùú¿ÿÿÐÿÿèÿÿðÿÿôÿÿøÿÿðÿÿÙÿÿáÿÿóÿÿìÿÿàÿÿÝÿÿÖÿÿÒÿÿãÿÿôÿÿôÿÿñÿÿõÿÿïÿÿåÏšvÓ‚[ÿÔ“ÿÿÃÿÿÙÿÿðÿÿèÿÿàÿÿàÿÿàÿÿàÿÿâÿÿÛÿÿ×ÿÿÕÿÿÕÿÿÍÿÿÇÿÿËÿÿÑÿÿèÿþêßÅ×Ý´ïÚ±ñÕ«òÚ°ùÒ§óÆŸçÀ™á¿˜ÞͤèÖ­íÓ«èűÈÿÿöÿÿúÿÿðÿÿêÿÿæÿÿÛÿÿÓÿÿÑÿÿÑÿÿÏÿÿÍÿÿÏÿÿÑÿÿÉÿòšöïþû˜þÿ˜ÿÿžÿÿšÿÿ˜ÿÿÿù•ÿú§÷æ¥Æ»‰nkkihp†fwkz€t…v‡–h|Šn‚rƒ’vƒ•{ˆšv”v~’ƒˆ–£§­”¡¦¡°¶ˆ—ƒ’šŽ˜ œŸ§””’Ÿœœ˜‰ž˜ˆ›–ƒ ›ˆ¡›‹¢›¡›© ‘­¥“µª™´¬š³«™´©˜¾°£È½ªÂº¤ÈÁ¨ÎĬâܺÿÿìÿÿäÿÿêÿÿâÿÿÉÿÿÐÿþÆüþËÿÿàÿÿðÿÿðÿÿáÿÿ×ÿÿÖþþ×ÿÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ×À¦ôØ¡ÿÿÉÿÿÑÿÿÞÿÿêÿÿàÿÿ×ÿÿÙÿÿÛÿÿâÿÿêÿÿàÿÿÕÿÿÑÿÿÍÿÿÅÿÿ¿ÿÿÑÿÿÚóàÙÝ·ßåºñâ¯ùܯôÔ«ïÙ¯öÖ¬õÐ¥ôÌ ôÆð¿˜ìÇŸêÓ©ëˬÏÕÀÅÿÿþÿÿîÿÿæÿÿÞÿÿ×ÿÿÓÿÿÓÿÿÕÿÿÍÿÿÇÿÿËÿÿÏÿÿÅÿÿ½òðŠú÷ÿÿ–ÿÿ–ÿÿÿÿÿÿ•ÿÿšÿÿ—ÿÿ‘ÿÿŸÿõ£ýê§ØÆ–§Œvw||Zgpo•o€“p”r‚‘zˆ•y‰˜m~‘p€‘}ˆ›‘œ­–Ÿ®¡®·¡°¶‰˜žŽ—Œ–œ•›žŒˆ˜Œ›—ˆ›—ˆ—•„ ž¡Ž¢›¡š§ •®¤š´§žº®¢º® ²§–·ª˜Â·¤Á¹§ÀºšÀ¼íñ¯úÿ°þÿ¾ÿÿÈüýÍÿÿóÿÿöÿÿøÿÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿʬõï»ÿÿÙÿÿÑÿÿÙÿÿäÿÿäÿÿäÿÿâÿÿàÿÿàÿÿâÿÿÛÿÿ×ÿÿÏÿÿÇÿÿÍÿÿÓÿ÷ØßÂÎÛµÝß­òÚ­òݲûØ­öݯù׫÷׫úÖªùÑ¥ôÉžêË£îÆžìΣôƤڶšºÙÊÆÿÿòÿÿèÿÿàÿÿÛÿÿ×ÿÿÙÿÿÞÿÿÓÿÿËÿÿÏÿÿÕÿÿÓÿÿÑÿÿ¼÷íŒüúþÿ‘þÿ‘øÿüÿ•úÿ•úÿ“úÿ‘üÿ™üýŸ÷ó•ÿÿŸÿõ·ÿÿÿ˜Ÿª]m|r‚“w‡šu…”št…p~‹p|Š‡š¤™£«žª¶• ±†’ž†š’—ŸŽ–Œ‹›–Œš•‰—‰¡›¨¡–¥ž“§•¤”¬¥œ±§®¡˜±¨™·¯›µ°›²­š¾¹¤¾¶¢¾µ–¹ÿÿÍÿÿÉÿÿÖÿÿäÿÿéÿÿîÿÿðÿÿòÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÜÔÛ·­µ—‹š‰´¨‘ÏǘÿÿÎÿÿÅÿÿÍÿÿÕÿÿÕÿÿÕÿÿÓÿÿÓÿÿÕÿÿÙÿÿÙÿÿÙÿÿÕÿÿÑÿÿèÿêáÛ¼ÒÚ¯æà´òß±ùÐ¥î΢îרõÖ¢ôئ÷ئùØ©ûÕ¨üÓ¨ùϤóÊ¢í̦ðͨíÉ£æɲÃÿøÙÿÿèÿÿÛÿÿÙÿÿ×ÿÿÙÿÿÛÿÿÓÿÿËÿÿÍÿÿÑÿÿÓÿÿ×ÿÿÉÿÿ óô‰þÿÿÿ–þÿ—÷þŒüÿ÷ÿŽüÿ™ýÿ˜þÿ•ûÿ’ýÿ”üû«ÿÿÿÿÿÿ°·Âiuzˆ•v„‘~‹›x‰•q‚Œn‰‰—¢Œš¥’žª—£¯Žš¦Š”ž’™¢¤ …Š{Ž€‘Œ‚‹—’ˆ¡š¦œ’§ž­¢‘°¥’´©–·«²¥ž¬¢˜®¥˜³ªµ«¡»²£º¯ž¶¬×Ï©ÿÿéÿÿâÿüäÿÿûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûûýòðêãßÐÍʶÀ»¦¢œŒ™’‰›”‹›‘‹Å½§¢výÿ¸ÿÿ¶ÿÿÅÿÿÑÿÿÕÿÿÙÿÿ×ÿÿ×ÿÿÕÿÿÕÿÿÓÿÿÑÿÿÓÿÿ×ìØÈÓ®ÓÞ¶ìÚ¯øÔªóͦîÓ¬ôÕ«ôÖªöרúÖ§÷Ó¤ôרúÚªÿÑ¥öΣïÇŸêÍ¥ðΧïÔªóͲßǸÍÿÿúÿÿÕÿÿÕÿÿÕÿÿÑÿÿÍÿÿËÿÿÉÿÿÉÿÿËÿÿÑÿÿ×ÿÿÑÿÿÍõö˜ÿý•ÿÿ™þÿ–þÿ”ÿÿ—ÿÿ—þÿ•ÿÿ—ýþ•ô÷üÿ•þú°ÿÿÿÿÿÿÿÿÿ–ª¥m„ƒq„‹w„”{‰–v„~‹’“£Œ™žž¢‘£¨‰›¢”š›˜™‰†~Ž‹ŒˆwŒ‰}‘‡š— ›‘¦¡—¨¡˜°ªœ±¬™¶±ž°§˜ž™„ž™‚¡žˆ¡ Œ˜š~¨®Š´´—úõàÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòñäâáÉÓиÝØÁñïÒ÷÷ØñïÐùòÕÚҼú­œ„„ÙÇÀ«˜•ÊÄÿÿªÿÿ¹ÿÿÁÿÿÇÿÿÍÿÿÑÿÿÕÿÿÑÿÿÏÿÿÏÿÿÑÿÿÑÿÿÓàÍ´¸–­Ô­ÞØ©öÍ£ìÅ çÒªõÕªùÕªö׫÷׬ûΣôË ïΣòÍ¥óÃêÁ›è¿™æʤñ̤ǫ̂èƧÚàÐÏÿÿäÿÿÛÿÿÕÿÿÑÿÿÍÿÿÉÿÿÇÿÿÇÿÿÇÿÿËÿÿÑÿÿËÿÿÅÿÿ´øöŽÿÿ”ÿÿýÿŒÿÿ’ÿÿ”ÿÿ•þÿ•ÿÿ—ýþ•ýû•öîªÿÿÿÿþÿþõö¿Ð€¢q|t‡Žw‰}Š“†š”£Œ“žˆ’œ…’›~Š–€Š’•‹Ž‹‰†|’Œˆy’Ž‘€~žœ¢ž˜…ž–‚¤žÀ»³ù÷óÿÿÿÿÿÿÿÿÿÿÿÿþüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿù÷èëæÑäâÓîìææèÞíïåñóåøûèøüæûüçÿÿòÿÿ÷û÷è÷òßƾ¬Ê¾°Èº¯Æ´¯éÒÓɬ¶Šsíâ«ÿÿ¹ÿÿ¬ÿÿ¿ÿÿÉÿÿËÿÿÍÿÿÑÿÿÕÿÿÓÿÿÓÿÿÏÿÿÍÿÿò¸‘ ÈŸÈΤæÈŸãÄšã¿—âШöÏ©óɤëÏ©óÒ¬ùÒªõÓ¨ôÍ¥óÍ¥õШøË£ó̤òϤóÑ«îÑ®éʶ¿ÿÿÚÿÿàÿÿÓÿÿÍÿÿÉÿÿÉÿÿÉÿÿÉÿÿÉÿÿÉÿÿÉÿÿÃÿÿ¿ÿÿ»ÿÿ¡ú÷‘ú÷”ÿÿšÿÿ—ÿÿ•ûÿŒúþÿÿ›ûþ”üý–ÿú·ÿÿÿûøûÿÿÿ·¿Á•¨¨m‚u„Šu„ˆv„†…“•}‡Œ“‡–ž{”€’™Š™“¡£†„ˆ‰„ˆ‡~Œ‡}ˆ‚r‰m}wgˆx¹¶®îìèÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿø÷êïêÓÊ¿Ÿ¹«…½«Á´‰Æ¹“ÜÕ¸ÿÿòÿÿûÿÿÿÿÿúýûõüúôÿÿüÿÿýþþüûü÷ÿÿúéæÜâÝÑãÝÏêáÒðãÚçÔÔª™Š¢rýõ±ÿÿªÿÿ¹ÿÿÃÿÿÅÿÿÇÿÿÉÿÿÍÿÿÏÿÿÑÿÿÑÿÿÑÿÿ×ÿÿ˱’˜ÇšßÈžåÇ èÌ¢ëΣìϤíÆ›äΣïË ñÍ¥ó̦óШöÍ¡òÈìÌ¡ðΣòÌ¡ðÅ›äÉŸæĨÈ˼¶ÿÿìÿÿÍÿÿËÿÿÉÿÿÅÿÿÃÿÿÉÿÿÑÿÿÏÿÿÏÿÿËÿÿÇÿÿÁÿÿ¸û÷–ÿú›ÿÿœþÿ–ÿÿ–þÿ‘ýÿ”øø”ÿÿ™ÿÿ˜ÿþ´ÿÿÿÿÿÿÿÿÿŸŸ¡¨«µq{ƒyˆ¶ÆÇÅÔÏž ™¥Žš¦™¨‚Žœ|‡˜‰‘y€€gkeli_igX‰xÓÑÂÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüøÿçÞê¡šž†€}‰„xˆƒn¨ |·¬z¶«t½°wôƒÈ¸ËÁ§ãÞÔø÷îûü÷úûöÿýüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýøöñçñëÝöéâÜÉÉν³›Šy±¨nÿÿ§ÿÿ¯ÿÿ½ÿÿ¿ÿÿÃÿÿÅÿÿÉÿÿËÿÿÏÿÿÏÿÿÑÿÿÍÿÿÉÕ­º‘¼Ë ÙÌžæÉŸæΧíͦîÒ§öÉžíÔ©øϤðϤðÐ¥öУù΢öШøШöË£ñΧïÔªñɬո£±éãÁÿÿÍÿÿÉÿÿÅÿÿ¿ÿÿ¹ÿÿÁÿÿÉÿÿËÿÿÌÿÿÉÿÿÇÿÿÃÿÿÁÿÿ«ùñ”ùö•÷÷“öù‘ÿÿœÿÿšÿÿ›ÿÿ˜ýÿù÷ªÿÿÿÿÿÿÿÿÿ¦¨®³¶À…Œ•ƒ™Ôßâÿÿÿ™¤§š¡Ž˜ž}ƒˆcilt{{˜Ÿ“¿Ã­áâËýüæÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿàÛÛ¬£¤šˆ›Š€¢–´ª‡·®„¾¶‡Àµ‡·«}¯¢wªœv¤—q£™r£™v­¢„ö¢àÑÉÿÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøõöõððþþüÿÿÿÿÿÿÿÿÿÿÿÿúúúÿ÷ÿÖÄÚ©˜«µ¤·‡håä’ÿÿ±ÿÿ©ÿÿ¹ÿÿ¿ÿÿÅÿÿËÿÿÓÿÿÛÿÿÛÿÿÛÿÿÑÿÿÉÿÿ佤”½¸Æœå¿˜à»”ܽ“Ü΢îÉžêÒªøÔ¬úÙ®ÿÓ¨ùУ÷ÉñÈœòÇœëÌ¢ë˜ßÁ–ÝÄ¢ÉÁ©¯çÞ´ÿÿÅÿÿÂÿÿÃÿÿÃÿÿÃÿÿÅÿÿÇÿÿÁÿÿ·ÿÿ¾ÿÿÃÿÿÅÿÿÉÿÿ¾óæ–ÿùžÿÿœÿü™÷ô“úú˜÷ö—þþœÿÿŸÿü·ÿÿÿÿÿÿÿý÷ÂÀ¼ÉÆLj‹“…ŽÈÎÜÿÿÿ›¤±›¨”Ÿ íóêÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿìçç·°°˜ŒŽŽ„|†~lœ•z¥Ÿ}©£s¸¯r´®p·±v¯§t¯£zªžs«Ÿq§œn¤˜m›‘jƒ`nkH­®ŒÿÿðÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòîéÑǽ—Œ‰m^cZQVvnwöòøÿÿÿÿÿÿÿÿÿú÷ëÇ¿«xfcŒp~œ‹‡gññ¬ÿÿ³ÿÿ«ÿÿ»ÿÿÁÿÿÉÿÿÑÿÿÙÿÿÙÿÿÛÿÿÓÿÿËÿÿÙÿôÊ·–ŸÃšÕÚ×ÈžàÅ›äÅ™íÊ¢òË¥òЪ÷ͧöΦôÏ£òÌ ìΟìÉžçÈäɢڿȹ§îè­ÿÿÍÿÿ¿ÿÿ½ÿÿ½ÿÿÃÿÿÉÿÿÅÿÿÃÿÿ¼ÿÿ²ÿÿ³ÿÿ¹ÿÿ¹ÿÿ¹ÿÿ¬ëߊöñ—ÿý¡ÿÿžüÿ•ÿÿ—þü”ýþ—øø”ûö±ÿÿÿÿÿÿßÛÖÄÀ»¿¹´…‡…¡¹¾Ñÿÿÿ©®Á˜«– ªñùûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÚ×Ï–†wst|© ©¥y°ªz®£s¯¤v®¢y« rªžn¥še¨f¥™g¤—l¢–m –oŸ˜k—e‹ƒ]mcK@;3ƒ~‹ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿý§¦”€}qdaYTVL\`XMIDåÚÙÿÿÿÿÿÿÿÿÿ¾ÔÖ!'*UIM‡sz•x„©t÷ûžÿÿµÿÿ¸ÿÿ½ÿÿÁÿÿÇÿÿÍÿÿÑÿÿÕÿÿÕÿÿÕÿÿÑÿÿÏâÎÀ¸”ÇË£àÉžåÇäÉŸèÉžêÏ£ôÑ¥ô΢ñÌ¡èѧéͤæÈŸãÞÚÆ¢Ù¨¾À®¤óë¸ÿÿÃÿÿÁÿÿ¿ÿÿ»ÿÿ·ÿÿ¿ÿÿÇÿÿÁÿÿ½ÿÿ¹ÿÿ³ÿÿ±ÿÿ±ÿÿ·ÿÿ¶ÿý§ã̆øéšÿ÷¡ÿúžýù˜ÿþÿýœÿþ˜ÿÿ—üø°ÿÿÿÿÿÿ¾¹¹À½¼¨¨¨€…€ˆš®´Äÿÿÿ¹ÂÑ›¬•›©ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿĻɕ†\PdSJZ{vn œ~§¢{¬¦v¬¥z­£~§v£šp£™r¢•q¢•q¥—s¤”l¨•l¤•h¡•gŸ”f›b™d”Šc‡]“Š`pgHF>,/-'W\dÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÎÐƈ†w˜“~mj^HFB@>:LHE`_VÚÜÐÿÿÿÿÿÿÿÿÿÿÿÿdJpG,YcLf’‡‹}^Ê¿yÿü ÿÿœÿÿ¶ÿÿ¿ÿÿÁÿÿÅÿÿÉÿÿÍÿÿÏÿÿÓÿÿÍÿÿÇÿÿîа»»™ÀÆ ãÉŸæÊŸèÌ£åÈ ÝÄžÝßáÅŸàË¢äÆ ßÃÜŸʹ”±À°–ÿþ¯ÿÿÅÿÿ¿ÿÿ½ÿÿ»ÿÿ¿ÿÿÃÿÿÅÿÿÉÿÿÇÿÿÅÿÿ¿ÿÿ»ÿÿ³ÿÿ¨ÿÿ¦ÿÿ ÞÕÔÂÿô¦ÿöœùõ”ÿýšýú—üù–÷÷“ýý›ÿø¶ÿÿÿ×ÒÒ®¦¢«§¢›•z~Š™ª±¼ÿÿÿÄÎ؉—¤‚˜äëòÿÿÿÿÿÿÿÿÿÿÿÿ £ \cUkn[yx`–“r¨ x›’h¢–k£—l ”k ”k ”kŸ“h¢–h¡”k ’njœišišk˜Žg–c–c“Š`…`‚wWXQ6611-QNFæäÞÿÿÿÿÿÿÿÿÿÿÿÿ±ª£ypa{nZUF,I;bT0eT/_UMëçýÿÿÿÿÿÿÿÿÿÿÿÿ¿É´&. KG6ˆty€lŽ‡\äæ‘ÿÿÿÿ–ÿÿ³ÿÿºÿÿÃÿÿÇÿÿÍÿÿÍÿÿÏÿÿÉÿÿÅÿÿÉÿÿƺ—Æ—ÖÏ¢åÌ¡èÈŸáÆÝÅœÜÉŸßÆÝϦæ̤ßÅžÔ¼¢¦ÜÍ ÿÿ»ÿÿ¹ÿÿ½ÿÿÁÿÿ¿ÿÿ½ÿÿ½ÿÿ¿ÿÿ½ÿÿ½ÿÿ·ÿÿ³ÿÿ±ÿÿªÿÿ¢ÿÿœÿý£äØ•·§aäЉÿïžÿï—ýó’ÿü•þû“ÿý•ÿÿ•úô‹ÿ÷°ÿôø¢””‹ˆ©œ—“Œ…vsvƒ†’•š¤ÿÿÿÙáå{„ƒ†„ãããÿÿÿýýÿÿÿÿÿÿÿÒÖÐ{€uzzj~{g—w£šnž•iŸ“j¡”n¢•qž”o›‘l—f™Œf”Šc—h–c›d–a–c“‰d”†g”†g•‡h‰~`pfLHA(5-/((F?V¬­Ãÿÿÿÿÿÿÿÿÿùüëw}Yf^+šƒA´œMÓ¸]åÎxúç™É½ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿm?wa>\}biy~znp§¡oýþ—ÿÿ©ÿÿ©ÿÿ·ÿÿ¿ÿÿ¿ÿÿ¿ÿÿÇÿÿÑÿÿÏÿÿÏÿÿÇÿÿ¿ÿïŪ‰–¼–¾ÇáÇžàÈŸß̤áË£ÞÂ×¾™ÕÀ¤Â»§§àØ¥ÿÿ®ÿÿ»ÿÿ¿ÿÿÃÿÿÉÿÿÁÿÿ¹ÿÿ»ÿÿ½ÿÿ·ÿÿ³ÿÿ«ÿÿŸÿÿ—ÿÿ’ÿÿœÿ÷ž×È}­—\ؾyÿâ“üèþò’ÿõ’ÿô‘úñÿø–ýú”ÿþ–ÿø¯¤¡¤€zu˜Ž„š“Š‡€ya\\NMTcbgÿÿÿú÷ö¢Ÿ—ÖÓËÿÿüÿÿÿÿÿÿÿÿÿÿÿÿòòâ”’u‘‹i¢•o¸¬ƒ³§~¡”nŸ’nši–‰g”‡a–Š_•‰`–‰c–‰c–‰e”Še–Œg“‹cˆ`‘‰e‘‡k‘‡oŒpniTLI1752.0.76yûûéù÷ñýùÿÿÿÿæåÜßá¬ó÷–ÿÿ¶ÿÿÅÿÿÙÿÿîÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþ£»ch7€W‹zkˆo~~q]ÆÄŒÿÿ»ÿÿ¢ÿÿ²ÿÿ½ÿÿ½ÿÿ¿ÿÿÇÿÿÏÿÿÑÿÿÓÿÿÍÿÿÉÿÿÛàÇ¥´”¡ÅœÙË¢äÇ æÆ¢äÅ¡ãʧמ¿Â¬”êã“ÿÿ·ÿÿ¯ÿÿ·ÿÿÁÿÿ¿ÿÿ¿ÿÿ·ÿÿ±ÿÿ¬ÿÿ«ÿÿ©ÿÿ§ÿÿŸÿÿ•ÿÿ–ÿÿ˜õé–¼¦p°–UæÇýÝŠÿÝ‚ÿä‹ûç’øç”öè–þó—ûõýú’ú÷ýò¨xvr†Žˆ’‹€xwj\ZT>9=OBKÆ°Áöáí¥‘šxktÈÁÍÿÿÿÿÿÿÿÿÿÿÿÿÿÿö¦›ˆ¢—yŸ’lŸ•pšo”‹a”‰Y’ŠW“ŒV“‹X“ˆZ“‡\•ˆ_•ˆf’†kŽ‡jŽŠlŠ‡o‰…t‡…v„w|ymmj^MJ2@:7,/C/{aǹ—ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúÿþôÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøçïÚ½~jF’€TŠs‹us~r’ˆpääÿÿ¦ÿÿ¨ÿÿ³ÿÿµÿÿ¹ÿÿ½ÿÿÁÿÿÃÿÿÇÿÿÇÿÿÇÿÿÍÿÿÓÆ­¡¿™Å¼˜ÏȤæË©ÝʨѴ¢˜ÊËÿÿ«ÿÿ±ÿÿµÿÿ»ÿÿ½ÿÿ¿ÿÿ»ÿÿ·ÿÿ±ÿÿ¬ÿÿ­ÿÿ³ÿÿ±ÿÿ¯ÿÿ¦ÿÿõê¢×Ø­”_ήoïÊ„ÿÖ‹þÛ‡ùÞ€øà†ùåŽûëŽÿò“ýôŽûöŠûõŒúñ‹ùt‰†|•Ž…‡„xqqaXWL42./-) - -&!!NGIFCFž¢ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¢š„•q™Ž^ša–Ša“‡^•ˆb“†b“…f‡h†iŒˆnˆƒn†‚q…€t~|m||l}{j‚~m|dzvZl_4^HwY!hA ­–@æßmÿÿ¢ÿÿÂÿÿàÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýõÕÐÈ•‰rmZ‡azrC„w;­žo›‡e†v`‰zt§ŸnýüŸÿÿ¦ÿÿ¤ÿÿ¯ÿÿµÿÿ¹ÿÿ¿ÿÿ¿ÿÿÁÿÿÁÿÿÁÿÿ¿ÿÿ¿ÿþÕ¹›ª»œ½¼šÐ¼¤®Ã±“ñì©ÿÿ¶ÿÿ¿ÿÿÅÿÿÃÿÿÁÿÿ»ÿÿ·ÿÿ±ÿÿ«ÿÿ©ÿÿ¥ÿÿ­ÿÿ³ÿÿ­ÿÿ¤ÿþ®ÜÍ ¦“aµœgà½õÇ„úχôÌ~òÏ{ùÚ€üäŠúæøè‰üí‹þóþô“üö‘ýú’ÿø²€r‰‡xŽŠ{„uzynWUO2/0&#$&!%<79g`b|w„©¨¿ÿÿÿÿÿÿììîÑÎÑÄÀ±–y¡™sš‘e™h˜‹i”†g“„jj†yg~vdyufurfqpesrgsrgsqbtq]leHqg@•ˆOƳléØ€ÿò‹ÿÿ ÿÿŸÿÿŸÿÿ½ÿÿÀÿÿÇûñÕÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿâÝÝ œ—~yoxsing^iaO“‡n‹~Sˆx= Zñƒ‹{cˆuuƒzPÇÆrÿÿžÿÿÿÿžÿÿ©ÿÿ®ÿÿ¹ÿÿ»ÿÿ½ÿÿÁÿÿÇÿÿÃÿÿ¿ÿÿÞêÒ¿±•š¾ž»Ûȯÿÿ³ÿÿÅÿÿ½ÿÿÁÿÿÅÿÿÃÿÿÁÿÿ¹ÿÿ³ÿÿ­ÿÿ¨ÿÿ©ÿÿ©ÿÿªÿÿ«ÿÿ¤ÿÿ™Óχ¡”n¬yãăò͇úÏ…ñÇzóÇzóÊüÖŒÿâÿì”ýêŽúê‹ùê‹þò”ÿù˜ÿù˜ÿð®€ynˆv„}r†t„}tYUR2.4'*'POFkjawtlE?:LA@TMOWQXf`]†{›“—‹pˆƒl|zkwthrogmjbpkclialjdjkdklgrr`rrS˜[À¬eãÒ|ÿó‘ÿÿ¢ÿÿ¥ÿÿ°ÿÿ»ÿÿ²ýÿ˜óû”úÿ£ÿÿ¶ÿÿÃÿÿØÿÿóÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿáÞᱩ°†Š” ››ž™™Ž‹~}e‰g’†[†zJŠxHˆ{=¬¡Wð‰ŠokŽi”jÜÞÿÿ”ÿÿ“ÿÿ“ÿÿ›ÿÿ§ÿÿ·ÿÿ½ÿÿÇÿÿÑÿÿÑÿÿÑÿÿÉÿÿÁóñ™ïè–ÿÿ´ÿÿ¹ÿÿ»ÿÿ½ÿÿÁÿÿÇÿÿÁÿÿ»ÿÿµÿÿ¯ÿÿ­ÿÿ¯ÿÿ¥ÿÿ£ÿÿœÿÿ‘ùõ—ÑĈ°kÉ­‡åÀŠñÀõÈ~ôÆxôÆz÷ÈðÂ}ñÅ‚òÎðÔ€üãŽüå‘ÿð–ÿ÷™þò’ùë‰ýì­}vkzsj|un€{qupfXVP111% "H@>LGGNNP]^Y`_Vkicgeaqpe„„tˆŠ|{}qtvlopihidjgfkiefd^ge_qokomiqnmyu[šaóî«ÿÿ³ÿÿ¯ÿÿ®ÿÿ°ÿÿ¼ÿÿÀÿÿ­ÿÿ£üÿ›ÿÿ¦ÿÿ°ÿÿºÿÿÁÿÿßÿÿçÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõñ÷±­³“”Ž‹Œ–”˜—Œ—•†—”~–{¯£uƲt×ÀzÓ¹kˆq-ˆs:|k,‘‚@¼¬o¶¥p~`|w®§oïòˆÿÿ•ÿÿ‘ÿÿŽÿÿ”ÿÿ©ÿÿ·ÿÿÁÿÿËÿÿÍÿÿÏÿÿËÿÿÉÿÿÉÿÿÉÿÿÅÿÿÃÿÿÁÿÿ¿ÿÿÁÿÿÃÿÿ½ÿÿ·ÿÿ¹ÿÿºÿÿ³ÿÿ¯ÿÿ¨ÿÿ ÿÿ›õí”̾wµ¢nؾ}ðÌôÌ~úÎ}ôÈwîÂsíÀvóÅ€ódžöÉøÓúÜüâ’ýå”ûê”öæ÷ê÷ëýî®pkarmcvofwrfspd^[O2/%'/*,84:NQPGLHcg__^UzwmxqfjeY|wkˆ…{tpknjgohjgbdfcdec_kjanm`ttdxxh|ym~|RÄ¿zÿÿ¶ÿÿ¿ÿÿ¿ÿÿÄÿÿÍÿÿÛÿÿÑÿÿ´ÿÿ®ÿÿµÿÿ¿ÿÿÈÿÿËÿÿÎÿÿêÿÿùÿÿÿÿÿÿòõô³°±‰…‚‰„|‘Ž„™˜–”ƒ•’z˜“l§h¿®oÙ¾wîÏ…ÿÛ‘ÿÛ”øΊ·›Yzk+„u3„u3¥—PÓÆz¢“d‰xgŒSÍÉ}úþÿÿ}ÿÿ‹ÿÿŽÿÿžÿÿ³ÿÿ»ÿÿÅÿÿÇÿÿËÿÿÉÿÿÉÿÿÉÿÿÉÿÿÇÿÿÇÿÿÃÿÿÁÿÿ¿ÿÿ½ÿÿµÿÿ¯ÿÿ­ÿÿ®ÿÿ¥ÿÿŸÿÿœÿÿ”èÛ‹Æ°Ê®uß¿~éÄ~ç¼tç»vãµrîÀ}ò€øʉðÁƒøÉ‹óĈñǃóÍûÝŽþä”ûã’ýè–ûë•üï˜ÿñ¶hb]d_WgbZoj`xsgd`[+(+ .+,]XZmfhIGAPRDZ\Rca]kh`ql`ytje^We][lcfmfhmhjomgutiyxkxxhzxg~zi€~VíéªÿÿÂÿÿ¿ÿÿÉÿÿÐÿÿÙÿÿÙÿÿ¹úþŸüÿ¬ÿÿÃÿÿÈÿÿÉÿÿËÿÿÍÿÿÈÿÿÆ̳£‘qŽ`J[KBGqkfŒ€’Žt—k¥šeÇ´qäÏøà„ÿî–ÿô¢ÿêûÖŽé¾â±×±ƒrJƒm7„s2”†A·©bȹŠ‘~g…wX˜Žiäáýÿ…ÿÿÿÿ‹ÿÿ•ÿÿ¢ÿÿ®ÿÿµÿÿ½ÿÿÇÿÿÅÿÿÅÿÿÇÿÿËÿÿËÿÿÍÿÿÅÿÿ½ÿÿ·ÿÿ±ÿÿ§ÿÿ›ÿÿ›ÿÿ¢ÿÿ£ÿÿ˜ýøœàÌŒÁ¬ḻsåÃ~òÇñÆ~ê¿wë¿zñÂïÁ€÷Ɉèºwé¹ué¹wôÆôȇøΊøÔ‡÷Ú†úÞŒþä”ùåøè’ýè¯ed[acW^`Reg]nlhWWW!%IDDhc[‰†zusda\Rjb^voh{qi€vpmb_nhcmifljfljfmoeoqetshvskyud€xb—gÿÿ·ÿÿ¼ÿÿÅÿÿÎÿÿÓÿÿ×ÿÿÑÿÿ¸ÿÿ¬ÿÿ»ÿÿÂÿÿÇÿÿÐÿÿÖÿÿÚÿÿËÿÿ´Ûߊˆ`~|]tq]zqR fÀ«pÚ¿vì΄ù׎ÿâš÷ݘÿêŸÿìœÿã™ýÖ‘óȉç¸~Ë£p¤„Yw`2…yI„C²£Tɺz¼ª~Œ}cwo¤Ÿhâàzüÿ†ÿÿ‚ÿÿ€ÿÿŠÿÿŸÿÿ«ÿÿ»ÿÿÇÿÿÅÿÿÅÿÿÁÿÿ½ÿÿ¿ÿÿÃÿÿÁÿÿÁÿÿ¿ÿÿ¿ÿÿ¯ÿÿ£ÿÿœÿÿ–ÿÿ¡úñ›ÙÉůvϯuåºç½yëÁtã¸nä¹qîÃy÷Ë~îÃ{ïÀíÁ€ì½ì½ƒì¼…çº|òÈ‚îÈ~òÎ÷ØŽ÷Ü•üã—üç—þç¶_^UZYPYWQa_[^[\FCD4/1<85A>6,+"B=3YOE]XNPME[XNd_Upk_vpbxsimgdhd_ie`mgbld`ogcrjhumiwokzqd€u`»¸‡ÿÿ¼ÿÿÂÿÿËÿÿÎÿÿÕÿÿÈÿÿÒÿÿËÿÿ¯úÿ­ÿÿÄÿÿÙÿÿâÿÿàÿÿÖÿÿ½ÿÿ¥ô飖S¢T¾ªgÞÅyôØ‚ÿð•ÿó”ÿõ–ÿð“ùà‹ùÓ‰íÃè¹}è»쿃â¶~Ô§vÅžu±n…kKr[?ˆyJ›‘R°§m°¥s”ˆo„tu…{V¶²håæ{ûÿwüÿyÿÿÿÿœÿÿ«ÿÿ²ÿÿ¹ÿÿ»ÿÿ½ÿÿµÿÿ¯ÿÿ±ÿÿµÿÿµÿÿ·ÿÿ·ÿÿ¼ÿÿ¬ÿÿžÿÿœÿÿ”ïãк‡Ã¨lÖ³qä½zé»zå¹vݱlæºuç»xìÁwìÂsëÁtæ»qìÁyðÂóÅ„î¿í¿~ò‚õÅ÷ÈûÏŒúÒ’þÜ“øÚ‹üÚ«ZTQQOKMMKSPOMHH?=99:3;@59>104,54)CB.<:+:7-[YJdcOdbSa^Tif^ie`a`Wfe\feZhe[niaphdrkdwmgxlU‚rJÚÊïà•æàŽúÿ§ÿÿ²ÿÿ¹ÿÿ½ÿÿÑÿÿ×ÿÿÕþÿºþÿ¸ÿÿÎÿÿæÿÿäÿÿâÿÿËÿþ§üñ—íÙ€æÖwÿú˜ÿÿ›ÿþ–þü’ÿü’ÿü—ÿûŸÿôüÞíÉ~æºu׬o˜dº•a´‘b©†\œxU‹jQpSDwa@†xD’„P›ŠWœ‰p„prnbƒhÒ͈íîƒûÿˆÿÿŠÿÿšÿÿ©ÿÿ°ÿÿ¶ÿÿ·ÿÿ¹ÿÿ²ÿÿ©ÿÿ¨ÿÿ©ÿÿ¯ÿÿ±ÿÿ©ÿÿ¤ÿÿÿÿûô”á͈ɱrƪqá¾€áµtݱnÛ­hßµoâ»täºvîÂñ„ð¿„í¿~óÇ„ìÀ{ôÇîÃ{æ»sìÀ{ïÀõÉ„òÇõ̃òÌ‚÷ÖŠùÚúׯLJF?>5BA4:90D??=:9888::89:50/4(!'GBFZUUYUR_YTohaŒ„[\UXZPbdZ_`Yc`_db^db\gc^jd_nhcogeyhY˜}dàÉ›ÿý¹ÿÿ³ÿÿ¬þþ§ÿÿ³ÿÿ»ÿÿÄÿÿÅÿÿÌÿÿÕÿÿÅîô¦ÿÿ»ÿÿÐÿÿâÿÿÑÿÿ»ÿÿªÿÿ™úð‘úå“ÿðšÿôžÿó£ÿæÿäšýÛ’ÿá™ÿÙ“ùÍŒç¸|Êžh¿”h¯‰]ž{S‡fD|\@rVBfIAfP:veD‹xQ“TŽ|`…tj‚smƒsr¡”nÏÇ|èå‚ÿÿ‹ÿÿ—ÿÿ£ÿÿ¥ÿÿ§ÿÿ§ÿÿ«ÿÿ«ÿÿ«ÿÿ«ÿÿ­ÿÿ¦ÿÿžÿÿ“ÿÿÿû”îߒκsÅ«jÓ±jìÂuå¹tܯqÙ­hØ­cí¿zëº}ñ½ƒìµ~è´xæ³tî¾~óÅ„ë¿zç¼rãµpêºzí¿|ìÀ}ç¼tõÈ~ñÆ~ôÈ…üÒŒøÑŠ÷ЩHED585PUQ585.+,,),/+11132220.8$2:78OMILIAXUKb]Soldlhclkbgf]_]Y`]^bc^cd]ge_hdajdaofgyd[±|бŒæÊ“ÿó®ûïœñç˜óè áÞñó ÿÿÄÿÿÎÿÿ½ÿÿ¶ÿÿÍÿÿÉðö¨ÿÿ½ÿÿÅÿÿÆÿÿ¶ÿÿ§ÿúžÿîšüãóÖ„ôÒ‰÷ÏóɇðÂç¹xã´vâ³yÖ¤pÉœkº‘d§ƒ[•tRƒcEtV>gK7V:-Q;'dQ:zhJ{gCqYzha‚rq‰x~•ˆdÓÌ~ïí…ýÿÿÿÿÿ“ÿÿ–ÿÿ˜ÿÿžÿÿ¢ÿÿ¥ÿÿ¦ÿÿ¢ÿÿžÿÿšÿÿ•ÿÿÿü‰ãÖÊ´yŨkÖ°sÈ¡ZÏ¥VÕª`ç¹vðÂõdž÷LJê¶zݬoã²uâ´qôÆïÁ|õÇ„ëÀxæ¼oè»sðÀ~í¿|îÂïÃ~ìÁwìÁwîÃ{íÁ|øÌ‹ïÄ£\YXLMHFGB032!%&! 026>AB**,PMN]XX[WRb]Sa^T_^S_\Rb[Tb_Wec]fe\fc[kd]pb`ubbsY]pTB–rOÔ²€öГÿéŸèÏzþì›ÿõª÷ð ×Ö„ðòÿÿ²ÿÿ²ÿÿ®ÿÿ¾ÿÿ¾ÎÌàßÿÿ¤ÿÿŸÿÿœÿö’üá†ÿ׈è¹rå¬rݧiß©kÝ©mÝ©qÒ£gÉœ`º‘X­…R¥ƒQ{N‹kD|\>nQ4bG.S:*^E@]GAnXRkXUlXZvaf‹v‹|d¹¯xÿÿ¢ÿÿ‰ÿÿƒÿÿ‰ÿÿÿÿ•ÿÿ–ÿÿ—ÿÿ“ÿÿ’ÿÿŠÿÿ†ÿÿˆýý‰ìãÑ¿ˆ¹¤n¨vЯsܲpíÀ‚ê»éº~è¹}à³uÛ°qÞ´pÙ®fæ»sðÃ{ñÀテæ·}Ú¬uÞ±uë¿~÷ɈøÇŠïÀ‚ê½ç»xè½uòƃúÍóȉòLjýÒ±vpkd`]-*))+!GI=KJ=RPJSPQWUQXVPXVP][WZ[VXXV^\VdaYebZhb]jd_ldbmgbnhckebjabp^RwYA˶}ÿÿ¯ÿÿºÿÿ¯ÿÿ«ÿÿ®ÿÿ¥ìëŒîð‹þÿ™ÿÿ ÿÿžÿÿ ÿú™âÑ{àÅ|óâŒýñ“ÿø•ÿü•ÿö—ÿ×…îÂuס_Å•QÊœY•WÆ›`Á™]»’Y³T¥„H¡€I—uF‘sGv[2jP0bG3]I;TB?`MMr_aƒot‹w€‰{n•ŒkãâŽÿÿŒÿÿ‡ÿÿŠÿÿÿÿ•ÿÿ‹ÿÿ‚ÿÿ|ÿÿxÿÿ{ÿÿ€òì‡ÞЉ½°tº«~Ѹ€Û¸vѬh×­kÖ©mÔ¤oÒ¤mשrê»}ñÁø˃úÏ…ðÇ~ç½wè¼wæ¸sß±lðÀ|ôÄ€÷ăò‚ê¹|é»zã·véÀwîÆxòÉ€ïÀñƇðÅŠïçohhfcb###   A>?WQXQNQURUUUWVUZVVXYVWYWS^\V^\V_[V_[Vd`[fb_faagbbhaahb_hb_ogem__jSTiGItY>Ì·~ÿÿ»ÿÿÇÿÿ¸ÿÿ´ÿÿ¯þùŸäØ…ðÞ’ÿðÿòšÿòšÿì–ïÏ|â½nïÏ|ô׃ýàŒÿäÿÛŠÿÓ„ëÀváµrϨc¾™U¹“T´U·”VÁž^µ•V«ŠP¡ƒK˜|E‰nAx^\D:_IEs_a‹tw–|€™†ƒ‹|v´¯vÿÿ™ÿÿüÿwÿÿxÿÿzÿÿ|ÿÿ|ÿÿ|ÿÿ}ÿÿŽõç•×ɄŴƪsÌ¥kš\Ë aΤ`Öªeáµtß²vá´xà±uÙªpܬwØ«o׫jß´là¶iç»n÷Å}øÈ„ï¿ﺅã´zæ¹}îÂóÅ‚ø˃ñÄzñŀ꿀òÇŠ÷Ë“ø̲]VV414  -     +*!?:2;93AA?>>mZU~kky~”ƒ‡‘€†›˜gáé‚ÿÿ¢ÿÿ‹ÿÿ…ÿÿ}ÿÿ|ÿÿ}ÿÿ‚ÿÿ‡åÝ„À­y¶eήtàº}å¸zç»zé»záµpä¹oä¸uÚ«oÙªlÝ­mÛ­lá³rí¿~ê¼{î¾|óÀíº{æ²xÜ­oä¸wà´qîÀ}õÇ„ïÁ~ðÁƒê»ê½ë¾‚ïÂõɆöÊ…öÊ…ôʦYSP854  21(YVNWOKKE@IEBGE?KJAOMIQNQOOMPQLQRMRPLSTOSSQYUR]RQ`WXcZ]b[[`\Y`\Yb^[ca[ca[fcYhdUgbVjcZb[TTLJKBCJ>BC/6P3?}ZQÄ›~÷Òžÿãšÿê™ÿäþÖ†ïÃvîÀ{øÇŠùÌŽÿÕ˜ÿÛÿçýÓ‚è¹pÔ¤bÏžcÒ¡dÑ cÛ­jà²må¸pã¶là±jÛ¨eΠ]Çœ]šZ»“U©„S–rOz^HiQIu_[€ln“†‘|ˆˆ{i¶­ÿÿ¯ÿÿ¤ÿÿ–ÿÿ”ÿÿŽÿÿ‹ÿü’ç؉нsÒ¶vá¾~â·xÕ©qÚ«~Ø©yÙ¨x߯zï¾…ðÁ…ñ„óÇ‚õÊ€ôȃôŇã´zèºyãµpèºwï¿í¿|ê¾{ìÀ{çºrá³rè·~è¹}ê½îÁƒöljöȇöÈ…ôȃôȃøΨVSKTVL.2*!%#$(&"_^UliaUOJJFCJGFKIENLHMIFRLIPLIPMLQNOQLPNNNMPMUSOZRP\VS\UU[VVZWX\YZ_\_a\^d]_b^[a]X^ZUIC@+% 0)"NIARLGJDAC<7091-% 944uollihSSSPNJPLGMIDKGDKFFMHJMIFQLDNLHMMMMNIPNHQOKRMOURSWTUWTUWRTVST\Y\^[Z_[Xa]Z`[[FFF6:=‚¿À¹…ˆ…TVZpqlkh\ZZJIL9BD8?=9;--H-4oOC¢y^㵊ÿÓ™ÿÓ“ùɇï¿{å³mæ´ló¿uó¿uë·mäµlá´lØ«mǘfÔ¤mâ±xë»{ï¿{é¼tß´j΢_¿TÀ“U–UÆ¡[Ǩ`³–[’wLx_AmVEdSI`RPh[Ti]Qwo]ˆs§›€¸§„Ä©|Ú¶}å½ä¸uß³rÙ¬pà³uÞ²qß³nÖ«cÌ ]Ñ¢dÓ¦hÕ¨jܲnå»uå¹vé»zðÁƒê¹~éº~å¶|ã¶zã¶zå¸|çº~íÁ€íÁ~ïÂòŇë¿~è¼yç»vîÁyè½uòÇøÎùÏ€ùʤUOLWSN^]TSQM2/0 $XYTvqqZWXBBDOOMSQMPLGJB>JFCNKLKHGLIHJJLJIPJINKHKNKJQMJQOKRONSQMVROXTQYTT[WR]ZR\ZVQQQ585˜œ–ÿÿÿÿÿÿÿÿÿæèÿUZfovrw|q|ymrqha_[LMH=>9944:.47#(Z@Byhâ³ÿÖžÿèÿê•üÔyåºfÝ«c߯mݬqÛ¬nê»}è¹}Ñ¡jÙªné¸{é»zãµrå·tÒ¢b¾’QÍ£aÊ \Í£_ͦaϪdͯe¼£W—‚Ira>@Defank_VSK=96"""LGI]RQYSNXTOXUKYTHTPKPMNNKJJGFJGHJGJFFFDGFGGGKHKLIHOKFPNHRPJUSOWTSJJJ"#C?E²¨²õìø»²Âš”ÔÒ·€j]`M\^PYXOZVQ]WT_YT\TPYURWTUVVT]][ffdkhiWTS<980+-* (& (P+ ­„Y±ŠP y4Ø®jÜ°oÜ°oÜ®mâ´qç¹vß±nÔ¦cÞ±iã¶lõÈ€à²mç¼rîÄwôÌ|ÿÛŠçÃxȦaÍ«fÔ±oèÆæÄÍ«fÑ®lãdâh¸˜Y»˜V·”TÄ¡cЭmصsåÃ~ðË…õЈõЈõΉøÎŒðɆðɆðÉ„òÈ‚òÈ„æ¹{àµvÞ¶väºvãµpÙ­jÕ¨jàµxåºç¿ðÈŠùÔ÷ÕŽÿã•ÿãŽüÙ…øÓ‚ðÍ{ñÎ~ùÐ¥96*=;,B@1ROElhclggYRV856666,-( =94\TPVPKSOJUTKSRIPNJNKLLGKRHPPGJMECJD?KGBGDCFCFDAD<9JJ:GF9FE973.31+1/+410@;=JAF;+*-> aEتè·~ß±på¸pöÇ~öÅzà³iòÉ€þÙŠÿÛŠûÓ…ëÀvöІþÜ•õЊä½zà¸xëÀƒä¼|ݵuÈ `ϧiݵuê‚ñɋ龃ݵuæÁ{â½yܶuÓ®jˤ_É¢[Ѩ_Ò«dЩdÓ¬gÔªhͦcÊ¥aÌ¥bÕ«iÚ³nÕ°jÙ²o׬mÚ²rèÀ€ðΉöØþå›þëŸÿõ¤ÿó ÿñ ÿéûæ”õáŒöܪ.- 46(BG:QVKRVNEHE+*/---01,.2,"%"  -/0)BA8D?7A=8D??FCBGDCIGAKH@KH@JFANMBIH;FE:GC>DBCA;?=9@;=;87442333/,/+(+'"& *'(;:?NKJXRMVPKUMKQKFMIDOJJQLPMHHKGDLHCPLGMIDLHCLHCNHCMIDEA>=;564.-.'*+&'$#% "&"! "$42,LGIND>?-#X;,ŠbPÁ—sí¾ŒûÎ’úΉóÖ„ýéÿð–ÿä‰æÃoñÇzôȃݰr̤fÖ¯uæÀƒàº}̦gÇ¡bݶqê¿uÜ°kÓ¤fß²tݲsÜ´tà¸xèÀ‚ëÇæÀƒà¹Ý´{å·‚ê¼…è¹ê»í¾€òŇùÌøÍŽüÕ’ùÔöÑ÷ÓˆÿÛŠþÞùÛŒûßþâŽÿä‰úà~ôÙwòÔsñϘ-.)698CGLJOWMT_#(0" #$%%%$'(')-! - #,(.---01,/0+00.670:908:0?@9@A??<=C>@GBDHCGFCD@=>=;5A>4?:.<5*72&2/#-*(%!450DE@GHALJDKJAKH@JFAHDAGE?GF=GD8:57301,,.((('$%!%&%" !!!1*.A8;I=AA--[<9hZΠ‰ðÄðÇùÚ—ÿîžÿð£ôÐ…íÃ}üÎìÁ‚ΦjÜ·sèÆ}à¾yϬnɦhÖ³uëÆ‚áºsÕ®iÛ³sâ»vëÁ{꿀ܮwÒ¦pΤpÉ iÈŸfÐ¥jÞ±wæ¹}å¸|ç»zç¹tÛ®dß³få¹lâµké½næºiã¼eçÆhëÍpçËrñÔ~ô×…ú݉÷Ú†ù×¥-.)5:8CINNU`AFY( $! #! !!!!$%  "$$"*'&-(*.+*20,53/965;89;6:<79F?AF@;FA7E@8D>;D@=C>>A=8=:2=<1;:/35)13)*+$&'"$% "#34-@>:DBFE:FE:FE8GF9HGC@4B?5@<7640///++)))'&'"$%"$#"!!##! %!!# #")/-9?5=G38\>8ŸteÕª‰ðÆ’ÿá›ÿê“øÐ~é½pú̓ôĀجgÛ´mîÉïʂضqʧiÑ®pä¾ã»΢jÔ©läºxìÀÙªlË¡_Ú³pÛ´oÛ´oݱnî¾|ñÇðÌùÜŠùà‹ÿæ‘ÿè•ÿç•ÿá“ÿߎûÛˆþâüä“üë•úê’ýí•ýí•úé“ýå–òת'+.3:CFO^PWb47A #$ !!!! # $$$*'****00.34/971:63<55>99A<<@:7D<:E>>E@BDB>BA8CB9@=5;9367245030/0,'.)!.))$&#!  -)/B=AJADF??IDDIEBJDALFCMECJE=@=187,32)/1'+-#+)#($!'# % #!!#%#%! $ %!!%($#("#*")8.88('K4'ŽlZÍ ‹ûÑ­ÿ×¥æ»|ì¿uöȃà°pÒ£eà³y꿄滀ڱxÕ¬uã¼wêÅrÓ­aѧeܱrä¹|Ù±sÒªlß´uçº|ë¿|ïÃ~ðÊ~ôÔûÞŠÿãôÑç¼tåºpæºmê¿uðÇ~îȇùÕœþÞ¢þã¥ÿðªÿï¡þëÿêŸÿæ» +,2AEBS]BLR"&)!$%   # !&$(,&,+"30(7/+<40>64B<7B=5C>4F?6ID8GC4A>4B>9CA;=>9B?@>6==68:125/,60+5/*/)&.*%'%"!!!!446BBDAACEEEFCDB?>=;7;87301/0++-#*+$))'&&&'#)###!!!"%#!""#%&"'#&&&)))(((&(,()4,+2-(,- `H>Ä¢ŽôȬ帊ê»}뾂УiÒ¥ká±zç»zåºp×®eÛ´o꿀تsÐ¥hßµsÛ°qÛ°uÖ¬jáµpìÂ|õË…öщûÙ’üÛÿà’ôÊ„é¸{è¼{÷͉ÿÞ’ùßýàŠø×{ñÏxä¿nã¾mÞ¶hà¸fã¼g⹌*4<@MTHW]D@;GDLHCGB:HA:D<8A97;5051,32'*)%$#"!#/**;50=;7220/0+,-()*#()"(*'&'$)$)$(!$!#$%&!()$+('0+--*+-*+0++4.+4.)5-)1)'7+/5$*-4_>%¦‚aΤ~Ù°…Ô©}×­yê¿„â¹€ÓªsÕ¬u⹂ݷzÓ­léÄ~úÓŒÿÖ‹ç½pÜ·hðÌøÛ‡ÿèŽÿæþÔ{è¼mç·sçÂs÷܃ÿäŽòÏêÁvïÀyîÂ}óɇðÌîÑ}ûØ©6>P;GUBNZ%-1  -   # ## !(%&*+&,.$35)68,=;5C>@E@@HDAJFCHCCLKBSREXXH\\LUUEYVJUPF[TMYTLSOJMH@OHALDB@7<<85:9./1#02$*/$(+(#'!"#,)*/*.2-1.)-,''($!($!'""*#%+!)'# '&*) +'",(#-)&0))2),0)+0)+.)).+*+,',-&.,&0,'0++/'.-&."; bE6›{]Àsάwâ»Ô¬pË cܲnëÀvîÄwæ¼oôÊ{ÿÕ†óÉzëÁtòÏ{øÝ‚úã„ÿìÿ݇ñ½sã¸nëÆ~ÿã‘ÿæùÖ„ôÇ}ç¹tôÆ…ùÍŒ÷Í‹òÀ¢9AUBN\@MV "         - -!!(%(,(./,-30/944?88?96GA>G?;QFCUPHZWM]ZN^\Mb_Sd_Wea\fb_f`[`XTb]U]XPZXIPO;KG8LE9036//5..1+(0(&)%"#!$"! #%)#&'$$$&&$)*%)*#*("($.(#,)!+( +*!)+!+-!+-!,)!/'%-)&-+',*$.*%.,(.+,-*+,),-*)-+'-(*/%/,>+$mR>¢_Æ tæ·…ÚªuÝ«uí½}õÆ}ê½uìÀ}ùωùÒ‹÷ÓˆøÔ‡ú݉ù݇ÿé‹ÿãƒîÇpîÀtòÌ€øÛŽÿã‘ýÚ†ôÌ|é¼rì¿wõÇ‚ýÊ©=FSCJU:?I   -           %&!'$#.)+4//71.952B==E?8>CPTYoquxxzvsr š•ŒdnxVgqNbpOcsPatQdy\o†`wˆf‹qŠ–t‹˜uŽœx‘¡˜©’¥º’¨À¤Á“¨Åš¬Ê›°Ë™°Êš¯Ê©»× µÒ¡·Ø§½Þ¯Ãå¯Ãã«ÀݬÁÜ°ÃÜ°ÃܶÈä°Åà´Ëå¸ÔæªÍؽÝë±Íß²Íß³ÉݸÐå®Åß¼Øî§ÉÝ­Ìá´Îç²Íã¯ÇÞ¬ÁÞ´Â橽ݯÈæ¾Øó²É㦽ٳÇé±Çæ«Åà¯Éâ¶Îå±Èä­Ãä´Èè¸Êè¶Íé¬Åã«ÂÞ¶È䨽ڱÇè¯Å䧾ڨ¾Ö°ÃØ«Á×®ÃÞ´Ìá©ÅÔ¦ÂѹÕä¨ÁÑŸµÉ´Å˜¯¾“«¾•­Ä—¯Ä™¯Å™¯Ã™¬Á’¨¼§¼‘©¾Œ¢¸¦¼¥½³É˜«Àµ‰•°ˆ—¯•¥½‘¥·“£{¡xˆž}¥}§}¥xŒœsŠ™t‹œo~•¸Áά®¿‰Ž¡z…šx~Œ37:499>CCZ_]rutwzw˜˜–‰bp}QcoWn{RfvTdzXk€^tŠ`wˆh|Œoƒ“z‹œn…–x£ƒœ¬“ª»¥»’¤Â”¦Âœ®Êœ´ËšµËµÌ§¹Õ§¼ÙªÀá©Âࢻ٧¾Øª½Ö¦¼Ô¯ÇÞ·Íã±ÄÙ±Éà¦ÀÛ¨ÃܼØî²Íã®ÆÝ°ÆÞ¿ÑíµÌè­Ææ°Ìâ³Óá°ÐÞ¯ËݬÇÛ¬ÃݬÁܱÃá«ÂܨÃܲÍã¼ÔéµÍä¶Ëæ­ÈÞ·ÓéÃßó·Òæ©ÃÞ¤ºÝ¬Âá®ÃÞ¬Ãß±Çæ¬ÃݯÅݳÊæ¬Åå¬Åã«Ä⧾رÄÛ¨¾Ö¦½Ù©ÄÚ¨ÄØ›·Ëš¶Ê”¯Ã™±Æ³Ç ´Æ›±Å³É ¶Ì¢µÌ¨»Ð¨¹Ì–­¾–®Á“«À’¨À£¹£¹Ž§·‹¤²Š¡²³}¥ˆ›²Š¡²‰ ¯|“¢~•¦y£~‘ª|¤{¡sŠ›m„•oš£ËÔã £¹ˆ¦„Ž¨{‡•<=J36@38@@FI^eew|x…‰ƒzƒ‚bqw\nsXkrShqVnxThv[k~gwˆk{Œ{Œ€‘¤Š ´{“¨†œ²’¥¼µ–¥¿šªÄ™¬Å¡¸Ò¡»Öš´Ï–¬Ë•¯Ê¸Ó¤¿Ú·Ò·ÐŸ¹Ò¸Ñ¤¿Ú«ÂÞ±Ã᫼ݮ¿â¨¿Û©ÃܳËâºÐè¿ÖðºÑí¨ÂÝ¥¾Ü«ÄâºÐï¬Æá¬ÆߨÃÞ¤¾Ü©Äß«Æß°Ëä¬Æß­ÈÞÀØï³Íæ¶Ðë°Êå¯ÈæªÁÝ­ÂÝÃÚô·Ñê³ÍæªÄݪÅÛ¦Á×›µÐ¥¾Þ©Â৾ڤ»×ŸµÔ¦ÀÙ¢½Ñ£»Ò«ÀݯÆà¨ÃÙž¶Ëž´È¥»Ó¢´Ò™«Ç•¨Á›«Á°ÀÑœ°Âš°Æ‘§½”§¾”ªÂ–­Ç—­Å ¸Ž¡º“¥ÁŒ¢ºŠ¢·‰¡¸‹ »‚˜°}“«{“ªx“©|”«„–²~‘ªyŒ¥r…œq„™n„˜rˆžsŽ­³¸ÎÕà•š¯†¨Ž¨y†–BNZ5?E2995<DQSWllnrwgs_l|gt†fs‡dp‡^mƒ]mƒbuŠh{’q„›uˆŸmƒ—wŽŸ‚›«ƒœ¬Š¢µŒ¢¸‹£¸§¼²Í ±Òž³Î§½Õ³É¦¼Ò£¶Í¨¸ÐµÇ㧸ٲϴδÉä¶Èæ¬ÁÞ¯Æâ«Á৽ިÂà¨Åâ¦ÄÞ¬Êâ©Äߥ¾Ü«ÅàªÄߪÄߦ¼ÛÄÙö»Íé¬ÃݦÀÙ°Êã¿Öð´Ëå³Êä³Îä¯Ë߬ÇÛ¬ÄÙ¿Úî­ÈܪÆÜ©Ç߬ÈÜ¥ÀÒ¦ÁÕ¨ÃÙ¨ÃÙ¥ÀÖ¦Áפ¿Õ¦ÀÙ¦ÀÛ¡»Ö¤½Û§ÂÛ§ÃÙœ¸Î£½Ö£¾×œ·Ð™´ÍšµÎ•°Æ™±È¨Ã×¢½Ï—²Ä ¸Ë³Ç—§½•¨½¢µÊ´ÄÚ”£»³‘¡·‘§½‡Ÿ¶‡Ÿ¶†›¶…šµƒ•³„—°‚•¬Š´‚•¬{‘§tŒ£tŠ t„œn–g~tŠÏÎÓ¡¥´–¯ƒ¤{‹žt†HW]S^aTX[8;<88:RUTjrtly€ct~^o€[o\o„Zp„Zr…_zŒa}n‡—p„–t‡œv‰ |’¦„œ¯Œ§¹‡¢¶Œ¢º•¤Ã˜ªÈ–ªÊ—®Ê—®È¨¿Û¬Âá³Ô³Ö¶Ö¡»Ù¦ÀÙš²É¯Êà¨ÂÛ¡¼Õ©ÄߥÀÙ¬Æß«ÆߦÄÞ£ÁÛ«Åã®Éâ¦ÁקÃ׫ÇÛžºÐ«Æ߬ÇݯÅÛ¨¾Ô§½Ó´Êâ¾ÐìµÇã·Éç¯Ä߯Æà«ÆܧÃÙ¯Éâ³Éè¬Åã©Âà¨Âݧ¾Ø¬ÄÛ¯ÅÛ¶Î㦾ա»Ö¥¾ÞœµÕœµÕ¡»Ù ºØ¡½Ó¤ÀÒ›¶Ì¦ºÚ§½Ü›´Ô´Ðœ¯È˜¯Ë—°Ð—²Ëœ¸Ê“«¾”§¼ž´Ì‘¦Ã˜®Æš°Æ“©½’¥º™°¿”«¸£¹‡˜¹ŒžºŠ´€–®˜²€›±~™¯ƒ›®ƒš«wŽŸ~”¨|¦v† r‚šr™{ŽÒÌÓqqƒ‡Š«ˆ’ªŽ yˆlrkrsnkgdEHG28=39>@LOPjlpqv€em^j[j‡cvj}”k‚“o†•p‡–xŒœyŒ¡‚’¬‡š³‚˜° ·Ÿ¯Ç°Å˜®Â’ª¿•°Æž¹Ï¸Îœ·Íœ³Í£¹Ø˜¬Ð›¯Ñ¡²Ó§¸ÙµÆé¸Îñ ¹Þ¡»Ý©Ââ ·Ó¦¸Ô®Àܯ¾Ý°Ää¨Áá«Åã©ÃáªÃá®Ä㦽٧¼×§¼Ù®Ââ®Åß¹ÑèÀÛô°Íê²Íè°Êå«Åà«Áà­ÆäªÄâ¹Óì­ÅÚ¬ÂÚ§¹×¥º×±Èä¯Æà¯Äß«ÀÛ´Æâ°Á⤵ڞ´ÕœµÓ¡ºØœµÓ—±Ì“­È’©Å›¬Í¯Íš¬Êš¬Ê–¤Æš¬Ê•§Ã“¦¿¢²Ìš©Æ—¥Ç‹ ½Œ£¿¦ÀŠ ¸ƒ˜µ‰¿Š¡½‡Ÿ¶ˆž¶…”±‘¡¹†–¬ µ~”ªuˆz‰Ÿu„šr™l|”l|–j}”fyWiu;NNpw€?9K! ?KYDR_FScFVgK[nTduGWh7CO8=G;@HPV[itwhuz[itYfzfzŒd}n‡—p‡˜r†˜xˆž‚•ª’©ˆ›°ƒ–«Š²ŒŸ´“¦½“¦¿”ªÀ“«À’ªÁž³Ð™¯Î ¶×£¹Ø«Áà ·ÓŸ¶Òš®Î¡²Õ™­Í”¨È™°Ìœ³Ï›°Ë¨·Ô´Æ䧸٤µÖ«¼ßªÁݨÃÙ¥½Ô­¿Û¯ÅÝ°ÆܶÌäµÇå®Âä°Ãê³Éê±Êè³Íè²Éå¬Àà²Ãè®ÄãªÅà¦ÀÛ«Àݧ½Ü¨¾ß³Éꦼߧ»ÝÊÛþ°Ä䨼ܤ¾×§ÃÙž¹Òœ¶Ñ£ºÖ¢·ÔžµÑš°ÏŸµÔž´Ó¤ºÙš°Ï™®Ë™«É“¥Á¢»‘©¾“®Â‘¬ÂŽ¥Áˆ¢½…Ÿ½… »‚œµˆ¢½‡¾•µ…–·…˜¯Š›¬‹ž³|¨£¹—¬|¦x‡Ÿt„œzŠ¢vˆ¤j{œi{™fx”]m…Xd{&7 !() ?O^BSbCTcHYhTdsRbsN^qBNZ9@G7?C;ADPYXhtretx^o{p„’e|‹vžl‚˜k•{Ž£}§‚•®ƒ™±}“«†œ²Ž¡¶˜«Â’¤À”ªÂ–®ÅžµÏ¡¸Ô¤»×¤¸Ø ´Ô›¯Ñ™¯Ðš³Ó’¨ÇŸ°Ñ£µÓ¡³Ñ–­Ç§ÂÛ¬Áܬº×¬»Ú­¾ßª¼Ú­¼ÛµÊå«ÃÚ«ÃÚ¦½×¨¿Ù«ÀÛ§¾Ú¦¼Ý¥¾Þ¬Åç±Ëë®Èæ¯Êå¯Êå²Ëé­Á壼ܨÂà­Çâ«ÀÝ­ÃâªÃ㦼ߢµÞ¥¹Û®Àܦ»Ø§½Þ¨ÂÝ¡¼Õ¹Ï¡½Ñ¤¼Ó¨ºÖž³Ð¡µÕœ³Ï¦À§Á¥¼Ø–°Ë—±Ì•­Ä˜®Äš²É’©Ã¦À¥À† »„ž¼†¡¼ƒ¸€šµƒš¶¢¿‰˜·‚•®€“ª}§{‹¥w¥rŠ¡vŽ£o…›p†œpƒšp‚žq‚£j}–k~“YlScyGWf,7@PaBSbHYhAUc=Q_ARcFViFTa?LS4AF5@CALO^ilgt}`m}]m€dsdtŠp”r…š„—®€–¬‡Ÿ´Œ¢¶ŒŸ´£¹‹ »ˆŸ¹Œ£¿§ÂŸ¹Ôœ¶Ïœ´Ë«ÁÙž­Ê£²Ñ£°Ò˜©Ê™¯Î•«Ê˜®Ï¤ºÛ¥»Þ›´Ò¥¿Ú¨Àש¿Õ­ÂÝ­Áá®ÀÞ¸Çæ»Í뤹ֳÈã»Ñé·Íå®ÀÜ®ÀÜ·Éå´Ëå«ÅÞ¨¿Ù§¼Ù¯Êà®ÊÜ°ÌÞ°ËߪÂÙ§¼Ù­ÃÛ¯ÅÛ¬ÃݪÀߤ¹Ö©»Ù¨¾Ö¤¼Ñ³ÉÝ­ÀÕ§¼Ùž±ÚŸµÖ˜²Ëš´Í¢¼Õž¸Ó¥¾Ü »Ö¸Ó•°ÄœµÅœ·É•°Ä§¾¥ÂŒ¡¾¥ÂŽ ¼¡°Í¡½Šœº–³{’®}’¯‚“´„–´‰˜·ˆ¸y”ª‰¡¶w£w¥}’­u‹£r…žt„œp•m€™lƒŸl„›mƒ—dxŠUfwPapARa$5?$=IbHUiKVgFScGFJSR^ilanu^o{jzw‡Ÿx‡¤wŠŸ‚–¦ƒ—¥¡­Ž¢²ŒŸ´ŒŸ¸ŽŸÀ‰ º‹§½“®Ä´Î•¯Ê”­Ëš±Íš¯Ê µÒš«Î›°Ë³Éš°Äž´ÈŸ·ÌŸ·Î§¾Ø¨¾Ý¬Å壻ࣸީ¼å§½Þ£½Ö£¾Ô¨À×±ÉÞ²Êß®ÆݶÍ駼ٺÈêµÊåªÅÛ±Èâ¶Èæ®ÃÞ¯ÅÝ­ÈÞ©ÈÝ®ÊÞ²Íá¬ÇÛ²Êá´Ìã®ÃÞ§¾Ø­Äà¬ÃߤºÙ¦¼Ý¨»â©Âࢽ֡¼ÕšµÐ›¶Ñž¸Ó¨ÂÝŸ¹Ô—°Î•®Îš°Ïš¯Ì•¬Æ•¬Æ‘¬Â•°ÆŸºÐªÀ•­Ä›®Ç†œ´ˆž¶€˜­}•¨…›³†—¸~“°˜²z‘«v‹¦zª|‘®}“«†™®{‘¥o…›n„šh{”e{“`ud{•h™_wŽXp…LeuF]jK]HUeHVcFWcARaEVgK[nDTc@Q[APX8EN5=ACHHSY^disbm~l{•t„žn€œtŒ£v‘§z•«~™¯…²’¥¼ŒŸ¸ž½‹ »’©Ã–­Ç¡¶Ñ‘¨Ä‘§Æ•¬Èš±Ëœ²Ñš®Òž´Óœ³Í™±Æ£¼Ì°Ëߥ¿Ø¬Çà®É⢽֦ÀÛ¨ÂÝ£½Ø¤»×©¾ÛµÌæ¹Ñè­ÅܳÊä­ÇॿةÄÚ¯Êà«ÆÚ«ÃجÄÛ«ÂÞ­Ãâ«ÁâªÀᦼݧ¾Ú®ÄܱÈ⧽ܪÁÛ§¿Ô¤¼Ó¦½Ù¦ÀÛ¦ÀÛ¬Ãߨ¹Ú¨¹Ú¬ºÞ¨¹Ü™­Ï³Ô˜®Ï”®Î­Ì•³Í’®ÄªÃŽ¨ÃŽ©¿¨¼«Á‰§ÁŒ§»“§¹‹ž³‹ž·Š ¸‹¢¼‡¢¸€œ°~™²›¹}˜±€›¯†¡·yªyªwŒ§qˆ¢j›tŒ¡sŠ›pƒ˜q™m}•t„œn˜gz‘[nƒUh}OcqG\eBSb9E\4FP?PcIYlIUlKXlJWiJZiM_kFXdI[gJ[e@LX7AG7?A=HIQ_a^pwctƒ`w†m†–rŸw’¨{’¬‚”²Š¶Š´‡š±‡š³‘¤»˜¨À ³Èœ°Â“©½š°ÈŸµË ³È£µÑ¦´ØŸ´Ñ¥¼Ö¡·Ï£¶Ï¨¾Ö¨¿Ù¨ÃܧÅÝœ»Ð¡½Ó¥½Ô¨·Ô©¾Û¢»Û¨Áá«Ää¬Ã߯ÄßµËá¯ÆׯÆ×°ÆÚ¯ÇÚ·Òæ±Ìिե½Ô­¿Û«ÀÛ¥¼Ø±ÌàÀÜë©ÄئÀÛ­Çâ±Êè©ÃÞ®Åß¡»Ô¥¿Ø®ÅᡵףºÖž¶Í´Î ¶Õ¡ºØ›´Ò”®Îœ¶Øš°Ó‘¢Ç“©ÈŽ¨ÁªÃ’­ÈŠ¨Â…¢¿‰¤º§¸‘§½Ž ¾¦Â… »†¡º‰¤º‡¢¸…œ¶ƒ¶›´“®Äƒ›²|“­uŒ¨v­q‹«uŒ¦{‹¡r‚šn}—dv’r†¦f{–]p‰Yq†ToMduL]pG[m=Te>TZAS]GXdFSeKXlQ]tQ^pXfsM]lO_pHYjDXh>PZ5GJ5BGBGOPZd`n{fv…t„•t„šy‰£~”¬…´ˆž¶…”±ˆ›´„š°Œ¤¹“«Àž¹Ï–±Ê«ÆŽ¨Æ—±Ìš¯ÊŸ´Ñ¦ºÚŸ³Ó­¾ß¤»×›µÎ¡»Ö£¹Ø¥¹Û¨¹Þ«¿ã¦ºÞ¦ºÚ©¾Ù­ÃÛ°ÃÜ­ÄÞ«Äâ¯ÊÞ¯ËسËà¶Èæ´ÉäµËã®ÆÝ­ÄÞ¬ÄÛªÂÙ©ÃÞ©Ââ±Ìç§ÂÛ±Ìå²Ìå·ÓéªÆܪÆܤÀÖ¦Á×­ÄÞ¤»Õ µÒ©¾Ù¦¸Ô§¹×¨¹Ú¥¹Ù ´Ö¡·Öœ³Ï“®Ä«¿—²È ·Ó¡¶ÓŸ±Ï²Íœ´Ë‹£º‡Ÿ¶Š¡»‰ž»ˆŸ¹ˆ ·‰¤¸‰¤¸~™­{–ª{–¬™²~˜±˜²}—°}—²y“®{‘°z‘­zªqƒŸržm€—mƒ—bxŽl‚šbw’bs”Xj†\l„ObyM`yObyK^sMci?Q[CT^HVcM[hO\lM^jL^hL`pJ]tE]rE`tD\oDXjZcK‘‘r¸®‡¬¤u©¡n¨ m§œj£˜j¡”k¢–m “mž•k¡˜n¡”n£•q¢”nžjœišg˜e“Š`Œ‚]“ˆhwpUPK842.JKXýþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ©©§‘‡€v^ZUQKFbWTSJV —³ÿÿÿÿÿÿÿÿÿÿÿÿehWNE8ZMFeUV…tz‡r~¨Ÿuóô”ÿÿ¡ÿÿ£ÿÿ¯ÿÿ·ÿÿ½ÿÿÅÿÿÉÿÿÏÿÿÑÿÿÕÿÿËÿÿÃÿÿÞ×Á©²“§ÇžÞÉ âÇäÀšÝ¿™ÜÂœÝÇžÞÄŸÛΩåȨлžµË¾˜ÿÿ¤ÿÿ¹ÿÿ·ÿÿ¹ÿÿ½ÿÿµÿÿ¯ÿÿ­ÿÿ§ÿÿ­ÿÿ®ÿÿ¡ÿÿ“ÿÿ™ÿÿ›çÙ…µ bÞÈ}ýä÷ßøÞ™ÿêÿï™ÿó“üô‰ÿó®ÿÿÿÿÿÿôôö“Š™“…§¢–‹ƒmmm{~ˆš¥ÿÿÿÄÈËv|‚õñìÿÿÿÿÿÿÿÿÿÿÿÿÀ¿Äzv~uqlxua˜‘v£˜x“†`›Žc¢–h¢–h¡•jŸ•n“p‘všmši—Žb˜a—^š]˜_•ˆb”Šg’‡iŒ‚fx]UQ774..AC9ÜÚÔÿÿÿÿÿÿÿÿÿÿÿÿåæߊŠz•”|njLE<;4I@1a\T¯¬­ÿÿÿÿÿÿÿÿÿÿÿÿ«˜·M4\L6I]IIwchŠu…xh¾´÷ô£ýÿ‡ÿÿ¢ÿÿ®ÿÿ¹ÿÿ¿ÿÿÅÿÿËÿÿÍÿÿÑÿÿËÿÿÇÿÿÉÿÿË»¨“®Œ³½›ÍÆ¢àÄžßÈŸãÇ¡âÇ¡âÀ™Ï¾˜Â¼£žÍÃŽÿÿ±ÿÿµÿÿ·ÿÿ»ÿÿ¹ÿÿ·ÿÿ±ÿÿ­ÿÿ§ÿÿ§ÿÿ§ÿÿ£ÿÿ˜ÿÿ‰ûð”ØÃ…¾¤cëÌ‹ôÖŽûÝüãÿí–þí•úê”ýñ“öëˆùè§ÿÿÿÿÿÿ•€{q–‘~•“„€vUXW>AIpqzÿÿÿáÞ៛–ÌÈÅÿÿÿÿÿÿüÿÿÿÿÿÿÿÿÛÚщ†r‡ƒg“Ši®¤}­ u¨œn¢–h ’lžp˜o—q‘‹i‘Œg‘Œc“Œa“Š`˜‹e–Œe“‰d’ˆa†_‘†f‘…n„yflcVE>32+$4(,L9I´¦¸ÿÿÿÿÿÿÿÿÿÿÿÿǾÃgWHq[:s]'”y0²•Xµ–fj]KÂÄÓÿÿÿÿÿÿÿÿÿÿÿÿùÿÙYcZZ(QD0fWQƒoxƒqlƒsbÖψÿÿ‘ÿÿÿÿ¢ÿÿ¬ÿÿµÿÿ»ÿÿÁÿÿÃÿÿÇÿÿÇÿÿÇÿÿ¿ÿÿ¹ÿÿÛ³œ¯¤¿˜ÎÇŸÚÇÝÇžÛÈŸÜƦÁ¾¦žÔÊ“ÿÿ¥ÿÿ»ÿÿ½ÿÿ½ÿÿ½ÿÿ·ÿÿ³ÿÿ¯ÿÿ¦ÿÿ£ÿÿ£ÿÿ¥ÿÿ¤ÿÿ§çؘ´¡^éfåÆ~óÍùÖ†þÛ‹ûÞŠþâŽÿì“þï’÷ë‹ýñ‘ÿñ°ÿÿÿœš–uql‡„z“€…‚xtrnPPR:8B^Z`ÿÿÿöí𠔚~w{éãêÿÿÿÿÿÿÿÿÿÿÿÿìêÛ¤‚ šz¤›z§Ÿy£šp—Žd–Ša“‰b’ˆcˆdŠjŽ‰d’Šb’‹`“Š^”‹a”‡a†a†eŒƒdh‹€mŠ~rlbXOE=92'3,!4/%@:5–“‰ÿÿÿÿÿÿùö÷óéÍ°žgÒ·{æÀòЇÿë—ÿú¯ÿÿ¾÷èÉÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ„‚Žle\xjMƒrfxchzggvgc…}Jæã€ÿÿªÿÿ•ÿÿ«ÿÿ²ÿÿ¹ÿÿ¿ÿÿÃÿÿÉÿÿÉÿÿÉÿÿ¿ÿÿ·ÿÿÍÿÿص™ž¾–ÑÁ™ÖÏ¥åͦÞÌ¥Ùº£¤àÕ¥ÿÿÂÿÿ·ÿÿ»ÿÿÁÿÿ½ÿÿ¹ÿÿ³ÿÿ¯ÿÿ«ÿÿ¢ÿÿ¦ÿÿ£ÿÿ¢ÿÿšäݪžnȳuåÆ~êÅõˉùÕŠûÛŠúÝŽùß‘õàŽùè•ÿñ™ÿò•ÿꯟŸ¡sqk{xl‚€qˆ†u|{nhf`JJJ+-3$#( *)0NLX87>­¬±ÿÿÿÿÿÿÿÿÿÿÿÿüøéš“vœ”p™d˜Ži”‰i’ˆc‘…\•‰`”‡^’ˆa‡c‘Š_‘‰Z†_”†iŒ€iˆ}l†~lƒ}m{l~yotoe_ZRE?1:2 (%K:~eC›‰ðâôÿÿÿÿÿÿÿÿÿÿÿöéï­ÿþ£ÿÿ«ÿÿóõ¢õö½ÿÿôÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøØÚ—uo1~m8žˆe¢†wwcctfv}r]£™bïð’ÿÿœÿÿ›ÿÿ«ÿÿµÿÿ½ÿÿ¿ÿÿÃÿÿÁÿÿ¿ÿÿ¿ÿÿ¿ÿÿÁÿÿÅÿðÒ·”²º”ü’Ò¼›¿¿§¯ñæ¸ÿÿ¸ÿÿ»ÿÿ¹ÿÿ¹ÿÿ»ÿÿµÿÿ°ÿÿ¦ÿÿ¢ÿÿžÿÿŸÿÿžÿÿœÿÿœïãŽÀ­h̲€ìÈöȇê»}îÂòÈ„öÑ‹÷Øýâ—ÿê›ýé”÷æŒøã­ooqspo{up„w‰„zytunnOJL($*! %$#*@@BYVWZZX½½»ÿÿÿÿÿÿÿÿÿÿÿÿùôèš•€š”t–Œe•gˆdˆb’ˆa‘„bŽbˆ|e„yhwe€xfxrb|ujwrfvsgvte{whojUe[C\S']Um-qPŸ†<ßÎvÿô ÿÿ¼ÿÿáÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿêÿÿéÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýééygƒoKˆvH­›dŠqq]b|ncƒya®®iüÿ“ÿÿŸÿÿ¢ÿÿ¬ÿÿ«ÿÿµÿÿ¾ÿÿ¿ÿÿÁÿÿÃÿÿÇÿÿÁÿÿ½ÿÿ×èѵ­“•¼¾É¸§öð°ÿÿ½ÿÿ±ÿÿ·ÿÿ½ÿÿ¹ÿÿ·ÿÿµÿÿ´ÿÿ­ÿÿ©ÿÿ ÿÿ™ÿÿ˜ÿÿ’êå‰Å³wͳpçÂzæ½tîÁyñÄ|ôÇóÇ‚ôÈ…öÏŠûÖþÝ‘õ؆÷ߎôâ‘þç¶sretqg|unzq~wnzwmnmbJKD$$$722ULMdX\n]esuh`\\UNUNGicU”Œz–Žx“‰q…q‡~oyiztdur^nmYmk\if\hg^fg`kh^f\RdZ@re?ƒv=¨–LÌ´eáÁnéÒoþî}ÿÿÿÿÿÿ‘ÿÿÀÿÿÎÿÿâÿÿðÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿíêí»µ¼‘Ž‚ŽqwmF†sAƒs6œ‘K½¬yžˆilZN~muƒ{UÁÃpÿÿšÿÿ†ÿÿ•ÿÿ¡ÿÿ¥ÿÿ¬ÿÿµÿÿ½ÿÿ½ÿÿ¿ÿÿ½ÿÿ½ÿÿ½ÿÿ½åä‰ÍÇuÿÿ£ÿÿµÿÿ½ÿÿÁÿÿ¿ÿÿ½ÿÿ»ÿÿ»ÿÿµÿÿ¯ÿÿ¦ÿÿ¢ÿÿ›ÿÿ’ÿÿ—îâȵpêuß¾‚êÀ~ôȇñÂóÇ„ë¿|è¼{ì¿÷͉úÔŠõÔˆûÝùß‘ýå–ÿã´rqfrogysntogupfyvnhd_LHE(#%***JJL@@@IFEURS^Y]][U_^QpkaŽ„~Œ…|€{qytlqieke`fb]ed[dcXdcXhe]gcGxoC•‰F»«UÛÏo÷ï„ÿÿ«ÿÿÂÿÿ§ÿÿ—ÿÿŸÿÿ°ÿÿ·ÿÿÆÿÿÈÿÿÊÿÿÆÿÿÅþøØÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïè꾺·—–uso_Z\c\U‚uŽ{f‚gLŠvK‰|@¤˜W¿±l˜„bv[[†veŠjÓÑ„ÿÿÿÿŽÿÿ”ÿÿ•ÿÿ—ÿÿ¦ÿÿ°ÿÿ·ÿÿ½ÿÿ½ÿÿ¿ÿÿ¿ÿÿ¿ÿÿ½ÿÿ½ÿÿ½ÿÿ½ÿÿ½ÿÿ½ÿÿ¹ÿÿ·ÿÿµÿÿ´ÿÿ±ÿÿ­ÿÿ¡ÿÿ—ÿÿ–ÿÿéÙdzp×·vîÁ…è¼{óÇ‚ä¸uè¹{ç¹xðÂðÃ{óÇzöÊ}õÈ~ôË€øÔ‰õÓŠùÚ”üÙ±rmenkcgc^gc^lhcqkfogcRKK"!+-#DC:NMDOKF`\W`ZUywhY\oge†€{‚~{nkjkicgf]db\ca]d`]h`^kd[ypc’‹^öð¢ÿÿ±ÿÿ·ÿÿÅÿÿÔÿÿ×ÿÿÐÿÿ´þÿ¡ÿÿ´ÿÿ¾ÿÿÈÿÿÒÿÿÙÿÿÛÿÿÎÿÿ¸ýÿÓýÿöÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ×ÒÖ·°´•‰…‚’ŠŽ…„‚s|wdsV¢Šc±šl|f0m6q9†z7¥›N¹¬s“[yhU‰yx•dÝÚyÿÿŒÿÿ€ÿÿ‰ÿÿ‰ÿÿ—ÿÿ©ÿÿ±ÿÿµÿÿ¹ÿÿ½ÿÿÁÿÿÅÿÿÅÿÿÇÿÿÅÿÿÅÿÿÁÿÿ½ÿÿ¹ÿÿ·ÿÿµÿÿ±ÿÿ¨ÿÿ£ÿÿœÿÿ‘ÿý˜åÒÌ´uÕ´}ëÆ‚ôÊ{ëÀvè¼wì¾{êºzì¾}èºyæ¸wîÀæ¹{뾂ðňóËøÓüØüØ®lhefd^\[R_]Wa_[fb_nheLGI997de^]\SKJ?XUK`_T_aUfeXxsgroe^\V_aW_aW_aUfeXlk`qpgvs_}sW½µ„ÿÿ½ÿÿÂÿÿÄÿÿÉÿÿÐÿÿÌÿÿÖÿÿÊÿÿ¨üÿ©ÿÿ¼ÿÿÏÿÿÜÿÿ×ÿÿÒÿÿÄÿÿ´ôø¹÷ùÐÿÿÿÿÿÿÿÿÿÿÿÿ÷òôÔȨ̈œ™ƒ|ˆ~v’‹‚”Ž€•{˜ŽtŸ”t´¢tеyàÁ{ðÊ~éÇ‚¾ždq[%‚pB}p4Ž†=ª¢YÁ¶n…wQ}jg„x]­§uéêŒþÿ|ÿÿ€ÿÿ‚ÿÿŠÿÿœÿÿ©ÿÿµÿÿ·ÿÿ¹ÿÿ½ÿÿÁÿÿÅÿÿËÿÿÅÿÿÁÿÿ»ÿÿ·ÿÿ³ÿÿ¯ÿÿ§ÿÿžÿÿ˜ÿÿ–ÿÿ™ÿÿ‘ç×Ó´uܶuç»xê¿wíÁtç¼råºrè½uë¿zïÁ€ð¼‚ê¹~ð¿„ñÂñÅ‚òÉ~ðÈxùͦfd^a_Y^\VYWS\YXfb_d^[946  '..QUOWTLYVL[VJ^[Qfb]kh\pn]wtha]XebZgdZif^mgbojbpkaumW€rSØË’ôã’ëâŽþü¦ÿÿ²ÿÿºÿÿ¿ÿÿÊÿÿÑÿÿÊÿÿ±ýÿ¬ÿÿÅÿÿÞÿÿàÿÿâÿÿÁÿÿ—õñ©úèÌÿÿÿöíû¸µ¸yzurpl|ww‹ƒ”‹~“‰q•ˆf¢bµœb˯m×µlçÂzÿÖÿÚ”ÿÔ‘ù˔ఆ–tEpZ)…u=‰|>›J¯¤Zº¬x}hKzjT„sgÁ·€óðþÿ‡ÿÿ|ÿÿ~ÿÿÿÿ–ÿÿ©ÿÿ°ÿÿµÿÿ·ÿÿ»ÿÿ»ÿÿ»ÿÿ¹ÿÿ·ÿÿ·ÿÿ¹ÿÿ¶ÿÿ³ÿÿ«ÿÿÿÿœÿÿ•ÿù—èÔβnÔ±qÞ·tïÁ~ñÃ‚í¾€ê½ï„è»}óĈì¾}é»vïÁ~ï¿ò€í½yîÁyê½uñÂøÉøÅ®]W^YTXXSUURQUSOZZXPPP664664>?:;<7&&(@@>NLFBD8JO@WYMb_Wnkcrniywqca[acWacUchYafWji^niavfSš€bÞÉÿÿ¬ÿÿªÿÿ¨þý©ÿÿ¹ÿÿ¹ÿÿ·ÿÿ¿ÿÿÉÿÿÕÿÿÃëñ¡ÿÿºÿÿ×ÿÿìÿÿàÿÿÎÿÿ»ÿÿ£šV_W3^V@TMFriZ‰g~Y¤ZÊ°mëÎ÷Þ‰ÿæÿãÿãÿ×ÿÍ‘ê¹|á²vØ­rѪp¹›hv_5ua2‰vB—‹Jª¢Yº­q¯qwgO€mmrXŹ‡éå‹ÿÿ‡ÿÿ‚ýÿyÿÿ‡ÿÿ˜ÿÿ¡ÿÿ¬ÿÿ±ÿÿµÿÿ·ÿÿ¹ÿÿ²ÿÿ«ÿÿ°ÿÿµÿÿ²ÿÿ©ÿÿ¢ÿÿ—ÿÿ üð›ÝÊ|È­fÜ·oå¸pì¿wé¹uæ¶rã³oê¼yðÂê½Ý°tâ³uê·xëºí½†ê»}í¿|ç¼tå½oïÃ~ï¾ð¼ QLWSOUOJNIFGLIJOLOGAH>9=@9;B;==68(%&@@@632/1'EJ;XZN`]Ua^Vb_Wsphb_WcbWbdVcfUbeTfeZjd_ueV¬‘xη„æÐ…ÿõ¤øí•õæ—÷äŸäÙ‘ðì¤ÿÿÇÿÿÎÿÿ½ÿÿ¶ÿÿËÿÿÅôú®ÿÿÉÿÿÕÿÿÙÿÿËÿÿ¿ÇÍŽ|ZvvWroW‹^½«}×¾„î΋ùÜÿð”ÿüœÿñÿåÿß’òÆ…í¸ƒÞ¯uÓ¦lÆž`¸’Qž}H…g?fO%o\3I™J¦™[£•_•†io]ZqbŒ}cÈÁvçèoúÿ|úÿtÿÿ|ÿÿÿÿ›ÿÿ¤ÿÿ¬ÿÿ³ÿÿ³ÿÿ­ÿÿ¦ÿÿ¢ÿÿ¥ÿÿ«ÿÿ©ÿÿ¢ÿÿ–ÿÿŒïæ‚ÛÂzÚ¼ríÉ~êÄzÞ³kØ«câ³læ¹qõÈ€ñÃ~õÇ„æ¸uâ´sè¸xï¼}ëºóÃŽôÅ‹å¶xé»xç¹tå·vé¸}å²™KICKHGB=A>=B@AJ2.4=6:63632799;856)))53-PMCYVNWSPZYNxxhfdSZUBb[RcZ]c\\ea^d`[fc[ic^kbco_`sY[rOB rWÔ®‚óÒ–ÿì¡åÒvúê’ÿõ¡÷ñœÙØ„ðô—ÿÿ©ÿÿ¯ÿÿ´ÿÿºÿÿ¯ÔÚðò¡ÿÿ¿ÿÿÆÿÿÁ³lÁ­hØÁkàÃmöÒ|ÿà†ÿæ‹ÿå‘ÿëýß’ùÕŠóÇ„ë·}ä²|Ü«yÊœg–`·[­„W˜tN†aEdF.\D1p\;3oif$%&!0!+%#/(',)))((($% @>8AB;NOH[WHpcQztd_\PcbY_]Y^\V`]Uca[fd`kgbkc_kc_pebn``l[_o[MqW9ɸyÿÿ©ÿÿ·ÿÿ­ÿÿ¯ÿÿ¸ÿÿ«îò“îõ—ÿÿªÿÿ°ÿÿ¯ÿÿ¸ÿÿ¶íí–çæ’ÿÿ¥ÿÿ˜ÿÿÿÿ¢ÿÿ¦ÿÿ™ÿñ‹ìÍsæ¿jïÁsñ¿yûŇúĆî·|ݬsÓ¢pÈœf½”]¼”džwPjB~`8iO/X@)[F)kZ9{nE}rBzpKsiQnbVwfj|pY¡–fÌÈnâädþÿ|ÿÿƒÿÿ‰ÿÿ–ÿÿ—ÿÿ”ÿÿ–ÿÿšÿÿ ÿÿ£ÿÿ™ÿÿŽÿÿŒüø‡ãÓ{Í°sƦcÖ¯jã¸y뾄óĆûË‹î¾~êºzé»vå¸pà²mîÀñÅ€òÇðÃ{êºvê»té·qìºtñ¾{ð¿‚꺃ã¶zß´uⲕVRXPMNb]]:78406""$=ƯÿÿÉÿÿÖÿÿÃÿÿ¿ÿÿ¹ÿÿ¦êîó÷šÿÿ«ÿÿ¯ÿÿ±ÿÿ©øø–èçŠúûŸüü¥ÿÿ§ÿÿ§ÿÿŸÿþ˜ÿë‰ÿÝ~óÊtæµhÙ¬bÍ£_Ï¥cѤfØ[·‹S©‚J£L›zHˆf7qR-`B*U=(UA/dT:l]>RC-XJ?`URofkvgŽ…dÏËóó}úÿÿÿ€ÿÿ‹ÿÿ‘ÿÿ•ÿÿ–ÿÿ˜ÿÿ—ÿÿ“ÿÿ‹ÿÿŠÿÿŠñçˆÐ¼uÅ«hÉ©mÛµxÝ°tÖ¨qצtÒ¤oשrÚ­oÞ°kå¸póÆ|ôÇ}ì¿ué¼ré¼rà²mç¸zìÀñÅ‚ôÆ…ð¿„í¾€ã¶xå¹xé»xî¹ LJF^^\ooqBDH948JGFIJEQOKSNNVQQVQQZTQZRN[SQ_SU`XVe]Yf`]d]]d`]ea\fb]ga\id\hc[f`[h`^iZ]\GPfKK‚aZ˶ÿùµÿÿ¿ÿÿ»ÿÿ°ÿÿ¢ûÿ–îñ‡ïòˆÿÿ™ÿÿŸÿÿŸøí‘íÜ„çÍ}Ù´nݶqæ¼xþÔ’ûÎùÍŠûΆîÂ}ã·tÏ£bŘZ»S¸R¯ˆP§‚QŸ}N“tFf=lR2\D-W@3I7-UC@UEDYJM_PUk[ezkn|oj­¨q÷øÿÿ’ÿÿ„ÿÿƒÿÿ„ÿÿ…ÿÿ‡ÿÿ†ÿÿ„ÿÿ€ÿÿ}ýö†óߊØÁ}ɬ}ЮwÔ©nÖ«lÙ­l×­kݳqã¹wã¶xìÀ{ì¿uì¿uâµmÚ¯gá¶nÞ²oê½îÂì¾}îÀ}èºué¼rç»nê¿wê¾{íÁ€î¿éµ™OJNYVU`^Z((&       - -5+3TMOTNKQMJRPLSQMQNMSPOWRRVSRXUVZWV_ZZ_ZZ`[]a\\d`]ea\d`[gc^ga^daYb_U`ZUSJKJ>@K).G'0{[O̪ýì­ÿÿ¨ÿÿ¦ÿÿœÿ÷”õÞ†ôÛ†üßüÞÿæÿå‘ÿîÿâ†ïÇnÞ±gÛªoß°vܬwè¹}â´sݲh×®ZË£SÀ—N±‰M«€T©ƒU£R˜{L…j?kS.aK,W@1J34S??^KMs_fzdp‚p{q}†{[ÒÌ~ÿÿœÿÿ†ÿÿ{ÿÿwÿÿuÿÿzÿÿzÿÿ{ÿÿƒÿüˆð߉ٻ…ήoâ½yêÀzðÃ{òƃóƈîÂìÀ}æºwá³rå·rã¶lçºrì¾yê¾{è»}ë¾€æ·yá³rä´tãµté»zí¿zñÄ|ðÂ}îÀ}èºyè¹{í»ŸMHHSQM@A<     2'&G?;GA3:8‰€¿Æ¶‡‹sZX;sq`kgb[VVMGND==?737$&?"*oLCŸv]â·ÿÚ ÿÔ”úÇ„ò¿|è²ræ®mõºwôºyì´uä´rÞ²qÓ«k¿™\Á›ZΧbÒ®cÔ³eÖµiѬd¾™U±‹L³N±‘N²“R¯Q¤‡LŽr>fP/SA5aOLkW^luŽu„Œx‰yx¾¸†ÿÿ¤ÿÿ ÿÿŽÿÿ‰ÿÿ|ÿÿ‰ÿÿŽïބܽ|Ô´uÏ«pÆ aË aУgÔ¥kà±uæ·yã´xè¹ç»zã¹sâ¸rßµqâ¸tâ¸væ¼væ½rë¿zì¾}íÁ|ìÁyå¹tãµrà´oå¹tàµmè½sëÀxïÁ|ï»GAHGGEOSKTXP;<5)*%+()OKFuph]WRVNLOIFE@@GEALJFJJHHHHLIHNHEOIDPHDRLGQMJRQHRQDRQHURQURQVSRXVRZXT\\ZNNN476œ¡ŸÿÿÿÿÿÿÿÿÿíîÌXUAvuywyvuqna_[QMJC=::2.<1.7%"S:7˜vdܱýÓ¡ÿÞÿÜ•ùÅ{ã®iÙ¡bݧiÝ©oÕ¦hàµvÛ±oĘUÌ ]à²qâ¸vܵrÙ³rÈ¢c·‘PÁ™Y¾˜W»˜XÀ¡[Ì®f¿£jƒh?`H1cMInWX„ltƒov|ksŒ€iÍÂÿþ®ÿþ”ýüÿÿýò–ëØŽßÃà¹ä¼‡ã¹‡ìÊíƒçº|î¿ã´vÙªlСeСgѤhΡeà²qæ¶rèºuë¿zå¹tâ´qÚ­oܯuÙ¬nß³rà´sì¾}óÅ‚õÇ„ñÅ€îÅ|ïÃ~ðÀ~긜DABNKJRNKYWQLND=A; #$/*"ni_rkbZWMVULPOFOLDPLGQMJOLMNJRJJLLONLIJNGINGGPHFQMHNLFOMGRPJQOIWUOXUTZWZWV[=;EGDCçâØöôðûýÿãèæÿÿÿŒ‘X[Z\^TfdUrmcƒ{w†wyufnl[YXD?;*70%5''' J-5›txÒ§˜óÄ¢ùÊšïÀ‚ä´râ¯lÒ¤aŘZУeתlϤe¼‘Rجkê¼yè¼yä¸uÏ¥aº“Nº•Q¾˜YÅ \Ó®hÛ¹rÍ«f³”U „M…mCdJ/bQ>]PIdZTmba†|°¥”·«’¿°‘DzŠÄªz¡oÛfˤlÇžeÃœbΧmЧnÛ¯wà´|òÄöÉÿÕ—ú΋ùΆìÁyë¿zè½uß´jϤ\Ñ£`Ô¦aÛ­hå¹têÀzßµsà³yá´xà±sç¸zïÀ‚íÀ„õÈŽú̱A?9JG?NIASOJVSR254""%"SRIpmepib\WOTPKXUMYTLYSNVMNVPWQLYLKRJMNGGELJFSOJSMHOKFPLIMIDTNIVPKVPKYUPXVRTTT-,3GHCæéؽÀ­óôßÅʽÑÖÔ¡¦¤Z]\Z[T^[Q^ZUXSSXSS_ZZtpk‰†|…‚vom^TPK,&- S*&«‚gÉœnݯzé¸Þ°mÚ¯eÙ°gÅžWͨbÖ°oÓ«kÒ¥gà´qç¼tæ»sß³nË£c¾—]ÆžbÕªmìÄ„ä½zÁž^µ”Z½ŸgÔ¸ÝƘžŠfWG4fXVmh^`_RrmX’†k­™w´™p¾ mØ·{Ô±sϧkË£g׬qÖ«pÙ«tÙ¬rÌŸcÄ—[À“YÁ”ZÓ¤jܯuã¶|íÀ‚øʉÿÑŽþÐÿÕÿшöÉë¿|ì½è·~ä³xõĉðÁƒñÂðÁƒî¿ƒêµœ>@6BA8HE=JKDLOL&,%%JOBvvfed[611UOJaZQaZQaZS`ZUYURSPOOOOOOQMLQIHMJFLHEHKFHGEAIJCLIATMFUNGTLHTPKWUQHKJ$);F7¥³“èõͱ¼‹‘“sÖÐÂyws[\e[[]XUTYWS]YV]YVZTQXTOWSNUSM^_Xeg]ik_SQMB;?7/-/"& -$L(¢y`°†bžqCÏ¥qϦmϧkΦhÒªlݲuÒ§hÙWÍ¢cУgתpÅ•^Ç™bТkÜ°oñÆ|æ¼xÉ¡cÊ¥aÔ²iæÇåÅ‚È°qºªr‘a¤—q¨–j±ši´˜_À aϬn×®uàºyéÄ~ñÊ…õˇôÈ…ûÍŒïÀîÂ}ïÃ~ñÃ~îÀ}å·vß³pã·rä¸uã´vÕ¨lУiÖ¨qݯzãµ~è¹õÆŠõƈþÐü͆ôÄ€öÂë»yôÄ„öÁ¨777997A?;EFAHHF23.A?9rnkd]]@=>A>?a]Z]ZR\WM[XPXVRTUPOPKNQNLONKNKJJHHHFNKLKHGFCBGBBB;=@9;SJO[TTYSPB=?%(DIE3A3qq_ÿúçèâÔrplVTPYWSWUQXSSWSPd^[ZVSWRRYTTYTVVSRRPLPNJSPOXVRXTOYSPL@B@78IDF^Y[kfhda`OLK;;9PQJVXNVULTUNQQOUVQVTNQOITPMUSOPMLNLHLJFGHABF>@D>@@@997632/0+672222,(.SMTWMWJ=FD5E?;A?;A444220//-++)-*-5/8GCKQPWPPRQNONNLQQOURQRMORMMSLLXTOTQIPNHOMIOLKKHIMFFNCBNFDULMLEEC>>;663..0)).%&' $&+,(087>IBFI:?9%%B$#oM=¶pÖ­‚Ù­uܯqÛ­jÓ¥`ä´pðÁxûÊ}êºxæ¶ýÐ’ÿÕ‘å¹vã³qìÀõÍá¹}Ò¦pÖªrãµ~ëÀƒÝ³qШjË¢kË¥hΨiΦhÝ°vã¸yé¿}éÂå¾{ä¿yÛ¹rá¼tâ¸rã¹wä·}溂뿉ìÀˆîÀ‰ïÁŠðÀ‹çº~ç»zå¹vã·ræ¼víÃîƆðÊöÓ‘úÛ“ÿܲ2-#0,'410860POD[XNVQG97111/442220@@@C?EC>@F??F>>:7722/,+,)($'$!&$ %!$"""777HHJMEA@.'T;-~ZI°ŠlԨ㴄æ´~æºyõ̃ÿÚ÷Ïâ¹pòƃûÏŒé»zתnà´|ëÇâº|ͧhÈ¢cضqá¿xÒ¯m̦iÖ­tÝ®|ß±|á³~è»ì¿äºxáºwÛ³uÛ²yÛ´zݶ|á¹}ä·{쿃óĈñÃŒóÄ”ðÄŒìÁ‚ìÂ|öÌõÊ‚ùÍŒøÎŒøÑŽúÒ’÷Ï‘ñÊ…ìÆzìÆš/,",(#4/1@=>OLMHEF523((&-.)00.333! $&,636:57<55611944<85B<9C<>F>EE@DGDGE@@JDAIC@LFCJFAEB:D?7E=9B<7=7294,61)/,$+*!'% $ 71,MB?RJFRJFNHCJFCIEBKEBHE;GE6FF6HH8KI8NJ9JH9GF9?>397112---+)*%$%#$$%##!!#!"%*,2>=DE>JA31T=0ƒaQ»‹|Ù­†Ý²sïÈ…ÿÜ–ÿâ—ïÊ{ðË|ÿÜ÷ч׭gä¾tðÌèÃ{Ó®jɦfЯuäÁÛ´mÕªkÚ¬uã¶zë¾€ã»}Ö¯uϨnÊ£iÄeÄšfÇžgÒ©rÛ³uÛ´qÞ´pجiФaФcÓ§fТaتeØ©bÚ­câµkæ»sç»xîÄ€ðÆ‚õ·õцùÏ«-)&+('222???GDE<9:# !()$*+$*,".-$&()%")$&)#,,(.*).//12/0:55?88@:7C=:B<7F>:H@>@C>>=:9450/0)+,%*("(&"&#$!!  !! %!+!#$!$ 2.)@92K<6`G;”paÈŸ„æµÿÔœÿá˜÷͇îÄ€ÿÚŽüׄãºqè»}ùÏôʈܴtË¥fѬhá¼và»wË£cÒ§lã´‚ìÀŠÓªqÅœc×®wÔ­uÒªuÑ«là¹tçÀ{ìÂ~òÌ€öÑ€øÓ„ÿÖÿÕ‘ùÌŽø̇ôÉùÓ‡úÙûßøá‹ùâŒøá‹ùà‹ûßôÒ£//1///410A>?84:!!%%%##%"" &$$(" -   !$$"'%!+('3.0634<9<;68@9;B;;D>;@;3FA5GB:LEEGC@DB>BC5>;3=:293.4.)-'$-'"*"$.)-B?@B?@FCBHCCHEDGDEHEDJEEHDA@:7:613/*/1%',&-!!&"%&$! # $""# &##!%"%&++%,6/1=-,O63Šj^ÈŒùϧÿà ôË€üÓÿ܈îÃoÚ°aå¼sîÄ~å»yÖ¯hÒ¬`á»oêÄzÔ­jÎ¥lÛ²{ß²ЦtÌ£vÔ¬wÙ²xÞ¶xå¹xç½{íÃôÊ„ùЇë¿|ÛªoÕ¤iÓ¢iݬoç·wæºyõÊ‹ûÖ’üÝ•ÿêšÿë•ÿè”ÿç—ÿå³*).')-0498A@($ #!!!  "" +&(-((2++4/1517:7:=:;=:9@=<@>8EB8HE=D@=B>;@<9EA? "   % %"!%%#))+-,3002:78967:78:;49>/AC7B@:A@7DA9E@8E>7HA:G?;D=6E>5C>4D?7=747024//61120,/0)%&!!(%(C>@GA>E>7;726724102-11/++-!(-"&*$$'$%%%##%#"!&#"'!!# ##%(%(***+++)-%(/!).#31+3..1(-2"qM*Û¯y纀ì½×ªpÙ®qæ»|éÁƒÔ«r̦gÕ¯nߺtÆ¡YÒ°kÒ¯qÚ´wÜ´x̤h׬q龃ñÄŠîÄ€îÈ|ݸpÊ¥aϪdä½vúÚ‡þä†ýã~õÖnóÑo÷ÑwüÖ|ÿÜ…ÿ߈ÿãûá±- %/>EL9?B# - - -  "!!!"'# ,(#.,(3012/0412;87<:6@>:B==GA>H@IBBB>9>;3<;298/32)2/'.+!)$$#-*-634634724//-*-*%+$$,%#+" &!$!##%!""$%$&"'%)*#',!*/$*.&)-',,*2-/0++2,)0))3*-4%*.#+cA&¯ˆcÙ©ß²„Õ«yׯsëÄã»{Í¥iШjÜ´tÔ¯kÄŸ[ݶqëÁ{ïÈÖ¯hΧdã¸{ëÆ~÷ׄü׈îÃyÛ­jß®sãºqòÏ{ÿ܆ñÈtèºlë¶qí½yîÀ}ëÄ}ëÌ‚øÔª'4<@DOP).,   -   #)*%+()2.43.984:969=:9B>;B@KGBPLGSMJIDDOJLKFFPKKRQHPOBKH>MEAGB:<7/=:063)0-!0++&)$&$ "$)*%///-.'*, (-"!%"& %%##$&$ &#"'$%&'"&+ *+$+)%-*)-(,.''2'&.(#-+%,*$/+&2,)2)*2)*/&)--=$bD,›zXÀpͨtÛ´z̤o¸`ȤkÒ¯oÖ³qΨgݶoëÀvá¶lת`å½oïÊy÷Ñ…þ×õɈà¯vجkç½wý؇ÿá‰öËwñ½qæ¸lïÂzõÊ€öÌ'.9@JTAJW#+  -     # +#!-*",+ 21&54)87.>:5>:5D>9KF>RKBRMATOCZSL^RT]UQ`YR`YR[SO[VNWTLWTLSMHID7HGUPFZRNYQO\SVZVSa_YdcZ`_TebXb]S]ZP^[S]ZR\WOTOCNJ9KI:B?3?>39:316),3#+*,$ )$$!% ")""0$&,#$-&&*($%&$( &*$)-%*,"(,$$(")*#*) ,+-+.- *, *, ,+ .,&.+*1/)43*05(07' KI8mcKeP5Ÿ„[ЫuÖ¯uÔ©lÞ±sì¾}æºyì¿ôƃñ¿yß²jݱlòÍ~÷Õ~úÕ‚îÄuìÃxòÈ„û׌ÿã‘ÿãùÔƒñÇxé»o໘ \ No newline at end of file diff --git a/example/dev/file_grabber/image/img0252.ppm b/example/dev/file_grabber/image/img0252.ppm deleted file mode 100644 index b5fef0de7fe..00000000000 --- a/example/dev/file_grabber/image/img0252.ppm +++ /dev/null @@ -1,16 +0,0 @@ -P6 -128 128 -255 -ao|dugw†gu€is{vyz¯©¤}€szƒq~…m|„m|‚s€‡p‡dr}^oyu†‘¢¬ ®»¤²¿¥³À¬ºÅ¶ÄϸÉÓÀÒÞÈÚäÉÜãÓãäáíëâêìïóøñôõñññóóõöõúýüÿ÷öûø÷üóòùùûÿÿÿÿÿÿÿÿÿÿþÿÿýýýùüûðóôäêíÙäçÔãéÍßëÆÛäÊßèÃÛåºÑÞ¼Õå¸Ðå¹ÑèµÌæ²Éã²Éå·Ìç·Êã¯ÅÛ­ÅجÂÖ¶ÆÞµÈá¯Äá²ÊáµÍâ¶Îå³Êä­ÅܨÀ×¢½Ó§ÃÙ±Ìâ¯Åݨ¾Ö¨¾Ö©ÄÖ§ÄÓ§ÃÕ¢½Ó£»Ò­ÃÛ§¾Ï¤¸Æ§»É£·Å ´Æ¦¶Ðª½Ô©¼Ñ£¶Ë¤·Î¦¹Î ³È£·É±Ã¢¶È¥¶É¢¶ÆŸ³Áœ­¼¥µÄªºÍš¦Á—¤¸˜¦³”¢¯’ ­‹™¦‡”¤‚Ÿ|‰™v‡˜o‚—f|aw‹_r‡[kVgzUevVfw^k}Taj`m}eu„dt…hvƒnx‚wzw®¨š‚ƒ~u{€pz€n}ƒp}‚w‡mzƒepboƒq€˜Šš­—§¸›¬¸§¹À³Æ˲ÈʵËÏÂÕÜÇÙàÏÝèÔãéÛéëàëìçîîèííîñòëîïðòöùüýòòôïòóðóôùüýýýÿøûüöùúòõöýÿÿòôøóòùíñöæìñßìñÎáèÄÚÞÂÛÞÂÚâÉÝíÁ×ë¸Ïé¯Êà­ÈܱÉÞª½Ö®ÁÚ°ÃܱÉÞ¸Óç·Òä¸Óå«ÆÚ¬ÇÝ´Ïã¶ÑãµÍâ³ÈãªÄݨÃܲÎä¬ÇÛ­ÅÚ¶Ìä­ÄÞ£¼Ú¤¿Ø§ÃקÃÕ¨ÃÕ¦ÁÓ§¿Ô£¼Ì¥¾Ì¥¾Ì£¼Ì¤»Ì¤¸Ê´Ã ·Ä¦ºÊ¥´Ê¨¹ÌŸ³Å°ÅŸ²É¡´É¦ºÌ¥¶Ç¥µÆ›¬½›¬½®¿œ­À”¥´–§³”¤³œ°‰š­ˆœ®“£yt‰”nƒŒk€‹hyˆdt…boƒ\lWgzZk|UfuIX\am{p~‹mzŠl{ƒjw|vzt¸²¤‡ˆƒtyly€m~ˆn‰q‚Žl~Šav`t‚q‚•‘¢˜¥µœ¬»¦·Æ¯ÄÏ´ÉÔ¶ËÖÀÒÞÇÙåÆ×ãÌÛãÔáèÚèêÜêêÛæçäêíêîñéëïëíñòñöòòôúúüøøúýýÿøøúùõûðïôðïöòôøíïóçïñßíïÖèíÊßèÄÙâÃØãÃ×å¹Í߶ÉÞ°ÃÜ°ÆܹÑä»Öè±ÌÞ·Òæ°Ëá¬ÈÞ©ÅÛ±Íã³Ïå°Ë߯ÇÚ¬ÈܪÉÞ¨ÇܪÉÞ­Ëã¯Êå®Éä±Ëæ°Êã²Éã®Åß­ÄࣾԬÇÛ¯Êà©ÃܯÄß­¼Ù­ÃÛªÂ׫ÄÒ ¸Â¡ºÈ£»ÐŸµÉ¡µÇŸ³Á­Âͨ¼Ì¡´Éœ¯Ä°Ç ³È›¬¿ °Ã¨´Ëž­Ã™¨¾˜©ºš¬¸‘£­¡«Šœ¨ž­ž­†–§€£€Œ£|ŒŸq”g{‹hŽcw‡_pƒ]m€_k‚Zg{Q\oDMZ\m~\m~cs„ky„lv~uzx»¸®†…Šwv‹nw†j{‡l}‡n‰k}‰h|Œ_sƒk‘{ŸŒ ®˜¯¼Ÿ¶Ã©¾Ç®ÀDZÂÌ»ËÚÁÓßÅÚåÅÚåÑãïËàéÒèîÒäçÛééåðñêðóëñôåëîíòòøûüïòóöùúøûüðïôø÷üóò÷ðôùäéñÜæìÖåéÈÚáÈÚæÂÖäÁØéºÖå¶Óâ¾ÛêÂÝï½Øî»Ôò¬Çâ«Æß®Éâ«Æß©ÃÞ±Çæ±Èä³ÊäµÌæ³Èå°Åâ±Âã²Çä²Éå¯ÉâªÄÝ´ËçµÉé¶Çè¸Æꮿâ°Á䧻ۯÄá«ÀÛ©»×Ÿ´Ïš¯Ì ·Ñ¦Á׬ÂØ°ÀÖ§½Õ¥»ÚŸ¶Ð¦¼Ò¨¾Ò¶ÍÞ¢¹È¡µÃ ´Æš­Ä¢¶Èš®¾’¦´–§¶œ¬½¢­Â˜¨»—§½šªÀ‘¡·‘¤¹¢¹¦·…œ«“£’£€‘¤tƒ›m}•dweu‹fv‰XizQbqQapQ\m?IO^mƒ[k]mƒdujw|tywÀ½µ…ŠŠpz„iuƒo|Žrs€n~m~rƒ”l|’vŠšˆœª–§¶£³Äª»Ì¯ÀѱÅ׶ÉÞ¸ÌÞÂÓæÌàîÊâìÃÛåÂÚäÌáêÓæíÑãæØèéÞîíÝíìÚéæâëêëóõêñøäïòàëìäðîáíëÔââÍÚßÔãéÛíôÒçðÍäñÏæóÍäóÃÚé½Ôã¶Òß±ÎÛªÇÖ°Ìà®ÊÞ©ÅÙ¡½Ó¥¿Ú«Æ߬Çà¬ÈÞ°Ëß°Ë߯ÇÞ·Òæ±ÌÞ´Ìã³Èå´ÈèµÆë²ÀäµÂä´Â汿娹ܤµØ°Âà­¿Û¦¸Ô©»Ù¦¸Ö¤¶Ô¨ºÖ¨¸Ò¦¼Ò¡¹Ì¨ÀÓ¨ÀÓ¦¾Ñ¡·Í ³Ê¡±Éž®ÆºÉᨼΜµÃ¢¹È¢¶È°Å¦¶ÎŸ¯Å•¤º›¬¿”¥¸ ¶·ˆ›´‚˜°—«“¥|¢{‹¡zŠ¢w† q™i|“_u‰_u‰WnThzUfuO`l6AD^o‚Zk|^o€j{…gt{ryw¿¾³‹Žpz„my…ss€o|Žk{Œm}Žizm€•sŠ™‚›§“§µœ¬½¦¶Ç«»Î²ÃÖ¯ÃÕ¸ÈÞ»Êâ¹ÉßÅÕë¾ÒâÁÙãÊâêÊàæÎáèÖèïØëòÏâéÒäé×æìÇÖܽÊÑÊ×ÜÜçêèóôíöõçòóãñóÉÜßÌåêÈâë¹Õâ¶Òá½ÕèÃÜìÓêûÁÚèµÎÚ¯ËÚ³Îâ·Òæ¸Óé¾Ùò¯Éç§Å߬Êâ¥ÁׯÇÞªÅתÆÕ¶Îá¼Òè¾Óî·È뫿㪿穽ߪ¼Ú®¿à¦´Ø­¾áª»Þ³È妻֟¶Ò¡ºØž·Õ¡ºØ´Ð¯Í¡¶ÑŸµÍž´È¦ºÌ±Ãœ¯Ä•¥½˜§Á¢²Ì¦¶Ð ¶ÊœµÃ›²Ã ³È˜«Â­Ç˜¨¾˜©¼™¬Á™¬Ã”§¾Šš´ ¹€–®~”¨~•¦z‹ž€¡{‹žtƒ™p€–m}•aw‹c|Œ^u„ctƒpWep5@CZhu]kxepeq}\irmtt½»µŠŽ‘qz‰lz‡q‚Žq‚ŒqƒŠhz„ev…fzŒo‚™zŠ „‘¥‘ž² ¬ÃŸ®Ä«ºÒ°ÁÔ±ÂÓ¹ÉؾËÛÃÓæ¼ËåÄÕèÅÙçÎâðÉÚëÅÙéµÌÛµÉÙ»ÌÝÒàëåï÷åò÷èõúÚéíÔæëÕçêØçëÛëìéùøßõù¿Ùâ¿ÜäÀÞæÄâêËéñÅáî½Õè»Óè®Åß°Åà¸Êæ¬ÃݬÆá°Êå®Åá­Çà±Ìå³Êä²Äà´Êâ´Êà¯ÇܲÍã°Ëä¯Íç¬Çâ¸Òí®ÆݱÄÙ¯ÅݹÐì²Éã¬ÂÚ£»Ò§¿Ö­ÄÞ¯Æ⤻ש¾Û§¼×¢´Ð¤·Î¤¸Ê¡´É›®Å­Å§³Îž®ÆŸ²Éž´Êš°È™¯Å¢µÊœµÅ–²¿–­¼Ÿ¯Âž­Ã©Âš¦½›§¾•¤º ¶‡š¯‹ž³“¥‚“¦‚Ž¥ƒŠ§{Š p„–j~oƒ•gzbuŽeuam†am†S]w%.;_j{Ydu[fy]fscjqpus´µ®ˆŽ“s~n{‹r‚“pi~‰bw‚hz†m~o€“wˆ›…•«Œ°¡²˜©¼£³É«ÂÓ©ÅÔ®ÅÖ¸ÉÜ·ÈÛ»ËÞ¿Ïâ¹ÉÜÀÐãÁÎâÂÔàÕëïÏçïÇàìÈâéÄÝâ¼ÕØÊãæÇßç¾ÕâÂÚäÍâíÅÝåÃÝäºÖáÄßñ»×æÅáîÄàï½Øê»Öê·Òè³Îä±Ëä¯Êà±Éà³Ëâ®Åß©ÄݦÄÜ°Êã¯Äá³Èã±ÄÝ°ÃܶÈä«ÀÛ«ÀÛ°Êå®Èæ¥ÀÙ¯ÊÞ¯Êà¯ÉäªÄߪÃ᤻ן´Ñœ´Ë§¿Ô¨ÀÕ¯ÅݬÁܤµÖ¦¼Ô¥»Ï´Å ·ÆŸ¶Å¡¸É¤»Ìž´È¢¸Ì¢µÌ¡·Íž¶Í˜¯É˜¯Ë—­Å’¥¼”§¼›¯Á±ÃŸµ µˆ›²ŸµŠš­‰š­Šš°‚™ª|•¥€—¨‚–¨|¢r†˜n‚’rƒ”q‚•ixfu`l…]i€R^u0?EmuwZgnYgt_mx_lumsv¸¹´†Žr€‹k}‡jŠj{Šhu‡cs„k{Žm~oƒ“tˆ˜}ŽŸ‰š«‘¡´—¦¼¬Æ¥µÍ¤·Î ³Êª½Ô¨»Ð³Ä׸ÌÚ¼ÑÜ»Ïá»Îç¾ÑèÆÙî»Îã¸Ëà·ÍáÁÙî¼Øê»Ûé¼ÙæÂÛçÅáîºÕçÂÚï¾ÔìÄÚîÅÙé¼Ïä¿Òë·Íã²ÈÞ´Ìá´Ïå´Ïå»ÒìªÂÙ¯ÇÞ³Êä³Êæ±Ëä³ÎçÁÛù¸Ñó²ÈçÂ×ò²Éå±Çæ±Èä«ÀÛ«ÃÚ±Ìâ®ÆÛ­ÀÕ°ÆÞ¯Äá­ÂݯÄߪ½Ö¯¿Ù«¾Õ¯ÅÛ¦¼Ò­ÀÙ¯ÂÙ°ÀتºÒªºÒ¨»Ò§ºÑ¨¾Ö§¼×¢¸ÎŸ³Å ³Èœ¯È™¬Å˜«Ä–¬Ä’©Ã—­Ã“¦»•¨½–¦¾–¥½—£¾‘¡¹Ž¡¸ˆ›²Žž¶ƒš«‚›§|•¡„›ª‚–¨†•«ˆ—¯w† l|’p’rƒ”hyŠhyŒaq‰YizAO\$/2y€~itu`mt_lu^jvlrw²²²†”o|Œjz‹fwŠhyŠdu†arev…fw†o€‘tˆšx‹¢‚•ª ³Žž´–¦¾Ÿ²Ç¡µÇ«»Ñ­¼Ö¦¼Ô¥¿Ø¯ÅÛ·ÇÚ°¿Õ²ÁÛ·Ç߶Éà¶Ëæ´Èè°ÅâÂ×ô¾ÓîÀÓìÀÓìÆÖð¹Ëé»Ìï¹ÎëºÑëÀØï¼Òê»Ñé¶Èä¶Ìä¹Ïå½Õì²Éã¯Æà´Ëå³Îä·Òè¸Ðå¶Ìâ´Ìã¨ÂÝ«ÂÞ­Áá¯Åæ®Ãé¯ÈêªÃå½ÔðÇÝõ¶Íç±Ëæ³Ëà»Ïß¼Òê¬Â㣼ڹÓî¬Æá¨ÂÝ©ÃÜ«ÂܦÁתÅÛ¦ÁÕ¡¹Î¦¹Ò©·ÖŸ®Ë¢±Î¡³ÏŸ±Íš°ÈŸµÍ¢¸ÐŸ´Ï¡·Ï–¬Âš°Èž³ÎŸ¯É¥±Ì™¨Â˜§Á›ªÂ—¦¼ µŠ ¶ˆž²‡š¯„—®Ž ¼‚˜°~”¬’§’¥yŸq„™s‰o‡œl‚–p€–l}dt‡Xh{9FZ!.3tx{u|…`lzXdpYfojps­ª©ˆ•mx‰cs‚]qarƒ`m[k|^o‚cs‰l{“sƒ™t‡œ|¤†™®Œ¤·ª¼¨¸™­¿Ÿ²É¥´Ó¤¶Ô¤¶Ô«ÁÙ¼ÒèµËß·Ê߯ÂÛ´Æä®ÃÞ¶Îå³Êä¸Ïë±Ëæ²Ëé´Îé»Õî»Òì¾ÐîÂÔðÂÒìÂØî¾Ùë±Ìà°Êã´Ïã³Îà¯ÊÜ´Ïá¸Ðç¹Íí´Ëç³Êæ¸Ïë²Èç±Ëæ°Ëæ®Éâ°Êã³Íè¬Åã¨ÃÞ¬Çà³ÏáÀÜéÃßñ®Éâ®Å᫼߸Îí¦¿ÝŸ¸Ö£¹Ú¤½Û¦¿Ý£¿Õ©ÅצÁÓ¦¼Ò¡·Ï¢´Ð¢¸Ð¢¸Ð¤ºÐ¤·ÎŸ²ËŸ±Ï¤³Òª·Ùª¹Ø£²Ñ ²Ð¡³Ñ­Ç°¼Ó£²È£²Ê¨¸Ð˜«Â›«Áœ¬¿˜¨¾‹ž·£¹‹¡·†˜´„’´…—³„—®’©~‘¨z¤|’¦{ŸzŠ™q‚“j}’g{au…K[l7BU46<;:?Y\]rutzxt—’ˆ‡Žgj~T_t]l„TexTevXixctƒev‡l|q‚•wŠŸt‡œ|¤‚–¨£³’¦¸’¥º“¦¿«Í˜­Ê™°ÌŸ´Ñ¦¸Ö¤»×¨ÂݦÀÛ£½Ø¨¾Ýª»à¤µÖ±ÃߺÎî­Àç¯È棾ץÀÙºÔí´Ïå¯Êà­ÈÞ¼Ôë·Íå´Æâ²Ìç³Ðï±Ëé°Êå­Çà«ÃÚ¨Ã×­ÈܧÃÕ§ÄÓ´ÐߺÒåµÍä´Ëç­Çâ¹ÓñÁÛù¶Ïí¨ÂÝ¢¼×«ÅÞ¯Êà©ÄÚ¨À׫ÂܯÄá²ÉåªÃá®Äã­Á᤽۩Ãá ¾ÖžÀÔ¥ÄÙ¬Æßž´ÊŸ¯Å—­Á™±Æž¶Ëš°È™¯Åœ¯Æ ·Èž·ÅŸ¶Ç°Å“©½—­Ã”ª¾’¥º‹¢±Š¡®Œ£²‘¤¹Š¡²Š¡°|“¤†™°‹ž·‹¹}“«€–®z¦z¤vŒ x‹¢r…žon~‹™›ËÕÝšž¯†Ž¤‚‹ª|‰™9@K*4:.9<@CRWWkswoyƒct€]q[oarƒ[o\o„cvh{”n„šmƒ—o…™tŠž|’¦…˜­ŒŸ¶‹ž·¢»•¤Á˜ªÆ˜ªÆ™±Æ”±À¦ÂÑ­Ã׳ɰɢµÎ¨ºÖ©¼Õ­Å´Ç઼ؤ¹Ô¬Ãߧ¾Ú®Åá¯Åä­Á㨼ܯÄá³È婺۬ÁÞ¯Äß ·ÑªÄÝ«ÆÜ­ÈÞ¤¿Õ¦¾Õ¯ÊÞ¹Ôè²ÊáµÇå¯Äá­ÄàªÄݦÁ×­ÈÜ°Ë߯ÇܬÂÚ«ÀÝ©ºß®¿â°Áâ¶Ë覽٤»Õ§¾ØžµÑœ²Ñ¡»Öž¹Ô¡½Ó¦ÁÓœ¸ÅŸ»Æ¤ÁÌ›¸Å™±Ä›­É›®Çš­Ä›®Å£³Ë”§À‘¦Ã¢´Ð”¤¾˜«Âœ¯Ä–¬Â¦¾œ¯È–¦À ¹‡š³‹ž··ƒ–¯„–²…˜±’©…˜±†•²v‹¦{’¬w£q„™oƒ•n‚’t†ÌÑÍkr{…£ˆ’ª‚Œ¦w…rpjqrmhhhHHH77987>D?L[\gqt~ktƒ`m^nZkzXiz^o‚dtŒhw–o‚›r…œu‰›‚–¦ˆž²–±…›³ˆ›´–¥Â•£Â¡½‘§¿“«Â£»Ò¤ºÐ¡´Ë©»×®Ñ­¿Ý°ÂÞ¨ºØ¤²Ô­¾ß­¾ß®Ãৼ٪ÁÝ¥»Ú¤¸Ú¦·Ü¯½á³½à«»Õ§ºÏ¤ºÎ§½Ó¦¾Õ¬Æá©ÄÝ­Ëã¯É䮿à±Ãá¹Ëé·Ëë®ÂæµËì³Éè¯É䡼թÄÚ«ÃدÅÛ±ÁÛ¦»Ö¥¼Ø¥¼Ø©½Ý®Å៹ҡ»Ô§¾Ú¤»×¡·Ö£ºÖ²Ï–­Çž¸Ñ£½Ö‘«Æ›µÐ›µÐš°Ï™­Ï“©È–°Ë™°Ê–«Æ¥½Ž¡º“©¿’¨¾§¼‘©À¦À‘§Æ‰ž»Ÿ½‹ž·†™°‘¤»ˆ›²ƒ™¯‚š±Š¢·}“©|¨|Š©x‡¦yˆ§u‡£qƒŸo—q€–tzˆÈÇÌBLV2FX{ŒŸ~‹Ÿ|ƒŽ_]YQRMDGD8;<46<68<8;AINNcgjux€gp_n†Xh€Xk‚_r‰j}”f|’l‚šn˜xˆ ¥‚’¨‡—¯‰™³ˆ›´•¨ÁŽ¡¸•¥½’¥¼™¬Å—¯Æ·ÐŸ·Î°Çš°Èš¯Ìš±Ëœ¶Ïœ·Ð§ÂÛ¥ÃÛš»Ô¥ÃÛªÄݨ¾Ý§»ßŸ³Ó§¼Ù«ÂÜ«ÅÞ­Çà¦ÀÙªÁݧ»Ý«¿áµÆë¬Àà®ÅᨿٲÊá°ËáªÅÞ©ÄÚ©¿×²ÅÜ°¿×´ÄܱÄݱÈâ¾Øó¸Ïé°Åà¬ÄÛªÂٸʩÆÕ®ÊÞ«Åࢼգ½Ö«ÅÞ˜²Ë ·Ó ±ÒŸ´Ï¤¼Ó¡¹Îš²Å•­À‘©¾’©º¡µÅ–©¾™¬Å£¶Ï™¬Å“¦¿¢»’¥¾Šœ¸‰™³˜§¿œ¹•¦ÇŠŸ¼…šµ…›³„—®†™²ˆš¶€’®y‹§x‹¢xŒžzŠ ‰˜°tƒ™p•p•etŒXjtUli‚‡“"&%'-3:E9?O>CXO^HVc8AN1;E9@KHOVgmpnyzcqs]kx_k†aq‡j~j}’r…œo…™wŽŸz“¡{—¤‚ž«ƒœ¬‹¢±œ°Àž´È–¬Ä“©Á—­Å ·Ñž¸Ó˜²Ë˜°Ç¦¾Ó˜®Ä›±Ç ³Ê¤·Ì¶ÊܶÍÞ£»Î£»Ò­Äࡸҡ·Ï¨¾Ö­ÀÙ°Âૼ߬Â㣽ݩÃáªÄߟ¹Ò¥¿Ø¤¿Õ­ÅÚªÅÛµÐé¿Ûï²Í߶Îá°ÆܬÄÛ¬Ãß­ÇâªÄ߶Ïí¨¾ß§½Ü£ºÖ¡»Ô°Êã«ÆÚ¯ÇÚªÂׯÇÞ¬ÃݤºÙœ²Ñš°Ï¤¸Ú¢²Úš®Î–«Æ’ªÁ”¯Ã—²Æ•­Ä“®ÄªÀ˜¯É’¦Æ¤ÁŸ´Ñ”ªÂ–©ÀŒŸ¸¡¿‘§¿‰¡´†œ²‹ž·ŒŸ¸‡™µˆž²˜¤Œ£´’©Š²¥t‡œwŠ¡t…˜t„•iz‹iz‹l}fvŒYh€BKjlo…DBP >JXERfHSqIUlP]oTbmJY_6AD7<<=;>;??=SXTmtpgqw_l|v‡šf|’s‰Ÿmƒ™o‚™{‹£y¥}˜¬ƒž²™®„œ¯Š¢µ¦º“¦½–«Æ˜®Ï›µÎžºÌž¹Í¥½ÔŸ·Î´Î˜°Ç³Ë”©Äœ®Ì ¶Õ›´Ö”®É¦ÁתÅÙ¤¼Ï§¿ÒªÂר¾Ô­ÀÙ²Ê᥿جÃݧ¼×«¿ß¬¿æ§½ÞªÀߨ¿Ù®ÆݲÊá¯Æà®ÆÝ®ÆݲÍã©ÅÛ£¾Ô¨¿Ù­Ãâ¬Àä®Ä娾ߥ¿Ú¡»Ô ¸Í­ÀÕ¨ºÖ©ºÝ«¿ß¡¸Ô£ºÖ£¹Ø£¹Ø§»ÝŸ³Ó¢·Ô´Î¨¿“®Â¤¿Ñ’®Ä–±Ì“­È–ªÊ™®Ë•§Ã’§Â¤¿‚³‚¡´…¡·…Ÿ¸‚—²Š™¸Ÿ¼‡–³„“°‚‘®©zŠ¤xˆ¢w†£{Ž¥rˆœr…šq—v† s€¢k}™i—]qTfpDU_$2 =M\DUaLZgFTaDR_AR^AS_ET\@JR8>C9<=FIHbedksuans\mwcw‰f}Žjƒ“p‡–„•¤…–§Šš°ŒŸ¸Ÿ½¢½‡ž¸…Ÿ¸ˆ¢»ªÃž¸Ñ—²È•°ÆªÂÙŸ±Í ²Î¡³Ñš°Èš°Æ“©¿˜®Æ¡¹Ð¤¼ÓžµÏ¥»Ú¤¿Ø£ÅתÅÞ­Ãâ«ÃØ´ËظÑ᤼ѴÌá»Óè³Ëâ¬ÁÞ®ÁÚ´ÄܵÈݯÂת½Ô©¼Õ¯Äá±Çê³Éê³Éè®ÀÞ©·Ô©¾Û«Äâ¬Æߧ¿ÖŸ¹Ò£½Ø¦½×¨ºÖµÆ篽㡵י¯Ðš°Ñš°Óš³Ó¡ºØŸµÔ¦ºÜ¶Öž¸Ø•¯Ï›´Ö–°Ð“­ËŠ¤¿¢½Œ£¿‹¡À§Â™´Íˆ£¾ƒœ¼}–´z‘­}”®}•¬€›¯œ®„œ¯|’¦‚š­sŽ¢t£z’©tŒ£m‚q„›m}“m€—k~—i•h~”`y‰QjxOei@TO&38&9J]GXdHW_BT[9JTAR\M[hIWbEQ]K]FVeFVeEYg=Vb?WaL^jDUaCP`BOXE?FMW\damycs„du†r†–w‹}¥{“¦|˜ª†¡µ‡ž¸…œ¸ƒ—¹Ž¥Á’©Ã•°Æ—²Æ¨¿š¯Ê´ÎžµÑŸ¶Ð¡¹Ðž¶Ë¥½ÒŸ·ÊµÈ¢¾Ò¡ÀÕ§ÃÕ©ÅÒ£»Ð¦·Ø¢·Ô¡¶Ó§¼Ù¦¸Ö¨½Ø­ÅܬÃÝ®Åá³Îä¬ÇÛ­ÅܯÄ߯Æâ¸Îï¯È裼ܡ»Ö¥¿Ø¤ÀÖ£¿Õ¯Îá¼Ûî¥ÄÙ¢½Ø«Æß°ËáªÁÛ«¿ß¢¶Ø¨¼à­Á㡵סµ× ±Ô±ÑŸ¶Ò¢·Ô ±Ò˜­ÊžµÑ™°Ê¦À“«Â‘§¿‘©À•¯È§ÁŒž¼Œ¡¾¢¿§Ã‰¢ÀŒ¦Á…Ÿ¸„Ÿ¸‡¢»… »ƒœ¼ƒ¶™¬“«À‚™³w‘¬r‹©vŒ«vŠ¬vŠªwŒ©n„œm€—dxŠr†–f}Ž[q‡Wo„Sn„Oe{L\tIXnFQfBS]=QcEYkCWiIZmP`sN_pOcsL]nP]qKXlHUiCO]>HR8BHAIMS]eamyev‡n†o† r‡¤|“¯„š¹† »™´…œ¶…šµŒ¡¼•§Ã¡·Í™²Â•­Â‘¦Á™±Æ–±Ã¹È¤½Ë¶Æ©¿Õ£»Ò›µÎŸºÐž¹ÍŸºÎ¤¼Ó¨ÀÕ£»Ð¦¼Ô«½Ù¬ÂØ­Ã×®ÄÚ¯ÁݲÇâ±Èä°Êã°Êã±Ëä°ÊãªÄß«Áà¬Â᫿ߪÀߨ¾ß²É姾زÍá°ËݹÔêªÃá©ÃÞ¤¾×£½Ø©Âࢻٞ´Ó¨¹Ú§´Öª¸×«¹Ö§ºÓŸµÍ¡¹Î™±Ä–­Ç‘§Êš°Ñ¢¶Ö¡µÕŸ°Ñš®Î™­ÍŠ¡½ˆŸ¹Š ¶Œœ²ˆš¶ŠžÀŠ ¿‰ ¼–°}”®|“­€•°€•°–³ƒ•±‚‘®­Ž­z¬x‘¯k… lƒŸi•n‚”cs‰n}•cv‹]t…Tk|[oRfxM`uM`uK^sMcg>K[AS_CXaH]hIZkJ[lL]pN]uP[yJYqJZpG[mCWi;MY0?E8FHYdekz‚w‡šv†œzŠ¤|’ª{’¬€—±‰ž¹ˆ ·‡Ÿ¶‰Ÿ·¡½–¬Â“ª»Ÿ²Éœ«È¬Éš©È›­É¯Ë›®Å¡´É¤ºÎ¡¹Î ¸ÏŸ¶Òž¶Í ¸Ë¯ÈدÆÕ¢¸Ì©¿×§ºÑ¨¸Ð°ÀÖ¨¹Ì²ÅÚ­ÃÛ­ÃÙ³Éß°Åà´Åæ­Âߨ¿Ù§¾Ø¤¹Ö¥¿Ú¨Âाܣ½Ý¢¼ÚŸ¹Ô´Ð®ÀÞ¯Áߧ¸Ù¨¹Úª»Þ¨¹Üª¸Ü©·Ù±¾à©·Ù¤²Ôš¯ÌžµÏ¤¼Ñ«ÃÖ¡¹Ð˜¯Ë˜¯Ë ¶Õ´Ð—®Ê“­Èš³Ñˆ¢½‚œµ…²“©½¥»ˆ¸}”°}–¶ƒš¶ƒ˜³€–®ƒ™±Š ¸…›³}“«ƒ•±Œžº‘¯{‘©x¥p†žm|›n€œm€™k~—l{˜gu’bmXfƒbq‹WgUhSf}H[tOakR`>UbC[eH]fF^hMdsPgtOfsOfuQewQdyNaxJ[j=OT1>CGMRfszqƒ{›z‘ {’£~‘¦‡›­…™«Šž°“¦»“¦½‹¹”§¾Ÿ³Å¯ÂÙ¡³Ï¦¹Ò¨¸Ò¡´Íš­Æ›±Éž´Ì¡·Í¤·Î¢¸Ì¡·Ë¶Ä¶Â¤½Ë¬ÅÕ«ÃÖ«Áמ¶Ëž¶Ë¬Âئ¹Ò®ÀÜ©»Ù¨¿Ù¬ÇݬÆߧ½Ü¨¿Û­ÄÞ©¿×ª½Ö¨½Ø§¾Ú§¾Ø¥½Ô¬ÇÛ«ÆØ­ÅÜ­Â߬ÁÞ§¹×©»Ù¢±Ðž­Ìš¨Ê°É³Çž´Ì¢·Ô˜¯Ë™°Ì¤»Õ«ÃÚ¨½Ø¨ºØ¦¸Ö›­Ë™­Í–¬Í—®Ê‹ »Œ¡¾Šž¾Œ£½Ž¦»§¾ˆ¸„œ³‚š¯…›³‡™·‰ž¹—®yŽ©„’´}Ž±~‘¸—ºz±x’­{–¬v§lžm‚h{”fyŽk|g{buŠ]p…Zm„Tj~Vl€Vi€Sc}N`lASZEWaHYhN^oO\pTdw\m€VjxQisZq~VjzVjzVj|VgvQ_j:DLì¼Zÿÿ›ÿÿ—îÝž¨—‹˜šžŒŸ¶„œ±‚³~™­‚š­„œ¯™¬v‘§x’­w’­u­r¨s¨tŒ£}¥o…›e|–f}—e|–f|’bvˆcw‰eu‹_u{m}Žu…–|‰›t„•yŠ›žz‡—u‚”Ž¢…”ª€§~Š¡„¤ƒ“¤’¡‹œ¦Š™¡ˆ•ž”ž¨š¤¬ ª²—¤«™¨° ¯µ«ºÀ«ºÀ®»ÂÂÐÒÕáßØßÛßãÛêîèòõòýÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¾½Â')/b[[ÿóïÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûÿÿôÿÿåÿÿàÿÿåÿÿÌÿÿ¶ÿÿÃÿÿ¼ÿÿ½ÿÿ±ÿÿ¸ÿÿ¼òô¶ÛݪÂÆ®¼Àó½Ã´ÆͱÂÑ©¼Ó¨»Ð²ÅÚ§»Í¢¶Æž´È˜°Ç™¯Ç™«Ç˜«Ä¨¸ÐŸ¯Âž©¼°Ÿ£Ã”‹Õ{oëdWç^RæXOËpAðÉtÿÿËÿÿäÿÿ×ÿÿÍÿÿ¯ÿ®w‘ƒ™¡ŠŸ¼„›·‚™µ„›·~“°–±ƒ–¯{‘©wŒ§sŠ¤n…¡r‰¥n‚¢p‚žl{•ix•jxšdwbuŠar…kxŠewo|Œu‚”{ˆœr~•uœy†š{ˆ˜{‰”ˆ—Ÿ…“ž‚€Ž™~Œ—˜‚‘™‹š¢‹™¤‡–ž¦“¢ª’¤«—¦¬ž«²£°·ª´¾¯¹Áµ¿ÇÅÍÑÐ××Þåååéìêïïô÷öýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿèÿÿ»}…9ÒßÿÿêÿÿÿÿÿñÿÿïÿÿäÿÿÕÿÿßÿÿüÿÿüÿÿöÿÿøÿÿèÿÿæÿÿàÿÿÐÿÿÇÿÿÁÿÿÀÿÿÃÿÿ¸ÿÿÁÿÿÅÿÿÆüý³ÓØžÄË ¼Åµ±½Éª¼Æ­ÇЧÀÌ©ÀÑŸ¶Çœ¯Ä˜®Â”ªÀš±¾«ÁǸµ¶¸š—Ð{ìfdî]Xö[RÕaAÒ„Nÿò¸ÿÿÞÿÿâÿÿæÿÿÛÿÿÓÿÿÁÿÿœÿù§æÈ•”‘}‡›©’¨¼ƒ˜³„›·‚˜·‚˜°‡š¯{Ž§xŠ¨r‡¢mƒ›r„ r¡q~ r|Ÿo~i~›dy–av“_ubuŒbz„q…“q‚‘|‰™p}s€wˆ”}›xŠ”‰›¢„“›…’›~•˜š~›…“ Š–¤Š–¢‰–ŸŸ§¨Ÿ«·¥®½©¯½¨¬»ºÀж¾Ò¼ÁÔÍÑâäåîøõøóò÷ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿÿÿÿÿÿÿûÿÿóÿÿðÿÿáÿÿÕÿÿãÿÿèÿÿàÿÿçÿÿéÿÿåÿÿæÿÿÝÿÿÚÿÿÐÿÿÏÿÿÌÿÿÈÿÿÀÿÿ¶ÿÿ·ÿÿ§ÿÿ±ÿÿµÿÿ¹èîžÁÆŒ´·’£«¤«·Î¨»Ð™±Æ•­À•­À ­²º»´ÐŸ—àztçhf÷^bë\XßZQу]ÿý¾ÿÿÛÿÿâÿÿàÿÿÞÿÿÙÿÿÕÿÿÍÿÿÇÿöžÿë“èÓ•{“–’©€–ª|”§y£x‹ q„™y‰¡sˆ£n„£l€¢m~£m£u‰«n‚¢o„¡lƒc}–d|“awh|Št†’m}Œvƒ•t•s–xˆ™€Ÿ{Œ˜¨ˆ–¡š|Š•zˆ“€’—{„“™‰•¡ˆ—Ÿž¤”¡¨’œ¤™ ©¥ª¶§®·®¸À°ºÀµ¿ÅÄÊÍÚÝÜðóðÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷ÿÿíÚÔ¢¾³|ÿÿâÿÿîÿÿÝÿÿßÿÿçÿÿñÿÿãÿÿæÿÿÑÿÿÌÿÿÉÿÿÀÿÿÆÿÿÒÿÿÅÿÿ»ÿÿÂþÿºÿÿ¹þÿ®üÿ«ÿÿ²þÿµÆň©¨„«ª¡¢¥¢ ¤©ÂžÔ‡„èz{øjoúehö[[ÐeGÆŠNÿø»ÿÿÞÿÿàÿÿâÿÿÛÿÿÕÿÿÓÿÿÓÿÿÍÿÿÇÿÿ¹úóÿùùÞ~“†[Œ˜…Š€Œ¥ˆ—±Ž«v‰ z¤w£q„pƒœsƒor„¢wŠ£w‡j}”aw`xe|–bz„vˆ”rƒ’r‚“r‚‘u…”yŠ–‚›’ž…•¤ˆ™¥‰—¤}‹˜|ˆ–†“œ‚”ˆ•œˆ’œŽ›¢”¡¨œ¦¬£ª±¤®´§¯¡«³°·Â°ºÂ·ÄÉÐØÚåêêôùùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöÿÿùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïÿÿâøÿ°ÿÿ«ÿÿÍÿÿéÿÿÜÿÿÜÿÿáÿÿâÿÿØÿÿÑÿÿÓÿÿÎÿÿ½ÿÿÈÿÿËÿÿÂÿÿÂüÿ¸ÿÿÁÿÿÄÿÿºÿÿºÿÿ«ÿÿ¤ÿÿ¦ÿÿ¡ÿÿÁÿü×äÔº·¥™ÉŠ€èuövwûeoñ_cèWVÑ{Sÿø®ÿÿ×ÿÿæÿÿâÿÿÞÿÿÙÿÿ×ÿÿÓÿÿÏÿÿÇÿÿÁÿÿ»ÿÿ·ýí|ÿþ…óߟ‹…€‰Ž˜‚’ª‚’ª~Ž¦r…œ{‘©y§s‰¡v‰ y‰Ÿo‚™n€œq„™„•¤p„”l‚–h~’f|’Yrwp…Žr„t„“rƒt‚~Œ—…“žzŒ“€“š€’œœ€‘›€Ž™}Œ”‚˜Š”žŠ‘œ•Ÿ¥–¡¤¢°²ª¸º©³¹¨­¹¦­¶³½Ã´ÁÆ·Ä˾ÈÎÙßä÷üüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúûôÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöÿÿôÿÿëÿÿíÿÿæÿÿÐÿÿÝÿÿÑÿÿÀÿÿÅÿÿÇþÿ¸ÿÿËÿÿÁýÿ¹ÿÿ¾ÿÿÅÿÿ¼ÿÿ´ÿÿµþÿ­ÿÿªþÿ¥öýøÿŸ÷ü˜ùû–ÿóŸñ«gñ‡dÿvsühhý`cßaNÛySÿïºÿÿÙÿÿæÿÿòÿÿàÿÿÏÿÿÉÿÿÃÿÿ¿ÿÿ»ÿÿ·ÿÿµÿÿ¿ÿÿÅÿÿ£þçtÿü¦÷ÖŸ„s…Œ¥‰•¬y‰¡w‡Ÿ}¥{‘§vŽ£n„œt†¢sˆ£lžg~˜n†h€•i•i“fyŽ_uysŽlz‡v„‘uƒw„”Œ…¡ƒŽŸƒ‘žŽž{ˆœ€y‡”zˆ•|‰™…“ ‘Ÿªžª¶¡ª·£ª³¥ª²Ÿ§«ªµ¸¸ÃĽÉǹÄžÅÌËÑÔêíîøûüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿóÿÿøÿÿøÿÿòÿÿæÿÿëÿÿíÿÿñÿÿøÿÿëÿÿÖÿÿÌÿÿÅÿÿÁÿÿ³ÿÿ´ÿÿÃÿÿ·þÿ²ÿÿµÿÿ´ÿÿ·ÿÿ·ÿÿ«üÿ§ÿÿªÿÿ©þûšÿÿ›ú¿|òˆgþoÿnnñb\æ]QÞ‰aÿü¼ÿÿàÿÿîÿÿîÿÿîÿÿàÿÿÓÿÿÅÿÿ¸ÿÿ³ÿÿ­ÿÿ¬ÿÿ«ÿÿ·ÿÿÅÿÿÃÿÿ±ýêŒÿû›èѧŒŠ†Š›u‹£rŠŸ}˜¬y”¦w’¤tŒŸp†šo‡šh€“o‡šj‚—dz’fx”g|—dy”a{„p|“mzŒuƒy†–{†™~‹›~‹›œ›ƒŽŸ}ˆ{†—xu‚‹x…Œš¢¥¬·™£­™¥‘ž§›¥­ž¨²¢«º£­³³¿»ÁÊÅÍÕÎÓÙÒïðëññóÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿÿÿÿÿÿÿÿÿÿøÿÿóÿÿóÿÿôÿÿòÿÿðÿÿïÿÿçÿÿçÿÿéÿÿÛÿÿâÿÿÞÿÿÏÿÿÈÿÿ¾ÿÿÇÿÿ¶ÿÿ³ÿÿ´ÿÿ¹ÿÿ³ÿÿ´ÿÿ°ÿÿ¯ÿÿ¶ÿÿ´ÿÿ¬ÿ÷žÿã¤ÿŸ~ðscúbaÚbPãŒgÿûÉÿÿÛÿÿìÿÿüÿÿòÿÿèÿÿÞÿÿÓÿÿÇÿÿ»ÿÿµÿÿ¶ÿÿ³ÿÿ³ÿÿ¹ÿÿÁÿÿÃÿÿÅÿÿ©ÿåzÿõ©Þºƒ|q|¤|’¦|”©y‘¤z’¥—¬rŠ¡oŠ hƒ™l‡o‡žg–_vbw’fu”fw†o€“k|‹yŠ”}‹˜z…–~Š˜‡Ÿ…‘‚Žš}‹˜{ˆ˜zˆ•}‰•Ž“Š•–¢ª¬ž¤©”ž¦‘©›¥¯§®¹ª¯·¦¨®§¬¬ª¯­µ»´ÈÎÅÚÞÖíîéôôôÛÚßÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿôÿÿîÿÿíÿÿôÿÿöÿÿúÿÿùÿÿöÿÿåÿÿÕÿÿÜÿÿÛÿÿÍÿÿÐÿÿÕÿÿÐÿÿÏÿÿÏÿÿ½ÿÿ¹ÿÿÂÿÿÇÿÿ¿ÿÿºÿÿÁÿÿºÿÿ¸ÿÿºÿÿµÿÿ¯ÿ¹ƒóu]ïm^ä_XßbÿöªÿÿÕÿÿæÿÿîÿÿøÿÿðÿÿèÿÿäÿÿâÿÿ×ÿÿÍÿÿ¿ÿÿ³ÿÿµÿÿ·ÿÿÁÿÿËÿÿÏÿÿÕÿÿÉÿÿ²ÿå…ÿñ‘¿¨~ƒ~‹‡ŒŸ€ªz¦z’§y”¨x“§o‡œi•o‡šm…˜kƒ–e{‘`vŒf|’_t}|‡˜p~‹v„‘zˆ“w…{‡“†œŒ‘¤‚…|„–‹™{‰”€Ž™„‘˜š ¬º¼”¤¥¡°´—¦¬Œ›¡Š— ”™—¬©Ÿ»¸®Â½³Á¾¶ÈÆÂÐÐÒáßéûýÿûÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿìÿÿóÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿõÿÿûÿÿòÿÿæÿÿæÿÿêÿÿéÿÿîÿÿíÿÿèÿÿÛÿÿÚÿÿÕÿÿÙÿÿÒÿÿÖþÿÅþÿÇÿÿÄÿÿÃÿÿ¸ÿÿ³ÿÿ¶ÿÿ¼ÿÿ·ÿÿªÿÿ®ÿÿ±ÿÿ°þÿ°ÿÿ²þÆ}áyUýefàkRØ„Sÿí¯ÿÿÑÿÿÞÿÿìÿÿæÿÿâÿÿâÿÿâÿÿâÿÿäÿÿâÿÿâÿÿÕÿÿÉÿÿÅÿÿÃÿÿÇÿÿËÿÿÍÿÿÑÿÿÏÿÿÏÿÿµÿå†ÿ𱶙|…~|¨z¦u¢z’§x¥u‹¡n˜n˜p€šq‚•gw†ev‰jz’bw€r…œpƒ˜k{‘s€€‰–‹—„œƒŒ™{‘~„’ƒ‡–€‡’‰‘ˆ’£¨¦ª°³­²¼ ¦´—«ˆ•zŠ„„„µ®§¼¶¨¼´ Ã¾§ØÔºÞÛÃëêÔûùóÿüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿü÷ÿÿ÷ÿÿèÿÿöÿÿþÿÿÿÿÿÿÿÿüÿÿîÿÿîÿÿçÿÿáÿÿÚÿÿÛÿÿïÿÿßÿÿãÿÿÛÿÿÙÿÿÚÿÿÓÿÿÏÿÿÔÿÿØÿÿÒÿÿÅÿÿÀÿÿÄÿÿÀÿÿ¶ÿÿ±ÿÿ¶ÿÿ®ÿÿ¶ÿÿ­ÿÿ²ÿÿÃÿÿ¹ÿÿ§ÿÊësaèk]èe[Ô„Zÿè ÿÿÕÿÿâÿÿäÿÿèÿÿâÿÿÛÿÿÛÿÿÛÿÿÞÿÿàÿÿæÿÿìÿÿâÿÿÙÿÿÓÿÿÍÿÿËÿÿËÿÿÉÿÿÉÿÿÍÿÿÑÿÿÍÿÿ·ÿè•ÿë•¥”sŒ¡€¡v’¡qŽrŽ r¡s‰¡n„œpƒœo…™hi|‘o™dy„k‘p’iyˆq’|‰{ˆ˜}‹–x…Žyƒ‹~‹”{‰–y‡”t€Ž†ž«±Á¥¬µ²¸½–ž †ŽˆŽ‡‘…—’†¹¬£µ«£ª£œ²©œ¾³¢É½¯ìßÖüóæõïáóðæÿÿùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿÚÿÿäÿÿäÿÿêÿÿðÿÿèÿÿòÿÿòÿÿôÿÿñÿÿõÿÿöÿÿðÿÿæÿÿÝÿÿäÿÿâÿÿÞÿÿæÿÿ×ÿÿÒÿÿÄÿÿ¾ÿÿºÿÿÈÿÿÌÿÿÆóû«þÿ¶ÿÿ³ÿÿ®ýÿ¨ÿÿ²ýÿ±üÿ¸þÿ¸ÿÿ¸ÿÿ¸ÿÕ‘á[óbaÜnVÓŠYÿè¯ÿÿÞÿÿâÿÿæÿÿÛÿÿÓÿÿÓÿÿÕÿÿÑÿÿÏÿÿÓÿÿÙÿÿàÿÿèÿÿèÿÿèÿÿàÿÿÙÿÿ×ÿÿÕÿÿÕÿÿ×ÿÿÓÿÿÑÿÿÑÿÿÑÿÿ±ÿíû嬛Š{ƒŠŠrŽ o‹sŽ p†žs‚¡q„r…œpƒšx‹¤o‚—dxˆdz€k{Žp€‘o|Žp‚Žo„z‹•ƒŒ›t€Œq}‰€Ž™{‰”{‰”x„’¤­¨¬±¬°µ®±¹”›¢ƒ“§®ª§¬ŸŸŸ®«—¨¤“¡Ž§ •µ¨¡Ã¶­½±¥Â¶¨Í¿²ÞÓÂéáÍòíáÿûûÿüýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿîÿÿÞÿÿØþÿÑÿÿæÿÿêÿÿæÿÿîÿÿèÿÿëÿÿéÿÿìÿÿãÿÿéÿÿïÿÿîÿÿèÿÿÝÿÿàÿÿÕÿÿÓÿÿÈÿÿÂÿÿ½ÿÿ¹ÿÿ¶ÿÿ¬ÿÿ³ÿÿµÿÿ¼ÿÿµýÿ®ÿÿµÿÿÅÿÿÕÿÿÃÿÿ­ÿÔ‘ò‚ZãmNàbOÒ‹Wÿó ÿÿ×ÿÿìÿÿäÿÿÞÿÿÓÿÿÉÿÿËÿÿÍÿÿÉÿÿÅÿÿËÿÿÑÿÿÙÿÿâÿÿæÿÿìÿÿæÿÿàÿÿÛÿÿÙÿÿÙÿÿÛÿÿ×ÿÿÕÿÿÕÿÿ×ÿÿËÿÿ¬ÿó¥îÍ‘”‡s‰xˆ—n…’lƒ’v‰žw‡Ÿw† m}—q€q„gz“bw€lyly‹mx‹r‘t„—zŠ™~›sŒo{‡uƒŽw…~Š–†œ©³»§¯³ªµ¶›¦§Š–”Š–”¡¨¨›žŸ¥£Ÿ¨£™ ™¤š’¢œŒ«¦‘¹±Ÿµ©º±¢½¸¥ÉÁ¯ÚͽåÚÇçÜÇêáÒòèàõïìÿÿÿÿÿÿÿÿÿõ÷ÙÿÿäÿÿìÿÿôÿÿìÿÿäÿÿêÿÿìÿÿäÿÿöÿÿøÿÿôÿÿîÿÿÓÿþÑÿÿìÿÿîÿÿèÿÿèÿÿëÿÿßÿÿÜÿÿÝÿÿßÿÿÒÿÿÈÿÿ·ÿÿ°ÿÿ±ÿÿ®ÿÿ·õû­÷ÿ­ÿÿ¶ÿÿ²ÿÿ»ÿÿ­ÿÕ„ì‰V÷jWÒnDÔ•Xÿô§ÿÿÅÿÿ×ÿÿêÿÿäÿÿàÿÿÏÿÿÁÿÿÃÿÿÅÿÿÅÿÿÇÿÿÉÿÿÍÿÿÙÿÿèÿÿèÿÿèÿÿèÿÿêÿÿÞÿÿÑÿÿÍÿÿËÿÿÍÿÿÑÿÿÑÿÿÓÿÿÉÿÿÁÿÿ¢ÿë‰Í½‚…r„‰…s„“x‰˜~ŽŸv‡šn–mƒ™h}˜`xhƒ™j‡gq‰hu‡n{‹p‚Žq†r…Œu‡Žu†rs„Žs…Œz‰‘‹•Ÿª±º¥¨°±¸Á’œ¦…Œ“•› › œ’—Œ¬« ª£˜¥›“¤—’§•¬¢˜ª¡”®¥–®¨˜±«¾µ¦ÏijÝоÜ̹ØË·ÖɵØÓÀëêÝúøçÿúåÿÿ÷ÿÿúÿÿôÿÿðÿÿåÿÿÔûÿÕöùÖÿÿøÿÿüÿÿöÿÿðÿÿáÿÿÙÿÿâÿÿíÿÿèÿÿÞÿÿÖÿÿàÿÿÞÿÿÉÿÿËÿÿàÿÿÔÿÿÂÿÿ¾ÿÿ³ÿÿ±ÿÿ³ÿÿ¿ÿÿ·ÿÿ³ÿÿ·ÿÿ²ÿÿ¬ÿ×èŽZâqPìcWèbÿõ§ÿÿÍÿÿÙÿÿÞÿÿäÿÿâÿÿàÿÿÑÿÿÅÿÿÇÿÿÉÿÿÇÿÿÇÿÿÉÿÿÍÿÿ×ÿÿâÿÿäÿÿèÿÿîÿÿôÿÿäÿÿÕÿÿÍÿÿÅÿÿÉÿÿÏÿÿÑÿÿÓÿÿÑÿÿÑÿÿÅÿÿ¢ÿðš÷ݘ¥›vjmjy…w…’o€“o‚›g}•h~–j‚—l‡›i‡Šiqƒiuƒlz‡t‘vƒ•u‚’{‡•|‡˜w‚—t‘w…’}‹–—£¯š©±š©¯›ª®‹˜–£¦°š™ ™“š¦ŸŸ¦œ–£œ“¢›¨¢”¨¢’¤¡£ Œ«§˜±ª£²¨ž·«É¼ªÎ¾«ÒƯØ̵ÝѸèÜÃåã»üÿÌÿÿÝÿÿËÿÿÑÿÿçÿÿÞÿÿõÿÿôÿÿðÿÿôÿÿõÿÿêÿÿèÿÿãÿÿæÿÿäÿÿßÿÿÜÿÿàÿÿßÿÿÕÿÿÌÿÿÅÿÿÅÿÿ½ÿÿºýÿ¼ÿÿ»ÿÿ»úÿ¥þÿ§ÿÿ¶ÿÿ»ÿÿ·ÿÿ¹ÿöžüÕ~è‘^ój^ÞlRé‹fÿé³ÿÿÓÿÿÛÿÿæÿÿäÿÿäÿÿàÿÿÞÿÿÕÿÿÏÿÿÉÿÿÅÿÿÉÿÿÍÿÿÛÿÿæÈĨƒyq®ªŽÿÿìÿÿðÿÿôÿÿèÿÿÛÿÿÍÿÿÁÿÿÁÿÿÁÿÿÉÿÿÓÿÿÓÿÿÕÿÿÍÿÿÇÿÿ©ÿê“ÿõ¡ÿîŸðáŸÂ¼Š€lfkwjuŠm|›n€œh{”g|‡l|‹m~ŠsŒn‹s„•s„“y‰˜z‹—uƒŽr‰w„€Š”ž¥°—ž©Ÿ¥³”¡ª…”œŽ› ™¤¥”—–¡™—¢›”£™¤—’¡”¤™–¨¡˜¥Ÿ‘ª¡’µ¬Ÿ´ª¢²¥œ±£˜¹­ŸÂ·¦É¾«ÔdzÛÏ´ÚÌ­ÓÍ›ÿÿ½øü½ÿÿÑÿÿæÿÿîÿÿôÿÿúÿÿòÿÿÛÿÿÜÿÿéÿÿìÿÿâÿÿßÿÿÓÿÿÔÿÿèÿÿêÿÿÞÿÿÐÿÿÇÿÿÁÿÿÉÿÿÆÿÿ¼ÿÿ´ÿÿ±ÿÿµÿÿ©ÿÿ©ÿÿ¬ÿÿ´ÿÿÀÿÿµÿñ’ó¸uï‚`ëp_îefæŒhÿäŸÿÿÓÿÿÞÿÿâÿÿèÿÿâÿÿÛÿÿÛÿÿÛÿÿÕÿÿÏÿÿÏÿÿÑÿÿ×ÿÿÞÿÿðáÆÍÔ³ÓÚ²êͯËÒ¾ÀÿÿþÿÿîÿÿêÿÿæÿÿÕÿÿÅÿÿÁÿÿ¿ÿÿÃÿÿÉÿÿËÿÿÏÿÿÍÿÿÍÿÿÃÿÿ ôë…ÿü”ÿÿ™ÿøÿõùæŸÆºŠŽ‡nffdejhwo€‘rƒ”t…˜k|o€‘q‚‘t…‘wˆ’sŒs‚ˆ}ŽŠ˜š›¦©• £¤®´Œ™ „‘š‰–›™¤§”’œš”š—ž—Œš”†œ–ˆ ™Žž—˜Ž¢“¦¢‘°«–±¬™²©œ²©œ¼¯¦É½±Å·¬Ê½«ÍÁªâÝ´ÿÿàÿÿÖÿÿÛÿÿ×ÿÿÁÿÿÇÿÿ¾öûÁÿÿÚÿÿêÿÿëÿÿÙÿÿÐÿÿÈýÿÁÿÿÙÿÿäÿÿÖÿÿÎÿÿ¸ÿÿºÿÿ»ÿÿ±ÿÿ¶ÿÿÀÿÿ½ÿÿÀÿÿ½ÿÿ´ÿÿ´ÿÿµÿÿ®ÿÿ«ÿê•ñ­fë^ûikçrYç_ÿé¤ÿÿÅÿÿÑÿÿÞÿÿÙÿÿÕÿÿÕÿÿÕÿÿ×ÿÿÙÿÿÓÿÿÍÿÿÏÿÿÓÿÿèÿÿòâÃÛܯôÕ«ïÌ¢æÞØɧÙξÊÿÿþÿÿòÿÿæÿÿàÿÿÙÿÿÍÿÿÃÿÿÅÿÿÇÿÿÇÿÿÇÿÿËÿÿÏÿÿÉÿÿÅÿÿ¬ôåˆÿÿ•ÿÿ’ÿÿÿÿŽÿÿ—ÿö–ÿë›ÝÈŠ©to}Šiyˆl|m‹o‚‰pƒŠu†wˆ”o|Œpz‹•‘ ¦• £Ÿ­¯¡®³‰–‚Žš’š˜˜šŠ‰›—’™”Šœ–ˆ›•…¤›Œ£š¤—Ž¢˜Ž¥ž“ª¥™«¨œ²°¡´°Ÿ¯©›°£š¾µ¦¿·¥Á¸™Á¸Œëê¨ùÿ©ÿÿ¸þÿ¾ùûÄÿÿèÿÿîÿÿîÿÿæÿÿàÿÿ×ÿÿÌÿÿ×ÿÿçÿÿæÿÿæÿÿäÿÿáÿÿÞÿÿæÿÿÒÿÿÌÿÿÆÿÿ·ÿÿ½ÿÿÈÿÿÂÿÿÀÿÿ»ÿÿ¶ÿÿ³ÿÿ¦ÿÿ¤ýå‹ð§rôwiëk`éd]ížkÿù›ÿÿÅÿÿÓÿÿÕÿÿ×ÿÿÑÿÿÍÿÿÏÿÿÑÿÿÑÿÿÑÿÿÏÿÿÏÿÿÕÿÿÛÿÿîÔ´ÑÈ ÔÌ›æÍ¡íΣòÆžéÊ£ëƬÔɹÅÿÿüÿÿÞÿÿÞÿÿÞÿÿÑÿÿÅÿÿÃÿÿÃÿÿ½ÿÿ·ÿÿ½ÿÿÅÿÿÉÿÿÏÿÿÇÿÿ¬îëˆýþ“ÿÿ•úÿúÿ‘üÿ“öõˆÿÿ“ÿö±Y`^;IKct~rƒwˆ”t…‘~‹›r‚“m~‘p}ƒŒ›š¢™¤¥œ©®“¡¬˜Ž—‘—œŒ‰›•‡š”„œ—„£š©œ•¨›’§š‘¦™¯¢™«¥—§£”¬¦–´«œ´¬š²ª˜Á¶£¿² ½²”¿µŽÿÿËÿÿÄÿÿÎÿÿÛÿÿßÿÿÞÿÿÔÿÿËÿÿÍÿÿäÿÿìÿÿæÿÿÝÿÿÆÿÿÃÿÿÅÿÿËÿÿÎÿÿÆÿÿÇÿÿÀÿÿ¹ÿÿÅÿÿÉÿÿÄÿÿ¼ÿÿÀÿÿ³ÿÿ®ÿÿ©ÿï ì¸|ÿºˆôhôxeÿijÝnQè hÿò§ÿÿÃÿÿÏÿÿÞÿÿÞÿÿÞÿÿÕÿÿÏÿÿÍÿÿÍÿÿÍÿÿÍÿÿÑÿÿÕÿÿæÿÿíßÅ×Ó©ëÈžåÅšæÄšãÇœåÈœè΢óͨíȬåɾ½ÿÿäÿÿâÿÿâÿÿ×ÿÿÏÿÿÇÿÿÁÿÿ»ÿÿ·ÿÿ»ÿÿ¿ÿÿÃÿÿÇÿÿÅÿÿÅÿÿ¨õïŠüú”ÿÿœÿÿœÿÿ›þþšÿÿ›üø°ÿÿÿÿÿÿr}~L[cu…–t…–}ŽŸt‰’mƒ‡o~„”Ÿ’™¤•›©•¡¯Œ™©ˆ”¢™¦˜ ¢‚ˆ‹ƒ‹ˆ~•ˆ˜Ž£œ‘¥Ÿ‘¨¢’­¤•´¦›³ª¬¥š©£•¬¦–®©–´¬˜¹±·¬™´®ŽÒѤÿÿÜÿÿËþÿÀÿÿÆýÿÁÿÿÓÿÿÓÿÿÛÿÿÎÿÿÉÿÿ¿÷ý­ÿÿ¾ÿÿÁÿÿÉÿÿØÿÿÒÿÿÍÿÿ¹ÿÿ±ÿÿ´ÿÿÀÿÿ¿ÿÿµÿÿ³ÿÿ»ÿÿÄÿÿÃÿÿ»ÿë§ù¨z÷}føpaÿhbómZåoRî©iÿø–ÿÿÇÿÿÙÿÿÙÿÿÙÿÿÓÿÿÍÿÿËÿÿÉÿÿÇÿÿÇÿÿÇÿÿÇÿÿÑÿÿÞÿÿõãÃàÓ¬äبýÍ¢óÃ쾙ཙۼ•ÛÄšãÇ æɤ鼧ÃÌÇ»ÿÿðÿÿÛÿÿÙÿÿÙÿÿÓÿÿÍÿÿÉÿÿÇÿÿÃÿÿ¿ÿÿ¿ÿÿÁÿÿÅÿÿËÿÿÅÿÿ§õòÿý•ÿÿ•ýû‘ñóƒýÿ‹ýú©ÿÿÿÿÿÿÿÿÿäèùXa‚m}r…Œx‰“w…’‹—’›¨Žš¦Œ˜¦’ «‹š¢Ž“Œ—˜™œ™Š…}‹ˆ|Ž‹‘…˜•‹ ™¤Ÿ•§¢š«¤™²©š³®›¯ª—©£“¬¦˜«¦“±©•¶¬”º®•½¸øû£ÿÿµÿÿ³ÿÿÃÿÿÎÿÿÈÿÿÅÿÿÄþÿ»ÿÿ¸ÿÿ¸ÿÿÉÿÿÕÿÿ×ÿÿÄÿÿ¼ÿÿ¾ÿÿ¸ÿÿ·ÿÿºÿÿÇÿÿÇÿÿÃÿÿ²ÿÿ¨ÿÿ¨ÿÿ¸ÿÿ¯ÿý¶ÿç¶ÿ®–û„zþinød`ôbVÚx@î¼[ÿù›ÿÿÃÿÿÑÿÿàÿÿÙÿÿÕÿÿÍÿÿÇÿÿÉÿÿÍÿÿÉÿÿÇÿÿÍÿÿÓÿÿèÿÿîåÅàÖ«òÔ¨ôÏ£ôШøÏ©øÈ¢ìÄŸæ¿ã¼šà½›ßŠ幜ӭ–ÀÏŽÿÿäÿÿÛÿÿÓÿÿÏÿÿÍÿÿÉÿÿÅÿÿÁÿÿ½ÿÿ»ÿÿ¹ÿÿ»ÿÿ¿ÿÿ¹ÿÿ±ÿÿ•øö‡ÿÿ“ÿÿ’þýŽúúˆóð¡ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿitwq€}x‚ˆ‚ˆ–ˆŽž“§Š¢†Ž …‘Ÿ|Š•|‹“ˆ•œ†‹‡ˆ…y’Ž}’z‰y–€“Œƒ“‹‡¡š§¡‘ª¤”¬¦˜°«˜¯ª“®©’®©”±¬™²¬œ°¨–¸«™Â¼Šöõ¥üÿµÿÿÏÿÿÏÿÿÒÿÿÄùþµüÿºÿÿÌÿÿËÿÿ¿ÿÿÇÿÿÀøþ°úÿ°ùÿ¯ÿÿÂÿÿÈÿÿÉÿÿÄÿÿ»üÿ¬øþ£ÿÿ²ÿÿ¹ÿÿ°ÿÿ¬ÿú¥ÿï¢ÿ°†ÿ}wÿwuÿdiãiRÙ~OÿÓ‚ÿÿ¡ÿÿÅÿÿÛÿÿÞÿÿâÿÿÛÿÿÕÿÿÏÿÿÉÿÿËÿÿÏÿÿÉÿÿÅÿÿÍÿÿ×ÿÿìèÄàÔ­áÒ§öÒªøÍ¥õϤõѤøФõ΢ñšèÅŸìÃêÄžíÉ£íÅ åÁ®ÂØÔºÿÿèÿÿÕÿÿÑÿÿÏÿÿÇÿÿÁÿÿ½ÿÿ»ÿÿ»ÿÿ½ÿÿ¿ÿÿÁÿÿ½ÿÿ·ÿÿ·ýý›öõ–ÿÿ¦ûü•úþýû®ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿˆ“”v„}‡„Ž”z„Š‰“Œ’¢€‰–‹—ˆ’š—¢‚…„ˆ†‚Š‡‹†z‰†z‘Ž‚Ž€‹Š›–Š©‘ª¡’©£“¦£¢¡¢Ÿ‰©¤ª¥Žª¥³©¾¯’ÝÕ¦ÿÿÉÿÿÎÿÿÌÿÿÂþÿ·êð¢ÿÿ¹ÿÿÈÿÿÝÿÿßÿÿÓÿÿÃÿÿ³ÿÿ±ÿÿ¹ÿÿ´ÿÿ²ÿÿ§ÿÿ¥öý›þÿ¥ÿÿ«ÿÿ­ÿÿ¥þÿŸúü—ÿþ›ÿñ¯ÿ´–ë€nýxs÷noïajØaýØÿÿ¼ÿÿÏÿÿÍÿÿÍÿÿÑÿÿ×ÿÿÕÿÿÓÿÿÍÿÿÉÿÿÉÿÿÉÿÿÅÿÿÁÿÿÛÿûßâÄÕÑ¥ãÕ¨ëݯ÷ТìÕ£ôÌ ïÉžíÌ¡ðϤõÌ¡ðÉžíÁ–âÈœèÉìÏ ò˦àÀ§ÈáÖÅÿÿÙÿÿÍÿÿÃÿÿ¿ÿÿ»ÿÿ¹ÿÿ¹ÿÿ»ÿÿ¿ÿÿ¿ÿÿ¿ÿÿ¿ÿÿ¿ÿÿºÿÿ¬õöóïŽÿÿÿÿŸÿýµÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŠ•˜ˆ•œ¦Œ•¢•œ§•˜¢‡Œ˜…”…ˆ’‚„Š|yz‡|…€x‰„zŒ‰}’ƒ™˜‘‡–“‰¡œ¡Ž šŠš–… œ‹¢Ÿ‹ª¥©¤‘ª¤”³¨“¸©‘ðê¶õö¨Þàôó£ò÷¥ÿÿ·ÿÿ¿ÿÿÄÿÿÆÿÿÅüÿºòú®ùÿ³üÿ´ÿÿÅÿÿÎÿÿ½ÿÿ©ëòÿÿ¨ÿÿºÿÿµÿÿ¬ùü¢îõ—îõ•þÿ£ÿÿ°ùءﳚÿôôvvèjjÝ_aî¨{ÿÿªÿÿËÿÿ×ÿÿÓÿÿÑÿÿÏÿÿÏÿÿÑÿÿÓÿÿÏÿÿËÿÿËÿÿÍÿÿËÿÿÉÿÿØåÊÈѬÍÝ«ðÒ¡êÄ•âÊžíФõÌ¡ðϤóΣòФõÏ£òÇ›çÁ–ß¿”ÝÈéÌ¡òÄŸäĤ޻­«ôø¹ÿÿÏÿÿÁÿÿ¿ÿÿ½ÿÿ¼ÿÿ½ÿÿ¿ÿÿÃÿÿÁÿÿ¿ÿÿ¼ÿÿ»ÿÿ·ÿÿµÿÿ©õò‘ýý™÷÷“÷ó©ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõøùÿÿÿÔÝÚ‰˜•‹™›‹˜¡Œ™¢˜¥~‡”‚ˆ–ƒ‰Ž|~wxs‚wƒ~v‡€yŒ…|’‹‚”‡Žˆƒ•†™’‡™“…—Ž™Š¡ž’¡ž’©¤š¨£—¨¡–²¬ŠÃ¼†éçžééêñ‘ÿÿ©ÿÿ«ÿÿ²ÿÿµÿÿ¼ýÿµõü©ÿÿ·ÿÿ°ÿÿÂÿÿÊÿÿÂûÿ½òø¬ùý®þÿ¶ÿÿÅÿÿÍÿÿÓþÿÙÿÿêÿÿøÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿáͼ€eá•tÿßœÿÿµÿÿÉÿÿ×ÿÿ×ÿÿ×ÿÿÏÿÿÇÿÿÍÿÿÕÿÿÑÿÿÏÿÿÉÿÿÅÿÿÓÿÿÓçÑÏÍ¥ÙÓªçÊŸæÊŸèÏ£òÓ§øΡ÷Ñ¥öÏ£ïÆšéÆšëÍ¢îË¡êÇœèÇ›êÄšãÅžäÇ¡ä̦éŭǺ®¢ÿÿÍÿÿÅÿÿÁÿÿ¾ÿÿ½ÿÿºÿÿ¿ÿÿ¿ÿÿ·ÿÿªÿÿ¨ÿÿ¬ÿÿ±ÿÿ±ÿÿ¬îé’öõ–ÿÿžþù´ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿËÆÕŸ½Œ‘¨‰•£‹˜ª‰•¬}ˆ‡›‚‡‘uxwwxs~{s}zr„w†y†‘‡‘ƒ‘Šƒ“Ž„’ƒš“Œ¢›’¤’ ›¤¡•ª¦•®©”­¥}ÙЖÿÿºÿÿ°ÿÿ¶ÿÿºÿÿ¼ÿÿÅÿÿÂÿÿÉÿÿºÿÿ¹ÿÿ¿ÿÿºüÿ¾þÿËôöÏþýéÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ½¦•ãÈÿÿ»ÿÿ¹ÿÿÉÿÿ×ÿÿ×ÿÿ×ÿÿÓÿÿÑÿÿÏÿÿÏÿÿÏÿÿÏÿÿËÿÿÉÿÿÙëÕÁÍ«ÂÖ©êË¢äÄãÆœãÐ¥îÓ§øΠùÌ ôÍ¥óϤð΢îÍ¡ðÉîÇœíÇ›ïÛéÄåÇžâÌ¢âɨ׺¡À´ªŽÿÿ´ÿÿ¾ÿÿ´ÿÿ±ÿÿ¯ÿÿ·ÿÿ»ÿÿ³ÿÿ¦ÿÿªÿÿ°ÿÿ¶ÿÿ³ÿÿ©îâúò™ûóšüð¯ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÃÉ̵Ãņ“š–¥Ž–¨„Œ¢ƒˆ›†ˆ™}€ˆkno{xwyv}wryu„}vŠƒ|Šƒz‡€w‡‚xˆ~’ƒ—’ˆŸšŽ¤ž§£”­¨œ®¦”°¤©š‚Þ˲àÖºîìÏûýÔæì¸ÿÿÍýÿÆÿÿÖÿÿàÿÿíÿÿüÿÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿàÚ×ô¹¾¨¶¶«–¶·~ÿÿ´ÿÿ°ÿÿ¿ÿÿÉÿÿËÿÿÏÿÿÏÿÿÑÿÿÑÿÿÑÿÿÏÿÿÏÿÿÃÿÿ¹ÿÿÞ競”­ÌŸàÌžæÅ–è¿“â—æ̤òÉ£òÆ íÇŸíÇŸêˤìÌ¢ë΢îÇœèÄœçÇ æÇ¡äÆ ãÇžâÅ£×À¦Ê¼°•ùý ÿÿµÿÿ¦ÿÿ©ÿÿ«ÿÿ«ÿÿ­ÿÿ¥ÿÿœÿÿžÿÿ¤ÿÿ¨ÿÿ©ÿÿ¤äÙ‘ý÷ ýú”üõ®ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ±´³·º»‘”œ•—¦¡¤®±²»†‹•‰{~†onsttrzxrzvq€zw€|y€|y‚w†u‡€u€vnxrd|vfƒ~k”z¥¡‡¶²”À¾£ÙÖÂõôçÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûûûíëçëæÞæá××ÒÆÞÜÍÚØÇÅò§¥–“‰ƒœ‡ŒÆ´±Œ‚ÒÎÿÿ¢ÿÿ®ÿÿ¶ÿÿÁÿÿËÿÿÉÿÿÉÿÿËÿÿÏÿÿËÿÿÉÿÿÇÿÿÇÿÿ×ÿÿ趚Ÿ³‹ÁÆœÜÇ›çÅšæšåÅèÆžéÀ™áÄåÊ¢íÌ¡ðÉ¡ìÉ¡ìÆ êÆ íÁœá¿™ÚÆ ßÅŸÞµ™¹³Ÿ¡ìè¬ÿÿ«ÿÿ§ÿÿ£ÿÿ¥ÿÿ«ÿÿ¯ÿÿ±ÿÿµÿÿ·ÿÿ©ÿÿ›ÿÿÿÿ éàŠÓÅ€øñ¡ýø¡ýô·ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÄÄÂÇÄÓ˜•ž­ÇÎÙÿÿÿ£ª±€‹Žtywnjegc^gc^he[jeYjfWjfWxtc‡w«§–Ð̽òïãÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýúòíéäóïìõòêðëáæäÓàßÉßÜÄÛ×½âàÁîïÍô÷ÔìïÌúúÛüúßíëÐÁ½££™‘“ƒÔÃɲžžœiïèÿÿ©ÿÿŸÿÿ²ÿÿ½ÿÿ»ÿÿ¹ÿÿ½ÿÿÁÿÿÅÿÿËÿÿÍÿÿÑÿÿËÿÿÇÿÿê´—Ÿ²·Äšá¿›Ý¿žßžàË¢æΤëË ì΢ñÕ¦øÑ¥ñΣìË¡èÈŸãÈŸã™ÝÅÚÅžÖ¹¥§ÙÓ¡ÿÿÉÿÿ·ÿÿ¬ÿÿ©ÿÿ²ÿÿºÿÿ¹ÿÿ·ÿÿ·ÿÿ³ÿÿ§ÿÿ™ÿÿ˜õîŽÈ½côãÿõš÷íŒüð¯ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÎÈÃÈÅ»””“œ©ÊÑÜÿÿÿœ£ªz„Šmul¢¦Ž¶º¤¼¼ªÉʵÜÛÇôôâÿÿñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿòïîéæÞØÑÆÔ˾ÖȻȸ¥À°–º­‹·ª„»³ÙÖµö÷ÕöøØõøÓõ÷ÐóõÎöõÑôô×öõßööäòñäüüìöôåÚØÇÌÈ·¾¼ŸŽŽgÓÆ´Ì°µžŠz¥—uñí£ÿÿ›ÿÿ¥ÿÿµÿÿ³ÿÿ±ÿÿ·ÿÿ¿ÿÿÇÿÿÏÿÿÏÿÿÑÿÿÍÿÿËÿÿÓÿÿǪ”Žµ”àֽ™ÙÁß·ØÀ˜ãÇœë—æÊží΢îÊžêÌ¡èÌ¢äÈŸÜÅÕ¾œÃ¾¡¶ÏÁŸÿÿ°ÿÿ¹ÿÿ«ÿÿ§ÿÿ¥ÿÿ¥ÿÿ«ÿÿ©ÿÿ£ÿÿœÿÿ—ÿÿ•ÿÿöí‡É³fäÐ{ÿï“ÿñÿû•ÿð®ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿååãÇÅÁ¹µ°ŠŽ‘Š—¼ÃÌÿÿÿ¨­·w}‹iiyÈÀÕÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüþîèåÝÕÑÓÉÁϹ« ¬ ‡ž”x‰iœ”l¨ oœ‘_±¥s²¦v¶§zÀ°ˆÃ²É¸—ÙÇ«íáÈõíÙòïÙïîØöõáù÷æüûðýû÷ýúùÿýÿÿÿÿþÿòõôàìèÎë×ÜÑ°Ò•y—Ó»Õ¬–¤•€…£–tóï¥ÿÿ¬ÿÿ¦ÿÿµÿÿ·ÿÿ»ÿÿÁÿÿÃÿÿÇÿÿÉÿÿÍÿÿÏÿÿÓÿÿÃÿÿµÿÿÀµ“ƒº—°ÀšÝ¾™à¿™è¼•ç™îÇŸïÉžêÉŸèÈžåÅŸâƢ⿚Ö›ӷ›«¾®–ü÷´ÿÿ·ÿÿ·ÿÿ·ÿÿ°ÿÿ©ÿÿ¦ÿÿ©ÿÿ¡ÿÿšÿÿ’ÿÿÿÿ—øñ‘Ƕ`ãÅ}ÿç–ùèýí“ùéÿë²ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŽ»Ã½º¦ŸŸ~€†x¼ÁÍÿÿÿ¨©´nq}z}‰ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþùûðçêÛÐÏÁ±°¤˜ŠŽ„l†bxrP†Xœ˜j–iº®ƒ·«€À´‹¾²‡¹­‚·«€´§|¨œl©k¡–f¢—i¢˜q§œ~´ªŽÅ¾£ÕÒ¼õôçÿÿûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþìíèæçâYWSŠƒƒš‹’š„’||—Šzõò¬ÿÿ—ÿÿÿÿ¯ÿÿ³ÿÿ¹ÿÿ»ÿÿ¿ÿÿÇÿÿÑÿÿÑÿÿÑÿÿÇÿÿ¿ÿÿÃÿñŸ¬‘}ÀšÄÄÓ™ÝÀšÝßáʦèžàß߾šØÂÙÉ¡ÞàоžÄÄ° ÷îªÿÿÇÿÿ½ÿÿ½ÿÿ¿ÿÿ¶ÿÿªÿÿ§ÿÿ¢ÿÿŸÿÿÿÿ—ÿþ‘òåŽÍ³räÉ‚ÿä—ýä‘þçþê“úé“úä®ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÕÏʯ¢™¯§£•”tysŒ¯¹¿ÿÿÿ«®¯ffhsnpùðóÿÿÿÿÿÿÿÿÿÿÿÿºÁ·ª³”ˆŽhY`obY‚x`„x]‘ƒd¡”nµ©~½±†±¥z°§}¬¢}«žz¬žz¨›wªy£•q¨—v¥—s¡”n¥˜r¢•o¡”n¤–ršŒmƒjyrYwt^ëçØÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýóñëæÙÐÓàÙÛûöøÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþô“‡‰aK\n[ktasˆr…v‰“pööÿÿ¨ÿÿ—ÿÿ­ÿÿ¶ÿÿµÿÿ¹ÿÿ¿ÿÿÇÿÿËÿÿÏÿÿËÿÿÉÿÿ½ÿÿ±ÿÿ¿¶”„Áš·Æ›äÂœßÀŸÞ¿žÝž޽—ØÇžâ¿šÖƤØÆ©ÀÁ¨£íá¯ÿÿ½ÿÿ½ÿÿ¹ÿÿ·ÿÿµÿÿ±ÿÿ«ÿÿ¥ÿÿ¡ÿÿ¥ÿÿ£ÿû£äÏ‘»¡^àÁ{ñÓ„ùÚ‚üàŽþãšúå•ûê”ÿëµÿÿÿÿÿÿÿÿÿÿÿÿñîí’‡¡›¨£›‰„„impmz¬³ºÿÿÿ®°´fffvvvøõöþþÿÿÿÿÿÿÿÿÿÿ©¢®i^onbh{ni›Œv³¢}¥˜o¦™p¨œs¤—q£—n ”k¡•jŸ“h›Že¥”qžl¡”p “mœŽhœk˜Žk™j™Œh“†b¢”r~fpbUGB8DDBêêèÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúöñÏÈ¿ ›“kgdNKLYU]À¿ÆÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÐÌÇUMIdXZ`NYcN\ˆn€‡wf—‘_ìï•ÿÿžÿÿœÿÿ²ÿÿ´ÿÿ¹ÿÿ½ÿÿÃÿÿÉÿÿÑÿÿÍÿÿÉÿÿÃÿÿ¿ÿÿÏÿüË¥„¾‘ÖÆáÉ¢èÆ ãË¥æË¢âÊ àÂ׸™Ìº¢ªßέÿÿËÿÿ¿ÿÿ½ÿÿ»ÿÿ·ÿÿ³ÿÿ©ÿÿŸÿÿŸÿÿ£ÿÿ¥ÿÿŸëߌº¤kàÄ„ûÖ’öÒ‡öÑ€ï΀øÚ’ÿëšÿî—ûâ­ÿÿÿÿÿÿÿÿÿÿÿÿ†ˆŽ}y—’†‘Ž†{wtNNPILVš›¤ÿÿÿ±®¯xroŽˆ…ÿúûÿÿÿûøùÿÿÿÿÿÿµ»´u|prrb|tbš‘p¢—išŽc›Že ”kœg‘hœfšŽc›bš_œ`›a›Žc™d”Še–Œg†a“‰b’‰_‹^†zag\IE;10,';>=ØÛÚÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÐÎÈ•’Š~vf`[YQO[OSXEb™}¶ÿÿÿÿÿÿÿÿÿÿÿûÒûpWTXDD]IN]IRbM[|ks‡x}–^äç}ÿÿ˜ÿÿ™ÿÿ­ÿÿ³ÿÿ»ÿÿÁÿÿÇÿÿÍÿÿËÿÿÉÿÿÃÿÿ½ÿÿ»ÿÿ»ÿýÕ¡~•°Š´¿•ÕÆÝÃÞßßÄ àÀ£Ì»¤·ßѲÿÿ»ÿÿÃÿÿ¿ÿÿ½ÿÿ½ÿÿ·ÿÿ³ÿÿ¤ÿÿœÿÿŸÿÿžÿÿžûñ’ɶhϯuæÄèÂvìÆ|ðÉ‚ùÚúß”ùß‘öÜŽ÷Ù­ÿÿÿÿÿÿÿÿÿ“jjj€{{…ƒ…|}sgkLDM@9I•ÿÿÿÏÌϯ«¨Â¿¾ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿËË»––{‘ŽkŸ•n¸«…±£}¢•o›‘j™‘k–l•g—f’‰_“Š^“Š`“‰b“Š`“Š`“Š^’‰]’Šb‘‰e‘‰c’ˆa‡~]oeMJE0/+-)&:5B½¸ÅÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŸ™–•‹…qjcHA:1-85!dVT„n|ÿÿÿÿÿÿÿÿÿÿÿÿÉÂÆkc_gYN\E6XE@]IRhVc|i{€v^œ˜Yæç‡þÿ‚þÿÿÿ˜ÿÿ¡ÿÿ­ÿÿµÿÿ½ÿÿ½ÿÿ½ÿÿ¿ÿÿÃÿÿ½ÿÿ·ÿÿÍÿ÷Ç«”»’ÏÀ—×Ç¡äʧàȧÖÀ¬¬àÕ§ÿÿ½ÿÿµÿÿ¹ÿÿ½ÿÿµÿÿ«ÿÿ©ÿÿ¦ÿÿŸÿÿ›ÿÿÿÿ—ÿø˜Ò¾~ÔµrîÄ~îÄ~ïÃ~òƃõɈ÷͉õ·õÓŒôÕüÙ³ÿÿÿÿÿÿ›™§ihmrsn~{sƒ|qxsgebXCA=-)/000yywxxvkki779ÞÝäÿÿÿÿøúÿÿÿÿÿÿ×Ô¼›–o—“g™’eš“h™j’ˆc…`…`ƒ`Œ„^‡a†\“‡\‘ˆ^‘‰c‡a†a…`‚^Œ‚_ŒcŠb‡}arnTUR>97(/,".)-;1Fž›®ÿÿÿÿÿÿÿÿÿÿÿÿìéá€y\}qA{n0o'–F‚USI1Œ‘ÿÿÿÿÿÿÿÿÿÿÿÿÿÿänh6|qCqa9j[>cRC`NKn]eylgwn_¨¥_ñõ{ÿÿÿÿ‚ÿÿ›ÿÿ¦ÿÿ±ÿÿ¹ÿÿ·ÿÿµÿÿ½ÿÿÅÿÿÁÿÿ½ÿÿ¿ÿÿÁÿïʵ’§º•¿¹“Ò¸˜À½ ³ÛΪÿÿ²ÿÿÁÿÿ½ÿÿ»ÿÿ¹ÿÿ®ÿÿ¢ÿÿ¤ÿÿ¨ÿÿ¡ÿÿ˜ÿÿÿÿ™ÝË}Óµ}ëňí¿~ì¾}ì½ñÅ„ôÈ…ñÈõÌöÒ‡öÔýÙ¯ÿÿÿ¨¥¦khiokhxskƒ~v€yrtqidb\>?:!!C@CHEH^^`êéîÿÿÿÿÿÿÿÿÿÿÿÿÚÕ˜ošm˜‹e–‰e”‡e“†d“†d‘‡`‡]…`‘ƒf„d„dŠ€dŠ€h‡|iˆzm‡{m„xl‚yl|ujupdb_SKI8<;'41*"$ +' ƒƒhÿÿ÷ÿÿÿûü÷ÿýâÉÀ”ÙɃùá…ÿðŠÿû‹ÿÿ˜ÿÿ¦ÝÑ£ÕÆÉÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ™z›ƒkc~l>{m7‘„F€rNeRKjXUudhwlN­§iôó–ÿÿšÿÿ•ÿÿ§ÿÿ©ÿÿ«ÿÿ²ÿÿ·ÿÿ·ÿÿ·ÿÿ½ÿÿÂÿÿÁÿÿ¿ÿÿÍûë³­•‹¸—»¹¦ŸÚÒ¡ÿÿ¸ÿÿ¹ÿÿ¹ÿÿ¹ÿÿµÿÿ²ÿÿ¯ÿÿ«ÿÿ¡ÿÿ™ÿÿ˜ÿÿ•ÿÿ–æÔÔ¶nÞ¶xá´ví½}ï¿}ñÁóÆ~ñÄzðÃ{ôƃîÆòÉ’÷˯³±­sqmmjiqkfyog|unwokolmXZ`;=A""$B?@UNNjccÇÀÂùôöçâäãàßáÞÝý­™ršo˜‹i‘‡bƒ^Œa‹|b†za‚x`~s^|o]znbyoiqkflggkiemkgokfogckdY^UFIA>7IA=0dP–z!»žOÖºvË·—óçíÿÿÿÿÿÿÿÿÿÿÿþæñ­ûÿ˜üÿùý ÿÿ¶ÿÿËÿÿïÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿµÂ·kkNrCq=†y@œb‚`gWH`OUzlj|rj­ªuõ÷”ÿÿ¢ÿÿ—ÿÿ¦ÿÿ©ÿÿªÿÿªÿÿ¬ÿÿ¬ÿÿ³ÿÿ¹ÿÿ»ÿÿ½ÿÿ¹ÿÿµÿúŸ»§`â؇ÿÿ®ÿÿ¿ÿÿºÿÿ¶ÿÿµÿÿ°ÿÿ¬ÿÿ¥ÿÿžÿÿ—ÿÿÿÿÿÿ‡çÑtÙ¶váºwãµrì¾}ê¹~å·vê¼yæ¸wç¸|ê»ï¿ˆóÄŠ÷ÈŽúÇ°qnmomiljdmlcnkckgbmhhidd[VV<9:87,IG8HE;GA<40-.+,4//8/0lbZ“‡y†y…~u}xnvqioldkh`ge_ec_a]Xc]XfaY`[Sa\I`Y>g_0qe"|l&y0¤?Ä°YÞÑhôìtÿÿ“ñç†å×uÿ÷”ÿô¥ÿÿÊÿÿîÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿìúûÙúøÒöõÝÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþê…xVte8s?|l4ˆ{B¤—^žŽdoYA[IB{kwƒxc¶¯yûúÿÿÿÿ“ÿÿ£ÿÿ ÿÿ›ÿÿžÿÿ¦ÿÿ©ÿÿ±ÿÿµÿÿ¹ÿÿ¹ÿÿ¹ÿÿµÿÿ±ÿÿªÿÿ»ÿÿ¹ÿÿ·ÿÿµÿÿµÿÿ®ÿÿ§ÿÿ¢ÿÿ ÿÿœÿÿ™ÿÿ–íÜ‚Û½nß³pç¹tñ¾{ï¿}í¿~è¹{ëºê¹~ê¹€í¾„êºƒì½ƒç¶{ﺣlijlijkfhgdcbb`ab]ec]dcZ\[P9971/+WSP894JPIVXNa^RaaQ^^Lqq_ˆˆxzyppkkhcce```]`_[ca\Tc[Gg]8fX"q]–z8¶ŸKØÃaÞÑhýõˆÿÿ¡ÿÿ¨ÿÿ ÿÿ¥ÿÿÆÿÿÞÿÿÛÿÿÛÿÿÉÿÿ¯ñö¤þÿ·øüÔÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûñëÿîàÄ©—‡eQx^<ƒoBt;‡C¥V§œVk\=XCJyfc†qh¼²}÷ö—ÿÿ–ÿÿŽÿÿ’ÿÿÿÿ”ÿÿ¤ÿÿ«ÿÿ°ÿÿ³ÿÿ·ÿÿ»ÿÿÁÿÿ½ÿÿ»ÿÿ¹ÿÿ¹ÿÿ³ÿÿ¯ÿÿ±ÿÿ²ÿÿ¬ÿÿ¡ÿÿžÿÿ˜ÿÿœÿÿœ÷çÜÀ~ß½xíÁ|èºwî½€ì¾}æ¸wì½í¾‚ïˆ繂ã¸}àµxã·vì¾{í¹›if\hd_hccYVUVSRVTP[WR^[Z\Y\224%"%E@BTPMSPHSOL^Y]usmZ\NhgZ†unkaa]Xca]`]\[VV_XXgZH‚nJÀ«mþå’ÿøœÿý™ÿÿžÿÿªÿÿ±ÿÿ¶ÿÿ¸ÿÿÁÿÿËÿÿ·éñ—ÿÿµÿÿÊÿÿàÿÿÕÿÿÅÿÿ¿ÿÿ¸éì¼ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýøõîåÓÎÆ™”yq]€sQʲ„½™`}_3w^>‚mE‚p@Š}Až“M¦˜bq]9_N?{it…ze¼¶„ïðÿÿ~ÿÿ‚ÿÿ‚ÿÿÿÿÿÿžÿÿ§ÿÿ±ÿÿ¸ÿÿ·ÿÿ·ÿÿ·ÿÿ¶ÿÿ¹ÿÿ»ÿÿ¹ÿÿ·ÿÿ³ÿÿ®ÿÿ¬ÿÿ¦ÿÿ¢ÿÿ˜ÿÿ™ùèŽÚ½nÙ²mæ¼ví¿zå¹tà´qݱláµpæºyí¾‚ê»ì½å¶xãµtæ¹}â¶~㲘`_V_]W`[[]ZYWTSWUQ[WR_\[NKN   GBBgde==?E@BYPS[UR_[Vc^Txmd_U]YT^\Xc`_ea\hc[scM¯oÓ·~ëÑÿð™þî‘ôäŒñãßÛíñÿÿ»ÿÿÇÿÿ¹ÿÿ­ÿÿÉÿÿËñ÷©ÿÿ¿ÿÿÊÿÿÒÿÿÏÿÿÎûþÙÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿ×ÒÔ±ªªŠ…slcli]jl^][@‚xU¾§vͧj£ƒZlP:va;~m:€s5Œ„;Ÿ“R¯fp`H`OW‚tiŽ€cÇÁqóõsÿÿ}ÿÿ|ÿÿ~ÿÿ€ÿÿÿÿ¢ÿÿ©ÿÿµÿÿ¶ÿÿ·ÿÿµÿÿ·ÿÿ¹ÿÿ»ÿÿ¹ÿÿ¸ÿÿ±ÿÿ®ÿÿ¬ÿÿ­ÿÿ¢ÿÿ“õìˆÙÀvÕ·jñÈ}íÂzóÅ‚ã·rß³nà´qå¹xå¹xíÀ‚뾂à³yß²tà´qÛ°sÙ¯{Ö¨_]WWXSQQOQRMOMILHESMJVQQB=A3/*;8,87,,*$3..:57=8|mpŒƒYÔÏzðò„ûÿ{ÿÿ~ÿÿ{ÿÿ‚ÿÿŽÿÿœÿÿ«ÿÿ¹ÿÿÄÿÿÃÿÿÀÿÿ»ÿÿµÿÿ²ÿÿ±ÿÿ¯ÿÿ§ÿÿ ÿÿ›ÿÿšïä×ÀlÛ¸vèÁ|è¼wã¹s×­i×­gä¸sìÀ{ñÅ‚íÁ€æ¹}à³uà´såº{îÆܱrÙ¯mæµ”VSTJJJIIIKHGGBBA=:F@;D@=<9:;;;:::===636()4335/-)20*OLDWTJ_ZPd^Psj[pka_[Xca]ab]de`ec_geageaia_o[`pXNpQ<Æ°wÿÿªÿÿºÿÿ´ÿÿ³ÿÿºÿÿ³îñ—îð›ÿÿ±ÿÿºÿÿ¼ÿÿ¾ÿÿºêï›çëžÿÿËÿþãÿÿÿÿúÿÖÊЗ‹‘nehlcfwpp„}}‡„|‡‡w…‚jŽ„h¢•o®Ÿn¿©pÓ´uéƆä¹zå»yݱnÇ f¦ƒVx`9ZP-ph5ƒ{9“ŒE–FŸ–YŸ”fsfRaRYzkc‡x`ÈÀ~èå{üý‚ÿÿ{öýpÿÿwÿÿ‹ÿÿ“ÿÿ¥ÿÿ¹ÿÿ³ÿÿ«ÿÿ¥ÿÿ ÿÿ ÿÿ¢ÿÿžÿÿ”ÿÿÿÿŒòä‚ãÅ{Û¸v一å¸zå·rÛ²iä¾rîÅ|ïÃ~ìÀæ¹}â·zâ·zæ¼xìÁyíÁ|æºyݵwÖ¯uÒ¦ŒOJJB@:FE<@B8591TVL54+-.',,*1/+82/965002$ !,9<;IK?PSBQTAWWEYWFUNEbTTjb`[WT]^Y\`Z_c]bc^ec_e``fb_hb_kcal^^gOUfBPsY@ɸwÿÿ¼ÿÿÍÿÿÅÿÿÇÿÿÂÿÿ®êîôö‘ÿÿ°ÿÿ¾ÿÿÃÿÿ¾ûÿ³à訃[YYIONEIFGlkbzxi{xb‡€g™‘k¤™g¸¦jƬiÛ¼tùÐ…üщ÷Ç…ôÅ~õÆ}öÉê¼yÖªrÀ•i•tPjS9\K(h[2…yGŒ‚E•‹Q—‰UŒ~_fWO^PN‚sxˆ}]À·sÞÙ{ñðzõúwúÿsÿÿˆÿÿ™ÿÿ ÿÿ¦ÿÿ§ÿÿ§ÿÿ¡ÿÿœÿÿÿÿžÿÿ–ÿÿŒÿÿŽðâ€ÕÁlÌ­jЮiÖ¬jáµrñÃ~õÇ„é»zè¼{ç»zÛ´oà»sä¿wçÀ{ñÅ‚î¾|ê¼yà´sÞ·tÝ»vá´”TXPefaC@AHDAE@8gc`B=?%#! ##!&&$# ! 730E?:JHDPPN[WRŽ‡€ZWKSSA]]MYXM[]Q^`V_`Y`^Z_]Wdb\fb]ga^ic^jb^hb]hb]i[[^FLaFD€_X˶ÿù³ÿÿÃÿÿÅÿÿ»ÿÿªÿÿ¥ôø›ùýœÿÿ¦ÿÿ´ÿÿº§œlwk]pfN^U4xlCžŒ\É´yãÉ„ó܈ÿñÿô“ÿï‘þÛ‡úχï¿{õ¿ô¾~íµxê·xè¸xÞ²zÊ¢r¯Œb„hBdK)ZC'iU1zj@zj@xh@rdBvgM^OISBQpc\Š€fľ~ÞÛuïðwüÿxÿÿ‚ÿÿÿÿ˜ÿÿ ÿÿ˜ÿÿ‘ÿÿ–ÿÿžÿÿ˜ÿÿ“ÿÿ“ÿýŒíÜ‚Ö·vÔ±oÛ³sã»{ã»{ä¹|á±zÜ­sâ³yá²véº|ìÀ}ëÁ{éÂ}á¹yã¸yã¶zæ¹{è¹{çº~巀୘OLM\]XFG@XVPSOJ*'&//-9:5(&"MIFMNGQUMXWN_ZP]ZRWUO\[P^]P_\P`[Qc\Ug\Ye][d]_f`]h`\daYcbWYXMOLDGD)0K#7}YU̬ÿò½ÿÿÀÿÿ¾ÿÿ´ÿÿ¬÷ûœùù ÿÿ±ÐÅ£‘WðfêÑ|÷Û‰øÚ‹ñÒˆùÙ–ùÞ•øà‘ÿòœþñ˜ÿñ˜ÿåüÔ„ô¿xç±sà¦sߧsÞ©tשrÈ¡i´’[˜zDqY/VA&P=([J;ugJlc9f\9cW<[RCULM`TVudh‘ƒdÁ¸tÕÓkñôkÿÿ{ÿÿ}ÿÿ†ÿÿÿÿ‘ÿÿÿÿÿÿŽÿÿ‹ÿÿ„ý÷Žë؊ؾyÕµ{ݹ~Ù­uÞ³xܯuã·vç»vç»z麀ê»åµ~ß°vá²xß²vä¹zç¼}ì¿îÁ…콃æ·}â³y汘DF:BD6NN>lk^YXO +&(E>>A<>HD?LIAQNO+)3  -   -   - - &#I4A652%8)mLE¨ƒiïΙÿ÷ªÿô¤ÿí›þå’ïÏ|ðÐ}û؈ý׋ùЇüÒ…þÒƒöȃà¯vä³zð¿†ï¾ñÁê¼yá³rÉžaµŒU²‹Q¶S³’X«ŠU ‚O‡j;\F%H7$F5)E30M;8L:7RBCSBH\KQl[asg[‰eÊÈ}þÿ‹ûÿ€ùÿvÿÿ|ÿÿÿÿ~ÿÿzÿÿwÿÿsÿýëÛ|Ô»oÒ±wÙ²xá´zæ¹}á²vâ³wá°uä³xã²yæ·{å¸zè»}ê»}îÀïÁ~æ¸wã´xܯuß±zÙ®sâ·zå¹xé¹u겓B>;GC>MH@OLD+(  - -    '!>70C>6?94=94<:4IIGGJKGJKJJLIIKKHKMHHOIDTNITNIRNKSNPURQVTPWWUWWWZZ\NMT331›‘ÿÿÿÿÿÿÿÿÿäìÿOV]qyr}{u‚xrvqib_WPLIC>@;/39%,1\7:¥zm캞ÿÞ­ÿî©ÿé›ÿÔ€éºqå¯që´yñºò»€ÿÉ‹ûÄ‹Þ¦rÛ¬páºwâ¸tÞ²mÖ«l™b­…R¸bµ]²ˆY®ŒW­Y™€KjT!U?S<+I4)XB@XDFeQXfW^nalxktuio”hÞ݉ÿÿ“üÿzöütüÿxÿÿsÿÿrÿÿ~ÿÿˆôå†ãɆַvÕ¯p̤dΡcÒ£iÍšiܪvâ­xç¶{í¾€æ¹{á´xÝ°tÞ¯uÙ¬rݲwÞ±w鹂íÀ„îÂë¿~è»}ê¹|í¶}嫘A>=CA=GC>KIC:;6((&###TPK[TKPLINJPNNLFK@HIDLILIIKMLQLLNJGJKIEKJ?NMBPOFSPHTNIUOLXQSZUWZWZUUU9<;?C;ÝâÕöõìÿü÷çäÜÿÿÿ”’ŒZZX`]\jccxpnˆzx†~|{tvnjeWTJ?946-04"-& E%.™rrØ«–÷ÚÿÌœýÄŽó¼ƒò»‚ä°xÑœgá­uä°xÒ¢m¹Œ[Í¡iܱrÛ±oÕ«i–^±„V®„U´Œ\·ZÄȩq¾™ež}K…h9^E#Q;%XC:\GLiVXr_a}lt‚q‚ug§ sôô›ÿÿÿÿ‚ÿÿ‚ÿÿ‚ÿÿ‚ÿÿŽþëãÅ}Ø°€Ýµ€ìÊôÉŽÿÒ–øËõÈŽíÀ„ðÁ…ê½ã¶xÕ¦jÓ¢iؤlÝ¥qæ´~꺃á´zà³yݯxÚªuÙ«tå¸~è¹}ñÀ…øÁ©=:9@>8FE==;FG@KJ?SQBZ\PFJD%**"#&'`^XrqhebZ`^X^\X][U[XPUSMVSRTOORIJOJNLKRIIKKHIJHDLIAPLGPKKQMJQMJTPMXQQKHK"!(B9E®®öíû±¯½•‘ŒÖ϶}|f\_NXZNYWS\ZT[WR]YTYURXSSVOQYRRd]]ie`li_ZVQ>990+++&&# -'I"¡u]«€_œqGÍ£qÎ¥lÅŸbÃ^Å_Σh˜d¸d¿—d™bÊ£iº“Y¸•W½^È¥gÛ´zÙ³tÆ¡]È¥eͬpÛÀ„įtžŠ_„oTaOEeQZn]crchu^±¦táÒîØ‹ÜÉ}ÖÂ{߇ຌðÃ’ûÆ“öÁŒó¾‰ð¾ˆðÀ‹ë½†à³yÛ¯wÜ°zß²xâ³wתlÏ£bתpÞ­{á±|æ¶é½‡è¿ˆóÇõÆŒí¿~é¹uá±oç¶yí·œ;=/?A5@A:DE>HIBLMH634"%"XYRji`lkbge_c]XeZYic`_]YYVUWTUVSRTOOSPOMMMHHHOLMLIHIEBC@?99;?<;LHEVROVQQ>>77;0-. <^F®ˆ\ΧoØ®lÉŸ]Ñ¥dѦiЧn´UÀ˜eÒ«qÓ«kͪlµ“\¶’WË¥fàº{Û³uÕ­qâ¶~ïljëÄÓ°pɨlºœiÁ¦{“~cSA:NA:\UNf\RfZL…wZ¯œs̱„×µƒÖ±{ЧpÓ¬rÛµxß¼~ܼ}äÁìĆîÄøËûÎ’ÿÒ›ÿÔšÿÓ—ùÌŽîÂê»}î½„í¾€ê¾}å¹xܯqÕ¨lå¶|ê»ýÎýË­:9,:9.:90>@6BD:DH@030!JDAoidYSN62/^YY_ZZ`YYZUW[U\]XX_[VYUPZTOWSNVTNRPJRNINIAMF?IDGE?A<=::<9676112.+.(# !"()":;6HIBSQKSQKPNJONEKJ?OLBTOGQKFMFFKFFMHJKFHKFHJGFKHGJJHEEC9:346,-.'+)%'$#%"%##%""&11/JFLNFD>/)P8.wTGžy_½–oÇŸoÆšdĘbÔ§tâ·zݱnÉ Wܳhê¿wß±lÖªiä¹|óÈ‹è»ϤiÉeÙ²má¾nÓ®f̤fÔ¯kÕ°jÙ±qß±zç¿çÂ|àº{ܳ|Ö­tÙ°wܳ|Ý°Û±Ú²廇ìÀŠéÀ‡éÀ‡å½á¹}àµzì¿…ì¿ìÀìÀ{îÃyõÆõ½|ï¼{è¸x涗22"/1#-/#32%95&C@6^ZUa]ZKFH=;7B@:!! --/C@CJHDHE=A>6A>6DC8FE:GF=IGAOKHOHJKFHIFGKHKKGMJGHGEACB9FE:D?7E:7B74>327,+4)(.''$! 523C@CKGDPI@KH@IGAFGBEECDDDC@CE@@MECNHCMGBKE@F@=@:7;4460-1+&,(#($$"$! !" ,*$>99G@DG97P;2rWEœya³f¸—[ϧgì¾{ôÈ…Þ²qà´sõÈŠóĆݩoí¿zûÑ„òÈ{Ú¯eÒ¨d׬qä¼|Ú³nШhÓªqݵyå½ä¼~Õ­qͦlÊ£kÛhÁ˜mÂiÍ©nزuÙ±sݳqÖªgËŸZУ[Í£]ÞXÌ¥`ÉŸ]Ê ZѦ^Ø®aÚ°_à¶gæ¹oì¿wí¿zõ¡34/--(2-#82-LHCRNIMIF946632854+++41220,2/'43&33#74(>70C<5G<9F>B@>FCB@C@@E:CH9EG;DC:FE:IFE?:D>9@:554+02&,."(*#("& ""# !!# --->85P@?Y?8ˆcW°ŠnÇžsâ¹€õɆå¹tá¶nùÏ‚ûÑ‚ç¿qìÆzÿÚ‹ü׈á¼tΨiϬlÞ»}޺ǠhʦkÙµzå‚ЮiÁ¢ZίgѱnͪlʪiÖ¶uà¾yä¿yðÉ‚ôÉöÊ…úÌ‹ôÉŠêćåÃzâÂoèÈuêÇuíÌ~óшòÑ…öÒ…÷ÓˆüÕîƤ/.#.-"(%.- 8:,GF9NI?43*-.),,,1-51,7& -########!$$"))'*'&/-'54)<7-F<4C;9ED@;CB9?>3==-;;)24(+/)/0)+)#$% ,. =?1AC7GDB=586023.+.+',*((((#'&#$"""" $!"'""$##!"" $!"+$&:.4A10P>4dR³Žt徕úΖçÁwòÏtÿá‰îÉvã»mòÆúχñÆ|ܵpÓ­nܶw翃ѪrË£pÔ°wÛ·|Ë«lƦgЭoرwÙ¶vÙ·rÝ»råÄvëÈxòÊ|ßµqÌŸeÆ›^Ä™ZÈ `ΨiÒ«qංìÂŽõË—ÿÙŸþØ›ûÕ”þÙ•ÿ׳-((+)#&(,.$8:0>@6-+%,'',"*+$(*#%($!&"   #%,+"4.)5)+82-<;2@<9C:=E>>GA>EB8II9KJ=KJADFFH>FE9;86202(-1)*.((-"%'&' '$%$$$ #" $"#"#&%#%! %!$$$&&$&&$*+&*+&1**6',8% ^B7¾˜þÏ«õÆ”ÿÒ”ÿ×–ì¾}ç¹ví¿zìÀ{é¿yØ®hÙ­jå¾yÔ¯iʤcÔ®qͪlͪlÆ aѦiݲuâ·zâ»xéÂ}ëÄëÄÖ°sÇŸoΤpÞ²|í‡ñƇìÅ~ä¾rà¶pÕ¦hÕ¦jÓ¢iשhÞ±iÝ®ˆ.''+'",+ .-$:631/+"#&#"% "$! $" #!  !%$*$2&*0*%2/#94*?73?94@:5?>3?B1EG9GF=GF=FD>FE:EB6GF9DC8GD:JE;GD:@?6;:151,41)72(30(.,(#&%#&  $$&HCCIDF@9=;9568.46,02(-/!+.,+ (##&$ %&!!"!##!!$"#((%$))))-+'-+%,*$0))8,25(15(31& nI-Ô§yîÀ‹õÆŒøÉæ·{ä¸wïÃ~íÃ}Ù¯kÌ¥^Ö±iã¾zÈ bШjÔ¬pׯsܱvΣfÓ¦jàµvæ¼záºwáºwΨk¿—bÀ—`Ö¨sîÄùωõÊ€é½pìºròºyöÂüÌŒùΆÿÙ‰ÿد/(('%%',*$0*'" " !       "(!$"(& .,&/1'27,79/971;95>99;72FA9DA7DC6GF9B?3DA5GD:LFAH?@@;;@=>>:7>91;50<343...+*-*+&#&   +()65:44411/1.-0++.*%,)!)&'$(%'$#""# !&&!&&$'(+++.+*0++0'*1*,1*,,,*'.*&,%(,&,$ )& ^=&°‰d㲀ᅧâ²}á´xñÅ„é¾ѦkÒªnÛ³wÓ¬rÁœfرyéÀ‡æÀ˦`Äž]Õ®tÝ·vîÇ‚ðÉ‚â¸rÉžaÍ oÖ«nè½uòÇá³nÙ«hרjâ±tí¶{èºuëÂw÷ˤ*!$"!%! %!   - -  "!#!'&*)/,$1**71.80.93.@:5>83C;7B=5FA7JG;KH<36;485/6//-).#$&$# !()$,-(-.'+-#'+#$("#'$( $%'%!%"#'#+%%%&'"()",*$+)#-+%+*+**, ,.$*/$*.&,.".- 2,'2&*,!$ 5X<&¢~]Ë tÕ«yⵂϦm¸’SÆ£aϬjЭkÈ¢aÓ®jÛ¶pѬfÆ¡]Ö¯lå¸zç»zôƃä¹|ÉŸk˜dܯ|ñÆ‹öʉîÀå±uݪkì¶xò¿~ñÁ}í·œ!%%&$0! '    "!%!(#%-%,1*,3*+5,-901901=45C;9G?=KC?MF?NIALIAQMHRKKMJBLI=QNDOIDPMCKJ=DF8BD8@B635),.$*($'# +$$""   $#'%%'%'()$(((($,'#+(!-(((%+"%',)-)$.''+('(((+&&0(&/*",).-".-$+-!*, -,#.*'1)'5''1B* jN8Ÿ{Z¾˜jÚ±xÆžbÅaΦfÒ«fË¡_ΡeÙ¬nÜ°oà´qß±nè¹{ê»òƃñÆ|جgרjáµpñÆ|üÒƒõÉxê¾qà°lãµpí¿|õÁ£"%$297       - -   %"%'$%,''-(*3.27047-5@7:E<=JCELGKLGIOHJNHEUPHZUK\ULZUMXROUOJYQMYRKVOFPMAJJ:CB5;:/:9.87,21&10%+**) &$$#$!%$)$%.)(-*'*((&()$%&*(",)*+'/+%,.&-.''-'"*($**(--+))'()")++)#/**0,'30(63)30$IM7jeP^N;™€`Ç¥x̧sÊžfΦhÔ®mÔ¬lÙ¬nß³rÜ°mÉ¢_ʤcä¹zí¾€ñĆä·{ß´uç¼}ò͉üÚ“þÚöЄíÀxëµuÛ³“ \ No newline at end of file diff --git a/example/dev/file_grabber/image/img0253.ppm b/example/dev/file_grabber/image/img0253.ppm deleted file mode 100644 index 45916d2521b..00000000000 --- a/example/dev/file_grabber/image/img0253.ppm +++ /dev/null @@ -1,25 +0,0 @@ -P6 -128 128 -255 -aq‡au…bv„fu{kqtxyt¯¨Ÿry„r{ŠnyŒm{ˆs‚Šm~ˆ_p|]nq™ž¯®ºž°º¡´»©¼Ã´ÅϸÊÖ¿ÐßÃØãÄÙäÏáèÜéîãëïïñ÷ñó÷ññóðóôõøùúúüùöùûøùõòóúúüÿÿÿÿÿÿÿÿÿÿÿÿþýÿøúÿïóøáìïÖåéÑäéÉÞçÇÙåÎÛíÇØé½Ñã½Ñã¹Ìá¹Ïå¶Ìä´Êâ³Éá·Êá·Ç߯Â×°ÄÖ±Á×·Æà³ÃÝ°ÂÞ°ÆÞ·ÍåµËá·Êá¯ÂÛª¼Ø§¹×©ºÛ³Çç®Â⧼٩»×«½Û«¼Ý«½Ù§ºÓ¦¹Ò¯¿Ù¨»Ð¡¸Ç¤»Ì¤·Ì ³È¢µÌ«»Óª¹Ñ£´Ç¥¶Ç£·Ç ´Æ¤µÈ ¯Å¤´Ê¨¸Î¤³É¡­ÆŸ«Ä§³Ì«·Îš§»–¦·”¥´‘¢³ž´ˆ™¬’¥}‘¡vŠ˜r†˜q™j{Žfwˆ\p€Xl~RezTd|Sgy\p€Qcf`meu„ev‚hw}kvwsyp¨¨˜{ƒ|n{€kz‚lz‡p|ŠvŽn|‰bs_p|n~‹˜¨š¥¶›¨¸¤´Å°ÁгÅÑ·ÉÕÁÓßÆØâËÝçÒáçÜçêÞéêãìëäëëìññêíîññóøøúòòôððòðïôøúþûýÿøúþ÷öýóò÷þýÿòõöðóôêòôàíòÞðõÌáêÆÚèÂÖèÂÖæËÜí¾Õæ´Ïá¯ÊÜ«ÆدÇÚ¨¾Ô¯¿×²¾×´ÄܹÏç¶Ñå¶Òæ®ÊÞ¬ÇÛ±ÌÞ´Ïá³Îà­ÅØ«ÃÖ«ÃضËæ°Áâ¬ÁÜ´Ìã­ÅÜ¥¼Ö¦½×¨¿Ù«ÁÙ®ÁÚ¨»ÒªºÒ§·Ê­ºÊ¬¹Í©µÎ¥´Î¦´ÓŸ±Í ¶Î¡´É£³Ä«ºÒ¢¬Ï ®Ë¡±ËŸ²É¤·Ì£·É¡µÇ›ªÀž¨Ä ¬Ãž«½–¦·–¦·”¤µœ°Œ™«Œ™«„‘¥}‰ t„—n~‘m}Živ†dt‡_nˆ[j„Ye€Xg}UevHZ]`pohz„fxivszvµµ£„ˆ€rx}ls|qz‡q}‹p}m}Œeu„dtƒr‘€Ž›”¢­œ­·¨ºÆ±ÂÌ·ÆθÉÓÀÒÞÆØäÆÖåÉÚæÒàëØçïÚéïÚçìÞèîéñóèííêïïñôõïòóùùû÷÷ùýüÿöùúô÷øëîíîñðñööêîóåíïàëìÒäéÅÙçÃ×çÂÕêÂÕê»Ëã¶ÊܲÆÔ²ÆØ»Îå½Óç±ÉܶÎã²Èà«ÃÚªÁÛ´Ìá´Ìß³ÌÜ®ÇÕ±ÍÜ­ÈÚªÆÕ¯ÈزÍß®ÊÞ¬ÈÜ°Ëá¬ÈÞ¬ÈÞ¨ÄÚ«ÅÞ¦ÁÕ«ÇÖ¯ÇÚ®ÁÚ¯ÅݬÂÚ¬Âت½Ò°ÁÔ¦³Å¦µË¤³Ð ³Ì ³Ì¡´É°ÁÔª»Î¢³Æœ­¾Ÿ°Áœ°À›¯¿™°½ ·Äœ­Àœ¦À›¨¼—§¸ ¬ŽŸ©Š›¥’ ­ ¬„–¢‘ž{‹œr“k{Œiz‹ax…Xq}Vm|Vj|ThzO_u?PZan€^k{bolv€ot|vvt¼·«‰‰‰twƒmsƒlwŠoz‹q|l|‹j{Š`pmy€Œ£’œ¶©À¢±Ç«»Ì­½Ì¯Á͸ÊÖÂÒáÈÕçÆ×ãÓåïÍàçÐãèÒäçØçëßîòåò÷èóôäíììóóöøüëíñ÷öûùùûííïöùúðòöìòõáìíÚêéÕèèÇÚÚÈÚÝÁÓÝÂÓä¼Ïä¶Éâ¾ÔêÃÛîºÕé¾Ùï«Åã©Âç­Ææ°Ää«¿ß±Âã¯Æâ°Êå±Ìâ°ËݬÈÕ«ÈЪÆÓ­ÈÚ¬ÇÛªÁÛ¯Éâ°Ëæ°Êã¶Ìä¨ÀÕªÂ×¥½Ò¯ÇÞ©¿Õ¤·Î°Å°Å ¶Ì©¿×®ÁØ­½Ó«¾×¨ºØŸ·Î¡¼Ð¦¿Ï²ÉØ¢¶Æ£³Ä °Á™©¼£´Ç®Á“§¹’©º™­¿Ÿ®Ä—¨»•¦¹˜©¼“¤·‘¢³‘¢³ŽŸ®ˆ˜§‘¢Ž¤¨u€žk{‘fzˆd}‰]y„SlxMdsNcnM_iA3846:2BGC^ccvvtŠ†ƒ|bpp[jrYi|UfyWh{SgwUiycw‡hyŒu‰›z‘¢†®|¢‰š­‘ ¶ž±•¦¹–©¾š­Æ¢¸Ð¡¶Ñ™¯Å™¬Á™¯Çž´Ó¥»ÚŸµÖ›µÐ¡¼Ò¡¼Ò¥¼Ö«ÂܪÁݧ¾Ú§¼Ù©¾Ù­ÃÛ³Êä¹ÐìºÔï¸Ñ什ܪ»Þ­ÂߺÏê¯ÅݯÂÙ®ÄÚ¨¾ÖªÂÙ®Åß±Ëä«Åà®ÅßÀÕðºÑí²Ëé­Æä¯ÈæªÄß«ÂÜÄÙôºÉæ·Èé±ÂçªÀá¨Áß™´Í£¿Õ§ÃÙ£¾×Ÿ¹Ôž´Õ¥»Ú£¹Ø¥¼Ø¦½×¨ÃצÁÓž¶Éš°Æ¢¸Ð¡³Ï˜ªÈ“¤Åš­Ä¬½Ì›¬½ž®Á—¦¼˜§Á–¦¾”§¾”§¼¡³¡³£µ ·Ÿ½‡Ÿ¶†¡³‚˜®‘«~‘ªyŽ©~‘¨†–©~ŽŸ{ˆšvƒ•u‚”rƒ’q…“r‰«±¶ÐÔå••²†ª}ˆ¦w„–DNV8?F36>67@HFRigqzx‚twip{^jv_p|`q}\myUfuWh{bs†iztˆ˜xŒšsŠ™vž…˜­Žž¶‘¤½“¥ÁŽ¡º‘¤½°Å±Ã•©¹¡²Ã¢µÊŸµÍ ¸Ï¡»Ô¥¼Ö§¼×©¼Ó£³É­À׫½Ù§¾Ø©ÃܬÄÛ­ÀÙ°ÂÞ´Æä¯Æà±Ëä­Ã⫾å­Ã棹ܦ¿Ý¤¾×¨ÃÙ¬ÄÛ©ÄÚ¦Á׬Æß°Êå«ÆáªÄâªÄß®Åß®Â⭻᭾á®Âä®Â⫿ߣ¹Ø©ÂࣽبÂÛ¬ÄÛ¬ÂØ«ÂÞ¡ºÜ¶Ø ¶Ù¨¾ß«Áঽ٢·Ô¥»Ó©¼Ñ¥»Ï¡¹Î¨Àק¼Ùž³ÐŸ´Ñ›±Å§¼Ç¨¼Ì™¬Ã§¼ª¾Œ¨ºŽª¼Œ¤·£¶ÍŠ ¶ˆ ·‰¡¶ˆ ³‹¢³Ž¢´Œœ´…“°‚’¬…•¯„—®{Ž£~Ž¦w…¢q›q™o•jzo|…½ÂµºÆ”«‚Œ¤|ˆ£w…’>MUBOX8?J29B8=EOQUolotwkqam{er„br`p\nzYny^wƒa}Šl…“p„”n‚”x‹¢‚•¬„—®ŒŸ¶ŒŸ¶ ·‘¤½œ¯Ä¢³Ä ´Ä§»Íœ¯Ä¨¸Òž´Ê¤¼Ñ³Ë࠸Ϛ²Éœ³Í¯ÆàµÊå«ÂÜ®Åߨ¾Ö§ºÓªÁÛ«ÅàªÄß­ÇâªÅÛ¢½Ñ¬Âج¼Ö­ÃÙ¤¼ÏÀÙç¸ÑÝ«ÄÔ§¿Ö¯ËÚ»×â°Ìà«Åã²Íè°Êå¯Éä®Åá¿ÙòªÆÜ¥Á׫ÆÜ®Åß©»Ù§¿Ö¥ÁÕ¢ÁÔ¡ÀÕ¡ÀÕ ¼Ò¥ÀÙ£¾Ùž¹Ò£½Ö¨ÂÛªÁÝž¶É£¼È¦¿Íž´Èš²Éœ³Ï•¬Æ™¯Ç©¿Ó¤¸Èš±ÀŸ¸ÆœµÁ‘«´«¶š¶Ã®ÇÓŒ¡¬†ž¨‹¢¯”¨¶‰š«‰š«Šš­ˆ™¬„—¬„”¬…”®Š™³†”±{Ž§tŒ£p†œr…œn‚’g|‡s}ƒÎÎÐ¥¨´Ž“ªƒ§{†¤uƒMT[V^bU[`6:9@GHS`eqnt‚co}an€Yiz[l_s…g}‘f~“m…œm…œu¤y‘¨}•¬—«…™«ŽŸ²š¦½‘¡·‘¤»§º‘¬¾“¯Å™³Ñ›¶Ñ˜²Ë•°Ä–±Ã—²Æž¸Ñž¹Ò§ÂÝ©ÄÝ¢¼Õ¤¾×ªÁݤ¾Ù¡»Ùœ·Í¥¾Î©¿×­¾ß®Ä㤾ܥ¿Ø¨ÀÕ¨Ã×°ÌिتÃᨿ۰Åâ´Ëç®Åá¨Áߥ¿á¬Ææ¨Âà¬ÇݪÂÕ«ÆØ»Öè¶Îå´Å橾٦¾Ó ¶Î«½Ù²Çâ­ÂÝ£ºÔ£½Ö©ÄÝ”²Ì›¹Ó˜µÒš¸ÐŸ¾Ó¸Ñ˜±Ï‘«Æ©Ä©Ä˜±Ï©Ç’¨ÇžµÏ–®Ã¨¼‡¢¶Œ¤¹‡š³ˆ ³«º‡ ®’¦´‰¢²‚³‚±™¬„š®†™°~”¨u‹ŸtŒŸtŒŸuŒ›‰š©q…•k‘l}Žeu„_fohdjƒˆ„  '*4;F4:HDR3;?7@=HQLfmin|~]nz\l}[j‚aq‰gz“g”j…—m…šu‹£v‘§z–¬‚³…œ¶Š ¸Ÿ¯Ç™®É“¬ÊªÅ“­È¶ÔœµÕ—±Ï•°Ë¢¾Ô•°Ä™±ÈŸ´Ñ¡¸Ô¬Åã°Ê衾ݟ½×§ÃÙœ·ÍŸ·Î§¿Ö©¾Ù¬Ãߥ»Ú¦¿Ý¥¿Ý§ÂÛ«ÆÜ¡¼Ð¤¿Ñ£¾ÐªÂתÂ×´ÌãÀÚõ²Ìì²Ìê®ÈæªÄâ©ÃáªÄâ¨Áß³Í觾ئÀÛ¡»Ûœ¶ÔªÄߦÀÙ®ÆݨÃ׬ÇÛ©ÄÚŸ¹Òš´Í˜²Íž¸Ñ›µÎ•±Ç¬ÂŽ­Â®Æ–²È‘©À”©Æ•¦É•«Ê‘«ÆŒ¦¿š²É‘¨Â‘¨ÄŠ¢¹Š¢·§¼‰Ÿ·ƒš´‰ ¼‰Ÿ¾ƒ™º†›¸­‰Ÿ·}•¬†¢±z–¡oˆ˜wŠ¡r…šq—j}”fx”l|’iv†Zim>OGjspBEF ->K]DTcDTcDTcM]lTbmLV`9AE7<<C=?CSXXjooeow_o€t…–g{‹t‹œkƒ˜l…•wŽx‘¡|”©‚š±|“­‚³ˆ£¹Ž©½¨¼¨¾”®Çœ·Í¢½ÓŸ¹Ò¡»Öž¸Óš±Í™¯Î›¯Ñ“¨Å˜®ÆŸ·Î™±È“«Â¨¾Ö«¾×¨·Ô¨¾Ö¬ÄÛ¦ÁÓ¨ÄÓ°ËÝ¥½Ò¨ÀÕ¦¼Ô§¾Ú«Á⧻ݩºßª¼Ú®ÁÚµËã±Èâ±Èâ¯Æâ²Ìå¨ÂÛ¢¼×¨Áá¬Å妿áªÃã«Á⦼ݟµØ¥¹Ù­¿ÝŸ´Ñ¥º×¨½Ú¤µÖ¡·Ö¥¿Ý¢½Ø£½Öœ³Ï£´×ž²Ò¦Â“ªÆ¦»Ø˜­Èš°È“«Àª¼ž¶Ë“¨Ã¥Â¡Ãƒ™º‚›»ƒœº‚›¹€–µ…™¹‹¢¾‚™µ|”©~•¦|¤zŠ¤y‹§r„¢t‰¦m„ n†›lƒ”r‰špƒ˜j}”m}—\l„TcyKXh%/ - -  AN^FTaKYfBS]CT^@Q]DTeERbAJY9>F;>?BGE_fdjq|el…]i‚cqŽfvŽm€•p†š~”¨}•¨‚±ˆ£·ˆ ·Œ¦¿… »† ¹£»¥À¢³Ôœ­Îš«Ìª¼Ú›­Ë´Ð›µÐ˜¯É›®Ç•§Ã–¨Æ¡¸Ò¢¼Õš´Í¥¼Ö§¼×ª¼Ú¯ÁÝ«½Ù©¾Û±Çæ¶Í餻ׯÊÞ¹Õâ³Î৾ثÀÛ²ÄàµÈá¯ÂÛ§½Õ£ºÔ¯Æâ®Äã®ÆݬÄשÀϦ»Æ©½Ë±ÅÕ­Ãק¾Ø ·Ó¤¸Ø¦»Ø§¹×°ÆܪÃÓ¡¸Ò—­Ð›¯Ñ®Ïœ®Ì¦¸Ö µÒ¤¹ÖŸ¹Ò›¹Ñ«Ä™°Ê˜³É“®ÄŠ¥¹§¼Œ¢ºŸ¼Ž ¼›­Ë¢½ˆŸ¹˜²|‘®}’­€–®ƒ™¯‡š±‡š³{©…—³z‰¦yŒ¥’«x‹¢r‚šn‚”ki€‘i•k~•p€˜duˆWgvTeqBP]&4? $FBDHST]dercl{hyŒp„”n‚’vŠœy‰¡}¥ƒ—©„›ªŽ§³‡ ®Š¢µŠ¢·¦¾š­Ä¥µÍ“¦»¦º”ªÀ™®Éš±Ë–°Éš´Í˜¯É™¯Å¥µË²ÈÜ¥½Ð¯ÇÜ«ÀÛ£½Ø£½Û¤¿Ú¢¼× ·Ñ§¹Õ´Êà·Íá®ÄÚµÇã­Âݦ»Ø¨¿Ù¯ÇÞ¬ÂÚ®ÁÚ­ÃÛ¨½ØªÁÛ¨¿Û«ÀÛ©»×¦¼Ô«ÁÙ²É壼ޫÁ୿ݦ¸Ö©»Ù¥¹Ù¤ºÛ«ÂÞ¤¼Ó¡¼Ò¥¿Ø¤»×—«Í®Ñ˜¦Ê–¬Í’¬Î•¯Ï‘ªÈ§Á¥½¥À¥Â–¨ÄŸ¼¡½¥ÂˆŸ»ƒœº† »Š¡»…œ¶ƒš´˜²„™´—¯„š°‰ž¹y­yŽ«v‹¨r‰£f—t‹¥t†¤r‚œtƒ›l|”q„›o—etŒ^n†Tg~M`uJ[nAUe4HV1GIBNeFViFViIVjJUjMXkQ\mJWgJWiNWfEIX9>J7:D?BJWZbakubsct…sƒ™vŒ v‘¥{“ª~“®ˆ¸ˆš¸†˜¶†˜¶‹£º‘¬¾œ´Éš°È¨¿˜°Çœ´Ë´Î µÐ¢´Ð¡³Ñ§¸Ù µÒŸ¶Ò¤¾Ù¤¾Ù¦ÀÛ«Áࣺ֤»×¤¹Ô£µÑ¦»Ö¥ºÕ§¾Ø®Åá¨ÂÝ«Äâ°Êå®Å߬ÃݲÇä°Åà¶Ìä±ÉÞ¥½Ð¥»Óª¼Úª¼Ø§ºÓ²ËÛÀÜç¦ÁÓ¤»Õ¯ÄßµÇå¬ÁÜ­ÂÝ µÒ§»Û¬ÃÝŸ·ÎŸ·ÌµÊ—±ÊœµÕŸ¸Ö˜²Í•¬È µÒ˜­Ê‘¢Ã–«ÈŽ¥Á’©Ã–«Æ¦¾Š ¸‰ ºˆ¡¿Ž©Ä‡¢½‰¤½„Ÿ¸† »Šž¾Š›¼‰—¹„™´™°’ªÁ‚˜°z‘«rŒ§rŒ§t‹§t‰¤x‹¤q™m|”ds‹w† kz”`l‡]i‚^jƒP_uIYoFZj=U_?VUCT^GYeAUeGYeQ_jM^jRbqL]lN_pGYeEWa?QX8EN7>GBCNSWf`h|gtˆr™t‡ sˆ¥{“ª„œ±ˆž¶ƒ•±‡™µ†˜´ ¹–¦ÀŸ´Ï™¯ÎªÃ©¿•°É—±Ì›µÐ¤»×ž³Ð©»Ù¡¸Ò˜²Ë·ÒŸ¸Ø¢¼×¡¼Ò©¿×¨¸Ò©¸Õ­ºÜ¬»Ú°¿ÜªÁÛ¦ÄܬÈÞ­ÅÚ²ÈàµÇã²Çâ²Éå¨ÃÙ¨ÃתÅÛ¨¿Û§¾Ú¨¾Ý¬Çà¢ÁÖ°Ìà°ËݺÐæ°ÀÚ¨¾Ö¥½Ô§¿Ô­ÃÙ¦¼ÔŸ´Ï¦»Ø£´Õ¦¸Ö¨·Ô¤¶Ôž²Ò¡²ÓŸ­Ï–«È§Ã˜°Ç ¶Ì ¶Î¯Íš¯Ê˜°Ç‹ »Šœº‹»ˆ™ºˆš¸ˆš¶‰ž»Š ¿}’¯Ž«‘¯•·€”´€•²}”°}”°}’¯|Ž¬|Žª|Žªqƒ¡q¡l{˜o—buŒj}–cvaq‰Thz\p~QbuN]uO_uJZpObiBLfFPhGQiJZiH^dKagKagN`lJZmK[nN]sJZkGXdBKX;ILSfmm†wƒy†–vƒ—~Š˜”›¤—¢‘•¤–Ÿ®Š•¨Š—–Ÿšž¡„„‚Œˆƒ†}ˆ}”Ž€š“ˆ–£œ“§ •«¤™°©ž³­¯ª—¨¤“«§˜®ª™®¨˜´«œ»¯¡»µ“÷ôÁÿÿÆÿÿµÿÿÃÿÿËÿÿÉÿÿÇÿÿ»úÿ¬þÿ®ÿÿ¯ÿÿÅÿÿ×ÿÿÚÿÿÊÿÿºÿÿ·ÿÿ²ÿÿ²ÿÿ¸ÿÿÊÿÿÄÿÿ»ÿÿ²ÿÿ°ÿÿªÿÿ·þÿ¢ûÿ™þÿ›ÿÿ¢ÿÿŸõ÷”öø“ÿÿžÿÿ£ÿü“ÿÄì_ôldÿ[jíc`ÚjUó·yÿÿ³ÿÿÇÿÿ×ÿÿÕÿÿÓÿÿÏÿÿÍÿÿÑÿÿÕÿÿ×ÿÿÙÿÿÙÿÿÛÿÿðѱÌÀœÑ¿—ç¾–á¾—ßÄåÉŸèË¡èΥ黡ÇʽÈÿÿöÿÿ×ÿÿÕÿÿÕÿÿËÿÿÁÿÿ¹ÿÿ¹ÿÿ»ÿÿ¾ÿÿ»ÿÿ¹ÿÿ½ÿÿÁÿÿ»ÿÿ³ÿÿ§öð‰ùöú÷”ôð¨ÿÿÿÿÿÿÿÿÿÿÿÿÕØ×BIRp{t…‘x‹’ƒ’–—™Š‘˜Š›ˆŽœ}…—}‡‘Ž•œ‰ŽŽˆ†‚Ž‹ƒŽ‡|ˆ}•‹“Œƒ”Œˆ ›‘§¢–©¥–¬¦˜¯ª—®©’¬§”­¤—±¨™³ª›±ª‘¹³‘½†÷ó§úû±ÿÿÉÿÿÌÿÿÕÿÿÂþÿ¯þÿµÿÿÆÿÿÊÿÿÄÿÿÈÿÿ»øý©ÿÿªùþªÿÿ¿ÿÿÆÿÿÄÿÿÅÿÿÃþÿµùû¦ÿÿ±ÿÿµÿÿ¨ÿÿ›ùÿ–ÿÿ¡ÿÿ ÿÿœÿ÷Ÿÿñ¨äÇzÿð ÿì¢ÿ¾~æ|[öed÷abôX]ÖnLí¶pÿÿ½ÿÿÕÿÿÕÿÿ×ÿÿÓÿÿÏÿÿÇÿÿÁÿÿÃÿÿÇÿÿÉÿÿËÿÿÛÿÿîçÊÖÒ¦äË¢äÜ伕ۻ•Ø¹“Ö¿•ÜÄšáÇäà۹Íø·ÿÿãÿÿàÿÿÕÿÿÏÿÿËÿÿÁÿÿ»ÿÿ¹ÿÿ¹ÿÿ·ÿÿµÿÿ´ÿÿµÿÿµÿÿ³ÿÿ³ÿÿ¢óðýøœÿ÷¸ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ|‰™hwyˆŒ„‘šx€’‹™…‘Ÿ}‹˜}‹˜†“˜•ž›~‚z‰„zŒ‡}Œ…~†}˜Ž†‘ŠŠƒxš“Š©ž›©¡¦ ¦ ›£›—¢›’¨¡–¨¢”§¡‘°¦Œº­‰×Ñ–ÿÿ»ÿÿÆÿÿÆÿÿ¿ýÿµïõ¥ÿÿ¹ÿÿÇÿÿßÿÿÞÿÿÐÿÿÁþÿ³ÿÿ³ÿÿµÿÿ¸ÿÿ·ÿÿ«ÿÿ¨öýüÿ¥ÿÿªÿÿ©ÿÿ ÿÿšøþ‘ûÿ”ÿÿšÿÿ¦ÿÿ ÿþ—ÿê ÿ´…á\ÿ«xÿ–qílUùl^ÿfeìdUÚcIç¥iÿÿ¦ÿÿËÿÿÛÿÿ×ÿÿÕÿÿÓÿÿÓÿÿÍÿÿÆÿÿÇÿÿÇÿÿËÿÿÏÿÿðòÕÝͨÒÑ¢òФðФðÇŸêÁ›èÂœæš忘àÃœäÉ¢è›ῢÇį¶ÿÿêÿÿÛÿÿÑÿÿÇÿÿ¿ÿÿ·ÿÿ·ÿÿµÿÿ²ÿÿ°ÿÿ°ÿÿ³ÿÿ³ÿÿ±ÿÿ¬ÿÿ©ÿÿ ñíŒÿùµÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ›©©xŒ…ŸžŽ˜žŒ™¢›¨š}‰•‡‰€„~yzu‡ƒ€„€{‰„|Ž‡€šŠš“Š”„›‘‰§˜’¥›• ˜–œ–‘ ›“¡œ’¨¡–¨¢’«¦“°ªˆ´®~ðí©õõžÜã…éô‘íø—ÿÿ¬ÿÿ¹ÿÿ¿ÿÿÊÿÿÕýÿ¿õý¯ùÿ­ÿÿ®ÿÿ¾ÿÿÌÿÿÀÿÿ±ðö›ÿÿ¦ÿÿ¹ÿÿ±ÿÿ¬úÿ£òû‘õüŠÿÿšÿÿ¤ÿÿ ÿÿùöŽÿú–ÿÓõkì}`çkXìeXûjeýebþ\]ãcGõ–bÿê¢ÿÿÃÿÿÏÿÿÛÿÿÕÿÿÏÿÿÏÿÿÑÿÿËÿÿÇÿÿÅÿÿÅÿÿÍÿÿ×úæÖ̧ÊÔ«æΡ÷ÌŸóУ÷ÇŸïʤñÊ¢ðÅšëÇœëÅšéÅšæÅ›äßÔŦɻ¬¤ÿÿÓÿÿÕÿÿÇÿÿ½ÿÿµÿÿ²ÿÿ³ÿÿ´ÿÿ·ÿÿ·ÿÿ·ÿÿ³ÿÿ®ÿÿ¯ÿÿ«ÿÿ³øï™óæªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿµÅ»„”“ˆ™£ˆš¡Šœ£{ˆˆ„ˆ‹urq}z‚}u„}t‹„y“‰”…Œƒ“Ž†œ’Œ˜‘Š•Ž‡ ™Ž£¡Ž§¢–§£’©¤‘²¨ŽÁ´’éäŸéé…íî‡ÿÿ ÿÿ¯ÿÿ¸ÿÿ¸ÿÿ»ÿÿ´ôú¬ÿÿ¸ÿÿ®ÿÿÁÿÿËÿÿÁÿÿ½ñö¤ýÿ¦ÿÿ¯ÿÿÁÿÿºÿÿ±ùÿ©÷ü¦õùšùû–ÿÿ¨üý¡÷ûœüÿ¡ÿõ¤ÿÔ‘ï•sÿz|ølqô^hü_iÿ]göZVðZJìTÿè‰ÿÿÁÿÿÑÿÿÓÿÿ×ÿÿÑÿÿËÿÿÉÿÿÉÿÿËÿÿÏÿÿÇÿÿ¿ÿÿ×ÿ÷ÓϳÃÕ¬ðϤðΡõѤøÍ öËŸóÍ¢óΣôÈ›ïÛ黕ßÄœçÌ¡íÃœâÃÞÇ«Íį´ÿÿâÿÿÉÿÿ¼ÿÿ²ÿÿ¶ÿÿ·ÿÿ²ÿÿµÿÿ±ÿÿ§ÿÿ¡ÿÿ§ÿÿ¯ÿÿ¶ÿÿ±üô›÷í®ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ ¦«–Ÿ‹˜¡Š˜£}Œ”|‰’‰qvtwxs€{szrzs†€{‰„„‹‡‚ˆ€‘‰…“ˆ‡”†š“ŠŸšŽ¡Žœ˜‰¢‘¨¤•«§˜­¥}ÚÑÿÿ´ÿÿ§ÿÿ³ÿÿ¹ÿÿ·ÿÿ¹ýÿ¹ÿÿÄúÿ°ÿÿ®ÿÿµÿÿ¹ÿÿ¸ÿÿ¼÷þ©÷ÿ¡ÿÿ ÿÿÿÿ«ÿÿ³ûÿ©üÿ¨ÿÿ¦ÿÿ¤ÿÿªÿÿ«ÿÿ¥þÿ¡ýû•ÿÿ˜ÿÛ•ñŒiõzkÿouýgoÿdnû^aöVVßeAï˜QÿîŽÿÿ©ÿÿ¿ÿÿÓÿÿÕÿÿ×ÿÿÓÿÿÏÿÿÏÿÿÏÿÿÍÿÿËÿÿÉÿÿÇÿýÙݼÌϪÒÈžÞÐ¥ìÑ¢òÌ ïÈì΢ñÌïΣôş滕⸒߽•åÅëË£ñ˧åâÑÁ¯ªÿÿÒÿÿÉÿÿ¯ÿÿ®ÿÿ­ÿÿ¯ÿÿµÿÿ³ÿÿ¬ÿÿ§ÿÿ§ÿÿ¨ÿÿ¬ÿÿ®öôœòé¬ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûþýÿÿÿ×ãߎ¢‰› ‘¢€›|‹ons{vx‚wv~vrxq„|xŠ‚€ˆ€|‡€y‡€yŒ„€’‹„–†ž˜Š£ž‹¨£¬§”­ª”­ª”««uáàŒäå‡ëî†ö÷—ööŸÿÿ°ûÿ«ÿÿµÿÿµÿÿ¸ÿÿºÿÿ¿ÿÿÉÿÿÄÿÿ¸ÿÿ´ÿÿ®ÿÿµÿÿ°ÿÿ¯þÿ°òû¤ýÿ­ÿÿ³ÿÿ¶úü©úü©úÿ£ÿÿ¢ÿÿ¡ÿöû§zøopÿrsÿijÿlpÿbmò\[ë]Rê–`ÿíÿÿ¿ÿÿÉÿÿËÿÿÏÿÿÑÿÿÕÿÿÏÿÿËÿÿËÿÿÍÿÿÉÿÿÇÿÿÓÿÿÔßÈÉÍ¥àϦæÌ¢æÄšáÆŸçÉ£íÈ¥ñǤðÅŸìÈ¢ñÈ¡õÆŸóÅœñÂœëÁ›å¿šß¿›ÛãÝã۶ ±±¤ÿÿÄÿÿ­ÿÿ¨ÿÿ¯ÿÿ±ÿÿ·ÿÿ¯ÿÿŸÿÿ–ÿÿ•ÿÿ•ÿÿ—ÿÿžæÙ€ôä§ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÖÓÒ¯­¹‰Žš~Š˜†šˆ–|~‚pkoupp|vs~xuwu€xtyu„|x‡{Š‚~‹ƒ‰†~†”“†™™‡¡ŸŽ«¥—®¦’º®—ËÅ•ÿÿÃÿÿ¾ÿÿ¶ÿÿ¹ÿÿ¿ÿÿ¿ÿÿ¿ÿÿ¹ÿÿ¸þÿ´ýÿ¸ÿÿ½öü¸þÿ´ÿÿ­ûÿ§ÿÿ¬ÿÿ°ûÿ­ñùŸÿÿ±ÿÿ·ÿÿºÿÿ¯ùÿ¦úþüý–ÿÿ—ÿý“ÿñŸù¼…ÇiNÓUUÅEFÌJMöikúbcÜ]MÞxXÿÑ“ÿÿ¸ÿÿÉÿÿÓÿÿÍÿÿÉÿÿÍÿÿÑÿÿÑÿÿÓÿÿÏÿÿÍÿÿÅÿÿ¿ÿÿâñÛÙͬÎЦêÌ¡èÅ™åË ìΣòÍ¢ñÍ¢ñË£îÊ£ëÌ¡í΢ñÊžíÇ›ìÇ›ìÆ™íÅšéÈžçÈŸãÆÝê¹Ã¸šÿÿ¿ÿÿªÿÿ£ÿÿ£ÿÿ­ÿÿ¶ÿÿµÿÿ±ÿÿ¦ÿÿ¡ÿÿ—ÿÿŒ÷ô‘ÎÃ{úî¼ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÙØÝÃÆÎ}†“vƒ•}Œ”r{znsootppspstmzwozvq}wtyt…z‰ƒ~‹ƒ†–Œ„•Žƒ™’‡›•‡ šŒ¬¥ˆ¯¦|ÖÍ“çÜ’åá—ðô©ùý°ÿÿ´øü­ÿÿºÿÿ³ÿÿºÿÿ»ÿÿÊÿÿÇÿÿ½ÿÿ¸ÿÿ½ÿÿ³ÿÿ­ÿÿ®ÿÿ¹ÿÿÌÿÿËÿÿÄôù½øüºÿÿ¼ÿÿÇÿÿÎûýÔóõÕÿÿåýøáöòáÿÿýÿÿÿÿþñÍptçZqÈaYæ£ÿô±ÿÿ¿ÿÿÉÿÿÕÿÿÏÿÿËÿÿËÿÿÍÿÿÍÿÿÏÿÿÍÿÿËÿÿÉÿÿÉÿðÏÏ­ÂϪÔÉŸßÆœàÀ•ÞÆ›çË£óË ìÊŸæÉžåÊŸæÍ£êË¡èÏ¥éΡæÈæÅšëÅžæÃÞ¾™Ó¸”Ç­›‘êå¢ÿÿÂÿÿ©ÿÿ¤ÿÿ¡ÿÿ¨ÿÿ¯ÿÿ³ÿÿµÿÿ¨ÿÿ˜ÿÿ•þû“ÑÇfäÔzÿï°ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÉÐлÁÄ‹‘t€Œv|}zyjhdvrowsntpktqixskyvlyvj€{o†|t…~w‹ƒ‘‰…“ˆ…“‰–‰€š„¢•Œ£œ¤ rñò¨ÿÿ¤ÿÿ³ÿÿºÿÿºÿÿÂÿÿÂÿÿ¿ÿÿÀÿÿÄÿÿÁÿÿ»ûÿµúý·þÿÀÿÿÉÿÿÕÿÿãÿÿñÿÿüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïÐÖµ}‡½™qóâˆÿÿ°ÿÿ½ÿÿÅÿÿÍÿÿÍÿÿÍÿÿÍÿÿÏÿÿÍÿÿÍÿÿÉÿÿÇÿÿÃÿÿÁëß´¨˜Å£ÊÇœãÀ™ßº•Ú¹’ØÇäˤê›á›ãÈéÉžêÉžíÇ èÄãÄžáÃཙۿ›Ý¤и ¸ËÁœÿÿ¹ÿÿ«ÿÿ˜ÿÿ•ÿÿ’ÿÿ™ÿÿ£ÿÿžÿÿœÿÿ—ÿÿ‘ÿÿ•ÝÌ{ÝÍwÿöœÿî­ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÑÓÙÅÈÐ~‡”w„–¬¶¼ÿÿÿ‘–‹qpesriplgnmdsri{xp~vr~wp€yrƒ|uƒ{w„|x…zw~uh‚wd‡m‡xŠ‰e²¶ýýÒÿÿãÿÿõÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿëÿÿêÿÿôÿÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿñÿ¹—°º«Žúù©ÿÿ¼ÿÿ·ÿÿÃÿÿÍÿÿÉÿÿÅÿÿÅÿÿÇÿÿÉÿÿËÿÿËÿÿÍÿÿÅÿÿ¿ÿÿËƶyžƒÁ™ÏÂÙÁß¾šÚÃÞÄŸäÄžèÂœæÉ¡ìΣï΢î̤ïÅŸéžàžܿŸ×½žÓÀ¦¼Â¬¦øñ¹ÿÿ·ÿÿ¦ÿÿœÿÿ—ÿÿ”ÿÿŸÿÿ¦ÿÿÿÿ—ÿÿ˜ÿÿ–ëÛ~Ùºrÿç—úæÿè°ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ×ÒÒÊÅʼnr„Ž³½Åÿÿÿ«­³jlpllja`WKI8]Y?geHddEfdEhdHuuZŠ‹t±±ŸÖÕÈù÷ñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüóøÜÓØ¢•ž‰’¾£¬£“‚ÝÖ«ÿÿ¿ÿÿ±ÿÿ½ÿÿÇÿÿÁÿÿ½ÿÿ»ÿÿ¹ÿÿ¿ÿÿÅÿÿÇÿÿËÿÿÇÿÿÅÿÿ»ÿÿ±ÜÇ‘ª€ƒÀ™¸Â™Ù½—Ö¿›Ù½™ÙÄŸäȣ軖ÝÃœâË¡èÇäË¡êΤëÉŸã›ѻ™Â¬›ŠÔЈÿÿ¿ÿÿ±ÿÿ¯ÿÿ®ÿÿ§ÿÿœÿÿšÿÿ˜ÿÿšÿÿ—ÿú•ðÝ‘Ò¼qùà–ûæ–÷âùß­ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïìëÄÁÀ¶³²‚Š|„–³¹Çÿÿÿ¯²ºgkpjpi¼Á²ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõÿûêÿûìÿÿ÷ÿÿþôòìíéæâßÓÕÔÀÉÈ°ÒгÛØ·ØÒ°ÞÝ»ëëÎñïÔéáËÊÁ´”€…É®¹©–‘šŠyèâ¢ÿÿ¢ÿÿ¦ÿÿ¥ÿÿ­ÿÿ±ÿÿ±ÿÿ±ÿÿµÿÿ»ÿÿÃÿÿÍÿÿËÿÿÉÿÿÃÿÿ¿ÿÿËåÏ”¤†…·“ÊÂÙÀšÛßݶ’и”ÒÁÝÉ¥åÆ ãÉ£äÈŸßÅÚÆؾÁ½¡¯ÈÀ‘ÿÿ¥ÿÿµÿÿ´ÿÿ·ÿÿºÿÿ«ÿÿ ÿÿ˜ÿÿ”ÿÿžÿÿ•âÕz¾§aò×ýÞ–úÝÿã”ÿæºÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÂüÃÁ» œ—|x…Ž¶»Åÿÿÿ´²¼kiuw{~ÛäáÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïìíóñíéæÞÙÔÈÑÌÄýº©¢—Á¹§«£«£²©Š±§‚³©†È½éåÉïîÚðíÙñëÛðëÖñìÕîêÐñíÑõñÓòìÌôòÓûûàîìÑéâÉ×ÎÁªž }ipӷż¤ª›‡‡ ”iñï—ÿÿœÿÿ™ÿÿžÿÿ­ÿÿ¯ÿÿ±ÿÿµÿÿ¹ÿÿ¿ÿÿÇÿÿÉÿÿËÿÿÇÿÿÅÿÿÅÿÿÅüëÊ¢ƒ›¹—¾˜×½—Ö¾˜Ù¼˜ØÁ á¡àßßÅŸà™Ý™ÛÇݽŸ»¶£žöï·ÿÿ·ÿÿ·ÿÿ»ÿÿ»ÿÿºÿÿ¬ÿÿ ÿÿ—ÿÿ•ÿÿ¡ýò˜¾¬YáÃyðч÷ÕŽÿã›ÿåøدÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿåáÞ®§ ²ª¨˜’xw~y~Š·»Àÿÿÿ¯±·klwuy~ýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûûýðððßÝ×ÎËÁ»¸®°­¥¨¥›–“‡‡„p‡q‚x^—‹pšŽu©š„ªž‡®¢‹²£‹»¨‘ª—~¬™€®¡®¥{¶«}½±Àµ‡Ê½—ÔήáàÊèçÑëèÒêèÍóïÓöõÓùøÔ÷÷ØúúßýüäÿÿëþúéêáÔåâÖÎÐÆZRP Œ“»¦¯§Ž›’|v›ˆqàÙÿÿ’ÿÿ—ÿÿœÿÿ¯ÿÿµÿÿ·ÿÿ»ÿÿ½ÿÿÁÿÿÅÿÿÉÿÿÉÿÿÉÿÿ¿ÿÿµÿÿÃÿ﫪Œ‹¼’Ò™ݾ–á¾™àÁœãž༖׼–ÕÀ›×»—Λѽ¢©Ú̦ÿÿÎÿÿ»ÿÿ¶ÿÿµÿÿ¯ÿÿ¦ÿÿ˜ÿÿ”ÿÿ—ÿÿ–ÿÿÝÉ„Õ¶pïÀø̉ÿÔ‘úÓŒöщõÑ©ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþùý ˜–¤—©¡‰‚„kjqsw†¶¹Áÿÿÿ¨«¬ihmqpuëçïÿÿÿÿÿÿÿÿÿÿÿÿ•˜™kno]Z[UNNwpe”Œv‘†s‘r–‰u§›„®¢‰¨™©›~«œ}©›~¬ …«€°¡„¬Ÿ}®¡{®¤¨ |­¥}¨Ÿu£šn¤™k “mŸ‘tžp¢‘pº¬†ÒÅœÕÍ©êæÈüúßûúæûùêþûóÿÿ÷ÿÿüÿÿùÿÿþÿÿÿÿÿÿÿÿûûýñûöìöéâ’€‹eMlˆt‹|ŒŠz†Šz†‹‚cÊÆ|ÿÿ ÿÿ•ÿÿŸÿÿ³ÿÿ³ÿÿµÿÿ»ÿÿÁÿÿÁÿÿÁÿÿÅÿÿËÿÿÇÿÿÅÿÿµÿÿ§ÿÿͳ—±²½–ÜÅžäÃœâÂœßÃÞŸÚÅ¢ÛÁ¡Ëº›ºÈ¹œÿÿ¬ÿÿ¿ÿÿ¹ÿÿ·ÿÿ·ÿÿ­ÿÿ¡ÿÿ”ÿÿÿÿ’ÿÿòã„Ò±uê‚ò€÷ɈðÁƒòȆñʇûЯÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¢—–€yp—“‚•„|vqOOMLPS±µ¸ÿÿÿ•˜—_c[mrgýÿõÿÿúÿÿÿÿÿÿÿÿÿ¢¢¤hbihb]pjZ“‰m¯¡{£—n¥™p§žr£šn ™n•m ˜i¡–dœ‘c£–m‘h —mž•k›’h¡˜l‘f¡•j ”i›f£–p–ŒiŠbxp\jcZÑ;ÿÿðÿÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüûöðí÷òôÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõï꿶»WFYgVem[hk[gyiuˆxwŒ{oÆÀ€ÿÿÿÿ›ÿÿ˜ÿÿ¦ÿÿ«ÿÿ¯ÿÿ»ÿÿ¿ÿÿÃÿÿÁÿÿÁÿÿ¿ÿÿ¿ÿÿ¹ÿÿµÿÿ½ÿÿ½¸¡‡¡|Ÿ¶Á™Ù™ÛÙÝÇžàœۼŸ´Â®œþö´ÿÿ³ÿÿ³ÿÿµÿÿ¯ÿÿ¦ÿÿ¡ÿÿšÿÿ–ÿÿ–ÿÿ—ÿô‹Ö½hàº{íƒôŇí¿|óÆ~öÉ÷Ê‚ûÊ©ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¤©mftx|‚€yyidhA=EDBN¾½Äÿÿÿ¸µ´©£ž¿¹´ÿÿÿÿÿÿýúùÿÿÿÿÿÿ³µ«pwr]‚v_ž“s —m–a˜a›’f™h›’h›f—f—i–Žh—h–Žf–d—`—‹[šŽ^–Š\–‹]–Š_Ž[”‡e„y[j^GMD7@78ÈÃÃÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿæáÙÍÇĪ¡¤š“•´¯±öóöÿÿÿÿÿÿÿÿÿÿÿÿÿÿûàÝÕ]VKaTOdQS_PUWJSl]d…qzƒsbº­‚õð›ÿÿ—ÿÿ’ÿÿÿÿ¦ÿÿ¯ÿÿ·ÿÿ½ÿÿ½ÿÿ½ÿÿ»ÿÿ»ÿÿ»ÿÿ»ÿÿ·ÿÿ³ÿÿÇÔ¸„¡‡·ŽÐ¿™ÜÄŸæȤâá׽ª¥îå¨ÿÿÅÿÿ¹ÿÿ·ÿÿ³ÿÿ­ÿÿ¡ÿÿšÿÿ–ÿÿ’ÿÿÿÿ–ëÍ…ß½vîÄ‚ìÂ~ç»xç»vëÀxç»vïÁ€óÁ£ÿÿÿÿÿÿÿÿÿÿÿÿ¤£ªdadojj|xuzvqrnk^YY668-/5“ŽŽÿÿþª¡¤ˆ}Œvmyÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþ´ž–„™u¡—t´«©¡r”j›Žj—h”Še“‰b–‰c†_‘‡`‘‡`’ˆcˆbˆb’Šb‘ˆ^’ˆa†a†c’„e‰~`|pW[T;@;&21&476·º¹ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷ò굫¡‡€yf__TPMKGDa`SàáÌÿÿÿÿÿÿÿÿÿÿÿÿôðá~r[gXBdS@`NGZIOQBI\OXuloypq•_ßÜ{ýÿŽÿÿ‡ÿÿÿÿ«ÿÿ²ÿÿ·ÿÿ½ÿÿÁÿÿ½ÿÿ»ÿÿ¹ÿÿ·ÿÿ½ÿÿÃÿÿ¿ÿÿ½èÒ¯®…ž»”ú׶–¼·¢§àÕ£ÿÿ«ÿÿ³ÿÿ¯ÿÿ¥ÿÿŸÿÿÿÿ›ÿÿ”ÿÿ–ÿÿœÿÿšëÚ„×·{ß¹zì½æ·}緂巀꼅뾂îÁƒî¼ ÿÿÿÿÿÿÿÿÿ¥¥£ab[hf`tpkzypsrgli][VJ83+#0'*G@@GBBYVYÿûÿÿÿÿñõíÿÿÿÿÿÿ¼¸©•Žs’‰h”Še—h–Œi‡a‡aŒ‡`‰„]‹ƒ]…`‰YŒ…ZŒ„^Ž…dŒc’ƒi„dƒ`‚b‹€bf€j}p\_TA>9&2.-+%438¦¥ªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ½¼³‰†ztqeLI=<9-A>4Tc\2RNÿÿÿÿÿÿÿÿÿÿÿÿèØ×—}}gSvc:hV8]I7VD=SBFZIOucnph‘‚jØÑŠùù‡üÿ…ÿÿˆÿÿ™ÿÿ¢ÿÿ§ÿÿ±ÿÿ·ÿÿ½ÿÿ¿ÿÿÃÿÿÅÿÿÃÿÿÂÿÿ¿ÿÿÇ÷颫€¹¹»¢ÔÌ›ÿÿ²ÿÿ©ÿÿ©ÿÿ©ÿÿ£ÿÿŸÿÿ™ÿÿ“ÿÿ”ÿÿ”ÿÿ ùæšÛ¼yâ¹€åº{é»xé»zê»}ê½ä·}ä·yà²qå³—ÿÿÿÿÿÿ¸·¾eegjghlihsnnuqnmifhj`NSF/4)2/2OKHYRK€}uÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ»·¦•Žq•Œk”‡e‘‡bƒ^Ž†bˆ‚`‰ƒcˆf‹g‹fŠ~c‰}b…{a…~eƒ{e†~j€{dƒ~g€{hxkzubojU\WDE?/82$2+ 0*'6.5–›ÿÿÿÿÿÿÿÿÿÿÿÿÿÿø˜jƒv=we)r]~i.va+UE4uk~ù÷ÿÿÿÿÿÿÿÿÿÿôôòhe]rhP~kDyj9xn1rf=ZJ7TEA^K[o\lvcu‰}dÓΉÿÿ›ÿÿÿÿ‡ÿÿ”ÿÿ˜ÿÿžÿÿ¢ÿÿ©ÿÿ´ÿÿ¾ÿÿ¿ÿÿ¹ÿÿ¾ÿÿÁÿÿ·ÿÿ­ÿÿ˜§œ@¿ÀYýÿ–ÿÿ­ÿÿ©ÿÿ¥ÿÿ£ÿÿ ÿÿ ÿÿ’ÿÿŒÿÿ‘ÿÿ–ÿù“å߽̀vã·vê»}ñÀ‡é·è¹}â³uà³uä·{ä³™ÿÿÿ¸ºÀfeljjjgeaie`nfbmh`gd\_]WLLJ000&%DA5NI=cYQ¾®­Ê½¸Ë¾¹ÖÉÄÚÍÈ´¬˜”Žn‘Œg‘‰c‹€bŒ}g„zbyczubyrgxqfuneunerkdli_fh\hj`hf`ji\mkZmjVd_LXQ8E;-(4/1+(4(A3„‚eÿÿÿÿÿÿÿÿÿÿÿþäæ½ãå”÷ö€úùƒüø…òå|ü扴¢k“ƒrÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ‹gufPt`N}lIzk:†zJŽVrcFVD8VBDkQcs`b~pcÉÅ„ÿÿ“ÿÿ“ÿÿÿÿ•ÿÿ”ÿÿœÿÿ ÿÿ¨ÿÿ³ÿÿ³ÿÿ·ÿÿµÿÿ²ÿÿ±ÿÿ¸ÿÿµÿÿ±ÿÿ¤ÿÿ­ÿÿ­ÿÿ­ÿÿ«ÿÿ«ÿÿ¥ÿÿ¡ÿÿ–ÿÿŽÿÿ”ÿÿ˜íÜ„Ö¶sزqá´xå¸|ê»éº|éº|ä·yß²tæ¹{Þ±uÞ®‘ÃÃÓ`alhfpeegec_a_Y_[Vca[\]V\]XNKL//1! ?A5GI?1/)D@=KCAI;;@84E?:|wd‹‚cƒ|_|u\vkXpbWi`Sd^PdaU\^T]\SZVQ`ZUcXU[VLYVJXVGVTEKI.RL*h^9{jEqb3š‰T«x‘rBªHÚ¿dßÃqðÑ‹¿«‰çÞßýøüÿÿÿÿÿÿûûÞâèœÿÿŸÿÿ¢ÿÿŸÿÿ£ÿÿ¤ü÷´ðëÆÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ±¯©ƒzktaLqc?wk9zn<„xH‹~U‰xW[I=H3?iU\€lqtNÇÁoþÿ˜ÿÿ–ÿÿ‘ÿÿšÿÿšÿÿ™ÿÿÿÿ¤ÿÿ«ÿÿ¬ÿÿ³ÿÿµÿÿ¶ÿÿ»ÿÿ·ÿÿµÿÿ±ÿÿ°ÿÿªÿÿ®ÿÿ«ÿÿ¦ÿÿ¥ÿÿ ÿÿ”ÿÿÿÿ”öçˆÛÁsÚ±xß´yå¶zæ·{ê»îÁ…à³wç¸|ã²wÜ­qÚ­qÖ¥‹[Yca`g`\b__]^_XSTOWTSOPKUVQYWQROG%#40+QLDC?ƒyRM>:L=@n^h‚x`¨¡iÝÝ„þÿüÿÿÿ}ÿÿÿÿƒÿÿÿÿžÿÿ¢ÿÿ§ÿÿ¨ÿÿ­ÿÿ­ÿÿ²ÿÿ®ÿÿ«ÿÿ¦ÿÿ¦ÿÿ¢ÿÿŸÿÿ›ÿÿÿÿšüó‹ÞÇoã¼wòÆ…ñÀƒð¿‚æµzå¶xÞ¯qæ¸wí½}í¼çµÞ¯sÙ­lÖ¤ˆ\^R[]SWXSRPLSMJLGGIDFIDFOJLJGH2/0%%#'+%$( !93.;742/.HEDOLMQRMWXQgbXŠ~rhaV`]Sd_Ud]ThaZh`^ga\ga\jb`i]_cNUcBOlP>ë}ÿÿÅÿÿÑÿÿÂÿÿ½ÿÿ»ÿÿ¨êîñù”ÿÿªÿÿµÿÿ»ÿÿ¼þÿ±îð­ùûÔÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷ÿõèá̱͢j¥P}f8hV(i\1znCpg;um:{t<Œ„Q‹€RYM6J9=ued„uo¦qÖÐ~÷ù‰üÿwÿÿyÿÿuÿÿ|ÿÿ‹ÿÿ–ÿÿžÿÿ¤ÿÿ§ÿÿ©ÿÿ«ÿÿªÿÿ¬ÿÿ©ÿÿ¦ÿÿžÿÿ–ÿÿ•ÿÿþóŽì̓èÁ|ê¹|ç¹xæ¸wÜ®kà²mé»zí¾„ñÁŠì¼‡çº~ß³pä¸wà³w߬•]\SWXQOOMGHCEF?BB@98=99;>>@<8>:4=95;88:<9:.')0++0,'52*?>5NMDUTI^]PdbSztfc^Ra^Ta^Vb\Wb^[e`bd`]d`[fb]ga^f`]g``gX[ZEL\C@~aVį‡ÿø²ÿÿÃÿÿÅÿÿ»ÿÿ§ÿÿŸôú‘ôù•ÿÿ­ÿÿ·ÿÿ½ýüÍÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòïðãÜÜÑÉŪ šŠj–‰eìЙõÊ‚Ü´v±‰Vƒd?bL4dS.yj;xm8}r;{p;‹|K’„bhXIH:8lbl~rd£–rÜÖ†ðñxúÿzÿÿzýÿxûÿxÿÿÿÿÿÿ“ÿÿœÿÿŸÿÿ¤ÿÿžÿÿšÿÿ”ÿÿ‘ÿÿ“ÿÿ“ÿÿ“ÿù‰êÒxÜ´tجkâ²rá²tê»쿃è»ê½ƒå¶|ãµ~ãµ€ä·}è¹{éº|æ·yÜ«‘ZTOSOJGC>C@8C@8@;3E=9_XX+$(.(/-&2.*22.63/5+'-50(:3,G=7MF?RMEQNDSPDZUIpi`a[V`[[^ZW`ZW_\T`]Sc^Rd]Re^Ud\Xc^Vd_W\WOOGCG?;G<;=**@$'sVGʨ‰ÿí¹ÿÿ¿ÿÿÂÿÿ¹ÿÿ®öýùü¢ÿÿ¯ÿûÏÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿëæèØÑѹ²´ ˜Ÿ‹††|xskj]`aL^W:‡ySâÆÿÖï„ڪs¬†XvW4aH&cR1tg>|qAzD~w?‰N‹‚Vm`NH4=fU[|ko•‡cÖÉ}èßyøósÿýzöòmûýtÿÿ…ÿÿŽÿÿ”ÿÿ—ÿÿŸÿÿšÿÿ’ÿÿ‘ÿÿ‘ÿÿÿÿŠÿýéØ~Õ·mâ·|æ»~çº|ê½æ·}à±wá²xà±wå¶|çº~ê½뾂鹂ã³|߯zá®™YSPTLHeZWQKH@=7=687%2@#+yOR¼™ý߬ÿû³ÿÿ¶ÿÿ­ýøœíé»ÿÿÿÿÿÿÿÿÿÿÿÿæßãÈÂɬ¥±‹‚~{uqlurjwth{yjƒ~iˆ|c~a”€`›„Z±”cß¿~ÿÚ‹úЊïÀ„Ò¦pªTpP0\C3ZK1e`;zsFvDxB…€G~vNeZEG:5^K[|miƒw`»®rÜÍpíãwøówùûtÿÿ{ÿÿ…ÿÿ‰ÿÿ‹ÿÿŽÿÿÿÿ–ÿÿ“ÿÿŒÿÿ‹ÿüŠîÚƒÛº€à½èÀ‚ä¹~鹂ްyÜ®yá²væ¶tß°rä¶å¶|ä³zß°vÜ®wå¶|ã²y汚NHEDA@PPRPMNIDF_\]??A!#'668'"&:7:KGMYVUb^YQOIUSMVSRVQUVOQYPQYRR[TT]XZ\Y\^[\]Z[>D=.<.~‰xÁÉ´‰sYY:rr`khg]YTLG?C;9C495 ,6,kME¨ƒeóØœÿÿ¯ÿÿµüõ¬¾³“Œ}„b[_KGM]ZYkh`trcyvb€y`‰~`€U¥”_¼¨cÔ¸fßÂpèÄwà·nÚªhèµrõ¾zô¾|íºyÙ®qÞh™{OaH(R?(TF9_S:oe@md:pe7j`9g\>UG:D37I:=o`e}sYµ®xÓÌzá×kóôtýÿsÿÿ|ÿÿ†ÿÿ‰ÿÿ‹ÿÿ‰ÿÿ…ÿÿ„ÿÿ€ÿü„ìÝ{ßÂuÖ­tܯuä°xç¶{ç¶yê¼{í¿|îÁwíÁræ¹qá²tܯuÜ®yÖªrÞ³xß²xâ²{ã®—=@?>D=;B6?D9WUOcga&+) -      -87.=:0;:1HF@HD?MECTNKTOOSQMNOHRPJSOJTPMXSUXUVZWZ\X^PKV/15˜›ÿÿÿÿÿÿÿÿÿôñÛWPE{mmyt€~xsqmc`_OLK<987221(+(T3<¢ˆÏ¹¥ncNihTdaKRJ6k^<‚n?—‚L¬“Y¨cÚ½nêÆyß´jìÄtÿÛˆÿë–ÿê–ÿã”ý·â²pï»ê¶|á­uÛ¬r׫sÞj}RdJ*R:'SC-OC,g[BiZBVL4TL6JA2E;5A59L>Nmac{re¯¥pÑÆjäàmùûtÿÿwÿÿwÿÿ|ÿÿ~ÿÿ}ÿÿyÿÿvÿÿu÷é~ÞÀvÔ­jß®sâ²rë»yã´vç¸~à°{ÛªzÚ©w߯zà²{繂쾇쾇滀ݵwâ·zà±wØ¥Ž8àÝÑñöëôþöÞéÚÿÿý‹”„X\T\ZTc]Xsjkˆ|‚…||stqkhZVQ=9473.+'"%!^[Orn]l½¨r׸uæ¼mè¿kôÉsñÇvîÄwÿÞ“ÿãù͌߮sódžÿÝ—ÿà•üÒ…é¼tÚªhÔ¦eתnÕ®kÙ´nÛ¶pÅ \›~CjR$P<L;,>-!J;3I<5:-(;0-5,-A8;C6?[NYwfwƒlÓÊûú›óøy÷ýwýÿwÿÿwÿÿuÿÿpÿÿkÿÿ~ÿó‰ïÓ⻃ä¼~è¼{å¹vß³pÒ£gÔŸlÔ¢nاuß´yèÀ€Ý²wÞ°{ݯzקrשtß°~Þ¯}縆ò¾¬79?8:>??AGDEIDD<98      42.@=3LG?H@<:7/IKAMOELJDJGFKFJNKLNNNLLLMMMIIGPMLQNOQNQWTUXSSURU+*1FK@àçλ©íôÛÂÊ·ÍÓÊ ¤œZXR\ZTYUP]WT]TU[TT`Y[rni„w‚xnlfLQF'. &)/-#L0¸”nä¶øÌ‹ÿØŽýЈÿØ•ÿÕåºrðÀ|ÿÌŽí½yè»qöÉý·ûÍŠóĆá´zÑ£nѦkÕ­oâ¼}Ú´uº™]£…O‰qEcM.UE/A2*H;4L?:E;5J?N?FYHWkYoth\—ŽdàÝŒÿÿ÷þ~õývöþsüÿvÿÿtÿÿpÿÿ…ï×{бiΤrͤmÙ­uåº}õÈŠþÏ“ÿΕÿÓ™þÏ•îÂç½wçº|à°{Ù«tä¶ä·{áµtݲuݱ{Ö¤‘591593::8?<;G@@NGG?88)%"+)#$$"?=7YUPZRPaZZ_Z\LJFKICQOIPNJOMGKJAIJCJKFGGGIHMIIKOLMPMNQNOSQKVUJIIG"$*;C:ª‘í÷ت­Š{ÓÏÊyvy[YgZV\ZVS[VX\T[ZT[XRYVQQYVNVSI_ZNje[nhcVRO=:93..,#&##L%©|^Âj¸Ró¼ò»uî·sé±på²sè·|ß°tΡgÓ¤hÖ¥hà±uΞgÈšcÉ›dΣfÚ³pÒ¬o¾–a»™b¹˜cµq|\N=.L;?PAFG;ATDNUCP^K[n[mxgoxhgž–gêéŽÿÿøÿlþÿnÿÿqÿÿzÿÿ„ýó‰êЀàÁyÙ±sÔ¬nÛ°uݱyÛ®{Õ©qÍ¢gÔ¨pÙªxÙ­wß³}èÀ‚ã¾zîƆòÇŠæ¼zâ¸rÖªiÛ¬rᬓ162162698::8E@@MIF[UPHDA2/.)/&ch[^_Xa\\g``g^a_XX[URUSMTVLQRMLLLLLLOLMLIJGDEIFGE@D@=@GGISPOXTQ@=@#)CFC=D6heYÿõíèàÜrmqSPOXVPVULVSKZUMg`Y]ZRTVLUVOTUPQRMPMLOMGNMBVULXVPSQKFD>=;7;6691-/ $ -@gNÇ™pè¸óÀ}à¯rß­wÙ©rبq¿Z˘gÙ©rÚ«oÖ«pº“Yµ‘XÁœfÔ­uÑ¥oÄeÒ®uß¾„Þ¼…½£q’€ThV:]K?J83J:;ZJKm\`xgo~hyrb¬¥xïîœÿÿšþÿ‹ÿÿŽÿÿ“öð‹âÐ}ݽ~á»~ïˆì¿õɈöʇüÐÿÖ“ÿÓ’ùÍŒîÂæ¼zæ»|ç½{æºwã¸yÔ¬p̦iÔ®qß³{óÂúÅ°.3/474777A?;HE=IH?PRHHIB&'"!KRFjoddf\b^Yca[db\ca[ea^_]WZXRXYRUYSQUMPQJMOEIKAHIBDA@?=9<8531+87.32'+*PLGULMJ>@C47>58NFMVQQRPJSRIXWNVUHSSCSPDXSIVSISRIPNHPKKMIDMJ@ONAJL>GI=@B87833013.26.5A7AJaOCn]ctdc~oi£™vÜÓ–êà¡Øȋ͸˯{ŤrÆ rÄœlÆ™hÁ˜aÆdÓ«mϨeÒ¨fÌŸaÒ¥iß±zàµzëÀƒòȆõÉ„üÒŒõˇøΈñÇé¿{æºy涗10'54+:7/@;3E=9E?DC8BA88:027,.3(/1'+,'414DDDNNNPQLMNGQOISOLRNITNIRMERMC[VNVNLSMJRLIOKHKIEJHDIDDLHCQNFLFAD;<>794.5-*+))'%"#'"&+'/75AGBFJ?>:(#@&[?+ €`½žp½œbº˜a´’`­‹V¶‘[»š^À _µ”Z¸’dѬvÚ´wÈ¥eɦfܶwê¿„Ö³uŦgÉ©fÝ»téʂ׹s³šb‚mEdQ:[IFcTLpdVyoS}vK¤–`ĬmÚ»|Ú´wܶwÙ³tÙ¶v×·xݺzç¿êÀ~ë¿|ì¿çº€á´zÞ±wÕ­mЮgЩdجiØ®lÛ°qâ¸vê¾}11/632;44:20@54A:3C>4@=1%"BA6dcZSOJB;;aX[eXa`YY^ZUVULXWLWVMWUQRURPUUQUONPFQPGSOJPLGMIFIGACA;A?9=;5:9065,21(,(# "!**(=;7KDDYMQUOLQMHPMCLJ;QLBSKGNHCMGDLHEKIEKJAKJ?JIH@>?9451,/-)))'$'&!&& %%# $53/MDETGBE3)Q8*nO>rXªŠj¶—iµ”X³”U¼^ɪgÄ¥_¶“QÇ¡bÖ°sÌ¥mÅœeتuê¿€ã½sË©`£]×µnà»uÑ®nʦmΰxÀ§o±œc² fÁ¬lÔºwغtÙ·nÖ´mسoزuÖ®{Ö¯wÚ±xã»éÁ…å½èÀ€â¼}ß¹|ܶwã½~ß¼|ݽ~ß¼|á»|ã¾xá½pÛ·jÖ°f׫†24(24(43*21&54'96,@;3ID:KD;hc[YUP410886RPL^ZWYRROLDLK>PMCRKDPHFTKPTMOSLLRKKRKKPLIQMHONEIH?FE?:64.31+/-'+)# %51.B?>EFAIJEHF@LFAJFCJEEGEADBGI=GI?CA;=?379+13'+,%()"'%%&!###"""!!!".+.<8>D>GC79L96lUHs]¦ˆ`§†Lº”WÕªmà´sТ_Ó¥dæµzßµs˦^ݺjðÌvéÆrÕ²bΪ_Ö±kâ½wÚ³pͪhÍ®oÖ¶uá¾~ä¾}Ö¯l˨fǧf¿›`½•bÛhΦs×­yتuÛ°uШhÊ \Ì [ˤ_Ã\Æ _Äœ\ÄXÇ YÊ¥]̧_ЮeбiÛ³sä³zë´ž43(32'2/%2/%30(51,<55QKFidZZWKGF935+C>@=96C=8B>9@>8?@9AB;FCBHCGIGAIK=FH8HD?GA>DC:BD8BD:DE>DDBGCIIDDFA9C@4;;+63+5,//+(*("%&"#" #" "# ) !*"#.!$%-.)<83MB?XF<{_Rœ{d²Œn̤qß³pÕ©hÒ£eç¹tïÁuß°gç·súΉöψá¼xÏ©lÒ¬oà¸|Ý·xÆ aȤiÚµ࿅ͬp½œbÒ­yέsË«lͪlÙ±uá¹yã¼yëÄîÄ‚ôljûÌõȌ쿃ä¼~ß¹|â¼å½éÁƒìÁ‚ì€íÁ~ñÀôÄ‚çµ—31+/.%-,#+*--11!<9-SREZYNIH=<;2:::% ###--+1/+30/0+-1.-20,42,<:4A?;IDDC@?DABJHDJHBHCCLDKKHGPQJMOCKJ=LK@IF>JFAF@=B>9?=7<;054'87,32),+"#!-*)@AC?:;74502.+,***&)(#(& &#("  % $# $ %$&"%$"#,#%+216@99O?>v_R ~jͨ…事Φfß·göÌê»rÚ­eîÀ}ûÏŒíÁ~àµv׫sá¹{ç¿ϨnÈ mØ°}ß·„ͨwÆ tͨtÕ®vÕ®tÛ³wàµxç¸zë¿~ñǃ޳vÉœiÀ”\Á–[Å_Äž_Ç fÔ¬w⸄콋øÊ“øË‘òÅ‹÷Çÿʵ0-%/.#+*(%+%40!CA2JI@A>=53-21&13),-( !!)"$(!!'!%#$% *(".*%2/'74,98/<:4BA8GDHD?JFAQPELK>KH>MF?TMFMEAPHFKBCGAGE?BA8;:197350411/*.()-'+,'*'&+&(%##% $!$!##%"$#% &&"%+"&(+)#-((/*,3-4:,*WB9«{἞්ðÁ…ùÈ‹ç°uä³ví¾€ðÂí¿~Þ±sܯs꽃٫tË¡mØ°€Ì§vʨv¿fÊ©oÔ±oÜ·oà¹té¾ê¿€è»}Ö­vÅŸqÊ¢mÙ±uä¼|ç½yá¹yÚ±xÔ¬pÉžaÇœ_Ö\Ê›aÒ jÔŸ†.-$*) *) %".&"52*CB9GHC335,-&21$&(*+$ - #$&(*, 02(53-:90DA9B>9E?C?IH;LI=LG?MECOGEOGEMEATJDQLBGD:BA6<;265,73.32).-$$("$$!  )$$A=:HF@@>8:76:6<333/3--1+++)(+('*)#)" &$ "##"$ %!% & '#(.%*, -,!-*",-(-0/1.11)20!$&gF-Çšlá±zñ»}òÁ„å¶|æ·{óĈøÉ‹á²tתlÝ°t迆ŠjʨqÌ«vÑ°vÓ¯tÆ aÍ¥eÛ°sã¶|ã¶zà³wË¢k³Ž]¹’ZΦjéÁƒîÆåº}Ø«qØ«mجkä·yí¾‚ïÂôʆùÒ­-,#+*!,+"&$-((632::8/-)($!(& (* $"% -   !!!##%+%,/*.2+/61164.:84;87B@:BA8DC8HG@2=<1<:494630//0+,-&()"#%,'+:4==:=856111---)-''+#&,%"'%%**$&,"%&##! $!' $("(%$*("/.%,+".+#,,*)+/*/-).*(,&/-'0%$1#/_;°…Yâ°zó¿‡ìµ~ê¶zöÆ†í¾€Ö©m׬oÞ¶zÖ°sÄžaÙ²x⺅⻃ȟh¾•^Ó©uß´yì¿ìÁ‚Ú²tÄcÄœgÈ kÙ±|ãºÒ§lÆ›^Çš^Ô¥gÛ«kÜ®kãµrñ¿¡/)&+'$($!'%+*!20**'&(#%)"&'"$! -  -  -   $%!)%"+)#+*!01*23.68.79-8:.=<3=94F=>E<=KBCLFANI?HE=IE@CA;BC>FGBAA?>?:=>7>@487*99)42#-,*,"$%$! ",)(01,/0)+-#)*%&&&%%'('.&&($$"!$!#(&&)&&'"()$+(',)**&,('.&'0+*/,)*+('.*'.*'.*'1+(0%$/ )8e?(¨XÕªoâ·z뾀׬qÀ”^Î¥lÓ¬rÑ°tÀ dÓ°pÜ´tÏ©lÃœdÏ©jسoÞ·têÀ~ܶwº–[¶•Yɨlß½xã½sÛ²iÒ¦aÊž[Ú­oæ¸wé¹y䮓,*$(&"$!!#$$% "    -  !&!!)$$-&&/**0++1/+53/611<36@:5A>4@?4DC8IH?IGAJHBLJDJHDIDDIH=DG4FF4EC2DB3@=1=:.61'0+#-'$%!"!&!'""&#"((&&&&#&'"&)!(($++#**!((#(&)))**,+'-*).&%*&&(***,)(-)&.)+1)0.+.(+*++),*&/(*4$0/7kO9¤€]Æ¡pݵyʤeÅŸ`Ë©dˬbƤ_É¡eÓ«mÕ­oÔ®oÓ­nÛ¶rÛ¶nä¿yáºwË£eÆdÕªkä¸uïÃ~ç¹tÜ®kÔ£fÚ«mæ·{ﻟ%& ! -    -   ## &!!!!#$+)#,+"/.%2--2*1726;68;93A@5DA9GA>D@;HG>JI@LHCLHCOIDMH>OI;RK@PF>MC=I>;D?798/43*1/))% -'$$ #! !&#"**(()$)*#*'&+&*)$&,''.''0'*,)*&)(%*&%*&&)&,)(.+*,)(**(,,*)-')-%*.&01*23,34/MGBn_WcL?œ`Ï©{Ï«rÈ¢cË£c׬mѦkÑ¢pÖ©xÏ¥v¼—aºš`Ô´uÛµvà¸zÖ©mÓ§fÞ°mè½uõÌöÊ…ïÁ€å·tÞ°mÖ±Ž \ No newline at end of file diff --git a/example/dev/file_grabber/image/img0254.ppm b/example/dev/file_grabber/image/img0254.ppm deleted file mode 100644 index 5f598f39dda..00000000000 --- a/example/dev/file_grabber/image/img0254.ppm +++ /dev/null @@ -1,25 +0,0 @@ -P6 -128 128 -255 -an~bsev€iv}jrvvyv¬©¡|q{q~‡m{ˆk|†p‚Œo‹^p|]n}sƒ”¡­¯¹Ÿ±»¢³½ª»Å·ÅÒ¸ÉÕÀÑÝÊÙáÊ×ÜÔßàãêêåéìïñ÷ïñõïïñïòóòõöùüýöõú÷öûóò÷ûûýÿÿÿÿÿÿÿÿÿÿÿÿþþþ÷úùïòóäìîÔãçÏáäÌßäÃØáËßíÁÙã¹ÓܼÓä½Íç¹Ëç¶Ëè¶Èä´Ãà·Êã³É߬ÄשÄÖ¬ÂÖ²ÂÚ²ÅÞ®ÃÞ²Èà´ÊàµËá·Êá­ÃÙ¦¾Õ¡¹Î©¿Õ²ÈÞ®Áا¿Ö£½Ø¦¿Ý¨¾ß¨Áß¡»Ö ¸Ï®Áا»Í¢¶Ä¤»Ê¢¹Êš±Â¢¶È¦ºÌ©¹Ï£¶Ë¡´É¦·Ê£³Ä¤µÆœ°Â¡µÅ¢¶Æ£´Å ­Áž«¿©´Éª´Ìš¤¾—¤¸—¤¶’Ÿ¯œ¬ˆ˜§ƒ“¢€‘x‰“s…‘piz‰fwˆ\p€Xl|TetUfrTfp\nxQab_k‚fs…er‚ix€iv{tzs«©š|}q{ƒmzƒky†l~…qƒˆj|ƒbs^n}p€‘ˆ™¨–§¶˜¨·¦³Å³ÁζÂιÇÔÂÏßÅÖâËÝçÑãêÙæïÞèîåíïæíííðïêíìòòôøøúñðõïïñññóúúúýýýûûûøøøôôöýüÿóò÷òñöìðõãêñÞíóÇÝãÀØà½Öâ¿ÙâÇßç½Ôá¸ÌÞ°ÇØ«ÄÔ®ÅÖ©½Ï«¾Õ¯¾Ý°ÆÞºÒåµÎÞºÓã­ÈÞ¬Åå´Ëç¶ËæµÌæ«ÅÞ¥ÀÖ©ÄÚ²Ìå©Âà©Âà³Ìì«Å㡼ע¼Õ¦½×¨À׫ÃÚ¨½Ø¨ºØ¤¹Ô¤»Õ¤ºÒ£¶Í¦¹Î¢µÊŸ²Ç£³Ë¦¶Î£³Í¤·Îš°Äš°Ä›®Ã´Ã ¹Å¢¶Æ£³Æ—§¸™©ºž®¿ž®Á–¦¹’¢µ‘¡²Žž¯ˆ™¨ˆ™¨‘ ~‹›u‚”myn~‘iyŒbs„^o€[k|YdwZgwVdqIS[`q{p~‹ks‡lu„nt‚uxw¶³§………twƒnt‚ow‰p{Œs~‘l}^tˆ_v‡oƒ•~¢”¡µœ¬½§·È¯ÀÓ²ÂØ´ËÚ¼ÖßÀØâÂÖäÈÚæÐáëÖèí×éì×çæÞêèåðñâéðæìïîóóìñïöùöõø÷úúüööøôôöêíîïñõîõõåîëàîîÝìðÐãèÇßçÀØàÀØâ»ÕÞ´ÍÙ³ÊÙ±Á×°ÆÚ¶Ñã¹Õâ°ÍÕ¶Òá®Åß«ÆܨÃ×±ÌÞ²ÎÝ°ËݯÇÜ®Éâ©ÆãªÆܬÈ×°ËÝ­ÈÞ«Æá­Êé¬Æä¯Åä©ÄߨÆÞ¢¾Ò«ÆدÇÜ«ÁÙ¯ÇܨÀÕ«Ãا½Ó«ÁÕ ³È¢¶È£·Ç¢³Ä¦³Ç¢³Æ¯ÂקºÓ ²Ð›­É°ÉŸ²Éš­Äœ°Â¤µÆœ¬»›¨¸˜¨¹˜§½‘´’œ¶Ž˜°’œ´Ž³€“¨~’¤| yŸm}“cv‹fyŽ`w†[rXixZgyXeuQ_lAKS]pw[mybrƒhvƒiutyy½¸®††„ux€nu€nw†n|‰n~fwˆj{Žar…n}“Ž¤Ÿµ›¬¿ ´Æ«¼Í«»Ì®¾Í¼Ê×ÂÓÝÆ×áÆ×áÑâîËàéÐèðÎäèÕèèàðïâíîéñóäêïìðõùøÿïîó÷÷ùøøøìììöùúîòõëó÷ÜéîÙèìÔæëÈÚßÇÙàÁÒÞÂÒå»Îã´Ìá½Øì¿Úî·Óé¹Ôí©ÄÝ©ÃÞ±Çæ¯À㩽߮Äå«Æá¬Ëà®Íà®ÊÞ¬Æ߬Âá¬Ãß­ÄÞ®ÅáªÀß²Èé²Èë±Êè°Ë䣿զÁ×£¾Ô­Åܧ¿Ò¤½Íœ´Éš±Ë¡¶Ñ¯¾Ý¯¾Û­½×«»Õ©¸Ò¤´Î¨¸Ò«»Õ·Æã¡´Ë ³Èš­Äš­Æ ³È›¯Á‘¥µ—¨·›¬»ž®¿•¦¹•¥½–¥»’Ÿ³”¥±¢©¤¯‡›«~’¤~‘¦~‘¦r‚˜m}“gvŒhyŒbvˆUiyOcsParO\n:GP]j|[kz_o~gv~kvyv{y¼º´„ˆow‹hu…j{Šm~q’p€‘s€’m}Žk{Œv‡–ˆ™¨“¤³ °¿©»Ç°ÅбÅÕ²ÅܸËà½ÑãÌáìÊàäÃØá¾ÒàÇÜçÓåïÎáæÑäçÙëîÚéíØèçØéåæôôèòøâíðàèìãîñàëîÕãåÌÙÞÕçê×êïÏäíÊÞìÌàîÎâðÂÙè¹Ðá¶Îã²Ìç«Æá¬ÆäªÅà§ÂÛŸ¹Ò£ºÔªÅÛ©ÅÙªÅÞ­Æä«Æá¬ÇâµÑç¯ÊܲÎâ°Ëä®Éâ°Êã¬ÄÙ°ÃØ®ÆÛ©ÄÚ£¾Ôž¸Ñ©Äߥ¿Ý »Ö¤¾Ù¢¼× ·Ó¦¾Õ¤ºÐ¢¸Ì¦¹Î¬Âا½Õ ¶Î£µÑŸ¯Ç ¯ÅŸ¯Ç¹É㣶ͰǠ¶Ì ¶Ìž´È¢¶Èš®¾’¦¶—¨·‘¢® ±Œœ²‡›­ƒ—©€”¦€‘¤|¢xŒžx‹ t„œn˜f|’_r‰brŠ[l}UgsVgsP]m3@E[l}Xix]o{ix~kswtwt¿º°ŠŒpxŒhu‡p€“q’o|Žn{lyjzm}u‰™š¨‘¥µŸ¯À£´Å¦ºÌ­ÀÕ¯ÂÙµÈݶÉÞ·ËÛÀÕà½ÑßÄØèÌáìÉÞçÌâèÕèïÙêöÏÜîÒàí×åðÈ×Ý»ËÌÈÖÖÛãååðñèöøáîóáî÷ÁÔÛÊåéÄÝé¸Ðã¶Îá¼ÒæÀ×æÏæó½ÖäµÍà¯Êà²Ìê°Îæ±ÐåÀÛô®Åá¨ÂÛ¯Êã©ÃÞ®Äã§ÂÝ¢ÀÚ­Ìá¶ÒæºÖê®Êà§ÂÛ©ÄߨÃק¾Ï¨ÃÕ¡½Ó¥Áפ¾×°Ê㣺֘²Ëž¸ÑŸ¹Ò ·Óš±Íš¯Ì ¶ÎŸµË™±ÈŸ¶Ðž³Î¯Ë•¥¿™¨À ³Ì¥ºÕž´Ê˜®Â™¯Å›±É—¯Äš²Ç’©¸–«¶–«¶˜©¸•¦·ž±‹Ÿ±€”¦~’¤£}ŽŸz‹œx‰œr‚˜o‚—j}”brŠix’arƒas}l}‡S_m2Dmt{VdoWh{\my\iplss¸¹´ƒ‹o}Šk{Œl{‘jzfs…fv‡iz‹k‘k•n„˜x‹¢†™® ¶•¥¿˜¦È¢´Ò¡³Ï ²Î­¼Ù¦¹Ò°ÃÚ·Êß¼Ðâ¹Ìá¸Ëä½ÐçÅØí·ÍãµËã³Îä¹Õë¶Õè¶Øê·×å¿ÜéÁÞéº×ß¿Ûè¼ÔéÁÜð¿Úî¸Ðç»ÐëµÌæ²Éã´Ìã´Ìã²Ìå¹ÓîªÃá«Áâ°Ää¶Èæ²Çâ¶ËæÁØò¶Ðë±Ëæ¿Õô­Çâ¬Æá«ÆܦÁÕ©ÄÖ³ÏÞ¬ÇÙªÂÙ«Åà©Âä©Ââ¬Â᥹ۭ»á«¹ß³Áç©·Û¯½á°Âà«ÁÙ¥»Ó¥»Ó¢·Ò¤µÖ«½Ûª¹Ö¢µÌ±Ã³Ç˜®Ä”ªÂ•§Ã–©Â˜¨Â˜¨À”¤¼”¤¼“£»”¤¼Ÿ¹ ºŸ¹‡š±ŒŸ¶„—¬ƒ–«~‘¦†–¬’¥ƒ“¦…–©t„šk|jz‹m~‘iydtŠ_o…Yi|=J\&-8z{grs\ns\ir`fvpnx¹­±Œ‹’qz‡iw„iyˆj{‡ev‚^nhtetŠl}sƒ™y‰£‚’ªž´Ÿµ—¦¾Ÿ¯Ç¢²Ê«»Ó¨¸Ð¨»Ðª¾Ð°ÄÖ´ÄÚ¯ÂÙ±ÃßµÇåµÆç»ÊéµÃà±ÄÝÃÙñ»Óè¸Óç½ÕìÀÕò¸Éê»Éí¶Ëè¸Ðç»Óê»Ðë¼Îì¶ÄæµÊå²Íã¸Òë®ÄãªÃá³Ìê®Ìæ±Òë³Ñë°Êå¯È調åªÀ᫿߬Âá¬Åã«ÅàªÄÝ»Öê¿ÛêµÎÞ²ÈܲÈÞºÐèºÑë¦ÀÛ¥¼ØºÏì¯Ã㫿᭾ᬺޭ»ß­»ß©¾Û£ºÔ¦¹Ò§¶Ðž­Ê¡²Ó ²Ð¬Ë›®Å¢¶È¢µÌ¢±Î¡³Ï™«Ç›®ÇŸ¯Éž®Ä °Ã—§½—§¿—§Á•£Âœ¹Œ›¸‡™·‡˜¹…”±‘ º…”ª€££€‘¤}Ž¡r‚•t…˜t…˜o€‘o€‘i}‹]qWgv6AR$,0vyvs{}_ls[eo]cqmqtª¨¤†Œ‘lx†er‚`p^o‚]mƒXh€_nˆaq‰hxr‚šv†ž{‹¥ˆ—´Ž¡¶‘¥µ’¦¸›«Ã¡±Ë¥´Ó¦¹Ò¡´É­ÁÓ½Ñã²ÈÜ°ÆÞ¯ÁݶÅä­¿Û¹Ìå´ÊâºÑë°ÄäµÆë·Ëí½Óò¼ÒñºÐïºÑë»Óê¿Öð¼Óï¯Éä¬Åã²Ìå³Îâ¬ÈܱÐã²Íæ´Íë°Êã³Ëâ³Îä­Çà®Éä¬Ææ®Éâ¯ÊÞ²Êß®ÄܦÁשÄݳÏã¿ÛíÁÝó¬Æá®Å᩾۹Î騾֣µÓ¨¶Ü¨¼Þ¥¾Þ£¼ÚªÀߧ¼Ù©¸×£´Õ ´Ø¢¶Ö¤¹Ô¢¸Ð£¶Ï›°Ëš®Î²Í¤·Î©¹Ó¢°ÍŸ®Ë¡°Ïœ¬Ä­¾Ñ¡±Ç£³Ë£¶Í–¬Â•¨¿™¨Â—§ÁŽºž»œ¹‡—±‚’ª…–©†—¨£¥{Ž¥|¨vŒ¢s‰m€•iyiyŒboP]o4AS9CK\^bvyƒnrƒ^dr\bpkmq«§¢…‰Žhp‚]jz\m~Wg}Wf€UexYix\m|hyŠj~n˜wŠ¡ƒ–¯Š ´Ž§·“ª»›¯Á ¶Ì µÒš®Î ´Ö¬ºÜ¯¹Ü°½ß°¾à«¾×µËß³ÉÝ°ÃبÀÕ¶Ðé®Åá²Æè¯Ãå³ÇéµËì³Éê´Ëç´Ëå³Ëâ±Éà­ÃÛ´Çà¶Îá»×æ¶Ò߶Òß°ËݯÉâ²Ìå±Èâ®Åß®ÃÞ²Çä­ÁãªÀá¨Áá­Ãâ´ÉæµÌæ¹Ôê®ÊÞªÆÚ®Éâ¨Áß³Ëà±ÅÓ©¿Ó¤»×¥¼Ø«ÀÝ­ÀÙ¬¼Ô¬¼Öª¹Ø©¸Õ¨·Ô«½Û¤¸ØŸ¶Ò¡¸ÒŸµË¤·Ì³É—®È—­Å°É¤´Ì¤³Ë¨¸Ðž®È™¬Å¤ºÒ–¬Â¦º–©À–¦À–¥½˜¤½š¤¾”›¶‘›·“œ»Š˜µƒ•±€“ªƒ–«ƒ—©‡˜©wˆ›r‚˜mƒ—kƒ˜i|“jy“gvŽbn‡Tdwm}Œ{ˆDGHbedzzzmqtV]dilm§£ ‰’dl~R]nVcsTdsQbsKboQjv[rj~Žo…™t‰¤y¥~’¤…˜­—§¿¤·Ì°Å˜«ÂŸ²ËŸ´ÏžµÑ§¼×¤·Ð«ÁÙ®ÃÞ²Çâ³Èã¬ÁܳÈ㧽ղÅܲÆؾÏà¸Ëâ°Åâ²Éå«Åà²Íã³Îà­ÈÜ®Åß«ÀÛ©»×°ÂÞ¯Áß²Èà¹Ñæ¬ÇݪÅÞ¬ÈÞ¬ÇÝ«ÆܲÊáµÌæ®Ãà¯Á߯½ß©»Ù©»×¨½Ú¤ºÙ­ÄàºÑí®Åß­Åܧ¿Ö«ÂܨÁߥ¾à·Õ »Ô »Ô©ÃܬÇݧ¿ÖªÂצ¾Ó ¶Ê§»Í¡·Ë³É¦½Î©½Í¢¶È˜¨Àœ¬Ä¦¶Î›®Ã›®Ã°Å¡´É°ÅšªÂ˜¨Â”£À–¦¾—§ºŽ³œ¶Žž´–§º³Œœ¶‰™±ƒ’ª‘§…™«“¥w‹yŠw‡št…˜oƒ•k‘o€“q‚Ž†“œu„Œ|Š•v†‡59=UUUoootttqrm›•†‹‹akuWcqR_qO`qL`rLalZpvcxƒo€“r‰šsŒœu‹ŸwŠ£„”ª•¥¸’¥¼Ž¥Á‘¨Ä“ªÆ™°Ì˜­Ê˜­Ê¦¸Ö µÐž´Ì¥½Ð¬ÅÕ®ÆÙ¨¾Ö§½Ó¬ÂÖ®ÄÜ´Åæ¯Äß²Êß¹Ñæ®ÄÚÃÛî±ÉܳËÞ²ÈÞ²ÎÝ«ÈÕ·Ôã¨ÄتÅÙ²Êß³Èã¯À㮿â´Å觼װÆÚ½Õê±È⣾ԫÆÜ­ÅÜ®ÀܯÄß´Éæ®ÃÞ¬ÁܯÆà²Ìç³Éá°ÀÖ©¿Õ±ÉॿجÆá±Ì⦾Ӧ¾ÑªÂÕ©¿Õ¯¿Ù¹Éã±ÀÚ«ºÔ¾Íç«»Õ¢²Ìœ¯Ä˜¯¾‘ª¸•®¾˜±¿“ª¹˜¬¾˜¨¾‘¢µ“¤µŽ¢²ˆœ¬¡³Žž´›®Ã™¬Ã‡Ÿ²›ª‚™¨“¤µŽŸ²~Ž¦zŠ xˆ›z‹žx‰œx‹ wŠ¡rˆžo‡žj~Œ|‹‘¹Ãͦ¨·†žw„–m|‚.3;589C@?ZZXsssyvu™””ƒ…‹djxP[l_l€UexScyUiycxƒ`t‚izk‚“s‹žp†šx‹¢„”¬•¤¼‘¤½Œ£½§¾–®Å˜°Ç—¬Ç›±É£¶Ï£¶Ï¨ºÖ©¿×¦¼Ô¦¼Ò¦¼Ò¤·Î°ÀÚ·Ê㫽٪ÂÙ£¾Ò¥ÀÔ¼Ôé²ÍߨÄÖ¥ÁÕ¸Òë±Íã©ÅÛ®ÊÞ²Îà±Ìà¯Æà®Ä㩽᫿á°Áâ­ÃÛ§¿Ò°Ëá·Ñì²Ìå°Êã«ÅÞ»ÒîÇÞú¸Ï맾ڥ¼Ø¨Áß«Åå©ÄÚ¬ÅÕ¥¾Î¬ÄׯÇÚ¬ÄÙªÅרÄÓ¢¾ËªÆÑ¡½Ê¡¹Ì¬Ä×­Ã×›²Ã˜¯À“©½œ¯È¢µÌœ¯Æ—­Ãš°ÆŸ¶ÇŸ³Ã¢¶È¢²È—§½šªÂ•©»‘¨·‹Ÿ¯Ÿ²Ÿµ ¹‡Ÿ´†¡³|’¨Š™³‘ ¸œ´€¨‘©zŠ {ŒŸzŠ y‰¡v† m|™o|ŽŽ˜ ÊÐÞ›œ²†Ž¢|‰›yˆ7>E0964=1BH?_c]uxw„†Œy~Šdl~XhyUi{SgwTetUfuWhwdv‚iz„vˆ’}›ŽŸ®~Ž¡†—ª ³Šž°“¦»“©½’ª¿Ÿ·Î µÐ™®Éš¬È–­Çš´Í¤¿Õœ´Ëš²Å¢¹È¤»Ì¥»ÑªÂרÀצ¾Õ¥½Ô¦¾Ó¬ÂدÇÞ´Îç¼Ôë¶ÌâªÂÙ¦½×ªÁÛ¸Ïë®Ââ¯À㫿ߦ¼Û¨Áß­Ææ¯Éä«ÅÞ¬Æß½×ò³Íæ±Ìâ«ÇݨÃÜ¥ÀÙ«ÆßÀÛô±Ìå®Êà§ÃÙ§ÃÕ¤ÁЕ²Á¢¾Ð¤ÀÔ¤¾×Ÿ¹Ò¡»Ö¥¿Ø¡¹Ð ¸Ï§½Õ­ÅÚ¥Àҵʞ´Ì¡·Ï³Ë“©Á–©Â™­¿¬¾Ê±Á›±Å¢·“£¹’©¸‘ª¶’©¸Ž¢´ŒŸ¶“¢Á‹ »‰¤º‡Ÿ²Šž°‚–¨’§{‘¥y£y’¢€™©x‘¡t‹œr†˜r‚˜tƒ›u›rzŒ®³½ÇÐÝŽ™ªƒ¢~Š¡uƒŽIL`:=I57=6:?ILTeinuy~nx€bp}[lv^qx]pw\mwUfp[lvdv‚i}tˆ–u‰—tˆ˜yŸ‡›­ŽŸ²’¦¸“¦»‹£¸Š¥»˜²Ë˜²Í’©Ã›°Ëž¶Íž¶Í¢½Ó¢½Óž¹Í¥½Ò§½Õ¡³Ï§¼×¥¼Ö¤¿ÓªÆبÃÙªÀß­ÄÞ±Éà³Éá²Äà®ÃਾݪÄßž¹Ò¦ÀÛ¦¼Ý¦¿Ý©ÄߨÃÙ§¿ÔªÂ×°ÆÞ®ÄÜ®ÃÞ«ÂܨÂݪÂÙ©¿ÕªÂÙªÁݬÆ᥿ڡ»Ö§½Ü »ÔŸÁÕ§ÆÛªÆÜ©ÄÝŸ¸Öž¸Óž¸Ñ§¿Ö­ÀÙ©¿×¢¸Ð¤¼Ï§ÀТ¸Ì£¶Í§¿Ò£¾Ð™²Â£·É±Ã¤·Ì§»Ë˜¬º©·Žª¹Ž©»Œ§½§º ·Æˆ ³‡Ÿ¶ˆ¡±‡ ¬Šž°Žµµ€“ª“¥‚“¤ƒ—©|¤yŒ¡t„œo—q™m€•j}’p‡½Ä®¸ÂŠ–­€Œ¥|†¢w„”AQR@NP6AD28=9;ANQYhmwpz‚fu}\mycs„arƒ]qƒXl|Zn~ax‡e~Œm†”p‡˜k•vŒ¢€“¬‚‘®Œœ¶Žž¶‹žµŽ¡º™¯Çš¯Ê›°Ë¦¸Ô˜ªÆ£µÓž´Ó¡ºÜ¯É랻ܕ²Ï™´Ï¯ÊÞ²ËÛ«Á×±Ãᨽڤ¹Ö¨¿Û«Åà¨ÂÛ¬ÆߦÀÙ£½Ö«ÂܬÁÞªÁÝ¡»Ö½Øñ°Ìâ¥ÀÖ¦¼Ô¯Êà¹Ôí¯Êã¬Çâ°Ëä°Êã¬ÇÝ©ÄØÁØò®ÂâªÁÝ«ÅàªÅÛ£¾Ò£¿Õ¤¿Ø¤¿Ø¡¼×¤½Ý¥ºà¦»á¥ºà¡·Ö¥¼Ö¨ÂÛ¤¾ÙšµÉ¢¾Í¥½Ð³Ë˜°Å˜³Å«½˜°Ã§¿Ò¡¹Î™¯Å¢²Ì°Ç“¦»’©ºŸ¶Å­ÄÕ‹ž³ˆ›° µ‘ªº‚Ÿ®‚ž­ƒœ¬ƒ™­…•¯‚•¬’©†®z“¡vsŠ™o†—q„›i•c{’r€ËÍÑž¢³Œ“°ƒ¥|‰rƒKVYU^[QYR6=95::SSQmrpovvdsyZn~[o}^o~Ym}Zq‚_x†c|ˆk‡’k‡”k‡”t›z“£‚š­Š¢·†œ´£¹“¦½“©¿“«Â–®Ã—­Á§½Ó©¾Ùš±Ë˜²Ë›µÎ¢¼Õ¦¾Ó˜®Â®ÆÛ§¿Ö¡¼Ò¥¿Ø¦½×­Âß­Äà¦ÀÛ£½Ö¨ÂÛ¬Æߦ½ÙªÀ߬Â㟸֩Âà¬Æ߬ÇÝ£½Ö¤»×°Êã·Ñê¬ÇÛ¯ÊÜ©ÄØ«ÆܪÄݦ¿ÝªÄß­Çâ©ÄÚ¥ÀÔ£¾Ò£¾Ô¨Ã×­ÅÚµË㪹ؤ¹Ö¥»Úš³Ñš³ÑŸ¸ØŸ¸Ú¤ºÛª»Üž³Ð¡¸Ò¤¿Ó—³Â•±À—¯Â“®Â–±Ç—®È›°Í¨¿¨»ž´È’¥¼”ªÂ™®É’ªÁŽ¦»—¯Ä‘§½‰Ÿµ…›±ˆŸ°…œ©~•¦—­—«|“¤„˜ª…•«v‰ž}¥yŒ£pƒœl‚˜k•s€‰ÌÏÐcmw|ŒŸ‚’¥{‹žv„pmctqehfWHG<450888EDIZ\`qsylr€^i~`k€^h€[g~^mƒ`sˆbxŽo‚—s„—r†–“¡ˆœ®€“ªƒ™±„›µŽ¦½Œ¢ºŒ¤¹Œ§¹Ž©½ ¸Ï ¸Ïž³Î§»Û™­Ñ¨¾Ý©ÃÞ£ºÔŸ±Í«½Ù«½Ù®ÀÜ©»×«½Û©ºÛ¤µÖ§¸Û­¿Ý®Àܦ¹Ò§ºÓ¤ºÒ¥»Ó§½Ó­ÃÙ«ÂܲÈé®Âä­¾á®ÂâµÊçµÊç¯Áß³Éá²ÈÞ¯ÅÝ¥º×«ÂܪÁÛ¬ÃÝ«ÀÛ¦»Ö¦»Ø¥½Ô¥½Ò¬ÄÛŸ´Ï£ºÔ¥¿Ø¡»Ö¡·Ö¤¸Øœ­Ð–ªÊ µÒ¢·Ô’¦Æš±Ë˜³É•¯È–­ÉªÅ•¯Ê–±Å•®¾Œ¥µ‹¡µ’¨¾“¦¿¤¿¦Å¥Â’¤Âˆ¸ŠŸº†›¸„•¶£»ƒ™­}•¨™®Š¢·{“ªw£v‰ t‡œyŠw‡r‚œm€—m€•pyˆÄÂÌBEY;Eaˆ¡†›|^Y[QNMFGB;<545.7:96:?AGL\bglq{ko~glbi„[h|^nbs†jz’m€•o‚—n„švŒ¤tŒ£€˜¯™¬|•¥‚˜¬ ·Š¢·Ž©½‘¬À•­Ä–¬Â¢²Ê¡±Ë¬ÉŸ±Ï£´Õ¥ºÕŸ·Îž¹Ï¥ÀÖ¨ÂÛªÁݧ¾Ú©¾Û¡ºØš´Ô ·Ó¨ºÖ±ÄÝ´Ç੿ק½Õ¦¾ÕµÌ椾׫ÅÞ¬ÃÝ®ÀÞ«ÀÛ°Åà´Éä°ÅàµÍä°ËáµÌæ®ÀÞ¨½Ú¬Àà°Å૾ղÅÜ®ÁÚ§½Ó£»Ð¨ÀÓºÓ㦾Ӧ½Ù˜²Í·Ò›µÎ·Ð±Ëä©ÃÞ£½Øœ¶Ñš´Íš±Ë’©Ã’§Â’ªÁ™±È˜­È¢´ÒŸ±ÏŽŸÀ’¤ÂŽ ¾‘£Á‘¢Ã‘¢Ã”¥È„™´‡Ÿ´£·”¥¸ˆœ®ƒ™­‰ ±ˆœ®~‘¨}Œ©v‰ xŒžuˆr…œpƒ˜k~“e|c|Š`sq­¶¦W`[ ,5Bai}jw|222141384/621865::79=:??GNN`fiouzco{_o‚Xh~UhZp„e}fm„•mƒ—s‰¡z¨}“«‚š¯ƒ›®‰Ÿµ•¥¿‹¡¹Š¢¹¨º’¯¾“¯Ã·Ðœ¶Ïš±Ë˜°Ç™¯Å™¯Ã¡´É ¶Ì¨½Ø©½Ý¢¶Ú¨¼Þ¬Àॿؠ¼Ò›¶Ê§¿Ô©¿×®ÀܯÄߧ¼×©¾Ùª¼ÚªÀ߬Å奻ڮÃঽׯÊà°Ìà«ÇÛ¥ÀÖ§¾Ø­ÅÜ«ÁÙ²ÈÞ¬ÂÖ¯ÅÝÁÖó¶Îå¬ÇÙ¨Ãצ½× ¸Ï¬ÄÛ¯ÆàªÀß¡»Ö£½Ö¦ÀÛ˜®Ïœ¶Ñ—²È·Ð£½Ø·Ðš²É“«À§º¨¿œ³Ï§Ã“©Èœ¶Ï“®ÄŠ¥»Ž¥¿£»‡š³‹žµ•¨¿‡š³”£ÀŒžºŒž¼‡™µ„—°„š°‚š¯~”¬y‹©uŠ§uŠ§z‰¦‹–´tƒ›l{‘m|–es’VfyXis€„“%'$-,841??;HO>MSBQYFS\:AL3:A8@BHQLgqglwxbnzYixZj€cs‰l|”h{o‚—o‚™vˆ¤yŒ¥’«€˜­›¯‡Ÿ´Ÿ¯Éœ¯Æ˜«À”§¼•¥½›±É´Ðš°Ï™¯Ð¡µÕš¬Êš¬ÈŸ²Ë¡¹Î¯ÊܲÍã·Ò›¶Ñ¤¿Ú—µÍ›¹Ñ£½Ö¦»Ö®ÄÚ§½Ñ¬Äפ¿Ó¨¿Ù­¾ß¦·Ú©¹á¦ºÚ¬Áܨ¿Ù³Êä¹Ôè°ÌÛ´Ïã¯Éâ©ÃܪÄÝ®ÆÝ®ÁØ·Í㨾֧½Õ¢·ÒŸ¶Ò©ÂॾܬÂáªÁݯÄߥ¼Øž´Ó›°Í¯Í¦¸Ö ²Ð–«Æ¦¾’ªÁ“­Æ—®Ê”¨È“ªÆ‘¨Ä”­Ë¦Æ‡¢½–²È©½«½€Ÿ´†£ÀŒ§½‰ ±…›¯ˆ›´Šœ¸†—¸ˆ—´ƒ¨‘ ¸€¨ˆ›²yŒ¥t‡ x‡¤p‡˜l†f~ˆhyˆk{Šhu…\dvDG]mp|?AE  7LU=U]>V^?W_G\ePcjDV]5@C7<<TTThnqisy[itXhyfwŠdtŒn„šn†o…›w‡‚’¨€§Œœ¶€’°…œ¶†¡·¨¼Ž¦»ª¼«ºª¼œ´É™¯Å¤´Ì£¶Ï¨ºØŸ¶Ò›´Ò–°ÉµÌ•¬Æ“¨Å•¯È—³É—±Ê£¹Ø­Çࢽћ¶Ì¦½Ù¥ÀÖ¦ÁÕž¹Ï§¾ÚªÁÛ©¿×´Ëå¬ÆáªÄ߬Æá±Ëä²Éã²Éå­Á᩾۰ÂÞ¬ÁÞ§½Ü§¾Ú«ÂܨÂÛ¥¿Ø­Çा٣»ÒÆÙî­Ãק½Ñ¥»Ñ¦¼Ô¡¸Òš±ÍŸ¶Ò ·Óš´Ï–¯Í™´Ï•³Íž¹Ô•¯Ê‘¬Â’ª¿Ž©»ˆ¥´Ž¦¹–©Â§Áˆ¢½„ž¼…ŸÁ†Ÿ¿‚˜¹„™¶Šš´„”®…”±†•²‰˜µ·{‹¥ ºƒ’¬yˆ¢y„¢vŸ|‡¥z†¡o{–gwŠhz†an€[b{ (> '%" @HZCQ^@R^CWeQeuLalH^d>MQ4<>59<;:ASW\hmubox]m|t„•gvŒxˆ k~—n˜{‹¡{‹¡‘§ƒ–­~¬™®‡¢´«¿Œ§½«½”±Àš¶È¹Í¸Ì¢¸Î³Ë›°Í–«Èš®Î¦Â“­Æ·Ð›µÐ«Á¨ÀÕ¨¾Ö£µÑ¨¾Ô«ÃÖ§¿Ö¨¿Û±É৿ԪÂÙ§¼Ù¬ÂÚ­Àצ¼Ò§½Ó¦½×¦¿Ý¯Éä®Åá°Åâ±ÂãµÇå¯ÁݤºÒ«ÁÙ¬ÄÛ§¾Ø­ÄÞ«Àݧ¾ØŸ¶Ð¢µÎ¬»Ó¨¸Ð¤·Ð¨¾Ô¡¹Î ¸Í£»ÒŸ¶Ð¥¹Ù´ÐŸ¶Òš´Ï©Ä•­Ä¥»Ï“®À“¯Á’±ÂŽ­¾™µÉ‘©À§ÀŒ¦Á€šº‚›À‚›»…™¹ƒ•±‰™³ ¸‡–®‚‘«ƒ‘®{Š§yˆ¥yˆ¢uœyˆ¢v…¢t„žr›u„žqœl|’m~Wh{P_uIVh%7 - - - -?L`FScJXeIUaGP]GP_KSgJP`DIU8;E<=HEFObclis}]nzVhrbt~fwˆo—q…—~•¢}”¡„›ªŠ£³‡Ÿ´Œ¤¹‡Ÿ´‚³ˆ¢½©½›¸Ç”±À“¯Á¦ÁÓ™±Æ³Ë¬É™«Ç™®É•§Ãœ«È¢µÌ¦¹ÎŸ²Ë¨ºØ¨ºÖ¨»Ô«ÀÛ¨¿ÛªÂ׳ÊÛµË᧹׳ÈåºÐï´Ë姿ԪÂÕ­ÅرÉÞªÁÛ£ºÔ£ºÔ­Äà¬Âá­Ãâ­Á᧼ר»Ò¨¾Ö¬ÁÜ®Ãस؟¶Ò£½Ö¦¾Ó¤»Ì²ÈÞª¼Ø£ºÔ—±Ì—±Ï–°Ð–°Î¡»Öž¹Ï¥½Ð¸Êœ·Ë”¯Å˜²Í•®Ì©É‡¡¿‰£Á‡¢½Œ¦Áˆ¢»˜¯ÉŒ£½ˆŸ»€•²~®}’¯}’¯€›¯}«€ªy’ ƒ™­w‡¡wŠ£~‘ªx‹¤r‚œpƒšj}”o™n|™m}—k~—brŒP_yM^q:N\#4@ '9NWCV]IX^EQ]>FZBM^O]jKZbBQW9CK8=G=CHLPS_fmcmw_mzfwŠq…—uˆtŠž}“§{“¦Š¢µ‰¡¶‡Ÿ¶‚œµ…ž¼„Ÿ¸ˆ¤º‘©¾°Ç–¬Â’ª¿–®Ã˜°Åž¶Í”©Æ˜­È›­É—­Ã›±Å™±Æž¶Í¤¿Ó¢½Ï§ÃÙ¢½Ø ¼Ò¤¿Ó¦¾Õ¤¹Ö¡¸Ò¥¼Ö­ÄÞ±Èä¬Æá³Í蟺αÍܯËÚ«ÃÖ®ÆݲÉå«ÂÞ­Ãâ­Çâ¨ÃÞ°Ëä¯Éâ¬ÇÝ­ÅÜ®ÄÚ­ÀÕ¤¼Ï©ÄÖ¨À×£µÓ¤ºÐ£¼Ì§¿Ö¤ºÛ£¹Ø™¯Î™°ÌžµÏ¤¿Õœ·Í–°Ë“¬Ì–¯Í—­Ì‘ªÊŽ§É¦Æ‘ªÈ¡¸Ô‘¦Ã“¨Å›­Ëƒ˜µƒ—·~“®{‘©€•°‚”²€’°„–´z¬s‰¨x«{­y‘¨}˜¬w“¢lˆ•l…•e{fvŽfrhxh{brˆ\kƒRbuHXiCBDJSY^]gmamykxŠs‚˜p™w‡ŸyŒ¡~‘¦‚’¨†™®¥»‰ ºˆ¡¿† ¹Œ§»•­À ¶ÊŒ¤»Œ¢Á“¬Ê–¯Ï–°Ë˜°ÇšµË—²È–®Ã¡·Ë®ÆÛ¤¼Ó¬ÆߪÄßž¸Ñ¢¼Õ¥¿Ú£¹Ú ´Ô§¹×´Ëç³Íè®Åá°Åâ¬ÃÝ¥½Ô¨ÃÙ­ÈÞ©ÃܨÂݬÃݪ½Ö¬ÂÚ©¾Ù¦ÀÛ¡»Ù¡¼Õ¨ÃÙ¬Çݤ¾×¨ÃÙ¦¾Õ ¸Ï¦½×¤¼Ñ¤½ÍªÃÓ¥¾Î¤¼Ï¦¾Õ¡¸Ò—­Ì—±Ì’­È«Ä“®Ä–°É‘ªÈ¨È¦É£Å‘¢Å‘¦Ã‹¡¹Š¢¹¨¾Š ¸ˆ—´†œ´ˆ ·„œ±ƒ›®‚˜°…—µ–³ƒ˜µ…šµyŽ©z‘«t‹§o†¢k€sŠ¤qˆ¢m…œl‚˜i“pƒ˜k~—bt’\nŠRd€O_yIXpBRh2EZ/HMAN^IVfGReFScGXdK[jMZnFSeKXjKYf>MU5?G:=E@EMV[c`lxeuˆ`t†o…™u‹ŸyŒ¡{‘¥{“¦…°†œ²ƒ™¯ƒ™¯Ž¡¶–§ºž­ÃŸ«Æ•¤Á›¬Íž³Ðœ³ÍŸ¶ÐŸ´Ïž´Ì¥»ÓŸ²É¤³Ë©»×§»Û¨¿Û¦ÀÙž¹ÏŸºÎ¡¹ÐŸ´Ï¥¼Ö£ºÔ§¼×¯Á߬ÁÜ­ÄÞ°Ëá©ÄتÅÛ±Èâ­ÈÞ±Íá­Èܤ¼Ñ¡¹Ð¦½Ù¦½×¤¹Ô²ÊáÁÙð¥¿Ú ºÚ«Æß«ÇÛ¦ÀÛ¬¿æ ´Ø§»ß­¾ß¤³Ò´ÐšµÐ™µËœ·Ë¡¹Ð›°Í—®ÈµÌ•­Ä¢½”ªÂ£¹§¾•¬ÆŒ¦Á‡ ¾† »‹¢¾“¨Ã‹ž·Œ¡¼…›ºƒ¶†¡·‚¶€›¶€›´}˜®“®Ä~˜±w’«p‹¤t‹¥u‡£vˆ¤w‰¥mƒ™h€“^v‰o‡šdzŽ^n†Zj‚Yh€N^vJZtDZp:Ug>TZCPbJWgFQbIWdM^jL^hOdmJ\hM]nGWhFSg=NX7JJ7AGCFPPZb]lrev€rƒ’o†•rŠ}“§‡š±…°}˜ªœ®ƒ›°Š ¸–¥ÂŸ±Í˜­È“¨Ã“¥Á™¬Å˜«Ä¡´Ë¦¹Ð³É¥½Ô ¸Íš²Çž¹Íž¹Í¸Ì£»Ò¥ÀÔžºÎ¹Ë£¿Î¨ÀÕ«½Û­¿Û¯¾Û´Æä®Ââ°Åà²ÈÞ±ÉÞ²Êá¬ÃݪÁÝ«Á⨻⤽ۥÀÙ°Ê㨽ڲÊá®ÆÛ´ÏãªÅÛ¨Ãפ¼Ñ¦¾Õ¬Áܤ¸Ø ±Ö¥º× ¶Î¥»Ñ¥»Ï¤¼Ñ´Î›¶Ê–²Á«½Œ¨¾”°Æœ¶Ï·Ð™°Ì˜®Í›¯Ñˆž½…œ¸‰ž¹ˆš¶…™¹ˆžÁ‰ŸÂ‰Á}‘µ{³{‘°}”°}”®–°z”­{•®{•°w°w®v«l„›mƒ™f~‘j‚•^tˆi|“ax‰]tUh}\kˆKawIatJbuE[oNcl;L[?SeATkG[mH\jE\iF]jM^oP]qJZmIYoGXgFXb=LT6@H=HKWbci{€r‡’rˆœsŠ¦y®z±{•®€œ°œ®‚š­‡Ÿ²Š¢·‘¬ÀŽªÀ˜²Ë–ªÊ—¯Æ«½—¯Â³É—°ÀœµÁ¡¸Ç£·É¤¸Ê ³È¡´Ë£¶Ï±ÄÛ¯ÂÙ¡·Ï§¾Ú¤¹Ô¤¶Ò«ÁÙ¤¼Ó®Äܬ»Ø«Á×®ÆÙ­ÄÞ®Äå¨Á᤾ࢻۤ¸Ø§¾Ú¨¿Û£½Ö »Ô¡½Ó¡¼Òœ·ÉªÃÓªÃÑ¥¾Ê¥¾Î¥»Ñ¨ºÖ©¶Ú©¸Õª½Ô¤ºÒž³Ð”®Ç˜·Ì¡½Ñ¥ÀÒŸ·Ì˜®Æ™¯Ã¢¶È´Ã–­º“¬¼š²É‡£¹µ… ¶¦¾Œ£¿ƒ™¼y‘¶}•¼›¹~š°{•®ƒš¶‡¡º€š³x“§}™¨‚¯z•«x’«v©nƒ j|šj}”m“j}”i{™dv”_nXk„]p‡WgWf€SbK]{J_jAO\AQ`ARcJZkKXjIZkOcsNbpNcnPapWdvO`oMbmI[eAOZ5?EGNNgruu„Š|™{‹¡}¥{Ž¥…˜¯ƒ–¯ˆ›´’¥¾¦¾†œ´”§¼¢²Ã±Áס±Ë¢µÎ¤·ÐŸµË•­Â™±ÆŸµÍ¢·Ò£´ÕŸ´Ïž´ÊŸ²Çž®Ä¦¹Ò«ÀݬÁÞ¦»Ø²Ï¡³Ñª½Ô¥¶Éª½Ò§½Õ­À׶ÆܯÅÛ¦½×¤¾×«ÅÞ¥¿Ø¤»Õ¤»×¦ºÜ§¾Úž¹ÏªÅÛ«ÆܨÂÛªÀߪÁÝ¢·Ò¤¶Ò¡°Í–¨Ä•§Ãœ®Ì ±ÒŸ±Í¥µÏš­Æ™¯Ç ¸Ï¥ÀÖ£¾Ô¡¼ÒŸºÎ™±Æ•°Ä“®Â‘¬¾‰¡´Œ¤»ˆº‰Ÿ¾‹¡ÄŽ¤Å‰¿…œ¸˜²™°„œ³ˆ¸~°|Žª‚’ª}©~¬~“®zªy‘¦{“¦vŽ¡mƒ—k—cvaw‹f}Œg{‹cs†YpToQi|Si}Si}ObyKag@R^AUcFZjL]nMZlS`r]j~[g~Xd}^mƒ[j€XhyYfvWdtQ^n8DR6?LR]nlx€¦x‹ Š´‚•®‚˜°–±… ¶‡£¹Š¥¹…°¦ºŸ¯ÇŸ²ÇŸ¶Ç°Å£³ËŸµÉ—°À™±Äš°ÈŸ·Î˜³ÉµÊ ¶ÊŸµËŸ±Í¤¶Ò©¸×«½Û¨ºØžµÏ¡»Ô£¾×£¾Ù®Êà©ÄØ ¼ÒšµÎ§ÂݪÃ㨾ݬÀ৹ׯ¾Û«¾×©¿×­ÅÜ­ÄÞ¸Ïé³È㥿ؙ´Í«ÄŸ¹Òž¹Ï£»Ð¥ÀÖ·Ò·Ò ·Ó—²È¸Ì˜³Å—¯Â¸Ì›¶Ì¦¾Õ–¬Ä‘§»±Ã¢µÊ›«Ã¢¸Î¤¼Ñ©Â‚›¹ªÅ•¬ÆŽ©¿¨¾… ´ƒ›°„œ±™°‚œµv«z”­‰¡¸‰ž¹x‡¦~”¬}•ª—ª{’£q‰œl„›h~–m}—j}–hz–g|—av“as]l‰[kƒ\l‚Zj€Vf~L^hIZkJ[nP`vO^tU_w\gzit…^i~[edp‹`l‡^keplz‡RcoLYiAI]^jƒw…¤~‘ªz’§z¤ƒ–«†™°‚”°¢¿‡¼‰£¼Š¥»’ª¿ŸµÉœ´Ç•­Â˜®Æ¦¸Ô–«Æ—®Êš±Í¢·Ô£ºÔŸ·ÎŸµË¦¹Ðž¶Ë•°Æ›±ÉŸ®Ë¡¶Ñ§¾Ø¢¼Õœ¶Ï¤¿Ø§ÂÛ¡»Ô«ÀݯÆâ´Îé¬Æá­Ä੽ݧ¸Ûª¼Ú³Â߯ÄߪÁÛš´Í©Âš²É°É¦¼ÔµËã·Íå¯Áݨ¾Ö¦¼Ô£ºÔ£½Ø¤ºÙ ´Ö£ºÔ°Ëßœ·Ë•°Ä”¯Å˜²Ëš²É˜«Â“¦½¢²ÊÂÒ螮Ě°Æ•°ÆªÀ¨¾©Â˜®Í§ÃŠ¡»~™¯y•«³„ ¶ƒ¶ƒš¶|’±…›¾{‘°wŒ©t‹¥rŒ¥y‘¨|’¨rŠ¡h™lœt†¢gz‘gzc{Vq‡]uŠ`vŒYpYm}Wh{]l„PbnIVfO_pSdwQbsN_pXixXixXix]n}`pepgt†er†er†Zf}Wf|[j€jys‚š~Ž¦‡š±€“¨†™®ŒŸ´ŸµŒŸ¶Š ¸Ž ¼”£Â•§Ã—­Å˜°Ç˜²Ë•°Æš²Çš°Æœ¯Æ™±È·Ð£¾Ô¦¾ÕŸ¶ÐŸ´ÑµÌ£»Î£»Ðž¶Í ¸Ï¦½×¥½Ô­ÃÛ¦½ÙŸµØ¤ºÛ™­Íœ³Ï¡¸ÔµËã³ÃÛ®ÁÖ¢µÊ›®Ã©¹Ï±ÄÛµÈá±È⥿ݨÂÝ­Äà®Ä㦼ݢ¼×³ÍæµÌ桶ә®Ë¦»Ø°Å਽ص̗²È•±Åš¶È¹ÏŸ¸Ö˜¯Ë•§Åœ´Ë–±Å«¿‘©ÀŽ©¿ªÀŽ©¿•¯È¨Ã‹¥Ã‹¦Á‡¡¼€šµ}“²}—°z•«}—°{‘°v«v©w‘ªt‹§tˆ¨q‚§~®r…žp… k€j›g~˜_u‹]p…cv‹fydwŽcv\l‚`o…YmSj{JeiGYeJ^lQeuQhuMdqVjz[l_pdu†fw†dv‚`pam„_k‚_k„bq‡iyk{“tƒ}§z’§vŽ¡~”¨ˆž´‰Ÿ·‰Ÿµ‘§»¥¹”§¾˜«Ä”¦Ä˜ªÆ›®Ç˜°Ç˜²Ë›µÎŸ¶Ð›±Ç¤·Ì¤ºÎ¤ºÐ¤ºÎŸ¶Ç©ÀѯÂקÀШÄÓ²ÊݱÄÛ¸Ê櫼߮ÀÞ­¿Û¶ÉâµÈߦ¸Ö£³Û©ºß®¿â®ÁÚ¸ÉÜ·Êá²Çâ°ÆÞ´Êâ¯ÇÞ¤¾×¡¼ÒªÅÛºÖìµÑç¥ÁצÁ׸ѷ՚³Ó ¶Ù¡·Øœ²Ñ•¯Ê©ÄŽ©Ä•°Ëœ¶Ï¥À˜¯Ë“©È‘«Æ–°É«Á§¾‘¨ÂŒ¢Á‡ ¾Ž§Å‹¢¼ˆž¶‰¡¶ˆ£·ˆ¤¶‰¥·š®ƒš´™²x’­y¬}­zª|“­v‘§k†šqŒ¢w‘ªt‹¥sˆ£kƒškƒšf~“c{aw‹jzhxdrZlˆVk†Um‚Sl|TmpHXiK[lZgyXhySdu]m~^k}^n}cs‚bs„at‰bvˆ]nXizcs†k|l}p”z‹ž{¡|’¦~”¨‚•ªƒš«Š¡²¤µŒŸ´‘§»˜°Ãš²Å”ª¾ ·È¢¹Ê´Ã§»Ë£¶Í£²Ñ§¹Õ¨ºÖ¯ÂÛ²ÅܯÂÛ§¹Õ°ÃܯÂÛ±ÄÛ¯Â׳ÉݶÎá´Ìß­Ãר»Ð¯¿×°Àد¿Ù¹Ìå¯ÅݬÄÙ­Èܨ¾Ô¬¼Ô«¾×­¿Ý«ÀÛ©¾Ù¬ÂØ«ÁÕ°ÇÖ°ÄÒ½Ôå´Ê⩿׫ÀÛ§»Û¢¶Ú¤½Ý¡¾Û™·Ñœ·Ò›µÐ ·ÓŸ¹Òš´Í˜³ÅªÃÏ–¬Àœ«È•¦Ç˜¬Ð”¨È’¤Â¤¿¢½“¨Ã¤ÁŒ¡¾’§Ä¦¾†œ²†œ²£¹£¹†œ²‚˜¬ƒ™­€–¬yŽ©v‹¦v‹¦„–²‚‘®tŠ¢vŽ£tŒŸrˆœm“s„—fzŒ`wˆ`vŠk™aw`sˆ[nƒYlƒZm‚[l]oyKYdM^hZlxarYiz^n`lƒcs†ar…^o‚^o‚Ym}Vjx[o_r‡etŒlv’s˜z†£…™«ƒ™­†œ²‰Ÿµ‰Ÿ·…›³‰ž¹¥½™¯Åš­Ä¦¶Î¤·Î³É¢¸Î¢µÌ§¼×§½Ü¡»ÖŸ¹Ò§¿Ò¦½Ê©½Ë¦¶Ç±ÁÐÁÏܺÊÙµÅسÃÙ°Àا½Ó£»Ð«ÃÚ«ÂܪÂÕ±ÊدÇÚ³Éá®ÆÛ»ÖêªÅÛ¨¿Û¬ÃÝ­ÃÛ­ÂÝ«½Û©»×°ÂÞ«ÁÙ¨¾Ö©¿Õ¨¾Ò¨¾Ô£µÑ¡³Ñ›¬Ïš®Ò¯Â롺ܕ²Ñ™´Ï•­Ä™°Ê£ºÖ™¯Î±Ó±Ñ’§Ä”©Ä¢½˜­ÈŽ ¾¢¿‘¦ÃŒ£¿‘ªÈ‘ªÈŒ¢Ã’©ÅŽ¥¿Š¢¹‡Ÿ¶Œ¢¸Ÿµˆ›²‹¹ƒ˜³{’®s‹¢n„šƒ›®„­uŽžu n„šs‚Ÿh{”g}“dzŽi|‘`t†bv†dwŒas]p‰dtŒZm„Vl‚RgpH\jOcqWhyau…Ym_s…\o„]t…WnYm}[l{\m~\l‚[rƒc|Œ`wˆl|’pƒšr…ž{Ž£…™«‹Ÿ¯¡±…œ­—ªŠ ¶”§À‘¤½“¦¿–©Â ²Î µÐ›°Ë¤ºÒ©¿Õª¾Ð¬½Î¨¼Ì©½Í¯ÃÕ¨»Ð¢µÌ£³Í²Êß©ÅÙ¤ÀÒ¦ÁÓªÂÕ­Ã×´Êà¼Òꩿק½Õ¨¾Ô²ÅÜ©¿Õ®ÆÛ±Ìà·Óé¨ÄÚ¨ÃÙ¦¾Õ¯ÁݲÊß°ËÝ«ÆÚ¥¼Ö¦»Ö¤¶Ò«½Ù«½Û¨½Øœ³Í²ÍŸ±Ï´Î©ÃܪÁÛ§¹×¥ºÕš±Ë™®Ë¦´Øž²Ò•¬Èš¯Êš¬È’§Â¢¿’§Âš­Æ“©Á‹¡¹Š¡»¦Å“©È“©Ê’¨É‘¥Ç‘§ÆŠ¡½†¡·†¡³—­‚’¬yŒ£yŒ¡}§q„x¥sŽ¢oŠžkƒ˜kƒ˜g}•e{“j|˜h~”bxŒ[q‡]p‰awYq„]t…dxŠXk€WgTirOdm\nzXhyar\m|_p_p\p€Ym}[oZm„_r‹et“m}•m~‘l|”sžk{•r‚š{Ž£ƒ–«‡›«ž­ˆ›°Œ¡¼‘©¾’«»’ª½“©¿›®ÅŸ¯É©¹Ñ±Á×­ÁÓ¯ÆÕµÉׯÀÏ«¿Ñ¯ÅÝ¥½ÒŸ·Ì£»Î´Å¬Ä׶Îã¨ÃÙ«Åà³Êä´Æâ®ÃÞ®Å߬Æß«Åà­Çâ²Ìç­ÇਿٮÃ୾ߩ»Ù®ÀÞ²ÇâÃÙñ¬ÄÛ¨ÂÛ¬ÇÝž¶Í¦¼Ô¨»Ô¥ºÕ¨½Ú©»×£²Ï¢²Ì¦¶Î¶Æ਷֜®Ì ±Ò¨¼Ü ´Ö™­Í›¯Ï‘¨Ä–­Ç˜°Ç—­ÅªÃ‹¦ÁŒ¨¾¹Í ¼ÒŠ¤½Ž¨Á©Â‹¢¼†›¶¢½¢¿Œ£½Œ¤»„œ³ƒ™±…š·„˜º~’´zŽ°}“²€—³vŽ¥vŒ¢u‹¡v‰ v‰¢n€œnšh{”e{]t…_v‡`sˆ`vŒYqˆawaq‡]nUfwRhnUfp\myYfv[kzZk|^n}dqiyˆbs„]n[l}arƒq’m~k|psƒ’q‚“t…˜vŠœ‚•ª„˜ªŒ ²†šªŠ›ªž­•¦µž¯À˜§½ž­Ã¤³ÉŸ°Ã¨¹Ê¡²Ã¢³Æ¢¶È ¶Ê®ÇרÁϨ¿Ì±ÅÓ©½ÍªºÐ¾Ôè²Íá¨ÃÕ¥ÀÒ±ÍáªÅÞªÆܯÊàªÅÙ§¿Ô¬ÇݳÍæ´Ïå®ÆÝ®ÁÚµÄÞµÈá¬ÁÜ©¿×¶Éà²Êá°Êã­ÈܨÁѨÀÓ¨¾Ö«ÀÛ¡¶Ó¥¼Ø£ºÖ§¿Ö¢¸Ì³Çœ¯Æ˜«Ä›­Ë¯Í¡³Ñœ¯È›«Ã•¨¿“©Á—­Å˜®Æœ·Í«Á©¿’®Äœ´Ë‘¤½Š ¸Œ¤»‰ ºƒ˜µ¥Â†—¸„›µ‚³… ¶ƒž´Š¥¹œ®z•©}—°x’«sŠ¦sŠ¤tŠ¢z¦}¥y‘¦l†Ÿf€™f}—av‘kz—gvgsŒdscreu‹n~^o~SgwOekWgvWhwVgv\p~Xl|]n_n„k{‘at‰]t…[rƒg€Žl…“lƒt…”rƒ”w‡s„—sƒ–‡—¨†–§‡˜©„˜ª‹Ÿ¯‰š«Šš«”¡µ˜¨¹•¦·š®À•¨¿˜¬¾ ´Â¢¶Äª¾Ì¤¸È£¶Ëª½Ô©¹Ó¦»Ö¬Åã¯Éâ¨ÀÕ³Éß²ÅÞ°ÆÞ´Êâ´Ìã³Ëâ­ÅÚ¨ÀÕ²Êá¬ÁܬÃݸÏé½Õì¼Òè¹Ðá¹ÍÝ´ÈÚ²ÅÚ¨¾Ô¥»Ó¬ÆߨÂàªÉÞ¬ËܯËÝ­ÅÚ½Óé´ÇÞ©¿×¢·Ò­¿Ý­»Ý¡³ÏŸµË¢½Ñ¹Ï—²È•¬Æ’ª¿™±Ä°Çž­Ç—¬É‘ªÊ˜±Ï©ÇŽ§Ç¦ÈŽ§Å“ªÆ–­Ç’¨À™¯Ç’¥¾•§ÃŒ¾…™¹—¸‡¡¼›´˜´ƒ—·|‘®|Ž¬’«~‘¨u¢l‡›vŽ£nšn˜n˜m€—i|•buŠcw‰fzŒ]nZn€^tˆg}‘]s‡Vi€Vf€PbnVgxWiuWisXjt_q}arev‰duˆfwŠdxŠ`vŠbyŠi€oƒ‘x‰˜o€‘q”rƒ–s„—~ž…—£Ÿ«„•¤ˆœª‡›«”¨¸”¨¸“§·™­½¬ÃÔ¢¸Î¢µÌ¦¶Ð¨»Ð§»Íª¾Î³ÄÕ²ÆÖ¦½Ì²ÉصÉÙ°ÃاºÓ¡¶Ñ­Áá´ÇÞ½Îß®ÅÖªÂÕµÍà²ÈÜ«¾Ó´ÄÚºËÞ»Ìß³ÊÛ¸ÐãµÎÞ±ÊÚµÉÛ¸ÈÛÄ×î½ÒïºÑí­Äà¬ÄÛ¦¼Ò±ÄݳÂß­¾ß¬Àä¬À⧻ݯÅÝ­ÄÕ ¸Ïœ²Ó ·Ñ¦¾Ó¥½Ô™°Ê£»Ò¥½˜®Ä–¬À—­Ã—­Å—¬Ç¤ÁŒ¥Ã§ÇŒ¥ÃŒ¡¾‘¨Â“ªÄš²Å©·•­Â‘¨Ä©Â™²~—µz“µ}“²|Ž¬}’¯yŽ«y¥{’¡|’¦uˆ¡r„ k}›i~™p… s‰Ÿp„–lƒ”`x‹e€’\w‹Zr‡[n…e{Yr‚Tk|RezQdkWdv]kx_mxdr}hvƒdtƒfwˆev‰cs‹fzŒau…kmrƒ’w‡–r‘x‚št€—z†~ŽŸŠ›ª…™§‡›©“§·Ž¢´”¨º’¦¸“§¹•¨½Ÿ²Ç˜«Â¡´Í¯¾Û«¾Õ§ºÏ±ÄÙ·Ê߬ÃÔ§ÀμÓâ·ËÛ®ÄدÇÞ´Êà½Ðç¶ÉÞ´ÅØ°ÃدÅÛ³ÉݸÌÞ½Ñã½Ðå·Îß¹Ðá¼ÔçºÒé¹ÑæµÍâ³ÉݸÌÞ·Ê߸Ëâ¹Ñæ¯Êà¶Îã­ÃÙ­À׺Éã´Ã⯽ã°Ää®Åá«ÃÚ¢¸Î§¾Øž´Ó¦½×¥»Ó—¯Æ˜²Ëš¶Ê•µÃ¬ÈÚ½Õꖮś°Ë”©Ä“¨Ã–­Ç•¬ÈŠ¡»¤¿Œ£½Œ£½š°È”§À¤Á…›¼‰Ÿ¾‡žº„›·„š¹„›·ƒ˜³~”¬~”¬{“¦y•¤w’¤oŠžtŒ¡tŠ n„œnƒžo‡œn‡—r‹™hŽo‚™ly›craq‹Tg~Yl]qƒUi{MciThzYm}arƒ_peu„ev‚m{ˆfwƒ`q}dv€fx‚fx‚hz†r†”n‚’q…•rƒ”‚’¡…’¢ˆ–£–¤¯Ÿ®¡´¡´”¤º”¥¸œ¬¿•¨½–¬Â³É£¶Ï¤·Î¬¼Ô°ÀÖ´Ä׫¼Ï±ÂÕ§¾Ï¨ÁѵÉÛ³ÃÖ±ÁÔ¹ÈÞ¸ÉܾÏà²ÃÖªºÐ®ÁÖ¨»Ò®Ç׿ÛæÌäîÔåñÇØçÅÙëºÑâ®Ç×µÌÝ¿Ðã·Êß³Éß²ÈܵÈݶÊÚ°ÄÒ²ÉÚ®ÄÚ¯ÂÙ¯¿×«»Õª¹Ø¡¶Ñ™±È¡¹Î£»Î¥»Ï¨»Ò¦¹Ð›®Çš°È¡¸Ò—±Ê˜²Í¢¼Õ«Á–­Çš¯Ì›±É˜«À“©¿”ªÂ˜®Æ“©ÁŠ ¶‹¡µ¦¾¢¿Ž¥¿‡¢¸‹£¶¡³Š ´‡Ÿ¶ˆ¢»›¶z‘«{‘©z’©{“ªš°x’«sŽ¤tŒ¡rˆ k}™q„nše{“ay^v‰g€Žd}‹]tƒZn~Xh{Wgz[j€Tfp^k{^k{gt„mzŒkwŽdt‡Zk|Zn|[p{fw†l|j~ŽhŽ{’¡xŒœr†˜xˆž€‘¤{Œ‚’£±ŽŸ²‘¥·£µ¡´“¤·‘¡´•¦¹›«Á­Ãª¹Ï²Á×±ÀرÀس¿Ø±ÂÕ±ÅÓÀÔâÆ×æ¸ÉܶÆà´ÃÙÀÍá²ÂÓ´ÅÖµÉÛ³ÉݼÒæ¼ÏæÑäûÏß÷ºÊâ¿ÏéÂÕìÂÕì¾ÒäÅÙç¼ÑܽÏÛ¹Íß·Êã·Íå²Èà¹Ìå²ÀݺÊä³ÃÛ¶Éâ­Âݨ½Ø¬ÁÜ©»×­¼Ù§ºÓ¢¸Î¡¹Ìš³Ã£»Ðœ³Í˜°Å¡·Ë£¶ËŸ¯Ç•¨¿”§Àš°Æ—¯Â™¯Å•§Ã—«Ë‘§Ê‘ªÈ«ÄŠ¤½¢½’¨ÀŒŸ¶Š ¶¨¿…²‰¡¶†œ²ˆ›²‹žµ…˜¯z¦z¦x¥tŒ£x“©{–¬oŠžq‰œs‹žk•o…›p†žo…t‰¤mƒ™k‘dxŠduˆbs†]mƒWn_xˆQjo^muWhteuˆdt‡crˆ`peu„k{Œjzu…–u…”r†–o…™vŠœ{‹žy‰š ‘¤€¥ˆ—­Š–­ ±ŽŸ®‘¥·–©À”§¾’¥¼›±Åš²Å¤·Î²ÀÝ­¼Ö®½×ªºÐ²ÃÔ¹ÍÝ·ËݲÅÚ«¾Õ¶ÆÜÀÏå¾Ïâ¶ÇÚ¯ÀÓ®¾Ñ­½Ó±ÄݽÐå¼ÐâÆÚèÀÕàÄØèÅØí½ÐåÌßôÄ×ìÄ×îÂÛëÁÝêÀÙç·ÎߺÑâ·Íá»ÑçµÈá¶ÉÞ»Ïá­ÀÕ²ÅÞ®ÁØ«¾Ó©¼Ñ©¹Ï¢¹Ê§ÀЬÇÙ¡¼ÐŸºÎ™±È–®Ã™¯Å ¶Îœ®Ê™¯Å˜®Â”ª¾³Ç™¯Ç¥Â“ªÄ‘¨Â“­ÆªÃ–±Ã§¾Ë™°ÁŒ¢¸¦¼”ªÂ£»‹¹†˜´‚”°‚˜°ƒ›²š°~™²y”ª|”©{“¦vŸo‹˜lˆ•lˆ—e€’l…•n…–i€‘j}’d{Œg€Žd}‰hŒ_x†]v†g~]p…TirXhw`pl|hu‰sz“p}‘p€‘m~hz†r‚‘v”t‘vƒ“z‡—‚¡‚’¥¦°Š—©š®™°–¢¹—£º‘¤»‹£ºŒ¤»˜®Æ±ÁÙ­¹Ð­¼Ò²ÂØ´ÄܲÁÛ·ÆÞºÆß¹ÊݶÊرÂÑ´ÄÓ¹ÊÙ½ÑáÁÒãÁÑâÀÑâ¸ÉܾÒä¹ÍßÀÔä¾ÒâÆÚêÉÚëÁÒåÁÐè½ÍåÁÑë¾ÑæÀ×èÀ×äÇÜåÆÛæÇÛéÀÔæ½Íå»Îç²Çâ¶ÌäµËá´Ìß³ÌܳÊÛ§ºÏ¥»Ï©¿Õ§½Ñ¯ÅÙ§½Ñ¢¸Ì¡·Í³Ë™¯Çš¯Êš°Èœ¯È™¬Á®Á—­Ã˜¯É²Íœ®Ê’¨À’ª¿«¿“®Â˜°Å”ªÀ³É“¦½‘¤»ž®Æ°Ç‘¤»ŒŸ¶†™°€“¬…”±~“°|’³z‘­€•°uŠ¥{«xŠ¦t†¢n…Ÿh‚›hƒ™j‚™e}”k‚œn†›f}Ž^v‰ayŽ`vŽ]l‹^mŒapUiy_sg|‡l~ˆj|ƒv…‹u‡Žj|†mg~ho‚—wˆ›y‰œw„˜ŠŸ€œ†—¦†—¨Š›ªŠ›§“¤³œ°À•©»˜«À™¬Á¨¸Î¹Êݧ·È«¼Ï®ÁÖ³ÄÓ»ÌÖºÍÔ¶ÉеÊÕ¯ÃÓµÉÛºÊâ»ÌßÁÑâÅÕæÅÕæÆÖåÄÒßÍÞêÇÙåÇÜçÃÛåÄÜæÊÞìÇÜçÕçñÊßèÆÛäÐãèØêíÏâéËÜëÉÝíËÞóÀÓè¾Ñè¿ÒéÁÑé¸Ëä»Íé¶Ìä´Êâ²ÂÚ´ÀÙ§¶Î¬¼Ôª½Ò¨»ÐŸµË¡¹Ðœ´Ç¶ÆŸ¶Ç¥¶Éš­Ä›°Ë«¾×¦¶Ð¢´Ð¢´Òš®Îš®Ò ¶Õ”®É“­È•®Ì–°É§¼…²£»–¬Â‘§½¨¿Œ£½Œ¡¼‹¹Œžº‚‘®…”±€¬xŠ¦|‘¬y§yŒ¥tŠ¢r‰£r‰£r‡¢o„Ÿlžh}šk}›g}•j‚•ax‰au‡aq‡_k„^jƒ_k†Zkzly‹n~l|m}Žvƒ—s€m{ˆop„’m~t„“|Œ›€¡¢~Š£{Š }£„•¦…•¤Žž¯Š™¯ŽŸ®–«´–¨´›«¼£´À¥¶À³ÄЫ»Ê°ÀѲ¿Ó·ÄÖÄÑá³ÄÓ±ÅÕ·ËÙÂÓâÀÑâÄÕè¿ÏàÀÍÝÈÔâÑÚéÊÕæÆÑæÒßñÒßïÓáîÐÞë×æìØèçÒâãÔãéÝìðÓâæÒáçÌÚåÔæòÎâðÐçöÄÛìÃ×éÂÒè½ÐçÁÖñÃÙñ¾Ñè·Êß¾Îä²Âد¿×°ÃÚ¯ÂÛ­¿Ûª¼Úž³Î¥½Ô§¿Ô ¸ÍµÊ–¬Ä“«Âœ³Íž³Îœ®Ìœ®Ê›«Å¯Ëœ­Î³Ò—°Î—±Ìš±Ë–°Ë•®Î©É™¯Ðˆ¡¿Ž¨Ã‰¢ÀˆžÁŠž¾Šœº‡™·‰—¹‡™·ƒ•³{«}“«yŽ©v‹¨uŠ§v‡¨v‹¨p… m…œo‡œm…šf~“`vŠk‘cv‹eu]m‡_n‹eu\l†Vkvq}‰m{ˆly‰r‘mzŽp’n‚’u‰™t…–x‰šz‹žtˆ˜y›}‘Ÿ„•¤ƒ”ž€—ˆ•¥‰•®™°˜­ ¯•§³›­¹ž°¼¥¶À©µÁ­»È«¸È²¿ÑµÁØ´Ä×¾Ïà½Ñß¼ÐÞ»ÌÝÃÓæÀÐãÀÐãÁÒáÇÜåÌÞèÏàêÖçñÇÕâÐÞéÓáìØçïÙæíãêõñóÿßåóÞèò×áëÜåòÚçìáñðÛêðÓáîËÜëÊÞðÍÝóÂÑéÃÒêÇÖîÅØíÊãó»Òá½ÑßÆÚè»ÌÝ´ÈØ´ËÜ­Åئ¾ÓŸ·Ì¡¹Î¢½Ñ›¶ÌžµÏ™«É˜®Æ˜°Å˜°Ãš²Åœ´É–¬Ä›°Ë˜ªÈ”¦Â•¨Á“«Â”¯Å”®Ç•¬È•¬ÆžµÏ§ÁˆŸ»‰ º‹¡¹¦À†Ÿ½‰ŸÀŒÂˆ™¼€Ž²}‘±|“¯tŽ§tŽ§qˆ¢r‡¢s‰{Ÿw‹›tˆšj‚—d~—ax”dx˜bw”g|—]s‹`sŠbxZoŒTlto€m~q‚‘mkq‚•t€—zŠ›y‰˜|™}‹–u†|™zŒ˜„–¢}™{”‚“Ÿ‡—¨Žž¯–£·•¥¸ ³Ÿ¯¾¤²¿£´À¦¶Å¬½É§¸Â­¿É¯ÄͲÈδÇÌÀÑÛÃÐà¾ÎÝÉÚëÄÕäÄÕäÊÛçÑÝéÊÙáÉØÞÒßæÑØáÙáåÜåäÖâÞàìæâîêéòñèïïïóöîô÷çíòêï÷èí÷×áëØæñÔæðËàëÄÙäÁÒáÁÒãÅÕëÊÞìÊâê¾ÒâÁÑé½Ðç¸Ëâ¹Éã¹Çä°ÀÚ©¼Õ¢·ÒŸ´Ñž³ÐŸ´Ñ µÐŸ´Ïš²É’ª¿–®Ã¤ºÒ«ÀÛœ®Ì–¬Ä–¬Â’¨¾”ªÂ‘§¿³Ë—®È’¨Ç¥Â‘£Á¥»˜©Š¡²Š ´’¨À‘£Á¡¿Ÿ½‹¡¹‡Ÿ´…°‰¡´}“§~Ž¦t‡ uŠ¥yŽ«vŠªmƒ¤h~¡cz–ayg’e~Œhq™dwŽdwbuŒVf~Xjtrƒm‹rƒ’q‚‘t…”s„•sƒ–wˆ—w‰•s„“}Ž¡w‹™}’}’›„– zŒ“~•’žŽž¯¢®˜ª´•§±—¨´®º­¼ž¯¹¨·¿·Æή¼Ç´Æ͵ÇÌ·ÉÎÃÒÚ¾ÐÚÀÔâ½ÒÝÆØäÃÕÜÎÝãÑàæÙæïÜæîßäìîòõçêëçëðèí÷æìïåìêðõõðòöñó÷ïñõòùùâëèæîðäëò×âåáìïÖåëÓåñÂØÞ¿ÕÙÑçéËÞá¿ÑݾÎæ½Ðé·Éç»Ñé³Éß³ÊÛÄÛè²ÉÖ­ÄÓ¤½Í£»Ð¨ÀÕ ¸Ï¥»Ó£µÑ®ÄÚž´È’ªÁ—®Ê µÐ”¦Â’¥¾–©Â•§Ã–¤Æ“¥Á–¬Â“«¾•±À‘­¼“«¾ª¼—²Æ¨¿“¥ÃŸ´Ïˆ ·‚š¯Œ¤·‡Ÿ´˜²™°€˜¯—ªx‘Ÿoˆ˜vŒ w£oq„r…žk™uŠ¥rˆ bxŽi•dz`vŒcv_uWm…`y~tƒ‹m~ˆqƒt‰”vŠ˜wˆ™u…˜z‹šx–p…y›}’”€’ž‡”¤…“ ˆ–¡‹œ¦¡­Šœ¦“¨±¢«‘£­—©³œ®º¡³½¨»Â«½Ä¯»Ç¹ÈйÈλÊмËÓÁÔÛÂ×àÀÒÞÌÙéÌÛãÖåéàîðäìðæìïêîñìðóòôøóøööþ÷ñ÷ãÿÿñÿÿïñîïëëíñð÷êìòôöüïòúæëõãêñäïòßîôÐáíÌÞèÎàêÎäêÉßåÂÔàÆÖéÅÔêÂÎé´ÄÜ»Îå·Ê߸ÌÞ³ÊÛ®ÅÖªÃÓ¦ÁÓ©ÄÖ£»Î¥»Ñ£µÑ ¶Î³É—¯Ä˜³É•¬Æœ®Ì–¨Ä•¨Á™«ÉœªÎ“¨Å’ªÁ‘©¾˜°Å•­Ä–«Æˆ¢»’­Æ¨¾¨¿’ªÁŠ¡»‡¢¸… ´”¯ÁŠ¢µ™¬‚š¯…°{“¦w“¢‚ž«v›tˆ–q…—q„›k~“rƒ–v‰ dy”ayf~“c{ŽXn‚[q‡]s‹]tn}…l}‰iyŠp€‘y‰œ}ŽŸz‹œtˆ˜w‹| €‘ w‡–{ˆ˜~‹›ƒŽŸ‹™¦‰—¤Š˜£‹™¤œ¤”£©—¦¬–¥­—¦¬˜§­¦´¿¯ºÍ®»Ë²ÃÏ´ÅѺÈÕÁÏÚÄÑÚËØáÒßèÚéïÛêðßîòàîðêòôíðñøúþôòüùøÿÿüÿóò÷ùøýÿÿ÷ÿÿþÿÿôÿÿøÿÿöÿÿëóóá÷òòøõö÷÷ùïóöèîóáëñÚéïÐâçÑäëÌáêÇÜçÇÜçÆÛæÂÖæÇÚï·ËݶÇÚ¸ÉÜ´ÃÙ±Å×®ÅÖ´ËÚ«¿Ïª¾Î«¼Ï¢³Æ£³É¡´É›±Ç³Éž´Ì¬ÂÚ§½Õ’ªÁ˜¯É‹£º”ªÀ©¿×¥ºÕ”ªÂ›±Ç“©¿—­Å•­Ä–±ÇŒ§¹…¡°…ž¬‰ ­‡ °ƒ›°„œ±†œ´‚˜°ˆ¸‘¨ÂtŽ©x‘¯y²tŠ«s‰¨n…¡n…Ÿmƒ›pƒœmƒ™f~“ayŒe|fzŒbrˆcs‰[kƒShqm†q‚Œp€t„“y‰˜s„“t…”s…‘u†’y‰˜zŠ›|Œ|‰›{‹š’ž…–¢ˆ™¥‰š¦‘ž®¡«Ž¡¨•§®™§²š¨µ¤±Á«¸È¬¹Ë¬½ÉºËÕ·ÉлÍÔÅÔÚËØÝÓÝåÜáíâêîâëêæííêïïñó÷úöþ÷öûúúüýüÿÿÿÿôðëÿÿòÿÿûÿÿöÿÿíÿÿßÿÿîÿÿæÿÿâÿÿÜÿÿâÿÿîôóèïòñîõõçïóÜéðÔåïÍßëÊÞìÅÝçÄÜæÀ×ä¾Õä¾Òâ¹ÊÝÃ×ç´ÈدÆתÂÕ§ÀСºÈ ¹Å´Á—®½š­Âž´Èš²Çœ·É–±Ã™±Ä›®Å–®Å–°É”®ÇŽ¨Á“ªÄ˜ªÆ²Ï¤Æ¦É§ÌŽ¨Æ… ¹ˆ¢»Ž¥¿Œ£½¤¿Š¢¹ˆ ·‡Ÿ¶ƒ›²Š ´Œ °†œ°z’©zª‚”²|‘¬t‹¥vŽ£rˆœn†™q‰žn†›j‚—a|c~”d“j‚—[rƒYm}Vlpk|‹p‚Žqƒoq‚Žwˆ’w…x‰“u†x‰•€€Ÿ~‹ŸŽ €ƒ” ˆ™¥ŽŸ«ªˆ™£‘¢¬–¦µž­ÃŸ¯À ®»¯½Ê¯½Ê¶ÄÏ»ÊÒ½ÊÓÆÐÚÍ×ßÑØßßææêíêêíìììîïòóñó÷÷úûøûüüÿþÿÿÿÿÿÿÿÿÿÿÿõÿ£ÃÀÿÿéÿÿéÿÿéÿÿôÿÿøÿÿåÿÿÞÿÿØÿÿÎÿÿÍýÿÓÿÿèÿÿììóçÞæèÓâæÌáêËàéËÝé½Ñß¼ÐàºÐä°ÆÞµÍä°Êã¨ÃÕ¦¿Ë¤ÀͨÄÓ¦¿Ï¦¼Ð¤·Ì›ªÀ£³Ë ³Ì³Ë•­Äš²Ç³É ¶Î˜ªÈ™®É“«Â‘©À²Í‘§¿“¦¿šªÄ˜§Á¦¼Œ§¹Š¥¹‰¡¸…Ÿº…ž¾‰¢À‡ ¾‡¡º€›¯€›­{“¦€˜­|’ªyªuŒ¨tŒ£vŒ¢s‹¢lƒŸl„›q‰žl‚–o‚—e}_zŽc~]xŠYq„Xn‚]v{p|•t„—p’p€t‚|‰™{†›w‡˜z‹š~ŽŸ€¡ƒ¢Ž €¡€£†—¦†˜¤Šœ¨ˆ˜§†–¥‹˜¨–¤¯š©¯Ÿ®¶¤²¿¯½È´ÂÍÆÏÜÃÇÖÑÚçÄÐÞÌÙàÙäçëóõôùùóøøõøù÷úûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ‡v™¬¢ªÿÿÿÿÿüÿÿÿÿÿøÿÿîÿÿãÿÿìÿÿäÿÿÝÿÿÎÿÿÅÿÿÅÿÿ¼ÿÿÃÿÿÌìóÆØàÀÒÛÏØßèÄÓÛÀÒÜÀÒÞ¾Ïà»Ïá»Ñå®ÁØ®½×±ÁÙ¶ÆܼÐ⫿Ϫ¾Ð­Å¥´Ñ©·Û¡²Õ”¨Ì“¥Á¤´Ê’¥¾•¦Ç“©È“¬Ê“¬Ê’¨Ç‘¦Ã‘£¿¦¼Œ¢¶Žª·š·Âˆ¥´‚ž´‰¥¹…¡µ‚ž²ƒž´€›±~™¯€›¯‚š¯š°u©r¦tŽ§pŒ¢nŠ k†¡nˆ¨q‹¦qˆ¢j‚—p‡˜j}’fvŽgz‘_u‹[q…]p…bx~p~‹uƒy†–{ˆšy†šzŠwˆ›rƒ–yŠ{ŒŸ}Ž¡¡ƒ“¤‘¢ƒ¤Š—©‰–¨Œ˜¦™¦“Ÿ«™¥±˜¤²Ÿª»ž«»¨µÅª¶Âµ¼Å¼ÆÌÃÑÓÓááÎÚØÕÛÞîïø÷øÿüýÿüþÿÿÿÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿèéänkaßÞÈÿÿøÿÿúÿÿüÿÿûÿÿðÿÿÿÿÿÿÿÿþÿÿðÿÿöÿÿïÿÿôÿÿíÿÿàÿÿÒÿÿÈÿÿÎúÿÃêó¼ÙãÂÆÎÅÀËÎÀÍß¿ÏÞÅ×ã°ÁÒ§¶Ì°ÀØ«¾×¡´Í­ÀÙ£µÑ¡°ÏŸµÍ—²Ä˜°Å›°Ë“¨Ã©»Ù”¦Â º“©Á–±Ç–¬Â‘¡¹ º•¤ÁŠŸº…Ÿº•­Ä—­Ã†œ´ˆš¶Œ¢º†œ´‹ »‡™·…—µˆ–¸€’®‚˜®„š°‚•¬y¥z¨z¨yŽ©q‹¤n‰¢o‰¢v§n†e}”d•b|•d|‘^u†^u†at‰]swl}Œr‡’uŠ“p…Žw‰“{Œ˜y†–p€‘}£‚“¦‚’£|Œ›žƒ” ’žž¨ˆ–¡ƒ‘ž‘œ­˜£´¥¹• ³™¤·Ÿ¬¼§µÂ«µ¿³¸ÂÆËÓÖÛãÖÝÝÚáÝèíéôôòþþþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿº·º.+.e][ÿõñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿóÿÿäÿÿãÿÿèÿÿÐüÿ·ÿÿÁÿÿ¸ÿÿ¹ÿÿ¯ÿÿ»ÿÿÀðö·×Ý©¿È°·¾Å¯½È²ÃÖ­ÁÓ§»Í§ºÏ±ÄÛ¤ºÐ³É³É˜®Æ™¯Ç“©Á“«À¡¹Îš°È–¨Ä’¨Àš²Ç’ªÁŽ¥¿‘§¿”¤¾…šµ‚œ·Š¢¹“©½š­Äœ¹„š²‚š±€›±œµ‚™³ˆš¶‚˜°—¯ƒ™¯{‘§—«‚•ª{Ž¥v‰¢tŠ o…›rˆ m‚nƒžfx”gz“jz”fvŒct…]qƒcvavly‹sƒ–w†œn}“q€–w‡˜zˆ•x‰•…•¤ƒ ƒŽŸŠ›~‰œŽž‚’¡Š˜¥Œ•¤ˆ‘ ™¨•¡¯”¢¯”¥¯™«²¢±¹¥±½°ºÄ·¾ÇÂÇÏÐÔÙßãæãçêèíëñôñýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿçÿÿ¸€ˆ:ÑáÿÿêÿÿÿÿÿóÿÿïÿÿãÿÿÕÿÿàÿÿþÿÿúÿÿïÿÿðÿÿãÿÿßÿÿ×ÿÿÊÿÿÇÿÿ¾ÿÿ¸ÿÿÄÿÿ¼ÿÿÁÿÿÆÿÿÏþþÈÓÖ¨ÁÇ¡¹Äµ­»Æ§¼ÇªÃϤ»Ê©½ÏŸµÉ˜®Ä“©¿’¨À–®ÅªÂÙ¡¹Ð“«Â§¼’ª¿˜³É“­ÆŽ¡º—£¾–ž°•˜ ¤¢“¢št•œ’Œ“– ‡—±‡š³†™²ƒ›®€¬©¸}•¨ƒ›°‚š±€–¬‡—¯w£tŒ¡o…›o‚›n„œh€—h€—i—k™k}™aw_wŽ^tŠ`sŠax…t…q‚Ž{ˆšn~‘m}“s„•yŠ™w‰“‡š¡‚“…“ |Š•~Š–€—~•…“ž‡•¢…“ ‡”¤œ¨š¤ž¨²¦­¸¥±½Ÿ­º´ÅÏ°Á˶ÅÍÆÓÚáçìôôöïñõþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõÿÿòÿÿäÿÿÑÿÿÛÿÿåÿÿÝÿÿåÿÿåÿÿãÿÿäÿÿàÿÿåÿÿ×ÿÿÖÿÿÈÿÿ»ÿÿ¸ÿÿ°ÿÿ»ÿÿµÿÿ¾ÿÿÆÿÿ¾êï™ÀÇ´²“¡¦¢ª´Ì«ºÒœ¯È’ª¿’®Â“¯Á¢¿Î¸Ê’ª¿’¨¾¢»—¤¶¡¥´¨š˜³”»€pÕ~qô¤zÿÇ„ÿÓƒúÔzγw¤‘x™–™ˆ–µ…˜±‚˜¬€˜«z•§}–¦|“¢tŠ w‰§o…s‹žrŠm…˜j‚—k™lœr‡¤lƒk‚œh€•c{Žd|`x‹d|„u…”m}Žvƒ—s~“v}–|‡š~Œ™{Œ–†˜Ÿ…”œƒ›{ˆ‘w„–}Œ’ƒ’˜ˆ—Ÿ‡–ž‘©” ®’š¬•Ÿ© ª°¥¯·®µÀ®¸¾³¾ÁÃÌËØÝÛðóôÿÿÿÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúÿÿìØСƷ†ÿÿãÿÿîÿÿÝÿÿßÿÿáÿÿåÿÿßÿÿæÿÿÑÿÿËÿÿÇÿÿÀÿÿÈÿÿÑÿÿÈÿÿÀÿÿÀÿÿ´ÿÿ¯ÿÿ¦ÿÿ©ÿÿ¶ÿÿ¸¾Áy¡¤v¨¨–¨«‘§¿”ªÀ–¬Âž´Ê•¨¿¡«³¤¢ž¶‘…É~mÖfXëTLêRQø\cÙr\Ιfÿÿ±ÿÿ©ÿþ“ÿì†Ñ½z›‹qŽŠ‰–¨€£ƒ’¨zŠ {Ž¥ƒ™­{“¦s‹žz¤vŽ£k†œj…™q‰žhƒ—k†šo‹j‰šf‚‘cw‰`vŒez•ax…w„”r‚“n~‘n~sƒ”z‹—}Œ”€‘›€Ÿ…–¢„’Ÿ}‹–}‹–“š”›‚”›ƒ’š‹™¤’ž¬—£± ¨º£­·—¢¥¢©°¯´À­´»¸ÃÆÏ×Ùâççôöúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïÿÿâùÿ²ÿÿ°ÿÿÕÿÿòÿÿÝÿÿÔÿÿÝÿÿÛÿÿÔÿÿÍÿÿÕÿÿÒÿÿ¿ÿÿÄÿÿÈÿÿ¿ÿÿÂþÿ¹ÿÿ¿ÿÿ³ÿÿµÿÿ¹ÿÿ±ÿÿ®ÿÿ­ÿÿ¨ÿÿ¾ÿÿÑÔÖ¸ˆ—”…—ž•¦¹ž«»¦µ«”—¹€xÉnbÝ`PäUOðNSçVUÖSMþµÿÿÓÿÿÑÿÿÏÿÿ¹ÿÿÿûÿñ²®¢‰~…‚Ÿ}£|¤}§’§yŒ¡v‰ž€¦}§o„Ÿs‰ŸwŠŸn–n˜qŠšy• qŠ˜lƒ”h€“d|‘Woyoƒ‘qtn~p”{‹šš{Š’„“›™‚ˆ˜ƒŽŸ~ŽŸ{Œ˜šƒ’˜‚”ž –¡¢¢°°©·¹©³¹¦­¶¤®´±¼¿±¿Á¶ÃȽÈË×ßãõúúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûüõÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿòÿÿðÿÿçÿÿèÿÿâÿÿÍÿÿÕÿÿÒÿÿÆÿÿËÿÿÏÿÿ¾ÿÿÎÿÿÂýÿ»ÿÿ¼ÿÿÃÿÿ¾ÿÿ»ÿÿ»ÿÿ³þÿ®ÿÿ®ùÿ£þÿ£üÿüÿ™ÿÿ¡ÿÿ¡ÿüµþåÅ뼨ÆyÐhièYgéPbîJbîK^êHXÏ`Kö¼ÿÿÓÿÿÙÿÿÙÿÿÛÿÿÓÿÿËÿÿ¨ÿëuÿïœ÷Ñ¥–ˆ{w‚•~¥{«€’®vˆ¤rˆžy‘¤z’§u¤m…œs‰¡rˆ l‚šg–n…Ÿg–h~–g}•dy”[s}n~hyˆp’qƒqƒ|Ž•‚˜ƒ™™‹™~†˜|‡˜s€w„”}ˆ™ˆ‘ž‘– Ÿ¤¬¢¥­¤©±¤«´ ¥¯­°º¹¿Ä¼ÂżÂÅ¿ÃÈÍÏÓëêïùøýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòÿÿ÷ÿÿòÿÿëÿÿÝÿÿÜÿÿÙÿÿãÿÿðÿÿåÿÿÓÿÿÊÿÿÇÿÿÄÿÿµÿÿ·ÿÿËÿÿ¼þÿ³ÿÿ¹ÿÿ¼ÿÿ»ÿÿ½ÿÿ³ÿÿ°ÿÿ°ÿÿ¨þÿÿÿŸÿÿžÿÿ¢ÿþ±ÿÆ‘ÞyeèYeéRcîMfíJ_ñL`åO[ÜUZá–mÿÿÃÿÿÏÿÿÞÿÿÕÿÿÏÿÿËÿÿÉÿÿÁÿÿµÿí†ÿô‡ÿxŒ„€~Œ©|Š§x†£xˆ €“¨z¤vŒ tŒŸo‡šo‡œh}˜nƒžk€bw”fw˜gy—dv”cw…m~hz†o‹p…Žq†‘{”|‰Š—…ŠŸ‡ŒŸ„—}†•u~‹r|„|†Œ•¡£©¬™¡¥–“£š¤ªœ¦¬œ¦®¢©°³¹¾ÀÇÇÌÑÏÓØÔíðíððòÿüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿôÿÿîÿÿæÿÿÚÿÿ×ÿÿ×ÿÿÈÿÿÓÿÿÜÿÿËÿÿÁÿÿ¸ÿÿÀÿÿ²ÿÿ´ÿÿ¸ÿÿ½ÿÿ¶ÿÿ¶ÿÿ®ÿÿ¬ÿÿ¯ÿÿ­ÿÿ¤þÿŸÿÿ¬ÿޙ݃dç`gë]fíTdëRbçN^îO\ðJUÝ[NÓrNÿþÈÿÿÕÿÿÓÿÿÑÿÿÉÿÿÃÿÿ¿ÿÿ»ÿÿ¿ÿÿÅÿÿ»ÿé…ÿóƒÿþ„ãÎŽws~†Šy’ y’¢y‘¤z¤}¥€–ªs‰Ÿo…j|˜q„pƒœh{”as`u_vax…g~‹i~‰w‰“y‹•s…‘yŠ”‚›„“›Ž—z‡|ˆ”w†Žz‰‘‹‘‹”¢¦©Ÿ£¦•¡’œ¤—¤«¡®µ©±µ£¨¨©®¬ª¯«³»´ÆÎÅ×ÝÔëïçóóóÙÕÝÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûÿÿóÿÿòÿÿöÿÿùÿÿüÿÿöÿÿñÿÿÝÿÿÉÿÿÑÿÿÏÿÿÌÿÿÑÿÿÓÿÿÕÿÿËÿÿÈÿÿ·ÿÿ°ÿÿºÿÿ»ÿÿ³ÿÿ°ÿÿ·ÿÿ¶ÿÿ²ÿÿ±ÿÿ©ÿÿ¨ÿ˘êsiîdjùZpóYfòY_ôX]ðSVíPSîNRÑfVÿɦÿÿÞÿÿÙÿÿÏÿÿÇÿÿ¿ÿÿ¹ÿÿ·ÿÿ·ÿÿ´ÿÿ½ÿÿ½ÿÿ½ÿøŽÿî{ÿù›ÿÝ”‹€b|…”€Ÿ€¨yx˜~’ ~¢n…–g’o‡šm…˜k‚“h|Ž`vŠc{Wrvw‡–m~s„•t„“uƒ{‰”„’„’Ÿ{†—zˆ•}‹˜|‹“Ž“ˆ”•™œ°¹¸•¡£¯­™¤¥š–Ÿ“™¦ª¸¹¤À¾¯ÁÀ·ÂÂÀÌÏÎÚÜàùüûûþûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòÿÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿûÿÿñÿÿðÿÿìÿÿáÿÿÝÿÿãÿÿçÿÿðÿÿèÿÿáÿÿÙÿÿÛÿÿØÿÿßÿÿÙÿÿÙÿÿÁÿÿÀÿÿ¼ÿÿºÿÿ¶ÿÿ¹ÿÿ¸ÿÿÀÿÿ¹ÿÿ©ÿÿªÿÿªÿÿ£ÿÿ¡ÿõ£ÿÓ”ð‡jõbkøbjþekúaeú^cõW_òP^ãPWÜVVÝ’iÿÿÉÿÿÑÿÿÙÿÿËÿÿ½ÿÿµÿÿ¯ÿÿ°ÿÿ¯ÿÿ°ÿÿ·ÿÿ¿ÿÿÉÿÿÃÿÿ¦ÿíƒÿôÿá—¢‰i~{s{ŒŸ{vŽ–{yŠuˆk~—m…˜ei…’c|ˆ_{†a}ˆ^xtsƒ–q”n~‘p‚Žz’|Ž“‚–‹‘y…x‚ˆ}Š“{ˆ‘|‰’…— §®ª°µ°´¹¤­Š–¤|ˆ”t€Œz‚„®²ª·´¨¼³¤Å¼¯×ÍÃÜØÉççÕùøïÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöÿÿúÿÿîÿÿøÿÿÿÿÿÿÿÿÿÿÿöÿÿæÿÿçÿÿßÿÿÛÿÿØÿÿÕÿÿäÿÿÛÿÿßÿÿÕÿÿÒÿÿÓÿÿÎÿÿÈÿÿÌÿÿÍÿÿÉÿÿÂÿÿÀÿÿÀÿÿ¹ÿÿµÿÿ³ÿÿµþÿªÿÿºÿÿ·ÿÿ³ÿÿ´ÿÿ§ÿÿšÿå¦ÿ€ìiaüeiÿmnÿhiýahûYiôQdðMbÖXQÉlIÿî¹ÿÿÕÿÿÙÿÿÞÿÿËÿÿ¹ÿÿ«ÿÿ¥ÿÿ©ÿÿ­ÿÿ­ÿÿ°ÿÿ·ÿÿ½ÿÿÇÿÿÑÿÿ¿ÿòƒÿð‡ÿñ‘°œo…‡‹‚Žšx‹ wŠŸxˆ x‹¢t‡žn„˜o…™l„—f~“b}‘e€”`{n‹m‹hz†pƒŠu‡Œyˆ}‰•r€‹sŒ€—w†Žx„’uzˆŽžª±¼£®±¯»¹’žšƒ‹†‰ŒŠ•‘Œ´ª¤²­£¥¢˜­ªž¸´¥Ã¾²åÞÕøóçðëßñðçþÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿèÿÿèÿÿäÿÿíÿÿûÿÿîÿÿòÿÿðÿÿðÿÿéÿÿæÿÿðÿÿîÿÿçÿÿàÿÿèÿÿåÿÿßÿÿæÿÿ×ÿÿËÿÿÃÿÿÃÿÿ¼ÿÿÄÿÿÄÿÿ»õü©þÿ¸ÿÿµÿÿ°üÿ¦ÿÿ®ùÿžþÿ¡ÿÿ¥ÿÿ®ÿÿ¶ÿõ²ÿ¹˜ôyzéhfùnnýmnûdhû]cøR]ïQYêQWÁ^EñÅÿÿÞÿÿèÿÿæÿÿæÿÿÙÿÿÍÿÿ¿ÿÿ°ÿÿ«ÿÿ®ÿÿ¯ÿÿ³ÿÿµÿÿ·ÿÿÁÿÿÍÿÿËÿÿÉÿþœÿí€ÿ÷¡Í­qŒ‚j}‰—w‡–xŒœo†—o…›q„™s„—oƒ•wŠŸp„–fwŠbx~iv†n‹k|ˆn‰rƒ}‹–€‰˜t€Œp}†~Œ—yŠ–{‰”z„Ž›¢«¦©³¦«³ª±¸Žš˜€Œ†¤­¡¤©šŸŸ°ªš§£”šŽ£ž’°© ½¸¬·²¦¿¶©Í¿²àÕÄìáÐñìâþþþýýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúÿÿìÿÿäÿÿÙÿÿéÿÿìÿÿæÿÿçÿÿÝÿÿâÿÿãÿÿçÿÿãÿÿæÿÿñÿÿðÿÿêÿÿÕÿÿÍÿÿÉÿÿÉÿÿÅÿÿÄÿÿ¿ÿÿºÿÿ²ÿÿ¦ÿÿ¯ÿÿ´ÿÿ¹ÿÿ´ýÿ¬ÿÿ²ÿÿ³ÿÿ³þý¢þý¢ÿû§ÿÙŽÜ—e߇qø£Œÿ¶žðymû`bü\^öOQíUTßTTÝŽpÿÿÛÿÿæÿÿðÿÿìÿÿêÿÿäÿÿÞÿÿÑÿÿÅÿÿ»ÿÿ²ÿÿ·ÿÿ½ÿÿ½ÿÿ½ÿÿ¿ÿÿÁÿÿÍÿÿÙÿÿÑÿÿÃýêŒÿóŒßÉŽŒ~s~‚…k~“m€•t‡œq„™q—i|‘n˜o‚—izbx~ix€lx„nw†sv’~Š˜€‰˜u~r{Šxzƒ’z†’‚˜§±·£«¯­²º¡¢¯ˆ•…“¥ªªš—˜¨¤Ÿ§ • ›‘˜ ›‘©¢—³¬¡´ª¢·­£¾µ¨É¾­×ʸáÔÀáÔÀçÞÏîçàðìéÿÿÿÿÿÿÿÿÿÿÿçÿÿëÿÿíÿÿôÿÿîÿÿêÿÿîÿÿîÿÿáÿÿîÿÿêÿÿèÿÿáûÿÉûÿÌÿÿìÿÿêÿÿâÿÿÛÿÿÕÿÿÌÿÿÍÿÿÏÿÿÖÿÿÈÿÿÂÿÿµÿÿ­ÿÿµÿÿ¶ÿÿ¶õú¤úÿŸÿÿ¤ÿÿ üÿŸÿÿžÿÿ ÿÿ¹ç¡~Ëžpúå¬ÿÿÄÿÛ™àrUü^føW^òLU×YPÈpUÿì¹ÿÿÓÿÿàÿÿîÿÿðÿÿòÿÿìÿÿèÿÿâÿÿÞÿÿÓÿÿËÿÿÇÿÿÅÿÿÃÿÿÁÿÿ¿ÿÿ½ÿÿÁÿÿÅÿÿÅÿÿÅÿÿ¹ÿøˆÿõ”óË{\y~ˆ|‰’~œtˆ˜i“lƒ”g~`y…hk„…boer‚mx‰ux„’tŠyƒ‹v€Šx~Œy‚y‚w„‹„’”§¯³¦©±³¸À“˜¢„Š—›ž›Ÿ—“‚«©˜¨¢’¤žŽ¢œŽ¤žŽ«¢“¥Ÿ­©š¬ª›©§˜¸´£ÐȶÙλ×ʸÖ˺Ô˼ÕÐÄîêåüøéÿúãÿÿÿÿÿÿÿÿúÿÿòÿÿçÿÿÖõùÑôöÖÿÿúÿÿþÿÿöÿÿìÿÿÛÿÿÐÿÿ×ÿÿàÿÿÜÿÿÐÿÿÅÿÿÌÿÿÎÿÿÅÿÿÆÿÿÜÿÿÕÿÿÄÿÿ¿ÿÿµÿÿ¶ÿÿ¼ÿÿÁÿÿ²ÿÿ¢ÿÿ›ÿÿ¡öýŸÿÿ¦ÿÿ¦ùÚ›Ò}ÿðºÿÿ¿ÿÿÊ÷²‡ào_ùZgöX`ïNUÑbJêªvÿÿ×ÿÿÞÿÿàÿÿäÿÿèÿÿîÿÿêÿÿæÿÿäÿÿäÿÿÞÿÿ×ÿÿÑÿÿÍÿÿÉÿÿÅÿÿÁÿÿ¿ÿÿÁÿÿÃÿÿÃÿÿÃÿÿ»ÿÿµÿÿžÿæˆðÚ§ƒvm‚…†t„“m~‘n˜k~•j}”hi†Žk‡„eqiw„jz‰t“v–u€‘x„’xƒ”u€“v’v‚~…œ¨ž£­Ÿ¦¯š§°‹™¤‹•ŸŸ¤®”˜›••“¤£š¡ŸŸŽ¡Ž¤žŽ§ž¢œŒ£©£•¯©›¬¦˜¶°¢Á»«ÊŲÏdzÓȵÚϺäÙÄáá¸ÿÿÍÿÿÛÿÿÌÿÿÕÿÿðÿÿäÿÿøÿÿöÿÿîÿÿòÿÿïÿÿåÿÿßÿÿÛÿÿÞÿÿÞÿÿ×ÿÿÕÿÿØÿÿÙÿÿÑÿÿÅÿÿÀÿÿÁÿÿ»ÿÿ³ýÿ´ÿÿ¸ÿÿ¿úÿ©ýÿ¬ÿÿµÿÿªýÿ™ÿÿ–ÿÿ™ÿÿ˜ÿÿ™þñ–ÚÉvÿõ«ÿÿ°ÿÿ±ÿõ°à„SäfNñQSñYVæUPÏyOÿÿ¹ÿÿÑÿÿÙÿÿÓÿÿÏÿÿÑÿÿÕÿÿÙÿÿàÿÿâÿÿäÿÿäÿÿäÿÿÙÿÿÑÿÿÏÿÿÍÿÿÍÿÿÏÿÿÍÿÿËÿÿÉÿÿÇÿÿÉÿÿËÿÿÃÿÿºýé’ÿêžøâ§À³Š…pgjtlwˆh{’h~’dzŽhz„kxŠly‰p{Œo|Œqs„Ž{Š’{‰”uƒp|ŠvŽ~‡”— ­“œ©œ¥´” ¬ˆ—Ÿœ —¥§‘–”žš•šš—‹š—‹œ—‹¢œŽª¡”¥œª –±ªŸ±¬¢«§˜«§–°­™»¸¤ÆÀ°ÐǺÙι×Ë°ÓÍ›ÿÿ¾üþ½ÿÿÒÿÿåÿÿìÿÿòÿÿöÿÿîÿÿØÿÿÖÿÿÜÿÿÝÿÿÒÿÿÓÿÿËÿÿÍÿÿßÿÿèÿÿâÿÿÐÿÿÅÿÿÀÿÿËÿÿÈÿÿ»ÿÿ®ÿÿ©ÿÿ³ÿÿ®ÿÿ©ÿÿ©ÿÿªÿÿ¨ÿÿ¦ÿÿžÿÿúø’ÿû›ï߉úõ›ÿÿ²ÿÿ£ÿÿ­ÿÃŒ×cTç[XúQ_ëY]Ø[Xû·‰ÿÿÅÿÿËÿÿÑÿÿÏÿÿÏÿÿÍÿÿËÿÿÍÿÿÑÿÿÛÿÿæÿÿæÿÿèÿÿäÿÿàÿÿÙÿÿÓÿÿÏÿÿÍÿÿËÿÿÉÿÿËÿÿÍÿÿÍÿÿÏÿÿËÿÿÇÿÿ»ÿü‘õázÿæ‡ÿîžùä¤Å¸Œ‡pjjhejgsk{‘p€–tƒ™lyt’tv‚y†–s€’q}‰}‡ˆ•š˜¥ª“ § ­¶Š— „šŽ• ž¡«Ž‘ŽœœŒ™—ˆ›—ˆ™•†™”ˆšŽœžœ¡Ž© “´¥µ¨£³¥¥±¦£¶¯¨Áº¯¾¸¨Æ½®Ì¾³âܺÿÿâÿÿÚÿÿàÿÿÙÿÿÃÿÿÈÿþ¸ùú¿ÿÿÚÿÿíÿÿñÿÿ×ÿÿÆÿÿÀýÿºÿÿÎÿÿÙÿÿÌÿÿÊÿÿµÿÿ½ÿÿ¿ÿÿ·ÿÿ¹ÿÿÅÿÿÂÿÿÇÿÿ¾ÿÿ¶ÿÿ´ÿÿ¶ÿÿ³ÿÿ´ÿÿ©ÿÿªÿÿ²ÿöªÝÓ„øñŸÿÿ·ÿÿ·ÿÿ²ÿú¦Ö€VèVXñUZúR]Ù[PÝŠiÿÿÏÿÿÏÿÿÑÿÿÓÿÿÏÿÿÍÿÿÉÿÿÅÿÿÅÿÿÇÿÿÏÿÿÙÿÿÛÿÿàÿÿèÿÿðÿÿæÿÿÞÿÿÏÿÿÁÿÿÁÿÿÃÿÿÁÿÿÁÿÿÃÿÿÅÿÿÅÿÿÅÿÿ¿ÿÿ¹ÿÿ¯÷é€ûñ…ÿÿ‘ÿþ˜ÿõ˜ûéÙÉŽ§thyŒfwˆk{Œl|‹p}sŽwƒ‘w‚“mx‹rzŒ†™–œª—œ¨¡«³¡®³ˆ—~Œ—ˆ’š”—Ÿ‹‹‹š–‘•’Šš•š• ›“š›˜Œ›˜Œ¢Ÿ“ª¤–°¤–·«Ÿ¶© ¯£—¯£—¾µ¦¼³¤¾·œ½µ‘îï¶ûÿµþÿ¼þÿ¾ùüÂÿÿäÿÿêÿÿêÿÿâÿÿßÿÿÖÿÿËÿÿÒÿÿçÿÿãÿÿàÿÿÙÿÿÜÿÿÚÿÿäÿÿÐÿÿËÿÿÉÿÿºÿÿ¿ÿÿÊÿÿÀÿÿÀÿÿ¿ÿÿ¹ÿÿµÿÿ³ÿÿªÿÿ¦ÿÿ¦ÿÿÿü™èÜ~äÜÿÿ²ÿÿ¯üÿ£ÿÿµó·{ÒgKïVZéSTëUTÎrLÿí¦ÿÿÓÿÿÛÿÿÑÿÿÉÿÿ¿ÿÿ³ÿÿ¹ÿÿ»ÿÿ½ÿÿ¿ÿÿËÿÿ×ÿÿÜÿÿæÿÿæÿÿèÿÿæÿÿäÿÿÕÿÿÇÿÿ¼ÿÿ±ÿÿ³ÿÿµÿÿ¹ÿÿ¿ÿÿÃÿÿÇÿÿÅÿÿÅÿÿ¿ÿÿ¹ÿý•ïä}ÿú•ÿü›úó‘ÿü™ÿñ³j{Šl|‹n{‹pt…‘uƒ›sŽn~p|ˆ…Œ—— ˜Ÿ¨ §²˜œ«ˆ™„‰•’•“‹‡˜“‰˜‘ˆž”Œ¢˜¦œ”¥›“¦œ”£©£“«¥•¨¢”«¦“±¬—²­˜±©—¾¶¢»³¼³’¹ÿÿÐÿÿËÿÿÒÿÿÛÿÿÙÿÿ×ÿÿÌÿÿÆýÿÈÿÿÜÿÿçÿÿäÿÿÜÿÿÉÿÿÈÿÿÎÿÿÌÿÿÍÿÿÉÿÿÐÿÿÈÿÿ¿ÿÿÅÿÿÇÿÿÅÿÿÅÿÿÌÿÿ¿ÿÿ·ÿÿ²ÿÿ«þÿ¡ÿÿ¥ÿÿ¤ûþ–ýý™þ÷¥îߟÿÿ¾ÿÿ·ÿÿ­ÿÿœÿå˜ã}Oæ`K÷PVçSQØXMî¨{ÿÿÍÿÿ×ÿÿäÿÿÓÿÿÃÿÿ¿ÿÿ¹ÿÿ½ÿÿÁÿÿÁÿÿÃÿÿ×ÿü×£’µ¢¤þúÞÿÿæÿÿâÿÿàÿÿÙÿÿÓÿÿÅÿÿ¹ÿÿ²ÿÿ´ÿÿ·ÿÿ¹ÿÿ¸ÿÿ»ÿÿ¿ÿÿÃÿÿÃÿÿÅÿÿ¿ÿÿ¦çã‚üï–ÿúœýý›üø°n‚m‚i{‡l}‰{ˆ˜t„“z‹œt…–q’p~‰ˆ’šš¡’Ÿ¨“¢ª‹š¢‡‘—‘—œž££………‹‡Œ‰Ž‰˜Žˆ–¢›”£ž’£ŸŽª¢°£‘µ¨˜°Ÿ“­ ®£’²ª˜´¬š¶° ³¬¡¯ª“ÔάÿÿßÿÿÈýÿ¹ÿÿÁýÿ»ÿÿÏÿÿÒÿÿÛÿÿÏÿÿËÿÿÂõû¯ÿÿ¾ÿÿ¾ÿÿÃÿÿÎÿÿËÿÿËÿÿ¸ÿÿµÿÿ´ÿÿ¹ÿÿ¹ÿÿ¯ÿÿ²ÿÿ¹ÿÿÃÿÿÁÿÿ¶ÿÿªùÿ£ÿÿ¯ÿÿ©öÿ•üÿ›ûüœÿÿ¨úÿ«ÿÿ³ÿÿ°ÿÿ¥ÿü—ù§lìbPðYQ÷PRÖZBÖ…Uÿý½ÿÿÍÿÿÕÿÿÞÿÿÕÿÿÍÿÿÇÿÿÃÿÿÁÿÿÁÿÿÉÿÿÓÿÿùˬÄ̪ÓÉ¡Þ½¤ÃâÖØÿÿøÿÿàÿÿàÿÿâÿÿÛÿÿÕÿÿÍÿÿÁÿÿÀÿÿ½ÿÿµÿÿ·ÿÿ½ÿÿÇÿÿÅÿÿÅÿÿÃÿÿÁÿÿ·÷ó’òíÿûŸÿö·k}‡ohyˆiz‰p’q’s€”z‡›u€•~‡–’—£‘˜£™£”¡ªŠ™¡‹‘‘—ššššŠ‚€‘ŠƒŒ…z‹†z‘Œ€›–Œ•‘¤Ÿ•¦¡•«§–¯ª—±¬™°¨–§¡‘«¤™°§˜²§–²ª˜·¯¹¸‹øý´ÿÿ¾ÿÿ¸ÿÿÃÿÿÐÿÿÆÿÿ¼ÿÿ»üÿ±þÿ´ýÿ³ÿÿÊÿÿÙÿÿ×ÿÿÆÿÿ½ÿÿ¼ÿÿ¹ÿÿ¹ÿÿºÿÿÇÿÿÂÿÿ¹ÿÿ®ÿÿ­ýÿ¥ÿÿ²þÿ¥üÿ¥þÿ£ÿÿªÿÿ¢ïðüþ›ÿÿ£ÿÿ¡ÿÿ¤ÿÿ¦úÿ¡ÿÿŸÿÿ™ÿüœÿÌ{âvMôWXñVTëTNÉmEÿà˜ÿÿÑÿÿÙÿÿ×ÿÿ×ÿÿÓÿÿÑÿÿËÿÿÇÿÿÅÿÿÅÿÿÓÿÿäåËÏÊ¡Ü˥軕⺖ÔƤÖñ¾ÿÿëÿÿìÿÿÙÿÿÕÿÿÓÿÿÉÿÿ¾ÿÿ¸ÿÿ¹ÿÿ¼ÿÿ¿ÿÿ¹ÿÿ»ÿÿ·ÿÿ³ÿÿ·ÿÿ»ÿÿ·ÿÿºüþ™ëè‚øï­AD3=B5EKDXa`^kpn{‚wƒw…’{ˆšƒŽŸ–¥„’…—ž”™yŒ‘}Œ–“‰Š…Šƒ|‘Šƒ‘‡Ž‡€“‹‡“‹‡–‹ˆ¡š“¨¡˜¥ž“«¡—°§š²©š©¤‘«¦‘®©–±«›ª¥·¯™ÂÀˆøû£üÿ¯ÿÿÉÿÿÎÿÿÎÿÿ¿úþ±üÿ¶ÿÿÈÿÿÈÿÿÃÿÿÉÿÿÇòù°ùÿ­ùÿ­ÿÿÀÿÿÄÿÿÂÿÿ½ÿÿ´ýÿ¨ùý ÿÿ³ÿÿ»ÿÿ³ÿÿ®ûþ¤ÿÿªÿÿ«ÿÿ«÷þžÿÿ£ÿÿ¢ÿÿœüÿ™ÿÿ¨ÿÿÿÿ ÿÿœÿÿ˜ÿÙð†cæ^ZóMhåY^Ô`Qé®xÿÿÅÿÿÏÿÿÛÿÿÕÿÿÑÿÿÏÿÿÏÿÿËÿÿÇÿÿËÿÿÑÿÿìÿñéȤÅÕ¤íÍ¢éÌ¢ëÁ–åÆ™ï̦齛ÍçÙÙÿÿìÿÿÞÿÿÑÿÿÍÿÿÉÿÿÁÿÿ±ÿÿµÿÿ»ÿÿ²ÿÿ·ÿÿ³ÿÿ³ÿÿ¶ÿÿ¹ÿÿ²ÿÿ¯ÿÿ­ÿÿ—øì«ÿÿÿÿÿÿÿÿÿÿÿÿÙØÍGMFOZ[pƒw‰‚‘•z…ˆ‰‘Šž~Š˜€Š—ž”Ÿ „‚†„€‰…€‹„}Œ…~•Ž‡‘‡‚}“‹§•§ —§ ™¦¡•¡Ÿ¡Ž©£•¨¡–©¢™®¦’·«ÛÒ¦ÿÿÌÿÿÍÿÿÎÿÿÁûÿ±íô¡ÿÿ¸ÿÿÃÿÿÚÿÿÙÿÿÎÿÿ¾úÿ¬ÿÿ­ÿÿ²ÿÿ´ÿÿ¶ÿÿ±ÿÿ´öý¦÷ÿ¥þÿ¬ÿÿ°ÿÿ¨ÿÿ¥õý˜ùÿ˜ÿÿ¥ÿÿ¸ÿÿ«ùÿ›öÿšýÿ¢úÿ™ÿÿ–üÿ›ÿÿ°ÿÿ§ÿÿ£ÿû£ÿÔŒìŽiô``ñU\óL^Ü]M×Oÿò±ÿÿÍÿÿÕÿÿÞÿÿÕÿÿÍÿÿÍÿÿÍÿÿÍÿÿÏÿÿÓÿÿÙÿÿÿÇ¥ÐÀœÑÀ—Ù¿–ÖÆžÛÅœÞÉžçË¢æě۽ÅÁª½ÿÿêÿÿàÿÿÕÿÿÍÿÿÇÿÿÃÿÿ¾ÿÿ·ÿÿ·ÿÿ·ÿÿ¸ÿÿ³ÿÿ½ÿÿÃÿÿ¹ÿÿ³ÿÿ¯ÿÿ°ÿù«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿapm|‰š¡ˆ•œŽ›¢™£Š—„—‚…€„{xw…|‡‚zŠ€xˆ“Ž„–„–Œ‚˜‘ˆ£›—¢›”¡š“™–ŠŸŒ§£’§¡“«¡™±¡’º¤öé¾úô´æä™ñóžóø¢ÿÿ²ÿÿºÿÿÂÿÿÌÿÿÎÿÿ½ôú®öü®ýÿµÿÿÁÿÿÆÿÿ¾ûÿ¯éòþÿ²ÿÿÁÿÿ·ÿÿ®øþ£óû–ùÿ”ÿÿ ÿÿ§ÿÿ¨ÿÿ¯òù™øý—ÿÿ¡ÿÿ ïì‰ìæ÷÷•ÿÿ«ÿÿ¨þÿŸÿÛÜ\ãnUóXZóU[ñPYÖhHÿÅÿÿÉÿÿÏÿÿÓÿÿ×ÿÿÑÿÿËÿÿËÿÿËÿÿÏÿÿÓÿÿÙÿÿàìÖÔÌ¥Û¿—ÔÁ—ÛÁ˜Ú»’ÔÀ—ÛÀ•ÜÅ›ßÅ›ßÀ™Ï®Œ³¯ œñòÄÿÿÞÿÿÏÿÿÉÿÿÅÿÿ¿ÿÿ¹ÿÿ¹ÿÿ¼ÿÿ»ÿÿ¿ÿÿ½ÿÿ¼ÿÿ¯ÿÿ¬ÿÿ³ÿÿ°ÿÿÀÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¬­Ñ€ˆš‹™›Š™Œ›¡z‰‘{‰”ˆ{}vsv†}€„{|…}{Š‚~‘Šƒ“Ž‚Œˆy”Ž~›“˜’‚”Ž€ž˜Š¢œŽ£¨£§¡‘ª£˜°ªˆ¾¹€ëéœíîíñ’ÿÿªÿÿ®ÿÿ³ÿÿ³ÿÿ¶þÿ°õü§ÿÿ±ÿÿ¦ÿÿ¾ÿÿÊÿÿ¿úÿ¶ðøžüÿÿÿ¢ÿÿ´ÿÿ³þÿ¬øÿŸùþ˜ôù•÷ø˜ÿÿ©ùü¤òù—úÿ—úÿ•ÿÿ–ÿÿ˜ÿû—ûëŽÚÁnÿùšÿÿœÿÿóåÛ˜XåkRí_TùWZñYZçWXé™mÿÿ·ÿÿËÿÿÓÿÿÓÿÿÓÿÿÍÿÿÇÿÿÇÿÿÇÿÿÉÿÿËÿÿÞÿÿãÈ«ÀФðÉ¡ìÅŸéÁŸã¼›Ü¿›ÝÀ™ßÁ—ÞÁ–ÝÇžàš× ÇħºÚηÿÿÞÿÿÏÿÿ»ÿÿ½ÿÿ·ÿÿ±ÿÿ¬ÿÿ¬ÿÿ¬ÿÿ®ÿÿ¥ÿÿ›ÿÿ£ÿÿ¬ÿÿ²ÿÿÀÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ±»ÃzŒ‰›¢…–¢{Œ–zˆ“€ˆŒqtqzxt€xvwszs…}yŒ„‚Žƒ€’„‚’…€”…”Š„œ•ŽŸšŽ œŸ›Œ£ž’¨¢’®¦”¬¤€×Кÿÿ¶ÿÿ£ÿÿ³ÿÿ¿ÿÿ½ÿÿÀÿÿºÿÿÅüÿ³ÿÿ²ÿÿ¹ÿÿ¶þÿ´þÿ¸õü§ùÿ¦ÿÿ¤ÿÿ£ÿÿ¯ÿÿ°þÿ¥þÿŸÿÿ¢ÿÿ¤ÿÿ¨ÿÿªÿÿÿÿ–õýˆÿÿÿÿ—ùõ—ÿò•ÿð–ïÁ|Ùœnÿê›ÿÿ–þß…à Z×nFöaYõXWúU[äbSà[ÿå¥ÿÿÅÿÿËÿÿÓÿÿÕÿÿ×ÿÿÏÿÿÇÿÿËÿÿÏÿÿÍÿÿËÿÿðàÅÐ̦ÕÌïÉœðÈ›ñÉžïË ïÇœë×æ×ã–âÄšãÅžæÞãƢ严µÇÆ¢ÿÿÓÿÿ³ÿÿ¯ÿÿ¯ÿÿ¯ÿÿ¬ÿÿªÿÿ¬ÿÿ¥ÿÿšÿÿ™ÿÿÿÿ¡ÿÿ«ÿýÀÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿµÄÁ…—š|‘œzŒ–~Œ—{ƒ…kogywq~xu~wwx{„~{‡‚z‡€yˆ}zˆ€|…ƒ‘‰…–Œ†ž•ˆ¦›ˆ« ²¦š¯¤‘³§µ¤ìÔ¨éØ£ïæ§öó­ñõ¨ÿÿ¼ýÿ»ÿÿ½ÿÿ·ÿÿºÿÿºÿÿ¹ÿÿÁÿÿ½þÿ³ÿÿ°ÿÿ«ÿÿ­ÿÿªÿÿ¥ÿÿ¡öø•ÿÿ£ÿÿ¦ÿÿ§úú¡úü«úÿ¡ÿÿ›ÿÿœÿÿ›ÿÿ›þú—ÿíÿÛ„Ý—ZÛ„aÿÁ{üÔmä“SäjSídXø`_òWUïRQ×nFÿ΃ÿÿÅÿÿÉÿÿËÿÿÍÿÿÍÿÿÏÿÿÍÿÿËÿÿÅÿÿÁÿÿÍÿÿÙùäÛͧÖË£àË ìÉžíÍ¡òÌ ñΞóÊžíę得ݹ“Ô¾•×Ê âÅ›âÅè¥ܺ¤É½²ÿÿÀÿÿµÿÿ›ÿÿšÿÿœÿÿ¡ÿÿ«ÿÿ£ÿÿ–ÿÿÿÿ“ÿÿ‘ÿÿ‹ôë•ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ§­{‰”‚Žš…Ž›u{€mmmvtn{vl|wo~vr~vr€xvƒ{w‡€y‰ƒ~‹…‚Ž‡€–Œ‚œ†£”Œ©œ“­£›«¦“³¯•ÉÇÿÿµÿÿ®ÿÿ¯ÿÿ³ÿÿ¼ÿÿºÿÿ·ÿÿ·ÿÿ¹üÿ²ûÿ·ýÿµúþ¯ÿÿ´ÿÿ±ÿÿ«ÿÿ®ÿÿ²ýÿ­ôü¢ÿÿ³ÿÿ´ÿÿ´ÿÿ©ûÿžýÿ˜ûýþÿ˜ÿûüûœûúóðÿÿ™ÿò¢ÿ¬ué|Uön\ôs^åkTç`Söb`ü_bÿZcëUTâ^Róªwÿÿ¸ÿÿÉÿÿÑÿÿÍÿÿËÿÿÍÿÿÏÿÿÉÿÿÃÿÿ¿ÿÿ½ÿÿÕÿÿÜÏ´¿Î¦ãЧéÌ¡èÍ¡íÊžïÊžíÉìÊžíÉì—㼔߻‘ÚÁ–ݘßÁ—àÄžáß߶Ÿ´©™ˆÿþ¸ÿÿ¤ÿÿÿÿŸÿÿ¤ÿÿ¬ÿÿ®ÿÿªÿÿ¡ÿÿšÿÿ•ÿüÖÎ…ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÖÞâvˆ”|‹“‰uzztoouqlvqgwrj|tp|tp|tpwsƒ{y‡~‰ƒ€Š„’Šˆ”Œˆ˜Œ›”‰¤›Œ­¡Š²£†ÚГéá†çã‡ôó˜üý¡ÿÿ©÷þžÿÿ¢ÿÿ¬ÿÿ»ÿÿ½ÿÿÄÿÿÆÿÿ¼ÿÿ·ÿÿ¹ÿÿ³ÿÿ¬ÿÿ¬ÿÿ²ÿÿ¼ÿÿ¶ÿÿ²øý©ùÿ ÿÿ›ÿÿ™ÿÿšÿÿ—÷õýù›ýø¡ÿü¢ÿñ•ÿ°yòscýsnüglïZ_ìV^ø\cýZbûV\ýV\Þ^DçWÿí£ÿÿÁÿÿÉÿÿÑÿÿÉÿÿÁÿÿÅÿÿËÿÿÉÿÿÉÿÿÃÿÿ½ÿÿàìÍÎ̧ÊÇáÊŸæÍ¢ëÊžêÈœíÌ¡ðÆ›êÄœêÆžîÅëÈéÅ›â™ÝÀ—ÛÆ›âÆáÄžß½§¸¹¶•ÿÿÁÿÿ¤ÿÿšÿÿ“ÿÿšÿÿ§ÿÿ«ÿÿ¯ÿÿ§ÿÿ˜ÿÿãÝtÝÏŠÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿØßÑ™ž‘{z…ˆqqqsolxrowomwrjwrhurfyvj|yo~{sƒ€x‰„|ˆ~‘Šˆ“Œƒ˜’„Ÿ–‡¥u¦ `ôñ ÿÿ¡ÿÿ®ÿÿ¶ÿÿ³ÿÿ²ÿÿµÿÿ¶ÿÿ°ÿÿ¯ÿÿ·ÿÿ»úÿ­÷þ§ÿÿªÿÿ¨ÿÿ­ÿÿ°ÿÿ»ÿÿÈþÿ´óû«øÿ¢ÿÿœÿÿ¢ÿÿžúÿ›þÿ¡ûü•ýûŒÿÿ•ÿÿ›ÿð¡ÿÀ‹çxcûhqÿisø`mö\gø[eûZcþVaòTZêVVÞ‡Tþàÿÿ½ÿÿÅÿÿËÿÿÓÿÿÍÿÿÉÿÿÇÿÿÇÿÿÉÿÿËÿÿÉÿÿÇýçÓʤÐ̤ßÅè—ãÅ™åË¡êÉ¢êÉ¡ìË ñÈìÉžêÇŸê¿™ãÞ忚áÄ àÂÙ½˜Ô¼—Ó­™™Þןÿÿ¿ÿÿ“ÿÿ˜ÿÿœÿÿ¡ÿÿ§ÿÿ¡ÿÿžÿÿ›ÿÿ—ùõ„ØÊaÿíªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿäçæ²´¸z~ƒtyƒilmsqktpkrliqkfwok~yq~yo~yo€yrƒ~r‚€o‹‡v‡wŠ„vŽ‡|•Žƒš“Š˜•tºº„ýÿ¶ÿÿ¬ÿÿµÿÿ¶ÿø¦ÿ÷¡ÿÿ¤ÿÿžÿÿ¬ÿÿ­ÿÿ¬ÿÿ¶ÿÿ·ÿÿ¿ÿÿ¹ÿÿºÿÿ´ÿÿ³ÿÿ¶ÿÿ²ÿÿ¹ÿÿÂÿÿºÿÿ°ÿÿ©ùÿ¢ûÿ ÿÿ¡ÿÿžþÿ’øòôäŒÿמþ’|íjdÿgrþfsö_nø`kÿbløW`ûS^á[KÝvMÿÒ†ÿÿ¬ÿÿ½ÿÿÉÿÿÏÿÿÕÿÿÏÿÿËÿÿÇÿÿÃÿÿÇÿÿËÿÿàÿÿïÙ»ÌÊ àÊ äÇœå×ãÑ¢òÌ ìÊŸèË ìÆžìÊ¢ðÉžïÌ¡ðÍ¢îÇæ—ÞÀ—ÙÅÚÄ¥Ö¼£Ë´ªÿÿ±ÿÿ³ÿÿ˜ÿÿÿÿžÿÿŸÿÿ¢ÿÿšÿÿ”ÿÿ’ÿþÛËlõÚÿå´ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÜàåºÀÅ{‚‚jomfd`pibqkfrkkqjjypqytlwufvsgzwozyn}|o„u…~sŠƒz‚†}“Œ˜‘fçà—ÿÿ¯ÿÿ¨ÿ÷¢óà’ìâƒôò…ýþ“ùü’íóŠðõ‘ëðŠäçíòŒöý›ïø™øÿ¦ÿÿ¹ÿÿÇÿÿÏÿÿÄÿÿ¼ÿÿ¯úÿ£ÿÿ®ÿÿªÿÿ§ÿÿ¢ÿÿ¤øÿ›÷ûšüô—ÿù£ÿÕ¤õunðegÿhuücs÷^pü_iÿbdóVWîSUÒjFî¹rÿÿ¶ÿÿÁÿÿÁÿÿÁÿÿÃÿÿÇÿÿËÿÿÑÿÿËÿÿÅÿÿÁÿÿ¿ÿÿÛûàÊÆ£¸Î¡âÅ›ÝÀ—Û¼–×Ä ÞȤæÇ èÁœáÄŸäÛæÇœíÉžíÈìÇœëÆšëÛ澙๞ɸ¢³ÕΡÿÿ·ÿÿªÿÿŸÿÿŸÿÿœÿÿ—ÿÿ˜ÿÿžÿÿ ÿö˜åÌ‚æÍøß“÷Ý«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÚÚÚÀÀÀ{‚‚]hkntmŒ‰}]YTtmotnivoftoeupfvqixrm{upyt‚~y€|y}x…€x‰…v‹†siÿÿ­ÿÿ´ýôžøì™ûìøòÿÿ§ÿÿ§ÿÿ¨ÿÿ¨ÿÿÿÿ©ÿÿ±ÿÿ¦ÿÿ©ÿÿ¯ÿÿ¯ÿÿ·ÿÿ»ÿÿ°ÿÿ®ÿÿ²ÿÿ·ÿÿ´ÿÿµüÿ¦øÿ¡÷þœÿÿžÿÿ¡ÿÿ¨ÿÿ©ÿÿ¤þ°zín`ðl`ñg`ã_SÚXIí_Vú_]åXXÚX]ÚŒdÿî›ÿÿÉÿÿÑÿÿËÿÿÅÿÿÃÿÿÃÿÿÉÿÿÑÿÿÇÿÿ½ÿÿ»ÿÿ»ÿÿØ̱›¿œ±ÉœßÇáÀ–ݸ‘×»”ÜÛæÆžì¾—ßÀ—ÛΤíÍ¢óΣôÉœðÄ™å˜ßÀšÙ½™Ð±›©®¢‰ÿþ¸ÿÿ±ÿÿ³ÿÿ´ÿÿ¢ÿÿ˜ÿÿšÿÿ™ÿÿ¢ÿÿéÞ†Á¬n÷á˜úáŽÿã¯ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÞßØÌÎÄtwx[^j™¢ÿÿÿÕÐÔuhqrjhuncrmatoewrjtnkyrrxz}xx€}|‚~{…|ˆ‚rŠ€dÄ»ÿø¢ôç—àцôêÿú¬ÿû«þûªÿÿ®ùø¨ÿÿªÿÿªÿÿ¯ÿÿ°úÿ«ÿÿ½ÿÿ¸ÿÿ¸ÿÿÃÿÿÀÿÿÁÿÿ·ÿÿ±ûþ¤ò÷¥ÿÿÈÿÿºûÿ³ýÿ¯ÿÿ«÷ú¢äãéÞ”æÑ‘²…Wˇjð¯‘䣇ÿ·£ÿà××fmìbzÓW_Ì^Vï³€ÿÿ²ÿÿÉÿÿÑÿÿËÿÿÇÿÿÃÿÿÁÿÿÉÿÿÑÿÿÇÿÿ¿ÿÿ»ÿÿ¹ÿÿÅÿò¬’uo¶‹Ä¿—Ôœݾ—Ý¿—åÆ›êÉìΣïÊ¢íÁ–âÈœëÊžïÆ™íÇœëɟ辘׽™Î²¢ØΧÿÿËÿÿªÿÿ³ÿÿ·ÿÿªÿÿ¦ÿÿšÿÿ”ÿÿ£ÿÿ¡Å¸aãÍ„üã™ÿå›ùÙ²ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýþÁÀ·¼¼ªjnhX]g£¦®ÿÿÿÀÃÄkkilk^{zdheQZTD]WG]WG^\M[]QXXHedPsq`“€§¤ºµ ùôÏÿùÆþûÆÿÿÍÿÿÐÿÿÒÿÿâÿÿ÷ÿÿÿÿÿÿÿÿÿÿÿúñðÃÿÿÅÿÿÇÿÿÇÿÿÐÿÿÎÿÿÖÿþÔÿÿÞÿÿçÿÿóÿÿöÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿäêØs…¿idÓŒpÿß›ÿÿªÿÿÃÿÿÑÿÿÍÿÿËÿÿÇÿÿÃÿÿÅÿÿÇÿÿÃÿÿÁÿÿ½ÿÿ¹ÿÿµÿÿ±ÿÿË«Œ‰¨…¡¾–ÓÁ˜Ú¾”Ý›㸑ٷÔÙÝÅ›âÉŸèÇžâÈžàÆœÜÆœÜÀœÏ½Å·§‘ÿÿ°ÿÿ¹ÿÿ­ÿÿ²ÿÿ´ÿÿ¥ÿÿ˜ÿÿ•ÿÿ“ÿÿšòë‹Ò½köÔõÐŒõÍòͬÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÜ××ÅÁ¾§£ hed^^^©©«ÿÿÿ¾½Ähjpfgbš™Œÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿà´Õ­ˆ‡Ä¤„ÿ÷®ÿÿ¨ÿÿ³ÿÿÁÿÿÃÿÿÅÿÿÁÿÿ½ÿÿÁÿÿÅÿÿÅÿÿÇÿÿÉÿÿËÿÿÅÿÿÁÿÿ½ÿÿµÇ®Œ¦z™»‘ÁÁ˜Ü½—ؾ˜×»•Ø½’ÞÀ˜ãÛ澙޾šÜº–Ö»—Õåѷž»ÑÉ¥ÿÿ½ÿÿ²ÿÿ£ÿÿ¥ÿÿ¤ÿÿÿÿ“ÿÿ“ÿÿ˜ÿÿÙÂ|ãÀê½ì¿ƒîÁ…øǯÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¶±³³¯ª–“‰gea_[a´°¸ÿÿÿ®©´jertu~ÙÜäÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ®¦¯¤™˜¤“‰ãßžÿÿšÿÿ¢ÿÿ¦ÿÿ³ÿÿ¹ÿÿ¹ÿÿ¹ÿÿºÿÿ½ÿÿÁÿÿÅÿÿÇÿÿËÿÿÉÿÿÇÿÿ¿ÿÿ·ÿÿÉðÛ¥¨‰†·Š½¼”ÌÀ—Ù½—Ö½˜Ô¿›Û¿šß¸’Õ»’Ö¾˜×¶‘Ë´š®¹¨—÷ñ³ÿÿ·ÿÿ²ÿÿ¬ÿÿ¨ÿÿ¢ÿÿ™ÿÿ•ÿÿ—ÿÿ”òç„Ú¿xåÃ|ë¿|ì¿ñˆóÀ§ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ´°«¡š©¢™‹„}hda^^^ÃÀÃÿÿÿ¢œ£kenrorùùùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûùóÿýýþú÷÷óð÷òòûôøîêåÿÿóõóäùõæîêÙîéÖâÞÏâÝÕðëëïëñìììåæáåäÙàÞÏÝÛÌÚØÉàÞÏßÜÐÑÏÀÚØÉØÖÇÌÊ»À¹°¢”’n]ev_t«”¥ž…” ’sçã—ÿÿ£ÿÿ•ÿÿ™ÿÿ¤ÿÿ­ÿÿ¬ÿÿ³ÿÿºÿÿ½ÿÿÁÿÿÅÿÿÉÿÿËÿÿÏÿÿÅÿÿ½ÿÿ³ÿÿ©ÿú«¾¡‚«Šœ¹“ÖÁ˜ÚÁ—ÙÁ˜Ú½—Ú¿›ÝÁßàٽ›Í³ ›ÚÔ™ÿÿ¾ÿÿ®ÿÿ©ÿÿ¢ÿÿšÿÿ’ÿÿ‘ÿÿÿÿ—ÿþåÏrä¿wæ¼ví½{å¶x꺃컣ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿº´½‡|—‡š•‰{vnSQMSSUÑÎÏÿÿÿ–Žqei{uróïêÿÿÿÿÿÿÿÿÿÿÿÿ¤£¨”–œ‘Ž‘‰‰£œ•¯£—–‘~Œ‹s“x¢š„š•~‘Žv•‘w”r‹g˜ŒsŠ~e¡•~“y›”w¡—{˜Œqš‹už|‰xeœŒv¦–|¯ µ¤¾«‚¿«‡Í¹™ãÓ¹ñáÎñäÐìáÎçßÉåáÇâàÁçæÄìèÊïåÍéâÇóìÏ÷ðÓíæËîçÎæÛÈ›‘‹bXb› Ž›’ƒ}‘zÖÓüÿÿÿ“ÿÿŽÿÿ˜ÿÿ¢ÿÿ©ÿÿ­ÿÿ±ÿÿµÿÿ·ÿÿ¹ÿÿ¿ÿÿÇÿÿÃÿÿÁÿÿ¹ÿÿ±ÿÿ­ÿÿ«èئ€†°‹®·‘ÒÀšÛě߿™ÚÁݽŸÍ·ž½¾µ”ÿÿªÿÿµÿÿ¬ÿÿ¦ÿÿ£ÿÿ–ÿÿŽÿÿ”ÿÿ–ÿÿ›òßÛ¾lâ¸vä·yç¸~è¹ì½ƒí¸¡ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÀ¼Ämdp}vvŒ…|‚ucbYA>?KFQàÝÞÿÿþ‚xgf]„wÿÿûÿÿúÿÿÿÿÿÿÿÿÿ““•]\a[WTg`WŽŠp§¢y¡™s£™v£™tª {¯¥~§žt¨Ÿu©œv¦œuª y©Ÿxª yª¡w¯£z°§}¬£y±¨|®¢w¢™mŸ–l¡˜n¡—p¥u®¦~³«ƒ¾´Ä»šÛÔ¹æÞÊæÝÐåàÍëæÑëéÎðîÑððÕïðÙóôÛùûßö÷Þìë×íêÖóîÛ°¦žYHN|ksŒz‡Šxƒy‚•…t¾±†ïê•ÿÿŒÿÿ“ÿÿšÿÿ¨ÿÿ²ÿÿ¯ÿÿ­ÿÿ³ÿÿ·ÿÿ¿ÿÿÇÿÿÅÿÿÃÿÿ½ÿÿ·ÿÿ¯ÿÿ©ÿÿ³ÿÿ©ª—p¢zŒ³Ž³½˜ÒÞØơݽ¢»º§ ìæ«ÿÿµÿÿ°ÿÿ¨ÿÿŸÿÿ˜ÿÿ–ÿÿ’ÿÿ–ÿÿ—ÿôßÁtáºwè¹ê»çµæ·}Ú­sã°™ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÅÄÉ^[\lheyvn{xlnmbTUN/15@@Píëõÿÿÿ»·´´¯§ÉÅÀÿÿÿÿÿÿùøýÿÿÿÿÿÿž ”{{kpoYwsYš”r —m“Š`˜ŽgŸ–lš‘g›’h—Ždš‘g“l˜Žišo—h“l›’hš‘eŸ–j™fž”mž”o–Œg “o™j“‰d‹‚c…{c·°•ÜؼßÚÃçâÏöôãøøèöùèöøêúüðÿÿöúûôûûùÿÿþÿÿÿÿÿýÿÿøÿÿïþûçÊúfW\bSZo]hsalvdqpxˆw}™ŽpÚÑ’ÿÿŸÿÿŠÿÿŽÿÿ—ÿÿ¡ÿÿ¦ÿÿ©ÿÿ·ÿÿ·ÿÿ¸ÿÿµÿÿ³ÿÿ³ÿÿ³ÿÿ³ÿÿ³ÿÿªÿÿ«ÿÿ½ÙÆž‚w¶Á¹“ij¾´žšÏÅÿÿ±ÿÿ£ÿÿ¥ÿÿ¦ÿÿ¤ÿÿŸÿÿ•ÿÿÿÿ”ÿÿ‘îÛ}ã¾zêÀå»yå»yà¶tݳoáµpà±ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¾ÁÀUUS__]mjiuppqjjdabHGL)(-84:ÌÇÉäÝÝwrte_f€†ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ©§˜™•y—q v·©‡©›u ”k˜e˜e—Žd–c”‹a“Š`“‰b†a–‰g”‡e•ˆf’ˆa‘ˆ^“Š`†_’ŠdŽ†b‹ƒ_“‹g‹‚c|pW`ZJLJF´´²ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷ü÷ëüøóÿþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúòðßÔÓo`chZXfYRgYYiWbjXevcs†r{†qvÁ´‹ôî—ÿÿšÿÿˆÿÿ‰ÿÿ–ÿÿ–ÿÿœÿÿ§ÿÿ±ÿÿ¯ÿÿ±ÿÿ·ÿÿ½ÿÿ»ÿÿ»ÿÿ³ÿÿ©ÿÿ¯ÿÿ¯ÿü©®‘`®‘„¸•±Á´øÿÿÿ´ÿÿ£ÿÿ¦ÿÿªÿÿ¨ÿÿ ÿÿ˜ÿÿ“ÿÿ•ÿõŒâÂmç¹xã´v麀å¶|à°yæ¶Þ®y߬—ÿÿÿÿÿÿÿÿÿÿÿÿØÛÜ[^[ab[cd]rplspohefcfcCJF#&#  (D;@;4@†‚Šÿÿÿÿÿÿêí÷ÿÿÿÿÿÿš˜‡‘Šo’‡i•‡eœŽhe’…\“‡^„Z†}S‰€Vƒ\ˆ~W‰ZŠ€YŽ[ŒY‘„`‚^_‚^Ž]‹\‰]€zXysSi_GTG7:3(640¯¬«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿêäßÓÌÅ»±©±ª£ËÃÁÿýýÿÿÿÿÿÿÿÿÿÿÿÿÿþôíãÛ}khq`Vn^MiZRl\]gV^aN^eP^kyn[”ˆVÒÎtþÿ‚ÿÿ„ÿÿ†ÿÿŽÿÿ‘ÿÿ˜ÿÿžÿÿ«ÿÿ±ÿÿ·ÿÿ½ÿÿ¹ÿÿ·ÿÿ­ÿÿ§ÿÿ©ÿÿ«ÿÿ³ÿÿ¶ÐºŒp\æÚ™ÿÿ¯ÿÿ«ÿÿ£ÿÿ¥ÿÿ¨ÿÿ¢ÿÿžÿÿ’ÿÿ‡ÿÿî×vܹií¼è¹}Þ¯uá²vâ³uÞ¯sÞ®wÕ ‹ÿÿÿÿÿÿÿÿÿÃÇÊ\becfeb]]ic`jb^daY^`TTVHBE4&(93:HEHKHI²²²ÿÿÿÿÿÿÿÿÿÿÿÿÿÿþš„’‰j‘‰eˆ`Œ…Z„ZŠ€YŒ‚]‡WˆVˆV†|Uˆ}_†ye†za‹|b‰~`„d‰\‹\‰Zˆ~Y‹Z†|UulMVN:721+/,$666ª­ªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõóí³°¦€|wd]_VNWC:Jmioÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûôô‚‚ncNƒyRxmOrbOaRJaPVXGOYGRm]g~nzuiN°§cäá€úü~úÿzÿÿ€ÿÿÿÿŽÿÿœÿÿ¦ÿÿ©ÿÿ­ÿÿ­ÿÿªÿÿ®ÿÿ©ÿÿ¯ÿÿ²ÿÿ©ÿÿ¡ÿÿ¡ÿÿ›ÿÿ ÿÿ³ÿÿ¬ÿÿ«ÿÿ£ÿÿ¡ÿÿÿÿ–ÿÿ“ÿÿˆüèèÁzä¹|㲀ܬw߯xæ¹뾄ޱuÚ­qç´ÿÿÿÿÿÿÆÉÊ\_`cceZ]ZZ^V[\WZUUZXRYXMNMD<:4$$&#.)+A<>3.2mfhÀ·ºÊÁÂÙÑÏîëãæèÚ™—|‘‡dŒ‚]‹\†|Yˆ}_ˆ}_ˆ}_„x]u\~tX}sW|rV}sYzsZzr\upYyt_vrX{tWyq[ypasn[idOUP=?6'8/"4*".+,.3=¨«³ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¿¸¸ƒz{oifKGB722D=ARYrJ^‹ÿÿÿÿÿÿÿÿÿÿÿÿéåâ•“c[ImbBuN}rDwjDvgHeTER>@VAM^G_q_jued“ˆXÜÔwÿÿˆÿÿ~ÿÿzÿÿ‡ÿÿÿÿ˜ÿÿ ÿÿ¨ÿÿ©ÿÿªÿÿ«ÿÿ´ÿÿ¯ÿÿ¯ÿÿ­ÿÿ±ÿÿ­ÿÿ­ÿÿ¬ÿÿ«ÿÿ§ÿÿ£ÿÿ£ÿÿ¢ÿÿÿÿœÿÿÿùãÉy㶃ⵂà±ä¶æ¸æº„ೀܳzÓ«oÑ ˆÿÿÿ××Ù]`a[[Y`\W\ZTYWSRNKOHHQJJVOOQNO:9>#!$("NNL412724@9=?67<105.'RKB…ozcxs\snYmlXhhVieTi`Qd]Te][d_U`^Ob`Qb]Qb]UaZZYVN^^N`^M`]I[YJNMDA>240)! 4(." **˜™’ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ˜‚•…k|Z‡oE‰sPo]?UEFdVvçà÷ÿÿÿÿÿÿÿÿÿñìâž“‚maJj[Ag]8xpAxp?~vC‡{RzkN_RBG<9KBEcXend^~t\¾¸xôñ‰ÿÿ•ÿÿ{ÿÿˆÿÿŠÿÿ‘ÿÿ˜ÿÿ•ÿÿ™ÿÿ ÿÿ¤ÿÿªÿÿ®ÿÿ²ÿÿ±ÿÿªÿÿ§ÿÿ¬ÿÿ±ÿÿ¯ÿÿ¦ÿÿ¤ÿÿ ÿÿšÿÿ›ÿÿ–ðÔ{Ú³lá±zç¸~í¼ƒïÀ†éº€è¸à¯}á³|Þ³x୔žÊTSXTWVVVTYTTVSROOOKIEJG?IF>RNIOLM,(08;8DHBBF@HIDRPJb_WOMG[[Y‚v{xdjfWhcYdaW_\T`[SaZS`[SZVQ[XNZVGWTJYUPWSNZVSk_S„q\’~^šƒY›…O“|:’y/Žu"šƒ+wdv²•CÀ¡`Å£vª™†ÿÿÿÿÿÿÿÿÿÿÿ÷ééÂÜÕŽÿø”ÿò‹ÿèøÞ€êÎz‘~J|q^ÿÿ÷ÿÿÿÿÿÿÿÿÿÿÿü¬™r‘{\w[ElV>dTB@1FE:KIC:;6 - .53RZS6<3;<5IKA]\QONEXTO|woqjaZTO]VV]YV][W^ZU_ZR_[V^ZW`\Wa\TZUMPHDJDAIBDMFHVMRlUÍ®~ÿç£ÿý¨ÿÿ¥ÿÿ›ÿÿšøÝ„êÕuÿü™ÿÿ­ÿÿÉôìÆþ÷ìÿþùÿÿÿÿÿûûãÌïá«ÿÿ­ÿÿ±ÿÿ§ÿÿ§ÿÿ¤òñ¯ÅäÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÕ»½¡}}Tx^@kRBjS9wa>xf:q=}s9€w:…yIveDL:3I6JlYizhsdÎÂóï“úýŠüÿÿÿÿÿxÿÿqÿÿzÿÿŒÿÿÿÿ–ÿÿšÿÿŸÿÿŸÿÿÿÿœÿÿšÿÿ•ÿÿ’ÿÿ‘ÿÿ‘ÿÿ‘ÿñ‡éÌxã¶zÞ®wà­|á±|ã³|ä¶躅è»å¸|à³yà°{߬“OKHSOL[WTQOIFG@DBTNIWNOqieyog]VM[VN[VNc[Wc]Z_ZZ_]Y_]YXYRBC<&%,)!GI?KPEDC:@:5@467%0A&/vSZ½Ÿ‡úá¬ÿý°ÿÿ´ÿÿ¢øúŠíìœíé½ÿÿûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿîíÀÛÔìç’ÿýœÿÿ°ÿÿÄÿÿæÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöàÈÝ•ͭlªŒY~b>fO3eQ?ob9zq4zq7oe0xr7†€@‚|LaW;=1%RCHsfa„vk­¡oÛÐxôòƒúýxþÿtÿÿoÿÿmÿÿrÿÿ}ÿÿ†ÿÿ‰ÿÿ“ÿÿ–ÿÿ›ÿÿ“ÿÿŽÿÿ‹ÿÿˆÿÿÿÿ‘ÿø‘èÐضoß°tâ³wç¶}߯xã³~åµ€â²}Þ®yÙ¨vÞ±uܲlⲓLLJQMJYQMNHCA=:;;;8:>446OJL//1(*0'*+***-*+0+/---%&,#&*$444C@?IEBQMHXUMid\jc\UPHXSKVQIZTO^[S^[Q_[V]XX?C=2:3‚‰{¿Å±„ŒƒLWXlrkgfYYVLMEAG?=>583&9(jMB§‡iñÝŸÿÿ¯ÿÿºÿÿÃÿÿìÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøýààá½÷öÞÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüõÜÕ¾à»wϬj¹™Z‹n=cK&_K'eW5wk@vk9lg.ml/yu4|7}qFM<)K<8rap|ojšxÎÆ„îå}ñòtûÿqýÿqôühõýiÿÿ|ÿÿƒÿÿ‡ÿÿŠÿÿŽÿÿŽÿÿÿÿˆÿÿÿÿ‡ÿÿ‡íÝ~ÔµtÞ»yã»{ëÁí¿~å¶zà°yتsݯxתpÞ±uß²tß³rܬHHFLLJOLKJGHQLP@;=>79;68QNQ(((#&%"$(#!+$#*'#)!!# #"//-611MDEJD?KH>NM@JI;3=536%+(Y6;ªŠ€óÕ½ÿùíÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿçáÈæ»s߶mÞ´nɦh QhP+[K1dU;qbHviEth:uj8uk4~w?ˆK^R7?/0cRZxew…tj¿®‰Û͈êÛ|øî‚õíwéêløý|ÿÿˆÿÿ‰ÿÿ…ÿÿÿÿ€ÿÿÿÿƒÿÿ€ÿÿŠôäŽÚÄwÓ·sÖ³qÖ«n׬qÚ¬wܯuç¸|ê½ë¾€æ¹}æ·}ã³|Ý«wØ£ŽGGGJGHIBDIBBg_]GAsfBqh>pg;pf?g]:YM?B5>4'0[KWlcV{vQ¾µ{̽pÓÇgôëxûü|ûÿwÿÿÿÿˆÿÿ„ÿÿÿÿÿý}òä{ãÆyðˇúÍ“ÿЖÿÌ”òÁ†éº~ã´vÞ¯qØ«oß´yß³{ⶀ׫s׫sÑž‰9=75:-:=*;;+=:.C@4B?3 - -   -   -&&(LMHFHGHCQSIUWI=?3$"MELB3Hrh{üöÿçÞêwhoTKPWRVYRRVNLYQMe]Y]YTVTPYVUURSSPOQLLPNJSQMYSPÏÀÔŒŠqkfD==QJNZSSb\Yfb_hdanjenkctpayeŠ€h‘…lm§”m¢Œ[º¢eùÛ‘ÿë”ÿÜ’ð½~ä°tê³|òÁˆà°yÍ¢eÖ°oÞ¾ʬt•|Wt]LZHAG;?K5EA?:<8343*:9045.++)OLMRMQD?A=66<98IIGQQOSPOVQSYRVXSWSNRQTQPXOQVKRQFPOBONANLHNJRNJR\Wb]Z[cbYQMHXRO`]\aaa]^Ya_Y\ZTYUPYLC‚n`´È°„Ì«vÞ¶zðɆîÅ|à·lðÇ|úЃúÎî¾zؤjÛªq踃á³|Õ§pΨkÔ´sË«jĤc¥Š_…oYXG8O@1:L?JdW`rbl~tX¼¹uõõ‘þÿ~õøqþÿvÿÿ~ÿÿ~ÿóƒãÆrÒ­eУgΡgÉ›fУiÞ¯sá´xê¿‚ñĆøʉýÑôʈòˈëÄå¾{ݵuÜ®“.31.10224444856;95FEAB;>;59104,-.)0+-8.6GBFPMNNNLLOLPMLUNPUNPTMONKJLMHQRKPQJMOCLN@JL@KJAIGCJEINKJ^\V]\Sa`WUTKHG>DE>?C=7=606/.10=9?JFCJC::)E)rL5Ο}ò¿Žó»|ñ»{ê·xá±oè¸tí¿|ë¾€Ò§lÇšgÙ°wÖ°sÃ\ÞZ̪eÔµoȧk½›i¶hª˜a—…UˆuNn[DXE>@-/F1=`M_m[sthnuk¼¸yúýŠÿÿ’ûÿøôƒùéŠãÊwÛ¶pßµsê»}è¼yë¿zëÀxè½uÞ·rÛµtÔ®mШjÒªl׬oϧiÓ«mׯsÞµ~ã·›*,0*,20.8408:4;B=?C>>HFBDE@**, EA>cbWeeUdcVgf]a`UdaWb_Ua^V_\R[XL\[NVUHVSKWNOVMNULMNGGKDDEB:C@4?>398/42,-((%$&%.-"<;2LHEULOSLNQJLLGKKGMOLKNMDHG]OOj^bpcl}ra«Ÿv×ËÛÉ™¼¨y²›mÁ¢rÕ­zṄ弅ä¾æÀâ¼}Þ¶zܶuâÀ{ß¼~ฃݶ|Þ¶xá¹yܵrÖ¯jÒ«dÓ§‚)'1)+/.10331944=96>:5@>8@>8!BD8kj__]Y`]`hedec_ZXR[WR]YTXTOWTJZWKZWKYTJYVNVRORNKVROVPMRIJLIAKJ=GF9C@4A>4>8341'21$*, '""632B?>FD@MIFJGFGGGGGGEEEFCDGBDGBBIEBNGGOFIKEBGC>A=8;7254+02(*,"*(""%"!&&##!!#$!%0(1@5BI;KB15N82vZM ~j¶–o¶”]¿ aÏ°mÖµyÁ™fÀ™aШlΨk¸‘WÉ©hÛ¼yÙºtʨaÆ¡]Õªkà½}ѲsĨfͱoζwª”YjDt]LgSAhWDvgMtR”‚T·žfÑ°tØ­pØ®jѨ]É¡SË£UÇ¢Z¿œ\Ä¢]¾œU»™Tà^Ƥ_ɧbʨaΩcѬfÔ­jܬ+&(.,(02(43*51,51,73.<91>;1'&?>3^`THJ@/1'LMFLKBMJ@PMEOKHNMDRQFRQFRQHRQHSOJSMHWOMVPKVPKSPHQNFRNIQMJKDDLCFMECLD@F@;B>9;749443..-&&*## &$640=:;DABGBDFCBDDBDFbW˜zb©ˆfÀžq˦pÃœbÀ•XÒªlÕ­qÄž_Ò¬méÂêăٳtÊ£iÌ©kݺ|Û»zÀ¡^ŦeÕ¶wäÇЫuÞhÔ¬yЬsʧiÌ©kÖ°sݵyãµ~ìÁ„ëÄîÇ‚óÌ…ñÇ…ì¿…æ»~â·xä¹zä¹|å½ã½~â½yá¼vä½vç¾uß°Œ&*$+0%13%11!51 4062#96*@?4POFa_YORO*// -)1=:;@>:=;5;72=:2B=5@=5EAKH>JI>EG;;=1591030-20)..&)&%&$$"##%##%#%#")#!+! %# ## !&!!$$" #"$$&628C:?O;DnTV•wq¼›‚Ь‚ÛfÐ¥fßµqÒ©`È¡ZÛ´qèÀ€ã¸{Ú²vϨnÝ·xä¾}Ì©gÆ£aÔ±qݹ~Ï«pÇ hϨpÖ¯wÖ¯wÚ²}Ý´}渃쾇ñĊݲuÇŸa¾™U¶”M¿XÃ^àb˪nÖ²y⸄íÆŽçÈçÁ„í‡ôÁ¨&.'*0'02(+-#+-#*,"10'42,EA>\ZVWTS?@;-.)**,2/2/,/.+./,+.*'3/*74,:90;<5?@9DB4@;1>;373.42.,)($" 474=A;BC>FCBHCEA>=?=9:556/13../-).,&*) &'"$'(!$%#"'""$"""#$!"$"%!%#'%*("+)%,)(-(*.))722>1*R=2¡…qϪ˥wÜ´tã¼wЦ`Ъ`ܶläºtç»xÖ¬jÓ«kä¼|Ö«lɦdÓ´qÅ©eÅ©g¿žbÈ kÔ®mÛ·lݹnä¿wçÂzçÀ{ЭoÁŸjÄ£iѱrݽ|à½{à¾y×µnÍ®d½ŸRº˜O¶‘K¸’QÇŸcÈ›{)-'-/%.-"+*('&(+,%42,KGDUSMHF@79/35+ # !!&!%# !%"!()"%')+21&43*971A=:JADGC@DF6DA9>:598-65(+-)+!+()=7>DAB?=9:7650241001,/0)*,")*%'$'*'('$%#$!"#$#$"#"#$% '$#,*&,*&()$(+()-%-/%0,'4)(6$!1fH.µ’eȤkÕ­mݶsΧbÖ¯jæ¼zëÄÖ®nЦdÞ²oã¼wÅ£^Ï­fЮeÓ°nÓ¯vƦeɪbÖ´mÜ·qÚµmÛ¶nɦf¶‘[µ‘XÉ¥jä¾ìÄ„àºyÌ©iɪbʬ_Ó²fݹnä¿yëÃ…ñĤ(-+-1++-#',#(#%,*$<;2HE=65*35'/.%.''(## - - -!!!#"!&%%%*($/-)30/854<79=8:C<>D@=DA9KGBMIFNLFQOIRNIRLGQMJSNPVPMUMING>RL>LG;GD:B>9<7764031+01*)*%"%" " !+++6346342/01.-/**.))-((,*&%&!$&#%$&#%"#&#"%&(* *,"-/%*+&-*+-+'.-$+,%,-(**(.+,-&*.*/X7 ¡yYÒ¡|à°ˆÚª€à²}ï„ê¾}׫hÕ«iß´wׯoÅŸ^Õ¯nã½|á»~ÇŸj»—^Ï«rØ´yã½€çÂ~سk¿œZ¼›_àbزuß·‚Æpº’_¼•]ÆŸgΤpÐ¥jÕ¨jä²–*+$)*#(& *("&"'#0,':61930;6,.*-(0(&($!   (!#' "/&+0)+0)+4//51.<77B;=C>>EA>FENI=VLBVOHWOMPLIQOKHDATLJSMHLIAIH?DC:A?9862:;6672-.',.$+)%+&("  !*'(-+'-.',-&)-'%*&"(%, #''%!%&&((* )+!*,"-+%,*$-+',+"+*-+%-(*.''0(&1)'2*(2,).(%,)8^;0œv\ËœxÙªz콃תnÖZÍ¥eÕ¯nÖ±mÇ¢^Ò¬kÙ³tʧižcÎ¥lÞ°yá¹{æÁ}زq¿™Z´‘QÆ£eÙ¶xÝ·zÏ©lÄža¿“[Ó¢pÙ¬rÜ°oܨŠ-,#*("($!'""' "*##5..500.)+'""$  - - -     '"$*#%1*,1*,3..30/722<55;66=88F@=MEANHCMIDQKHTKLTKLULMTNILIAONEIGALIAID:D>9C:;=8852131--)&'$#'$'#$$(""'##($'*)%%%'"&+()&&$,(%-"!,(#*,"*,",*$)*%#&%#&%(+,))+-'..+,-*),*$,+"-+%/,+/(,2$2/$7$!hM;£^Ášqݳ̣lÇŸcШjÕªkË cÊŸdÓ¬tЮyÏ«pÓ­nÙ³rÚµqâ½wݶoÃ\À™aÎ¥lÛ¯wâº|زqÈ¢a¿—WÍ£aÙ«h屓(%&))+%$+"%& !$#(+*!$#"""$$#    - - -   #""%"!(%$+(),)(1/+30/4/3:78<98?=9C?9@=5:9.65,2.),)!)$"!!!# #%%#)*%&*$$("()$(##(%&+(+.)+2)*,''*'&)*%)*%&)&(+*///-*++)%-+%-,#-,#,-&.1./2/00. QO>obNcH4 ^Ѭ{Ó®xˤlÌ¥kÒ«q̦ģcϬjɦh¸˜Y¶•YÑ®pÕ¯pزuˤjÇ hϧtÝ·zêÃ~éÂ{ãºqÖ¬jÒ¤mͨŒ \ No newline at end of file diff --git a/example/dev/file_grabber/image/img0255.ppm b/example/dev/file_grabber/image/img0255.ppm deleted file mode 100644 index 3299aa1627b..00000000000 --- a/example/dev/file_grabber/image/img0255.ppm +++ /dev/null @@ -1,15 +0,0 @@ -P6 -128 128 -255 -an€bt€aw}fvwirov~w¦ª¢u}nz†n|‡m{ˆm{ˆp~‹k|ˆ_p|`m}w‚•” ®¡­¹£¯»§°¿¬ºÇ³ÄзÈÒ¿ÐÚÇÚáÄÚÞÒååÜëèßèåïôòîñðòïðññóôöú÷úûôôö÷÷÷òòòúúüÿÿÿÿÿÿÿÿÿþýÿýüÿöõúñðõâåíØÝéÑÝéÌÜëÅ×ãÉÞç¼Õá´Ðß¹Ôæ¶Îã¶Ñç±Ëä­Çà®Åá²Ìå­ÇàªÅרÄÏ«ÄÒ°ÃØ°ÆÜ­ÂÝ°Êã°Ëæ®Éä®Éä¨ÃÞ¡»Ù¡»Ö§¾Ø¯ÇÞªÂÙ§¿Ô¥½Ò¦Áפ¾×§¾Ø¡¶Ó¢·Ò©¿×¤»×ž´Õ¡¸Ô¡·Ï›±ÉŸ´Ï¤ºÒ¡·Í ³È¥µÈ¤´Ê¡´Ë ³È›¯Á¡¸Ç ·Ä ´Â®¿›«¾¦²É£³Æ•¥¸”¤³–¤±‘¡°°‰™¬‚‘§}£t„šr‚šn}—iy‘at‹\o†Xk‚QewOcsSgy[kM\d^n„arƒct€iv}ksuv{wª© y€€ly‚ly€iv}n{„s‹kxˆan‚]nn‚‰š¦™¥³œ©²ª´º´ÁÊ´ÂÏ·ÈÔÀÐßÂÔàÇÜçÎàåÕãåÝèëäêïäêïêðõæêíñðõøøúððòííïððòùùûýüÿøøúôôôòõöøüÿîóóïòóéîîäêíàêôÌÙëÃ×ç¼Õå¿ØæÄÛê»Òã´Êà®ÆÙ¨ÄÓ¬ÈקÀЬÃÔ¯Â×°ÆܸÏé³Îä³Îâ¬ÇÛ«ÃÚ³Êä³Éè±ÊèªÄâ¨ÂÛ¬ÄÛ±ÌàªÅÙªÅÛ³Íæ©ÃÜ¡»Ö¡¼×£¾Ù¤¿Õ§¿Ò¥½Ò¦»Ö¡·Í§¾Ï¨¸Î§³Ì¤´Î¡³Ïž´ÈŸ¶Å¡µÇ£²È¥µÍž­Ê›®Ãœ°À±Á¤µÆ¡µÅ±Ã—¨¹™©º­¾™©º‘¡´–¢¹“ ´Œ™­Š—«ˆ•©€£{‹žt„—l{‘j{Žcw‡[rWp~SjyTexXh{TauDQZ^n}m‹ewƒlx„mr~wzy¶³§}{qw|jt|nzˆo~†p…j|ƒas`t‚n‚”¡”¤µ›¬½¦·Ê°ÁгÅϸÎÔ¿ÕÛ¾ÖÞ¾ÖàÇÚáÒáåÖæçÚèêÚåèãèðçíòäêíçëîñðõððòùùûô÷øùüýô÷øòòôììîððòîóóçíðáìïÛèïÕæòÅÙëÀ×èºÒå»ÔäµÎÞ±ÉܯÅÛ±ÉܹÒâ¹Òà±ÊÖ³ÌÜ®ÄÜ«ÁÙ©¾Ù´Êâ³Éá²ÈÜ°ÇØ°ÆÚ¯ÅÝ­ÅܯÇÞ±Éà®ÃÞ®Åß®Åá¯Æà®ÃÞªÂÙªÂÙ¤¼Ñ®ÆÙ¯ÇÞ«ÀݯÃ㧻ߩ½ß¦ºÚ©¾ÙŸ²Ë¤¶Ò¡³Ñ ³Ì¢²È¢³Ä±ÂΨ¹Ê¢²Êš­Ä°Ç°É™«Çœ¯Æ ³È˜«Â’¤À•¥½—¦¼‘ž²‘œ¯Š—§’Ÿ¯Šš«ƒ“¦~ yw‹›j~Žg{‹fzŒcw‰[oTk|Rh|SdwP]q>KT_mz]jzdqƒiulszv{w¼»®}‚~nx~ix~gx‚l~…m†i|ƒi{…\p~k~“{Ž£ µ“ª»žµÄ©ºÉ¬¹É¬½Ì´ÈÖ½ÑßÂÖäÂ×âÏäïÊßêÐâîÐâéØçíÞîïâñîãïíâêìíòòøøøìììøøú÷÷ùêêìôøûìò÷éô÷Úêë×ëëÎäæÃÙßÅ×ã¿Ðá½Íå·Íá³ËÞ½ÕèÁ×ë¹Ïå»Ñé®ÆݨÂÛ¯Æâ¯Àá­¿Ý´Ãà®ÄܯÇܱÉÞ²Êá®Åߨ¿Û¬ÃÝ­ÂÝ®ÃÞ­¿Û¶Èä¶Åä´Æä´Å槼ר¾Ô§½Ó­ÃÙ¦¼Ò¡·Íš°È›°Ë ¶Î¨¾Ö©¿Õ«¾Ó¤ºÎŸ·Ê ¶Ê¤·Îª½Ô¶ÆÞ¤´Ê¡±Çœ°Â™­¿Ÿ³Ãš«¼“§¹“¦»™¬Ã›ªÇ’¥¾“¦¿“¦½Žž´Ž¢´Œ ²¡±…–¥}‘¡“¥~’¢p„”kcw‡dxˆduˆSgwMaqM^oMZl4AH[j€[k~^kjt~msvyzsÀ¼­€€€qu„js‚mzŠn{‹o|Žl|l|o€“dxŠu‰›‰™¯“§·²½§»É±ÂÕ¯ÈÖ«ÈÕ³ÏÚ¼ÓàÊâìÈàêÂ×âÀÑàÉÞçÎäêËáåÒèê×êíÚéïØåìàêòèòøèóöÜêêÛëêàðïÛëìÔãçÇÖÜÑäëÔéôÒæöÐàöÎâôÍáñÂÖè¸Ëâ²Êá¯Éâ¬ÇÛ³ËÞ­ÈܧÃÙ¡»Ô§¾Ú­Äà®Ââ«Áà¯Åæ®Åá«ÃÚ¹Ñè°ÆÞ°Ëá¬Çà¯Éä®Ââ­Áã®Âæ­Âß©¿×¥»Ó¡·Ï«ÀÛ¦ºÚ¢·Ô§¹×¢µÎ ³Ê¢¸Î¡·Í£»Ðž¹Í©ÄØ£¾Ô¡¼Î¤½Íž´Èœ¯È£³Í¸Çᢲʟ¯Ç¥µËŸ°Ãœ­À£³Æ›«¾”£¹™¨¾‘ ¶Ž³‹š²‰™¯…–©…•¨€¡{Š x‡¡zŠ v‡šo€“ixŽcs‰`sˆVj|ThzTetM[h0=D\kZg{`k~ku}krrz{t¾¯„‡ˆow‰kxˆn~o€l}Œj{Œk|h|Žo‚—w‡Š–­•¥¸Ÿ¯Â£´Ç©¹Ï­¾Ï°ÁзÈÙ¹ÊݺËÜÀÑâ¾ÏàÆÖéÉÚéÆØâÍßéÕçñ×êñËÞåÑäéÑäéÄ×ܸÊÏÃÕØØèéáñðçõõãööØëîÀÖÜËßíÅÙé¶ÉÞ³ÊÛ»ÒáÃÚéÒæö¼Òæ±Èâ¬ÄÛ´Êà²Ê߶ÑçÄÜó®ÄܬÁÞ¯À㦼ߪÂé¨Á᧾ڲÉãºÒé·Òè«ÆߦÀÙ¨¿Û¥º×ª»Ü«½Ù¤·Ðª½Ö¢´Ð³È㢷ԙ°Ì¡·Ö¡¸Ò¢¸Ð›±Ç°Ç£¶Í¢µÌœ´Ëž¸Ó—²Æ˜±Á§¸˜¨¾¡±Ç¦¶Î¡±É¬ÄŸ®Ä£²È›«¾­¾–¥»¬Æ•¦¹—¨·”¥¶Šš­Œ°„•¨£¥y‰¡zŠ¤y‰¡r™n}•kw’brˆfzŒ]qƒeu‹n~R`m,9@ShqWis_p|`mrahfuyqÀ¿²€‰ˆj{‡hyˆl}ŽmjŠf{†ev…iz‹q—w‡‘§ž±®¿œ°À¦ºÌ­ÁÓ¯ÀÓ´ÅÖºËÚÁÑç¹ÇäÃÒêÅÔêÑáôÈØéÅÖç¸ÉÚ·È×¹Ë×ÍßéÝð÷áô÷ã÷÷ÔæéÓâèÓâæÖæçÙèìëúÿÚïø»ÔàÂÛéÂÛëÅÜíÎâôÂØì¹Ïç¸ÏéªÄß«Åà°Ê奾ܬÂã¬Åã¨Áß«Åà¯Æâ¬Æá¬Åã®Éä°Ëæ®Åá´Åæ¯Æâ±Ìå°Ëä³Îé«Æá«Åã©ÃÜ´Ìá¬ÁÜ©ºÛžµÑ¡»ÖªÄߥ¾Üž¸Ó¥¼Ø§½Õ£³É£³É¢±É£²ÌœªÇ­Å¢µÊš­Æœ­Î¯Ë­Åš«¾ž¯¾ž¯ÀšªÀ–§º­À›ªÀ—£¼•¤¼˜¨Â’¥ºŠ¡°†¬ˆœ®| ¡}Ž¡{‹£xˆ¢p~›hxm}“izev‰ev‡[l}^nMZl.6VgvShsUjsXjo\fluzxº¹°ˆ†o|ƒm|„n‹m~Škxˆcuf{†e~Šf‚oŒ”}—žˆœªŽž±—¨»¤´Ê­½Õ°¿Ù²Á×·ÇÚ·ÈÛ´ÈÚºÑâ³ÊÛ»Ëã¾ÉçÁÐèÓãùÍÞíÈÚäÌàîÄØê¸ÑáÅáð¿Øè¾ÒäÁØåËãíÃÛåÁÙã¼ÓàÁØé¸ÑáÄÜïÃÛî¿×ì¹Ôè³Ïã®Êà¬ÇàªÅÞ¯Éâ®ÃÞ±Àß«¿ß¦¿ß©ÃÜ­ÅÚ«ÆÜ«Åà«Áà²Æ觻ݬÀâ¯Åæ®Äå«¿á±Âå®Åß«ÆÚ¨ÂÛ¨¾Ý¢¶Ö ±Ò›°Í§¼×¦¾ÕªÅÛ¤¿ÕžµÏ¦¼Ô£¶Ïœ¯ÆŸ¯Å¡²Å¦¶É¤³É¥±Ì¡±É¡´Ë¢µÊŸ²Çš­Âš­Â—§½Ÿµ”¤º­Ã­Ãž´Ÿµž¶³ˆ™¬‡—¨‹˜ª„•¨~‘¨’¥‘ {‹œtƒ™p€˜nšm}“euˆbs„[l}TevK[l/>BeryXgoWhr^ms`jppuq¾»¯„‰…p}‚k}‚g}ƒf{„du„ctƒj{Œi}k‘r†˜{Ž£†™®ŒŸ´“¦»šªÀ¤³É§³Ê§³Ê­¹Ò¨¸Î°ÄÖ³ÊÙ´ÍÛ¶ÍÞ¶Éà½ÐåÁÑç¼Ëã»Æä¸Çä¿Ñï»ÐëÀÖî½ÓéÅØíÂÛë¹Õä½Ýë´Öæ¿ßí¾Úç¹Òâ¾ÑæµËß±ÉÞ³Îä°Ëä±Ìç¶Ðî¦ÄÞ¨Æà®Êà°Ë߯Êà¶Íé¿Úî³Ðß°ÌÞ¾Úî¬ÈÜ«ÆÜ«Æܦ¾ÕªÅÙ°ËݪÆÜ¥ÀÛªÅÞªÄÝ«ÂÜ®Ãॺר¹Ú¨½Ø®ÄÜ¡¼Ò¥ÀÙ¨ÄØ¢¿Î¥¼Í§¶Ì¨¸Ò¤¶Ô¦¸Ô§¹Õ¢µÌŸ¯Å¢±ÇžªÁ–§º“ª»’©º”§¼–¦¾–¥¿”¤¾”¤¾Ž¡¸ ·Ž¡¸Œœ´Šš°Šš°†•«ˆ”­¨†–°~‘¨’§€“¨q„™i|‘o—k~“dwŒbxŒYq†Tkz:LX/0w{~cmu^k{]ltZhjlut°³²}‡k{Šfv…fv‡iyŠbrƒ^o‚buŒdwŽl|”o†—t›~•¤ž±ŒŸ´’¥¼ž®Ä£²Èª¹Ïª¹Ï©¸Ð«ºÔ®ÁØ°ÆܨÀ×­ÄÞ²Çâ´Æâ·Ê߶ÊÚ´ÈØÃ×ç¾Òä½Ðç½Óç½Óç´Ìá¶Íç³Êä¹Ðê»ÓêºÐæ¹Ïç´Æâ°ÆÞµËã¹Îé¯Áß­Áá´Èê²Èç·Ñì´Îé³Êæ¬Æ᥾ܪÄߦÀÙªÃá«ÁäªÃá¨ÃÞ½Øî¿×ê´Ìá²Çâ¯Äß¹Ëç»Ð먿ۧ¼×¹Ëç«ÂܦÀÙ¥¿Ú¥»Ú¤¾×¥Á×¥ÀÖžµÏ¤·Ð§³Î ®Í¡¯Óœ­Ð›¬Ñœ®Ê ´Æ ´ÄŸ³ÁŸ³Áš«ºœ­¾Ÿ®Äž®Ä­Å—§½˜§½–¦¾’¥¾Š ¸ˆ¸„œ³„œ³—« ±“¥~‘¦|¤~Ž¦y‰¡q›q„™r†˜n‚’j~Œk{ŒcnƒU`s3;M!+1xxxtz^gtZdlYcinss¯ªª‡Œiw„boboƒ`p[l}Uiw[o}auƒiz‰p„’p„”yƒ—§Œ£´¦º‘¤¹—§¿ž®Æ¢±É¨¸Ð£¶Í­ÃÙ¸Ðå±ÉÞ«ÃبÃÕ­ÉØ©ÅÔµÎÞ°ÌÙ´ÐÝ«ÇÔ­ÉÖ²ÏÞºÖê¸Óç¸Ðç»Óè¹Ñä¿×ì¼Ôë­Çà«Åà³Îä³ËÞ®Ç×µÌݶÌâµÊå±Èâ¯Éä²ÎäªÆØ®ÊÞ«ÇݬÆá±Çè²Èé­Ãæ¨ÂݪÅÛ²ÏܼÞàÀÝã¬ÃЫÃÖ§¾Ú´Ë壺ԟ¶Ð¥º×¤¾×¡ÀÕ ¿Ô¨ÄÚ¥ÀÔ£»Ðœ¶ÏœµÕŸ¶Ò¤¹Ô¡·Ï¢µÎ™¬Åœ¯È ³Ì¦µÒ¦¹Ò›±É›±É°Éš­Ä¨»ÒŸ®Æ¦°Ê¦²Í›¦Ä–¦À–¬Ä’¨¾Š´ ¹Šœ¸–±z‘«—­ƒ–«}‘¡ŸxŒœ}‘£{Ž£uˆ¡j}”iy‘fvŽ`o‰IUn7>W>HR_ddtz}ltxZehWagjqoª«¤|„†dr[hz_k‚Xd}XdTc{\kƒ^o‚cw‡i}n‚”wŠŸ„”¬Žž¶ º’¥¼œ¯Æ¢µÌ¢²Ìž®È¢±Î¬»Õ®ºÕ¯¿Ù­ÀÙ§½ÕµËã²Èà­ÃÛ¨¾Ô·Íá±ÄݲÁà­Áá±Çè³Ìê°Éç±Ìâ³ËÞ±Éà¬ÃߪÄݪÅÛ²Îà·ÔãµÑç²Ìê­Çâ²Çâ³Èã²Äà¯ÆâªÃá«Ää©Âä§ÁߧÂݬÆá³Çç´Èè»Ìí²Êá¬ÇÙ¯ÇÜ­¿ÛµËã¬ÄÛ¨ÀÕ¥½Ò£ºÔ¨¼ÜªÂÙ§¿Ò¥½Ò¢¸Ð¦¾Ñ£¼Ì©¿Õ£µÑŸ·Ì¸Ê™¶Åž»Êž¶Éœ¬Ä™¬Ã™¯Çž´Ê¡´É ¶Ê—¯Â“«¾¤ºÎ–©À—¥ÂšªÂ•¦¹”¤¼“¢¿•£Àšº›¸Ÿ¹ƒ™±|“­}•ª€—¨}”¥…™«tˆšs„—p€–q€šl{“ixixŽan‚Wdvp}yˆŽGJGfkguzvjqqV]djom¨¦ ~†ˆ]nzP`oTduQbsQbuL`rThz]t…f|n„štŠ¢wŠ¡}£…•«˜§½£³Ëš­Æ”ªÀš°Æž¶ÍžµÏ¨À× ¶ÌªÂÙ­Äà®Åß²ÊáªÂׯÇܧ¿Ö°Åâ¯ÆâµËê°Éç«Åã«Æ߬ÇÝ°Ëá³Íæ­Äà°Á⩾٦¾ÕªÄݪÃá°Êå³ÍèªÄß«ÂÞ¬Ã߯Äá®Åá´Êé³Ê樿٨ÂÛ¥¿Ú¤»Õ«¾×©»×¦¸Ö­ÄÞ¶Ðé«ÅÞªÄß¡ºØ«Áâ©ÃÞ¢½Ö¸Ñž¸ÓŸºÐ®ÆÛ¯ÇÞ¦»Ö¥½Ô¡¼ÐŸ·Î©»×ŸµÍœ´Ë¦¾Õ§¿Ö ¶Î˜¨Â­Å£²È˜¨À™«Çš¯Êœ³Ï™°Ê”©Ä”§À–¥¿•¤Ã“¡ÅŒš¼Š˜ºž½•£ÀŒ›¸‡–µ†˜¶‘¯|’¨‚›«|•£r‰–tˆ˜w‡w†žu›o{”m|’t‰y—€†¦z‚–888MMKkkirutadelij©¢¢‚†‹ZhuR_oS`tP`oRcoO`oZn~^tˆayh€“r‰štˆš‘¤’¥º†œ²¦¼’¨À—®È™°Ìš±Ëš²É–±Ç »Ô¬ÇݨÀצ¼Ô¤·Ð¦¼Ô±È⢽ӣ¿Õ¥ÁÕ¬ÇÛ«ÇÛ¯Ëß´Ïã³Ëà°ËߨÄÚªÅÞ¡»Ù«Åå°Éë¯Åæ®Âä´Ëç²Íã¬ÇÝ­ÄÞ©ÃܦÀÛªÄݬÇݧÂݧÁá¨Áß«ÁàªÀߦ¼ÛªÅÛ±ÌÞ°ÍܯÌÛ±ÍܪÂÕ­ÅÚ¤¼Ó˜³Ç¡¼Ðœ¸Î¸Ñ¡¼Õ¥¿Ø¦½Ùª»ÞªÀߨÃÞ±ÍáªÆÕ±Ì޵ʗ¯Æ—¬É˜­Èœ¯È›«Å ®Ë˜ªÆ“ªÆ·Ð–°ÉšµË–®Å“¨ÃŸ¾Ÿ¼ž»º–¡¿ž¸‘¡»ˆ›´…˜±€“¬}§|¨vˆ¤x‹¤v‰¢~‘¨t‡žt‡ u‡£t…˜u†’ž¨²ÅÆÏ“§zžvŽ0557OVThnqqv~hl{ciygobp{_rwVktXo|au‡hx’nšp‚žnšwŠ¡€–¬‚˜°‡Ÿ´ˆ µˆ µ£»š¯ÊŸ±Ïœ®Ê¦¹Ò–¬Ä¡·Ïž´È¤»Ì®ÆÙŸ·Ìš°Æœ¯ÆµÈá´Ãâ®ÀܬÂÚ¦¼Ô¤¹Ô¨¿ÛªÀߪÀß®ÄãªÀߤ¸Ø­¿Ý°¾Ûª¼Ø¡¸ÒÂ×òµÇ㪼ڨ¹Ú³Èã»Óê¯Æà¯Äá´Éä±Ã߯ÂÛ°ÃÚÀÓì®ÀÞ§»Û®Âä­Âߦ¸Ô©¾Ù©¾Ù©¾Û¥¹Û¥»Ú£¹Ø¥¼Ö£»Ðœ·É¡¾Í£¾Ð¦¾ÕšµÇ¢¾Í£¾Ðš²É™±È˜°Ç“«Àš°Æ¨ÀÓ›·Æ—³Â¹È˜±¿“§·‘¨·ž·ÇªÃÑŠ¡®†¬¡³’¦¸‡—­†™°‡š³‚˜®—­~”ª’«†™°§yŒ¡p‡˜qŠšn†™h„‘c€ˆuƒ…ÒÏÎœ¨’ª„Œ¢{‡žv„GTYP[\KTS3::499:AASZZlrwnsen}_l€^n}]o{Ym{\p€duˆixŽq—o•q—y‰Ÿ}§„—°‰Ÿ·„œ³Š¢·¦¼”ª¾–©¾™¬Á–©À«¾×©»×°Éœ¯Æž´Ê¡¹Ð¤¼Ñš°Æ¯ÅÙ§½Ñ¢¸Î«½Ù§½Õ«ÃÚ©Ãܤ¿Ú¡»Ô¬ÂÚ®Äܤ¹Ô¨ÀÕªÂÕž¶É«ÃÖªÂ×­ÃÛ¦¼Ò¦¼Ò²ÊݸÐã¯ÇÜ°ÆÞ­ÃÛ®ÄÜ©¿Õ©¼Ó¯Â׳Ä×°ÀØ®¼Û¨¸Ò¨¸Ðª½Ô¬ÂزÊÝŸºÌž¹Í¦½×˜¯Éš±Í·Ðž¹ÏŸºÐ¢½Ó˜³ÉŸºÐ¢¼Õ™¯Î˜°Ç˜®Â˜®Â˜®Ä—°¾›¸¾ª°©²›²Ã‘¤½˜ªÆš¬Ê“©Á£·™°Á‘¨·ˆŸ°†™°‹žµ†™²€“¨‚–¨—«|’¨…˜¯‚’ªxˆž£xŒžl‚–oƒ•p’z‚†ÐÏÆ`ck‡‹¥„Ž¦~Š¡v‚Žroesrgce[DDB65<68K[ERbFScHUeZgwQ\mRWlBHV8=G5;>8?=U\Zhoobot_q{p…g{‰sŠ™k•mƒ—{Ž£w¡~”¨‚›©z–¡ª‡£²©¹¦º¦·–­¼™²Àž·Åž´È¦µÒž³Ð™¯Î™«Çž­Å¦º•°Âœ·Ë‘¨Â“©È©½á¥¼ÖŸºÌ£¾Ð¦¾Ó¦¿Ï§ÀÌ©ÀѤ´Ì¯¿×©¹Óª½Öª¼Ø¦·Ø©ºß§»ß§ºá°Äè¯Ãç¬Åã«Æ߬Å㦼ߜµ×¥¾ãªÃ奻ܩÃÞ¥¿Ø¥¿Øœ¶Ï¡¹Ð©¼Õ¡·Í¢¸Ì§½Õ¡µÕŸµÔ¶Ô¡¸Ò¥»Ñ›±ÉŸ´Ï•­Ä‡¢¸“­Æ ¶Õ–±Ç–²Á’ª½–©Â—­Ã‹£¸Œ§»‰¤¸œµ›»‚›¹ƒ—·}‘±†—¸Œžºƒ–¯|’¨{‘§}§{Š¤v‰žt‹švžr…šq„›pƒœq„l{˜h{’i€‘Vm~Nbt@Qd 3" " -=7?ABKJ^eeeps^muXhw`o…buŠd|l„—€–ª˜¨„­…¡®ƒŸ¬‡£²…²‡Ÿ´‰Ÿ·¦¼ž´Ê˜°Å™±ÆªÃÓ•®¼š²Å˜°Ç”©Äž­Ì’§Â™±È ·Ñ¡·Öš±Í§¼Ù¨¾Ô¨¿ÐªÃÓ©ÄÖ¤¿Õ³Êæ²ÊᡷͱÊÚ¶ÏÝ®Çר¾ÔªÂÕ­ÈÚ°Æܯ¾Û§µÒ«¶Ö¶Åä¯Áß°Åà¬ÁܨÀÕ¡¹Ì§½Õ«½Û®ÃࡸԷР»Ô¡¼Ò¢¸Î°Çا¾Ë›¶È’­È–°Ë—­Ì˜²Íž¹Ô˜³É£»Ð·Ð·Õ–­ÇŸ²Ë™¯Å“©¿‹¡¹Ž ¼ˆ ·ˆ¤ºˆ¤¸–±Å‡£¹‚¶{’¬~ªŽ­€Ž°‚”°€“ªƒ•³y‰±„•¸u‡¥vŒ¢z“£qœj…—l‚–k{“k~“j}’k~“k~“au‡QbuL]n;L] 0A *P\M^jJXcCPY7BE8???FDKRP]hkanw^o{fwˆwˆ›xˆžwŠŸ{‘¥|“¤Œ£²‰ ¯¡³ˆ›²Šœ¸ˆž¶Š¢·«Á˜²Ë“®Äª¾”°Â”±À¸Ê•­Ä™±Æ™¯Å—­Ã³Ë™±ÆŸ·Ê¢½Ï¢¾Ð¨ÄØ¢¼Õž¸Ñ£½Ø¢»Ù¢»Û¢¼×¦½×­ÄÞ­ÄÞ®ÆÝ°ÆÞ¥»Ó¶Èä±Éà¦Á׬ÇÛ³ËàªÄߪÃå¬Åç©ÁæªÄ߯ÊÞªÂÙ°Åâ°Å⨽ڥº×«Àݧ»Û ´Ö¥»Ü¦¼ß¥¿ßž»Øš¸Ð•±Å™µÉžºÎ¤ÀÖ·Ò—®Ê“§Ç™®É™¬Å“©ÁŽ¥¿ªÀ“®Â¸ÎŒ£½“«Â“«À€˜¯‚™³|“­|‘¬ƒ˜³‚”²~“®—¯w£r…œw¥v©v‘§~™­vŽ¡n…–j‚•d|“dy”as‘cu“ix—apZj„N^tHXiH$7:;K\CTcBT`BSbBRcDTcIZfBS_BP]?LS9AE9?BBGGSY^chr`n{g{p„”mtˆšx‹¢}“§€˜«‚š­‹£¶ˆ ³‰Ÿ³‡Ÿ²Ž¦¹•­Âž¶Í‹£ºŽ¦½“«À—¯Ä˜®Æš¬ÈŸ²Ë›®Å˜«Â¥µÍ°ÃØ¢¸Ì®ÄØ©¿ÕŸºÎ£¿Õ¢¾ÒŸºÎ¸Ì¦¾Õ³ËÞ´ÍÝ©ÄØ­Çà©ÄÚ¤¼Ñ«ÃØ®ÆÛªÅÙ¨ÃÙªÁÛ©»ÙªÀߦ¿á¥¾à£¸Þ¥¹Ù­½×°ÃÜ¥»Ó¨¾Ö¨»Ô¢·Ò¥º×£¹Ø¥»Ü¨¾Ý ·ÓŸ¹Ô£¼Ú ¶Õ™ªËš¯Ì–­ÉªÅªÈ–±Ê‘¬ÂŽ©¿¨¿§¾Œ¤»‘©ÀŠŸº¢½¢½…´‚š±ƒž´† ¹ƒž´‚š±~˜±€™·}”®…˜¯‡š³{Š©yŽ©r‰£l†¡e~œq‹¤n†›k†˜i…”k‚“q‚•m“buŠZn€QewO`qJZi@Q`4ET4GJRb>TX@Q[FWaFTaKVgPXlO\nQatIZmJ[nHYjBSd;LX6CL8?HFGPS]e\mwdu„m“n„˜rŠ¡x“¥‚ž­‚¯—¬ƒ™¯†™²Œ¢¸’ª½µÊ˜­È’§Ä¤Ä™«Éš©ÈŸ±Ï¢·Ôž´Ì§½ÓŸµËš°È¡·Ï¤¶Ò¥»Ó¥»Ó§½Õ£µÑ¨·Ô®¹Ù­¼Ù­ÀÙ«ÀÛ«ÂÞ¬Ã߯Æâ­Çà¯Êà­ÈÜ°ËߦÁÕ¦ÁÕ«ÃÚ¨½Ø¥¼Ö¦ÀÙ¯Ê㣾ٯÊã¯Éâ³Îä©ÄÚ¨ÃÙ¢¼Õ¥¼Ö«½Ù£¶Ïœ¯Æ¨»Ð¢µÊ¨»Ô¦¸Ö¢¶Öœ²Ó´Ð”©Ä«Á©¿—²Èž¶ÍµÌ™±È–®Å˜¯É…Ÿ¸ƒ¸ŠŸºŠš´…š·‡¾† ¹„ ´y”ª{’¬z”¯}–¶z”²y”¯x“¬{•®{“ªz¦y§xŠ¨m‚Ÿk€e|–h€—_u‹k{“at‹[n‡WgYh€N]uO^vN^tK^sJ`f;LXBRaCSdK[jJZiIZkH\nK_oJ[lH\lJ^nEYgEVe:KW1=K?FM_ddlv~u…”t…–vŠœ{Ž£}§ƒ–­ˆ›²ˆž´„š²ˆž´‹¡µ’©º”«ºš²Å•¬Æ–­Ç’§Â—¬Çœ®Ì˜­ÈŸµÍ¢¸ÎŸµÉŸ·Î›µÐš°Ï ´Ö¬ÂáªÄߟ¶Ðª½Ö¦¹Ð¤·Ì°ÁÒ©¶Æ°Ãا¾Ø¦Á׫ÇݪÆÜ«ÅÞ©ÃÜ¥¿Ú¡»Ö ¶Õ¥¾Ü¥¾Þ£½Ø¡¼ÒŸºÐŸ¹Òœ·Í©ÄبÀÕ¦¹Ð¦¹Ò¦¸Ô¥ºÕ µÐ¢¸Ð¨¾Ö ¸Íœ´É•°Æ™´Ï¢½Ø§Áßœ¶Ô•®Ì•¯ÈšµË˜²Ë•®Ì‘«Æ˜¯É† ¹€šµ„›µ’¨À‹¡·„š°}“©€“¬ƒ˜³€–µz”¯™´ˆŸ»‚—´{’¬z”­›´w‘ªw‘ªtŽ©i„šg”i•p€˜l}k|‹bv†[oUh}^n†Sf{ThzScyJYqK\h=JZ@Q]AS_FXbI[bIZdR`mS`pQ^rQbuObwRfxMaqGXg>K[5Ó—WÿÿÏÿÿÕÿÿÓÿÿÑÿÿÃÿÿ·ÿÿ®ÿÿ§ÿÿ­ÿÿ±ÿÿµÿÿµÿÿ¶ÿÿ¹ÿÿ¿ÿÿÅÿÿËÿÿÑÿÿÃÿø“ÿì‡ÿòαv•oˆˆ†q‚‘wˆ›|‹£q„™f|l‚˜ez•c{jƒ“i‚…hq~eqlwŠq|v‚t€Œu‚‹uo{‰v‚ŽxŽzƒŒ’ ¤­ºœ¨¶¬¸ÄŠ–¢€Š’•˜›œ•’‘ª¤Ÿ©Ÿ™£™‘ –Œ£ª¦—¦¡•®§ ®§ž®§ž¿µ«ÐĸÝоÙÊ´ÒÆ­ÒÆ­ÔжìëÕøùäûþíÿÿÿÿÿúÿÿøÿÿøÿÿéÿÿÕüüÓþýÛÿÿüÿÿÿÿÿöÿÿèÿÿÙÿÿÒÿÿßÿÿçÿÿãÿÿÝÿÿËÿÿÌÿÿÒÿÿÊÿÿÊÿÿÏÿÿÈÿÿ¸ÿÿ¸ÿÿ¹ÿÿ¶ÿÿ³ÿÿ¾ÿÿ·ÿÿ¤ÿÿÿÿšûÿ–ÿÿ‘ÿÿŽÿÖ†ó†aðnañYfþgküfcùb\ù]YóVWîMVêNSãJNÈaIÿß­ÿÿ×ÿÿÙÿÿ×ÿÿÕÿÿÉÿÿ¿ÿÿµÿÿ­ÿÿ­ÿÿ²ÿÿ±ÿÿ±ÿÿ±ÿÿ±ÿÿ¹ÿÿÃÿÿÉÿÿÏÿÿÃÿÿ¹ÿÿ©ÿê}ÿðšÿà¡ ‘rmpqx‚Œt„—p„–k•g}“j}–m€™nšg‡dqduiz†or„rƒv…z‡u~‹w€x{‡“—¤­š¤ªŸ¥ª™£©‹˜Ÿ˜›œ¢¥•–‘›–Š¤Ÿ“¢›’¡š¡š§ •¦œ’¢˜¥›•ª£˜°¬®¨šµ¬ŸÄ¸¬Ê¼±ÐñÔȯÛÏ´åÚ¼åݬÿÿÄÿÿÒÿÿËÿÿÖÿÿïÿÿèÿÿÿÿÿúÿÿôÿÿðÿÿåÿÿÜÿÿÛÿÿáÿÿæÿÿàÿÿÐÿÿÔÿÿÝÿÿÛÿÿÐÿÿÇÿÿÈÿÿÈÿÿÁûÿµùÿ³ÿÿ»ÿÿÂøÿ¬ÿÿ±ÿÿ·ÿÿ¯ÿÿ¢ÿÿžÿÿœÿÿÿú›ÿñ£÷¦üz{ðspéokÿ€~ðlkð`cöX`ôSZìIQãKTãT`؈oÿÿÙÿÿàÿÿæÿÿàÿÿÛÿÿ×ÿÿÓÿÿÉÿÿÁÿÿ¹ÿÿ³ÿÿ·ÿÿ½ÿÿ¹ÿÿµÿÿ¹ÿÿ½ÿÿÁÿÿÅÿÿÉÿÿÏÿÿÅÿÿ»ÿÿ¥ÿáŠÿëžÿéªñ᩹¸‰~p]csgt†l|’k{“jy“iz†mzŒl|l|m}q€–t„•w…’{‰”ur‰s‚Š}Š“œ£®”›¢ž¦ª– ¦ˆ•žŽ˜ž—¢’•–œ™˜›—’›–Œœ—š“Š¤š¨™‘§š‘¬Ÿ˜²¨ž²¨ž­£›¬¢œ´«žÀµ¤Ç¿©ÐÉ®ØÒ²ÓÍ«ÎÏ¡ÿÿÒþÿÇÿÿÒÿÿæÿÿîÿÿðÿÿôÿÿìÿÿÚÿÿØÿÿÞÿÿÞÿÿÚÿÿ×ÿÿÌÿÿÌÿÿÝÿÿèÿÿáÿÿÓÿÿËÿÿÂÿÿÉÿÿÄÿÿ¼ÿÿ´ÿÿ·ÿÿºÿÿ²ÿÿ­ÿÿ«ÿÿªÿÿ£ÿÿ¡ÿÿšÿÿ›òû‘ÿü—ÿïÜRðfí£uÿæ¦ÿâ®ï†`çdSöVZóQVíHNÞXEÈ_7ÿØ ÿÿÑÿÿàÿÿîÿÿìÿÿêÿÿèÿÿæÿÿâÿÿÞÿÿÕÿÿÍÿÿÇÿÿÃÿÿÅÿÿÇÿÿÇÿÿÇÿÿÅÿÿÅÿÿÇÿÿËÿÿÉÿÿÉÿÿ½ÿÿ±ÿüüæ€þé‡ÿíÿñžøå Åºˆ‰ˆfbh__l~btymzŒp}u€‘kxˆqn‹s„Žu‡Žo~„tƒ‹{‰–‰•¡š£°”ž¦ ª°Š”œ…‹™’š›Ÿ¢”’Ž ™Žš•‰š•‰›•‡œ“†Ÿ–‡ —ˆŸ–‡¥œª¤”®¨˜±«®§ž­¨œµ°¤¾¹­¾·¬Æ¾¨È¿žçä³ÿÿÛÿÿÖÿÿÞÿÿÙÿÿÇÿÿÈúÿ¼ùüÀÿÿ×ÿÿäÿÿßÿÿÓÿÿÎÿÿÄüÿ¼ÿÿÐÿÿØÿÿÍÿÿÌýÿ·ÿÿ»ÿÿ¼ÿÿ´ÿÿµÿÿ½ÿÿ¹ÿÿ¼ÿÿ»ÿÿ´ÿÿ´ÿÿ²ÿÿ¯ÿÿ®ÿÿŸÿÿ ÿÿŸùÿ’ÿù£ÿÇŠÏ‘_쬇ÿýºÿÿ®ÿï®ß}WègPöVOñLPïFVÕWWÒ~mÿÿâÿÿ×ÿÿÞÿÿæÿÿæÿÿæÿÿäÿÿâÿÿàÿÿàÿÿàÿÿàÿÿÓÿÿÉÿÿÇÿÿÇÿÿÇÿÿÉÿÿÇÿÿÇÿÿÇÿÿÉÿÿÉÿÿÉÿÿÉÿÿÉÿÿÁÿÿ¸ÿøôÜ‹ÿó–ÿÿ™ÿþ›ÿõ—ýëŸÙÉŽ«’tiyˆgw†l|n{‹oz‹r€w…w…o}ˆo~‚|Œ‹žŸ£ ­´ ©¶Š‘š†Œ‘’“—‘Œ‰œ“„•‘‚—”Š–”…™ˆœ–ˆ“‰¢˜Ž¥›“¨¡–¬¥š²¬ž±««¥•°¨–¼³¤½±¥¿³šÀ³úõ²ÿÿ©ÿÿ¹ÿÿÅþÿÏÿÿîÿÿìÿÿèÿÿßÿÿÜÿÿÔÿÿÍÿÿÔÿÿâÿÿÚÿÿÎÿÿÌÿÿÏÿÿÒÿÿÝÿÿÐÿÿÏÿÿÈÿÿ¾ÿÿÅÿÿÍÿÿ¿ÿÿ¹ÿÿ½ÿÿ¼ÿÿ¸ÿÿ³ÿÿ®þÿ¬ÿÿ¨ÿÿýÿšÿÿ¡ÿð¥æ¡mã¸{ÿù´ÿÿµÿÿ­ÿߧãlWí^\ùPbñL`éH_Â]MúΘÿÿÓÿÿÑÿÿÑÿÿÓÿÿÑÿÿÑÿÿ×ÿÿÞÿÿàÿÿäÿÿæÿÿèÿÿâÿÿÞÿÿÓÿÿÉÿÿ¿ÿÿµÿÿ¹ÿÿ¿ÿÿ¿ÿÿÁÿÿÁÿÿÁÿÿÃÿÿÅÿÿÅÿÿÅÿÿ½ÿÿ®øï‹ñá‚ÿ÷”ÿû•üñŠÿù“ÿñ®hyŠh|Œe|ksƒ’q‚Ž{Œ˜ok|‹k|†Œ•—¡šŸ«§±’žª‚––“ŒˆŒƒ—’ˆ•’ˆ–“‰œ—‹¤’£™‘¦™”¤š«¢“«¥•§¡“©£•°ªœ¯©›°§š¾µ¨º±¤»±•Ä»‘ÿÿÖÿÿÒÿÿÝÿÿèÿÿáÿÿÛÿÿÎÿÿÊûÿÊÿÿÞÿÿëÿÿéÿÿßÿÿÎÿÿÇÿÿÇÿÿÌÿÿÕÿÿÎÿÿÐÿÿÈÿÿÀÿÿËÿÿÉÿÿÁÿÿ»ÿÿÄÿÿ¼ÿÿµÿÿ­ÿÿ­ÿÿªÿÿ¯ÿÿ­øÿ™üÿ—ÿý™ÿû îƆަƒÿõ³ÿÿ¥ÿÿ ÿÿžÿÁ„Ý^NêUXôJaíNdÞK_ÈtaÿÿÕÿÿÙÿÿÙÿÿÕÿÿÑÿÿÏÿÿÍÿÿÏÿÿÓÿÿÕÿÿ×ÿÿÕÿÿÓÿÿÞÿÿèÿÿäÿÿàÿÿÏÿÿ¿ÿÿ¯ÿÿ¦ÿÿ§ÿÿ¬ÿÿ±ÿÿ¸ÿÿ»ÿÿ½ÿÿÁÿÿÃÿÿÇÿÿËÿÿÃÿÿªíåˆöæÿø–ÿþ‘úóªkm~lyl|xˆ›r‚‘~Œ™t…‘m~Šn|‡ˆ•ž››“Ÿ™•¤¡Œ™ž„‘–‹˜Ÿ˜ŸŸ†„€Žˆƒ‘†ƒŽ‡€”‡œ—¡š¡š§ •ª£˜¬¥š®¨˜©¤‘§£’©¥–®©²«¢µ®¥²«¢¯¬‹Ú×¢ÿÿàÿÿ×ÿÿÅÿÿÅÿÿÇÿÿÝÿÿÞÿÿæÿÿÒÿÿÉÿÿ½õü§ÿÿ½ÿÿÂÿÿÎÿÿ×ÿÿÐÿÿÎÿÿ´ÿÿ«ÿÿ¨ÿÿ°ÿÿ³ÿÿ®ÿÿ®ÿÿ´ÿÿÆÿÿÈÿÿ¹ÿÿ¤ÿÿŸÿÿ¨ÿÿœûÿˆþÿÿÿ—ÿý¨ÿ֜ˬf÷á”ÿÿ®ùÿžÿÿ£ÿÿ®Ü“bÜYQáKSñHbãU\ÒZSÿÿËÿÿÑÿÿ×ÿÿÏÿÿÇÿÿÃÿÿÁÿÿÁÿÿÃÿÿÉÿÿÑÿÿÓÿÿ×ÿÿÛÿÿâÿÿâÿÿâÿÿ×ÿÿÍÿÿ¿ÿÿ²ÿÿ©ÿÿªÿÿ±ÿÿµÿÿ±ÿÿ±ÿÿ¯ÿÿ³ÿÿµÿÿ¹ÿÿ»ÿÿ½ÿÿ´ÿÿšðî„ýú’ÿ÷¬j~Žkcw…hyˆr‚‘n‰r„‹w…u€‘~‡”•š¦–Ÿ—Ÿ“ ¥‰—™€ŠŽ• ’˜›ƒ}‰ŠƒŠ†ˆ€“Œ…š“Šž”Œ¥›‘§“©¥–¬ª›­¬˜«¨’¥Ÿ®¡˜°£š°£œ³©Ÿµ¯¡¸¶Žýÿ¾ÿÿÂÿÿ¸ÿÿÃÿÿÊÿÿÆÿÿÅÿÿ»úÿ§ÿÿ®ÿÿ±ÿÿÎÿÿÛÿÿÜÿÿËÿÿºÿÿ´ÿÿ³ÿÿµÿÿ¶ÿÿÂÿÿ¼ÿÿ°ÿÿªÿÿ®ÿÿ©ÿÿ´þÿ£úÿ üÿ ÿÿ¤üÿìôúÿ™ÿÿ ÿÿŸÿÿžÿóªÕžvæËÿÿ¶ÿÿ­ÿÿ¡ÿÿ¦ÿæšÍjIåO[ìN_óJdÙWZÌl]ÿñÁÿÿÍÿÿÏÿÿÑÿÿÇÿÿ½ÿÿ¼ÿÿ½ÿÿ¿ÿÿÁÿÿÉÿÿÑðêºÝÒ¿ÿÿçÿÿìÿÿæÿÿâÿÿÛÿÿ×ÿÿÏÿÿÇÿÿ¾ÿÿ³ÿÿ³ÿÿµÿÿ±ÿÿ®ÿÿ®ÿÿ«ÿÿ«ÿÿ¯ÿÿ³ÿÿµÿÿ­ÿÿ¬ÿÿ¥öì‹ïâ¦m}Œm}Œn{o}Šnz†p|Šv”u‚’z‡—„‘š˜›…“ˆ’˜„‘šzˆ•{ˆ—›…‰Œ‚‚„ŽŠ‡ˆ†}”Š‚‘Š“Œ…¢›¤ž¨¢”©¢—¯¨­£›«¡™¬¢š®§œ¯©›®©’¸²’ÆÄŠüþ«ÿÿºÿÿÓÿÿØÿÿØÿÿÃøü¯ýÿ²ÿÿÀÿÿÈÿÿÆÿÿÅÿÿµ÷ü¦ùÿ¤ûÿ©ÿÿ»ÿÿ¿ÿÿ¾ÿÿ½ÿÿºúÿ«øþ¥ÿÿ±ÿÿ±ÿÿ¨ÿÿ øÿ•ÿÿœÿÿžþÿŸ÷ÿ”ÿÿ˜ÿÿ•þÿþüÿû•ö݊ͧjÿõ©ÿÿ°ÿÿ§üþ›ÿÿ§ú»nÏb@ëNXëNXëLWÊaDݪgÿÿÏÿÿÕÿÿÑÿÿÍÿÿ¿ÿÿ®ÿÿ¸ÿÿÁÿÿÃÿÿÇÿÿÙÿüÒž‰Ž´Ç³—¹ÚÅÓÿÿüÿÿèÿÿâÿÿÛÿÿÕÿÿÏÿÿÅÿÿ·ÿÿ²ÿÿ­ÿÿ¯ÿÿµÿÿ±ÿÿµÿÿ¸ÿÿ¼ÿÿ²ÿÿ³ÿÿ¬ÿÿ«ÿÿ¤ÿÿ úò©g|…g|‡ev…hyˆj{Šl~Šs„v„‘}†•„šxŽ‰“…™{ˆ‘€—…“•’›š~~‡ƒ~Œ‡Ž„|Œˆy‘~{‡‡uš–‡¦œ”©Ÿ•©Ÿ•© “¥œ¤’§ —¨¡–©¢—­¥µ¬ßÝ¥ÿÿÄÿÿÅÿÿÇÿÿºöÿªîöœÿÿ¯ÿÿ¾ÿÿÜÿÿØÿÿÏÿÿ¾ýÿ®ÿÿ°ÿÿ¹ÿÿ¶ÿÿ¯ýÿ¤ÿÿ¤÷ûžÿÿ¬ÿÿ®ÿÿ°ÿÿ¥ÿÿ úÿ—úÿ•ÿÿžÿÿ«ÿÿ¢üÿ•üþ™ÿÿ£ÿÿ›ÿÿ—þú™ÿý©ÍÅløó™ÿÿ¬ÿÿ¨ÿÿ úýˆÿô¨ÛxYÝZPíKWãLRÞNOÅnKÿ÷±ÿÿÕÿÿÞÿÿÛÿÿÙÿÿËÿÿ¿ÿÿ½ÿÿ»ÿÿÅÿÿÏÿÿÿͦ×Чçš踑×ÈŸß¹ŸÃÜÌØÿÿôÿÿÙÿÿ×ÿÿÕÿÿÍÿÿÇÿÿ¿ÿÿ³ÿÿ°ÿÿ¸ÿÿ±ÿÿ³ÿÿ©ÿÿ›ÿÿÿÿ¥ÿÿ©ÿÿ°ÿÿ¯ÿÿ²ÿÿÄ@KLˆ‡Š‘‘]eg$($'TbdyˆŒƒ’˜‘ž£Š”šŒ™ Œ˜¤Ž—~ˆ’ƒˆ…‡‹zzz„‚~‡|Š€z‘Š•‘‚•“‚‘~˜”…£œ“¡š‘ –™’‡œ–ˆ¡›©£•§¡“¬£–°ªˆ²¯zòö©òù™ãìñùòûœÿÿ¬ÿÿ³ÿÿµÿÿÃÿÿÍüÿ¹õù¬ùþªÿÿªÿÿ½ÿÿÆÿÿ»üÿ©îô™ÿÿ¯ÿÿÁÿÿ½ÿÿ²úý¥÷ûœùþ˜ÿÿžÿÿ£ÿÿžÿÿžòø‹ûÿÿÿ›ÿÿéê÷ö‡ÿù’ÿôšóëÿÿªÿÿ¨ÿÿ¢ÿÿœÿÿšþÄ…ÕeWàXRîNPßNMØTQäšnÿÿÅÿÿÏÿÿÙÿÿ×ÿÿÕÿÿËÿÿÃÿÿÁÿÿ¿ÿÿËÿÿ×ÿëêÇÝÉŸãɞ罓ڼ–ÙàÙͯݶ¦¥ÜܪÿÿÜÿÿ×ÿÿÑÿÿËÿÿÅÿÿÁÿÿ»ÿÿ¶ÿÿ±ÿÿ¯ÿÿ§ÿÿ ÿÿ§ÿÿ©ÿÿ§ÿÿªÿÿ¯ÿÿ³ÿÿÇÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ §¥[biˆ’šŒ– Œ™¢š£|‰€Š’‚ˆ‹vyvqumw{}q€uŠ…}‘†ƒ‘ŠƒŽ‡~˜Ž„Ÿ‘†œ„•‹¡›¡Ž¡žŠ§¤Ž¤¡‹§¤°«†Ê¿ñí¡óõóùÿÿ¤ÿÿ®ÿÿ»ÿÿ¼ÿÿ¼þÿ²ôü¢ÿÿ²ÿÿ­ÿÿÀÿÿÅÿÿºüÿ¯òú üÿ¦ÿÿ±ÿÿÃÿÿºýÿ«öü£úú£ö÷™úú˜ÿÿ¥ûü öø•ÿÿ™þÿ•ÿÿ–ÿÿšþþšøù’ÿÿ›þþœôó–ÿÿ¤õý–úÿ›üÿŸÿÿ™ÿòˆÝ‹NçZIëSPïLVÚXKÊhGÿî­ÿÿÃÿÿÇÿÿÍÿÿËÿÿËÿÿËÿÿÍÿÿÇÿÿÃÿÿÉÿÿÑǶ¥É¤ÐʦÛÁÝÅŸâÅ›âÄãÈ£êÁ¢Ó¶š¸»­¢ñî»ÿÿÞÿÿÕÿÿÍÿÿÇÿÿ½ÿÿ±ÿÿ°ÿÿ³ÿÿ¯ÿÿ³ÿÿªÿÿ¦ÿÿŸÿÿžÿÿ¢ÿÿ§ÿÿËÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŠ“’‚ˆ‹Ž•œ‹•Ÿ~ˆ~ˆŽ‚ˆ‹ttvwxs|{r}zr‚|w…€xŠƒ|‹„{…}Žˆz’Œ|“}›’ƒ —Š¥˜Ÿ–‡ ›ˆ©¤¬§­¥väÙ“ÿÿ¸ÿÿ­ÿÿ½ÿÿÆÿÿ¿ÿÿ»üÿµÿÿ¹ùÿ¬þÿ¬ÿÿ¹ÿÿ·þÿ´ÿÿ¶÷ý¢÷ÿ–ÿÿŸÿÿ ÿÿ¯ÿÿ´úÿ«úÿ«ÿÿ¦ÿÿÿÿ¦ÿÿ©þÿ§üÿ©òù—þÿ™ýÿ˜ùö“ùö“üù˜ùõ™ÿù¤ìëÿÿ§ùÿ÷ÿ›ýÿ›øÿ“ÿüî·g×nFêOOëNQðMUÐ[EèŸnÿÿÍÿÿÉÿÿËÿÿÍÿÿÏÿÿÓÿÿÑÿÿÏÿÿÅÿÿ½ÿÿÛÿêÕ¹š²¼•ÛÀ™ß¿•ÜÁ—Þ¾“ÚÀ–ßšå›㹒ض˜Æ¼¥½Å½«ÿÿÒÿÿÓÿÿÅÿÿ´ÿÿ²ÿÿ¤ÿÿžÿÿ˜ÿÿ—ÿÿ™ÿÿ”ÿÿ‘ÿÿ’ÿÿ–ÿÿœÿÿ¼ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ°¦Å„œ€¡|‰™~‰šy~†oooyur~wp}vmxo„}t‰w†v†xˆxŒ…z‰{—Žž•†¥‹§Ÿ¯£•¬¡°¥”°ªzæã”åéŒêò‹õüšøû¡ÿÿ¯ÿÿ®ÿÿµÿÿµÿÿ¶ÿÿ¸ÿÿ¶ÿÿÀÿÿ¸üÿªÿÿ®ÿÿ®ÿÿ²ÿÿ°þÿ°üÿ°ñùŸÿÿ¨ÿÿªÿÿ­øÿŸúþŸüÿ£ÿÿ§ÿÿ¢ÿÿ¢ÿÿ™úûúùŠÿü‹ÿðŠùÞ…àÔtÿÿ§øþ“ÿÿ›ÿÿ˜÷þŽûÒ~Ý‚JÝ`EîNRêNSéRXÊnFÿïœÿÿËÿÿÕÿÿÓÿÿÑÿÿÑÿÿÓÿÿÏÿÿËÿÿÅÿÿÁÿÿèÓ·¼Ê¨ÏÀ–ß¿—âÀ˜æ¿˜à˜ß›ὖÞÄšáØß™ÝÂœßÀ§È²¤¤ëç»ÿÿÅÿÿ½ÿÿ°ÿÿ©ÿÿ§ÿÿžÿÿ¡ÿÿ¡ÿÿ™ÿÿÿÿ‹ÿÿ–ÿÿ“ÿúŸÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ°µÊm}—€¡ƒ™u||klevul|wm{ur}vz|ww|xs~zu…z‰ƒ~‡}†”‚•„™–Š£ŸŽ­¥“®¦¶¬’ÏÉ™ÿÿÆÿÿ½ÿÿ¸ÿÿ»ÿÿÁÿÿ¿ÿÿ¿ÿÿºÿÿ·øþ°ýÿºùÿ³÷ý¯üÿ°ûÿªúÿªÿÿ´ÿÿ²ùÿ©ðøœÿÿ®ÿÿµÿÿ»üÿ­÷ý¤úþüý–ÿÿþý ýü¡ùôóó‘ÿÿ™ÿÿ›ÿþ•ÿí–îÉ…åÒ„ÿÿ®ÿÿ¤ýÿ¡ÿû•ëÑjÛŒPèaTéVOîNPãRQ×SPÝ”jÿÿËÿÿÑÿÿ×ÿÿÓÿÿÏÿÿÏÿÿÏÿÿÍÿÿËÿÿËÿÿÍÿôåÊ›ÍÏ£ßÍ¢ëÉéÈœëÈéÅè¿—åÁ•é»ß×ãÈœèÔáÆ›â̢澧º¾·œÿÿ½ÿÿ°ÿÿ¢ÿÿšÿÿ¤ÿÿ¯ÿÿµÿÿ²ÿÿ¨ÿÿžÿÿšÿÿŠëàšÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ«¸{ˆ‘‚‰sxxqrmsqkwqlxsk{vlyupxuv{xw‚}}‰„|‹„y‹†z‘Œ‚“€˜’‚›•‡¡š©¢‡®¤}ÞÔšëÝ”èâ”÷ö¦ûþ¦ÿÿ¦ùü¤ÿÿ³ÿÿ²ÿÿ·ÿÿ»ÿÿÆÿÿ¿ÿÿ´ÿÿ¯ÿÿ´ÿÿ°úÿ®ûÿ¯ÿÿ¸ÿÿ¼ÿÿµÿÿ°ùþ¨ûÿ¢ÿÿ¡ÿÿ¡ÿÿ£þý ÷ò›ûú›úü—ÿÿŸÿû˜ÿ÷˜úé‘ÿèžà¦iðÒ…ÿÿ§þÿúÿ˜ûà‚Ú•JÛjIòU_òS^òP^ÞYRÒiOÿߣÿÿÃÿÿÉÿÿÑÿÿÍÿÿËÿÿÇÿÿÃÿÿÅÿÿÇÿÿÕÿÿæÚ¿ÆÇ¢ÞÈŸáËåÊžêÌ ñÌ¡òÇžñš꾓â»Ü»‘ÚÄšá™ÝÈžàÌœà›Ѹ˜À¡’xÿÿ¦ÿÿ©ÿÿ“ÿÿ—ÿÿžÿÿ§ÿÿ®ÿÿ©ÿÿŸÿÿ›üú’ÔÌÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ†Œšz„Žmqtsolxrmumispfrqdyvj{vl|ym€}qƒ€t…‚v‰z‰{‘Š‘Š–†ž”Œ¢˜~«Ÿv÷ó§ÿÿšÿÿ©ÿÿ±ÿÿ²ÿÿ³ÿÿ°ÿÿ®ÿÿ®ÿÿ´ÿÿ´ÿÿ´õü¥÷ý¤ýÿ¨ÿÿªÿÿ²ÿÿºÿÿ¿ÿÿÁýÿ±÷ý­ûÿ§ýÿ ÿÿ¤ÿÿ¡ùþšþÿ¡ûþ–úùŒÿÿ˜ÿÿ›üù–ôï‘ÿí–ÿæšÿÇÚ†hì€ÿýœÿþ”øñã¦[ÛfDç_MîSSóVWòRVÒdDä¢dÿÿÅÿÿÃÿÿËÿÿÓÿÿÏÿÿËÿÿÇÿÿÅÿÿÅÿÿÅÿÿÞÿùÝŨ½ÈžçÅžäÆ¢äÇ æÇæÇŸêÆžîÅëÀ˜æ½–Þ»•Ø¿™Ü½—Ú½—Ö¿šÖá×£Լ°•ÿÿ°ÿÿÿÿ‹ÿÿŽÿÿ”ÿÿ˜ÿÿ˜ÿÿ—ÿÿ–ÿÿ’ëäpîà—ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿÿÇƽ{xpli_rmcvqgrmeolbspf{vn}uq}wr‚|wƒ~v†vŒ…|†}ˆzŽ†‚”†›‘‰—“gÂÀsÿÿ«ÿÿ­ÿÿ¯ÿÿ¯ýø£ÿú£ÿÿ®ÿÿ¯ÿÿ¼ÿÿ»ÿÿ·ÿÿ¸ÿÿ»ÿÿ½ÿÿ¼ÿÿ¹ÿÿ²ÿÿ´ÿÿ±ÿÿ«ÿÿ´ÿÿ»ÿÿ¸ÿÿ­ÿÿ¥úü™úþŸþÿ§ÿÿžýÿ‘ïï‹éå‹ôì‘øëÿñžÿæœô¥vãxhÙ fúñÿåë¬_Íi?äXUìWZðRZïV\êR[ÖxSÿëœÿÿÉÿÿÏÿÿÏÿÿÑÿÿÓÿÿ×ÿÿÍÿÿÅÿÿÁÿÿ½ÿÿêÚ¼ËɧÎÉ âÉ äÌ¡èÊŸæÉžçÊŸèÇ›çÉžêÅèÅèÇŸêÄšãØáÆœàÁ—×¾›Éµ—³Ë¾˜ÿÿ¸ÿÿŸÿÿ–ÿÿ”ÿÿ”ÿÿœÿÿŸÿÿ™ÿÿ“üô—àÌŒÿêÀÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÛÙçy|’cdmnjgnlfomgqpgvujxwlxwnvsixsi|wmzp„w~t~{q…€vŒ…|‘‡–‘jåå ÿÿ±ÿÿ£ÿ÷ŸôÞ‘ì߆ïëˆøù’ôú‘éñŒëò”åèŽãâŽîð›ñö íôôû¦ÿÿ±ÿÿ¿ÿÿÃÿÿ¼ÿÿ»ÿÿºøý©ÿÿ°ÿÿ©ÿÿ£ÿÿ ÿÿŸøþ•öù‘ô÷ÿÿœÿÿ™ÿÿ“ÿó—ÿɈá|WóniäwWÿ¬tøeÞ^Bê]OòWWú\dôRbÞQQ×\Mæ¦rÿÿÅÿÿÇÿÿËÿÿËÿÿËÿÿÑÿÿ×ÿÿÑÿÿËÿÿÇÿÿÃÿýÜȤÀȣ͚Õ˦âÄ àÆ ãÉŸæÇ æÁœãÅžæË¡êÄšã–âÄšãÀ–ÝÀšÛ¿›Ùº¢º¯¡”ðð©ÿÿ§ÿÿ—ÿÿ˜ÿÿ•ÿÿ–ÿÿ•ÿÿ’ÿÿ¡ýøšÒÇoëÚ‰ùã­ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ×ÚוˆbgZlndkmaqperqhsojoneqpgroevofwth|{n€}s€zu~v‚v‡„n†i¥ gÿÿ°ÿÿ²ÿó¤öé›÷êž÷ó™þÿ›ÿÿ£ÿÿªÿÿ®ÿÿ¨ÿÿ«ÿÿªüÿ¤ÿÿ®ÿÿµÿÿ¶ÿÿ¶ÿÿ·ÿÿ°þÿ¯ÿÿ·ÿÿ¾ÿÿ·ÿÿ·ÿÿ§ùúœúûÿÿ¤ÿÿ¥ÿÿ©ÿÿ¦ÿÿ ÿüœùåÿÇú‹sçg\úhlðceåZ\ÝPPäTUð\Zó[Xú]\õPTØ[>Û‚Gÿí ÿÿÁÿÿÅÿÿÉÿÿÁÿÿ»ÿÿ»ÿÿ½ÿÿ¿ÿÿÁÿÿÑÿÿâÝÃÇÉ ÝÇžàÁ—à¿•ÞÈžçÇæË¡êÌ¡êÌêÊŸèÌ¡êΤíÈéÂ佛ߺ™Ö¼™Ò¹£´¶«–ÿÿ¾ÿÿ¦ÿÿ›ÿÿ–ÿÿ’ÿÿÿÿŽÿÿ”ÿÿžùä‚ѵcÿßÿå¾ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿËÅε®ºgdgijeklgnlhojjtmookfpmcpmarocyvj~{o€{qyuƒ~v‚}u‡‚oŒ‚hËÃ’ÿú±íã–àÑ‚öí—ÿü¢ÿÿŸüÿ—ÿÿœùÿ˜ÿÿ¤ÿÿ§þÿ§ûýªúÿ§ÿÿ²ÿÿ¶ÿÿ¸ÿÿ¼ÿÿ¹ÿÿ´ÿÿªÿÿ£óû–óú˜ùýžÿÿªÿÿ®ÿÿªÿÿ¨ÿÿ¢ö÷™óô–ôõ™ÿÿ¨ÿÿ«ÿµ‚éjZñg`úehõ_gçQ]ßMQì[Zô^_õZ\öWTôQKÚh:ú¸cÿÿ¹ÿÿ¿ÿÿÅÿÿÍÿÿÃÿÿ¹ÿÿ½ÿÿÁÿÿÁÿÿÃÿÿÓÿÿÎÀ¤§Ï¤ÛÇžÛÁ˜ÜÉ äÉ äË¢æÇžâÇáÉ›ãÉžçÇ›êÈœèÆšæ›áÁß½šÕº˜Ì¶¤¡ÈÆŽÿÿÅÿÿ«ÿÿ§ÿÿÿÿ˜ÿÿ”ÿÿÿÿ•ÿÿ¥ã̆éЈÿá™öÖ«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¾ÁÀ¯³«`eZdi\QTAUUEmkemj`ql`roconctpkyrtvpm|wo}xp€yr„z`„VìÛšöß‹ùèŽÿö˜ÿû þù¤ÿÿ§ÿÿ¨ÿþ§óá•çÙ…úï•ýù›ÿÿ¥ÿÿ§ÿÿ¦ÿÿ§ÿÿ¢ÿÿ¦òù™áèŠäêùÿžþÿÿÿ¨ÿÿ¢úùšùõ›ñî›óï£ûú¦ÿÿ§ÿÿ¨ÿÿ¢ÿï”ÿÓ|á€Sì][öedøbcð[`æS\îY^óZ^öX^øR]íQMíYIæXÿûÿÿ¿ÿÿÅÿÿÍÿÿÕÿÿÍÿÿÇÿÿÇÿÿÉÿÿÉÿÿÉÿÿææÍÁÃ¥¿ÃŸßÁß»”Ú»—ÙÅ¡ãʤçÇáÀ—ÛÈžåË¡êÈœèÉžçÈæÆáÅœÜÀ™Ï»–«™ïëªÿÿ¼ÿÿ¦ÿÿªÿÿ¦ÿÿžÿÿ“ÿÿ“ÿÿ›ÿÿ’ÚËiëÏ{õË…ôʤÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÖÑѲ­¥ca[cca¯¯±ÿÿÿ‘“—fkkjkfnkcpmerogtqi{vn|wo}vo|wm|wmz_›fìߣþï¢ÿ÷£ÿû¡úöšÿÿ¢ÿÿ«ùôšùíùç‚ÿù•ÿÿ¢ÿÿªÿÿ¬ÿÿ¹ÿÿÁÿÿÁÿÿÃÿÿÂÿÿÁÿÿ¶ÿÿ¢þÿ•ýþ“ûý˜÷ûžüý¡øöžôó–ÿüžýù›øô˜ýú—ú÷ÿé“ÿËŠÞoRóYbþekúagñZ^ò[_ø`aöY\óPZóJ\ÜQQßp]ÿÙ˜ÿÿ±ÿÿ»ÿÿÇÿÿËÿÿÏÿÿÍÿÿÍÿÿÇÿÿÁÿÿÁÿÿÃÿÿ䧮ÀŸÃÅ›ßÁ—Þ½–޶׻“ÞÅ›âÊ ä×ãÆ™íÅšëÅëÆžéÀ–ßÃœâœ߼šÎ¶™À»±•ÿÿ¶ÿÿ±ÿÿ§ÿÿ©ÿÿ§ÿÿšÿÿ‘ÿÿ–ÿÿ™÷êÒµzå„íÀ‚õƤÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòòâÑÎÆ£š›e`bdadÀ¼Âÿÿÿ–’šleqlgk_YVMJ@]]MggUop[ts_wsb|xi}xl€wV´~ôì¡ÿÿ£ÿÿ¥þÿ©ÿÿ®ÿÿ»ÿÿ¯ÿó•òêþùÿÿ¥ÿÿ¨ÿÿªÿÿ¯ÿÿ¹ÿÿÄÿÿÊÿÿÌÿÿËÿÿÊÿÿÄÿÿºÿÿ»ÿÿ¯ÿÿžÿÿ›ÿÿŸÿÿ£þÿŸýþžúû›ÿÿ¥ÿÿ¡ÿú™ÿåžÿ¢wåhZô\iûcpù_lóYdö\gû\kùThñM^ïK\Õ_NñªvÿÿÃÿÿ½ÿÿ¿ÿÿÃÿÿÅÿÿÇÿÿÇÿÿÉÿÿÇÿÿÅÿÿ¿ÿÿ»ÿÿܾ š¬‰¥¹“Ò½—Öě۾•×¾”Û›áÀ™ßÀ™ß›἗ÜÂâÁßÁݼ›Ø»š×ºžÎ³š¾Í¢ÿÿ½ÿÿ«ÿÿ ÿÿœÿÿ™ÿÿ–ÿÿ—ÿÿ˜ÿÿ’êÕuä½x꿀￈ò¿¨ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÏÅÏÊÃÕ’Šc`a_]iÆÄÎÿÿÿˆ‡Œiikjin´°¸éæÞÄ¿¨¯¬‰¢žpœšp“‘k…‚a†dˆkíçÇÿÿáÿÿêÿÿðÿÿîÿÿñÿÿíòêÂäئïç¸ÿþÒÿÿàÿÿìÿÿëÿÿÚüÿ¶ÿÿ¢üÿŸÿÿ¨ÿÿ¬ÿÿ²úÿ§öü£øÿ¤ýÿ©ýÿ¥ÿÿ¯ÿÿ¯ÿÿºÿÿ´ÿÿ¶ÿÿ¬üøœìæ‘èÛÿÒžä‚fÐ\MâYZßTTÝMNÚLQÛOXåQ_óXjäP^àQ]ÎwWÿå™ÿÿÉÿÿËÿÿÅÿÿÁÿÿ»ÿÿ»ÿÿ»ÿÿ½ÿÿÁÿÿÅÿÿÁÿÿ¿ÿÿ¹ÿÿ¬Î·‰§€³Ž±¿—Ô¿–Ø¿”ÝÀ™ßº•Ú±Ï¾šÚ¿›ÝÜ⽙۽™Ù·”ϸ•Î¾¦¾² ™òí¶ÿÿºÿÿ¯ÿÿ¦ÿÿÿÿ”ÿÿ‹ÿÿŠÿÿ—ÿ÷ŽßÃhè½sà´oéº|긜ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿñðç­¬˜²°¡ˆ…{ec_ebeÚÚØÿÿÿƒ}adaqsiÖÕÈÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòûÿëÿÿðÿÿôÿÿöÿÿ÷ÿÿðÿÿõÿÿõÿÿëöóßÿþñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþìéÝ»³Ÿ³¢“È«¥ÙĻϾ´¶››Î¥±Áv„Ë]pÉX_ÉVRؘdÿÿ¦ÿÿÁÿÿÇÿÿÅÿÿÅÿÿÁÿÿ½ÿÿ¿ÿÿÃÿÿ¿ÿÿ½ÿÿ½ÿÿ½ÿÿ»ÿÿ¹ÿÿÃÿý²¸‡¥Ÿ³ŒÀ¿˜à¸“Úº”Þ½˜Ý¹“Ö¾˜ÛÄšáºÔ¼ÔÁ™Ô´’Ä°šÃ¸†ÿÿÁÿÿ­ÿÿ¥ÿÿžÿÿ”ÿÿÿÿ‹ÿÿˆÿÿñÛsܹgç¸|éº~麀ç´ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿš™¤™–¡œ”|yqa\\icjçâæÿøú||da`ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿߨ²aj»gdóÇ‘ÿÿ¥ÿÿ¹ÿÿ½ÿÿ½ÿÿ¿ÿÿ·ÿÿ¯ÿÿ±ÿÿ³ÿÿ·ÿÿ»ÿÿ¿ÿÿÃÿÿÁÿÿÁÿÿ¹ÿÿ±ÿÿ³ö爱˜z«‡ª¶’Ž˜Ý¼—Ü»–ݽ˜ßº•Ü¿˜ÞÀ—Û¼šÐ·œÇ° êç”ÿÿ¹ÿÿ§ÿÿ›ÿÿ”ÿÿÿÿ†ÿÿÿÿÿø”à¾y㽀ⵂݴ}×®wÞ­•ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¦¨®ˆ…†£˜’…mh^OKHd`fÿøÿìßè|sxc\^„‚ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿۯЫ„´Žtþë¨ÿÿ£ÿÿ«ÿÿ¹ÿÿµÿÿ²ÿÿ­ÿÿ­ÿÿ¯ÿÿ·ÿÿ¹ÿÿ½ÿÿ¿ÿÿÁÿÿ¿ÿÿ½ÿÿ»ÿÿ»ÿÿ±ÿÿ§ÿÿ¤áÍtªtª…ª´‘Áµ‘Ï»—Ù¾™à»”ÚÁ˜Ü½›Íµ™¹À³‘ÿÿ²ÿÿ²ÿÿ£ÿÿœÿÿ˜ÿÿ’ÿÿ‹ÿÿŒÿÿŠ÷â~â¸vçº~ã³|ݯzܯ~ଚÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ°°°[[Y„€}Ž†‚{upWSP==;ilmÿÿÿÎÇÉnii][W®¬¨ÿÿÿÿÿÿÿÿÿÿÿÿõîü,!0=*'H4&7&2 I8)P?.UD1=,J:+1;.%;1))! xrRJ>'cQE[K56$9%E-%B+š…j\œŒdœŠl™‚qœˆzœ‰‚´§ ´¯§²¯£¬ª›¤¢‘˜–…˜”…˜Ž†¢›¢ž¡œ›”‹Œ‡}~vtifnZ_mZjs`{ œ¢’‘ØÓœÿÿÿÿ¡ÿÿÿÿ¥ÿÿ©ÿÿ­ÿÿ¨ÿÿ©ÿÿªÿÿ¯ÿÿµÿÿ¹ÿÿ½ÿÿÃÿÿÉÿÿÃÿÿ¿ÿÿ¹ÿÿµÿÿ­ÿÿ§ÿÿªÔÅf—}_ª¤²‹¼º‘Ó¼–Õßݺ¡À²Ÿ¡àØ¥ÿÿ¸ÿÿ¯ÿÿ¦ÿÿžÿÿ”ÿÿÿÿ‰ÿÿ‘ÿÿæÎtæ»|ßµsݱnã¶xÜ®wÞ«”ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿœ¡OOMnlfxvpyurfd`A>=0/4tu€ÿÿÿßßݸ¹´­«§ßÞÕÿÿÿÿÿùÿÿÿÿÿÿùøýtqrojjkf\xp^¤‚¬¤€¥›v«žx¦œu«£{©¢w¢›n¯¥~¨š{¦žz«¦£ }ª§†¨¥„·±‘¼´Œ¸°¼´…º®…¦s¨žw­¥t³©rº¯}¾³…¿¶ŒÎÆ¢âÛ¾ëæÑëèÐäâÇàÞÁÝÙ»ÝÙ½åÝÇìåÌìâÈá×»íãÇøñÖóî×êçÑÏκš’K8J}—…’™lÒÏ~ÿÿšÿÿ’ÿÿ—ÿÿœÿÿ¡ÿÿ¢ÿÿ¡ÿÿ¦ÿÿ¨ÿÿ°ÿÿ³ÿÿ·ÿÿ¿ÿÿÇÿÿÃÿÿ¿ÿÿ½ÿÿ½ÿÿµÿÿ¬ÿÿ¡ÿÿŸÿÿÇͪŸ‰f}²ŠÇ¶“άŽÊ§‘¦ºª™ÿÿÁÿÿ§ÿÿ£ÿÿ ÿÿ ÿÿ˜ÿÿŽÿÿ‰ÿÿÿõŠâÅqà³wà³uÙ­lתnÚ¬uØ¥Žÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ’žIE[a_inkjtqpgbbXSW4.7($,Œ“ÿÿÿ§ ¤‘‰’oftÔÐØÿÿÿÿÿÿÿÿÿÿÿÿíòð†ˆ~zxgsrZ‡…f˜’p˜Žk†|Y—j—f‘ˆ^“‹ZˆR–Ž_•ˆd˜‹g›Žj˜‹gŸ’p˜‹i “q“n›‘j£špž•i–Ž] ˜e™‘^š_Ÿ—h®¥yµ¬‚À³®¥†Ã¾§ÍɯÐÉ®ÓË·ÛÑÇØÒÄàÚÊÜ×ÀÞ×¼âÛÀëäÉäÝÄÎðÖκìçÒ§ ™PFPueq‡r€Œzw‘pµ®vçæ‡üÿÿÿŠÿÿÿÿÿÿ¡ÿÿ¥ÿÿ§ÿÿ©ÿÿ«ÿÿ°ÿÿ·ÿÿ¼ÿÿ¹ÿÿ¹ÿÿ¹ÿÿ¹ÿÿ¶ÿÿµÿÿ®ÿÿ£ÿÿ¥ÿÿ©ÿÿÆÊ«š—w„¯Ž»¶¥›ãßžÿÿ»ÿÿ—ÿÿ™ÿÿšÿÿšÿÿ‘ÿÿÿÿŽÿÿìÑvÛ·jà±sá´vê½Ù®qׯq௕ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¤ ¦RNT]W^a^]moelkbic^WTU0.8 !,&-@: 720-#BBBßßßÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿÿùööäÒÐÁ¸±¨ÇļïðëÿÿÿÿÿÿÿÿÿÿÿÿþýÿííïËÆÆh`\m`[wd_sd^sfaufiucpubr}j|~ok˜‰q¾µxäàÿÿ“ÿÿ‡ÿÿŒÿÿŒÿÿÿÿ—ÿÿ—ÿÿ¢ÿÿ ÿÿ¡ÿÿ ÿÿŸÿÿ›ÿÿÿÿŸÿÿ¡ÿÿ£ÿÿ¥ÿÿ§ÿÿªÿÿ¥ÿÿ¡ÿÿ£ÿÿ¢ÿÿžÿÿ ÿÿ—ÿÿ“ÿÿ•ûì†ãÆræ¸wå¶xã²yâ³uã·vç¸zã²yÞ©”ÿÿÿÿÿÿÿÿÿ¸ºÀTSXWWYYVWTTVONUGGIGGEJKFNLHCA;(& ;89=:;&!%<2:J:FVGNl]b‚wv†€„s~|myudzr`yq[{qYunUupYsnWwoYwr[wr]xs`uo_vs]urZroYwt`vs[|x^zsX~rYwpWhcLJE.722,0)1+(HBKòïòÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿèã㢗–pjgQOK?B?JOM½¾¹ÿÿÿÿÿÿÿÿÿÿÿÿÿÿýàÝÓqjcg\I|nQ|nQqTviWpa[jZ[cQ\k[etgrypc‰€_¾¶täÝ{òò|üÿxþÿxÿÿ„ÿÿ†ÿÿÿÿÿÿÿÿ–ÿÿšÿÿ–ÿÿšÿÿŸÿÿ¡ÿÿ ÿÿÿÿžÿÿ›ÿÿšÿÿšÿÿœÿÿšÿÿ”ÿÿ“ÿÿ”ÿÿÿûêÍyÛ´oä²|æ·{éº|ê½å¸|à³yÜ®w߬—ÿÿÿÿÿÿ’¢HCPVPWURSSPOOOMFIFAFB=DBDIGGJI775,,,AB=87.JI>KHINNNQPGOMGKHGIGCDB<==;;>??BC=<9/FA7gc`PLROMInka{xp]YVZTOc\U`[Q^[Q\[PXWNTVLOTIGM9EI/<=&63XUIVTNWUOPNJHIDEFA=?565(/2!14!B:$A.A- @,;- LA,ðëáÿÿÿÿÿÿÿÿÿÿÿÿÇÀÄwhP€k5cMcH K9 :.ZWh]c£ÿÿÿÿÿÿÿÿÿÿÿÿóéÏ­˜p…mHw]=mY9n`CrN„xM}uBƒ~E{sKj^G]L@\HHeTXl\ftg^šŽsÍȃö÷Œÿÿ“ûÿ„ÿÿ‰ÿÿÿÿ‡ÿÿ€úÿyÿÿ†ÿÿ‹ÿÿŽÿÿ’ÿÿ—ÿÿ˜ÿÿœÿÿšÿÿ“ÿÿÿÿÿÿ†ÿÿ…ÿÿŒþö‹âËwâ¼â·|ä³zÚ«qݯxÖ©oß²vß²xÞ°yÛª”™‘š=88JI@RQFTQGHFB@@B??A=:=44643865<0.:2.470051.-+%'&0.22"CB5FEyrg|wkyvlnkc`ZUJG?87.860965GB6g\G©•jõÕ”ÿö¸ÿê¯ìäÀÿÿÿÿÿÿÿüþùô͵¯_àÚuÿÿ–ÿÿ”ÿìyÿ¢LTFniV×ÓÐýûÿÿÿÿÿÿÿÕÅ­¨Œf¨Š`Ÿ}Pf?nZ:fX4xnI|sGxp=|u?xq;‚zI{rF^R7ZHAm__xktylc¡•zÙÑûõ÷øúÿtÿÿzÿÿwûÿrûÿrÿÿuÿÿvÿÿÿÿ„ÿÿŒÿÿ“ÿÿÿÿŒÿÿ‰ÿÿÿÿˆÿÿƒÿÿ†îÜwÒ´gØ«xÝ®|ç¶„í¾„í¾€å¸zã¶zß²xÜ®wÔ£/21HEDMFFVOONGG@=<88877523.68.-,!,+"'%!'%($+)%))'&($#)% A89G@@QJJQMH]\Qkj_WTLSOJWSPXTQXTQTTR8;åäÎõôçùù÷ãçáÿÿÿ…‰ŒWZfXW\g``tmm†}€|xssuifh\PRF=?520*-!# E1:¨–¡À´ºÓÌÎàÜÙçåßòëÎàÔ¢÷ð¥îëˆÿý•ÿý’úê‹íг¡qµ°ÿÿÿÿÿÿÿÿÿÿÿÿûîܼ£~¼ l»œY¸›`›|LpW2lV@rcDwmH†~M{@xr4„~@’ŠW†}SZP6J@6gYYwep„rk° †Öʉöë†øôúû{üÿvûÿqûÿqúÿrÿÿwÿÿ€ÿÿ„ÿÿŠÿÿ‰ÿÿ‰ÿÿ†ÿÿˆÿÿŒÿÿƒ÷è‚àÁwÝ·v巀ܱtÛ°qÛ°qÖ©mÔ¨pÙ¯{×­y᷃䶟EECFGBFD@KICOKFKJA68.34-775FCD&#% $'#)####"& !"1/+950F@;JB>F@;HD?NLFWUOdb\QMJRNKVROVTPWTSQQS)+1IPBßëÌ·Á¢êñֽ³ÑÔÓšžUW[XXXZVS]XXYRTTPM_[VtpkŠ†€tkj]OKF/(,zv~ÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿ×ýö­ÿÿŸÿý™íâúéÿô¥ôå´ÿÿóÿÿÿÿÿÿÿÿÿÿÿÿÿÿò˶}ʳqΰhÔµrÁ¡eŸ…S…mHgV3gY:vmC„~Jzu>mf.yt=ƒ}IˆT†|YSG9LE9¯»œßêÄ´»’‘’y×ÒÊuqw[XkXT\YURXVRXVR]YTYSNXUMWTLVSK_\Tgc`kfhQO[vwÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¬žzªˆYÿê§üë•ïã éá²ÿÿîÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÜÁ˜Ü¼‚Û·lÖ¶eØ»gŨY°’J¥P“|Pyi?viE|oIznEsj>sk9!#  -     (#%?88!B?@9:5Y]UFG@DB' $    -   - -!"JADZSWUMTB?B>>>DDBLLJNKJIDDB?B76=438:9>032*-*LOLNNLDB<<7-A97QEKULOULOTOORPLQOKPNJTOOYPUVOOTPMOMILJFNKLNJRMM]eh€ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõìÀûåœþÙvïÆrÛ«iØ«mã·Ù²xÆ¥kŦeʬf¼ iœƒ^~hPsaUm`LrkN{uUypQkaI_SEF<6:.21(-E;EaZSkcO“‹\¹±fÛÑpëàkñïpòõnôüqôÿqùÿtýÿwÿü‰ãÊsÊ«aÕ®tܶyç¿îÆŠôÈúΖôÆ‘ôÇê½ä¹~Þ²zÛª”59304,24*23,42.4508;8>?8/.#"$% )*#21&=94=66-((B==c\\d[\_[XYWQPPNNNPMMMLIJGDEFCD;:?75?44401*/0+965GDEQNQPMLPNJRMMSLNRPLOPIJKDMNGUVQOOOMMKLIHKIEJHBGHAEF?ELLQ^eÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿììîÒÒÒÔ̶ëÙ­æÉŒùÐ…úÒ‚öÌ{Û²iË£eÚ´sÔ²m½šX¾˜YÆ¥kέ{¹›o£‡aŽw[xdT^N?VJ>TH=;7431--+'##!%%'+++@@@OLKSOLRNKQLLLJFHIBLJFMHHHF@GI?IH?MIDMIFKFFHHH]`aÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþþÿëëë××׺º¸ œŒ‰wsumih`\^VRRGFC:;:14`L:£~ùÑžùɉñÄzöÊyöËwá¶bÁ›QÆ£cȨg¸™Z«ŽQºbÇ«kÁ¥a²”\°eª’d–„VyhCqaGdT>M<-<*#/ -%A3CdW`k_cƒzYÁ½uïð‰úýxòõlýÿsÿÿ‡ÿòŒéÏ㼄Ẃܵ}Û´|㺃߸€à¸ƒÙ¸|عxعvÒ²oίi̪cÉ¢{(0)*0'+-#,-&01,23,64.?=7GEAMNI01,  SUYa^ai`eb]]ec_db\a_Y\[R^]T`\W`YYZVSYWSVTPVTPURQRMQKHIJJHGHCEFA@A:8:045.31--+'#ɉBB@FG@IH?IGAGBBGEAFD@FD@CA=BC>FGBEO<7J+–¢Žptn`]\PGJ@46=-.<-0C7;JCEXSUa^]fd`mkeqoiijcfgbjhbXTOg]UfSL„eRÀ”xೀܭdäµlñ¿yé»xËž`Äœ^˧lâh®ŒU¾hÊ©wǦo¸˜\¹˜aÇ¥vÛºˆÐ¯}çsÁ§u´Ÿa{6M:2!R?AjWkscmtff¯¦zìçÿþ£õêÛÉŬr¿ aÉ¡aË£gÆšdÆ c¿œ\¿™ZÁ™]Ç¡bÈ¢cÊ£i̤oÍ¥pΦqÕ©‘,*$)*%'*),,.1-342,;;)>A0>@4=?5"#!TPK^WP\TP]QS^UV]TW]VV^YY][W\ZTXVRYTTWRRZUWWUQXWNWSPVOQTOOSQMLHCNIAMJ@IH=C@8D>9@:7>586/1+&*%%%+%";74A<HHFZUWaW_jcgJEILHE^[Sa^Vd_Wa^Ta`Sa`S\[PWXQNQPNQPKNMJKFA>6<83:63@86I;;Y@4jS¸pÉšvÕ«wسoÁœXº’RʤeÆ¢gµZÁœkЯuѲsĤe¾—]È¢eÚ²vÙ±qÅž[È£_Û¶räÅ„¸asZ8_J?gURhW_hVOq[ ’lž\š†FÍ´héÊ€ñʃïLJ迈㽀߹zá»zâ½yä¿{ä¼|ä½zâ»xã¸yå¸~ש"'%"%&&%*++-2/230/62-860:826:4#JEI\YXIGCFD>KGBMIFJEEJEGICJKFHPLIRPJVTNTPMSLNWRRVQQRNKTPMVROZUUXTQVPKVSKONENM@IG8JE9JC:D<8<34:6113).,&)%" !/,/;;;AA?DDBFCDHEFJEGYTV[VZ^[\[[YLMFHG77=53;74973=<3A@5FE@4B?5:3,83+0,'%$!!#779EEEBBBGGIHDLD@F@=@:7863220*.-$*("+(')*%&'"'$#'"&%"#%"#""" #" # !$!$$"(%&&&$))'))')))--/406<40VE;—hÀŸ}¹—hÆ¥i˧l¼•]¾—_Ë£nЭkÒ±cȦ_ЭmÛ¸xͪjÈ¥cÔ±oɪdÈ©cÀ¡[ήkÔµoعqÚ¸sâ¼{ä½zç»xÒªlÛfɤpÏ­{à½ä½xá¹{Ö­vΨiÞX½›V¯ŒL°MÁ›\Åš{*+&()"()".,&1+(/+(/**1/)43*<;2]\SmkgC@A$$&!1**/((2)*/+(,*$10'32)53-<77<:6@>:DE@LLJGGELLLJJHOMIYSPYNMTNKUSOOPKSSQXVPWTJUTKVWRQRKJLBIH?GB:C@8BA8A@554'-/%&&$ #" ((*ICJJEI>9=:7667245023.01,/-),*&-+'+&&+$&'""%#"" "%$"%&"$($#(($,****+$+,%+,%,-(1./0++3*+5& 6`E*¢‚Y¶“fÄškÇŸo¼“fÄ¡cѲhÚ¸sʤeÄ¡aѱrÛ»xÀ¡[ʪgήmÓ°pÓ­pàb˨j×´tß¹xÜ·qܵnÈ¢cµX¸“_˦uçÀ†ì€â·zÏ£kÆŸ\Ç£XÍ«fÔ°uÛ¸xâ¿}ðÆ¢-)&(& +)#/.#*)-,#,(%.*%30(DA9ZUMSPH:90+*!  #"! "" %%%(%$(##,')2-1724;66=96D>;D?7JC:LFANGGOIDSNFVQIYQMYSNRNIXUMWTLXUKXSGRN?WQCOH=MC=KF:AA1<9-;6,42,,,*&&&$!$  #&),+775997412/,+.,(,-(),)'*'&)(#'%'$&#%$% $#(*'*+&(-((2,).,(++),,.+*1,,,,-(-)$1)%1&%0%0S;$rQ»—málÅ¡fɦdݸrÛ¶r̤fͧfصsË«hÀ ]Ò¯mà¸xá»zÈ¢c¾˜YШjܱtçº~é¾Ö®rÀš]¿˜^Ç¡dÙ³tÛµvÄžaµŽT·X¼—a nÄŸiÈŸhÔ¨Ž/-)+*!,+,,)''%&#(&73$JE=LCD<8354+/+(  !'$'*'(-*)31-3/,:84;95CB7DD4LK>IH=KJ?PMERMC\RH\UL`YRYTHXTESPFVRMYSNTLHOJ@MJ>MJ>A>4>;395242,21(.+#/'#&"! "&(+,/21-0-01,)-'#($")")#(%'#($( )+!+*!+*!,*$,.$(-"(/#(/#(- *, *, .-",.$,-&/+&2'&1 $/<"V:&‘pL¼—c˧nÚ´wÌ¥m½•bÅ¡fаmЮiÅ ZÒ«dÙ°gͦcÆ cÒ¬o×®uܵ{佃ֲw»—\²’SãdصuÙ³rɧb¼W²’SÞhÍ©pͦnÌž‡,(#('+*!*) ($ # +)%64.DE>892(%$'"&&#&$!$ - - -     "" *'&.''4.)4/'72&84%;8,A>4D>9G>ALD@RKBVOHUMKULMYPU[RU\STYSPTPMWSNSOJQPEIK=DF:GF=?A59;-87*41'.+#0*''# &%+)#)$&+)#)++( /'#1&%3$)/'.+&1*&.+'/+*/(*.')-%$)*'(-)&.(%1()/(*/*.+('*+&(,&(.',*&1&%1#9(bL-™{Qº™gرwÃœdÄšf̤hÒ«hÆ¡]Ç¡`Ñ«jÓ«mÒªnÕ©sÙ°yÙ¯{⺅ڲ}¿›b¼˜]È¥cسmÚ¸sϬjŸa¸[¿™\̧cקŠ(((&'"$%$&%$!# ,)(854/,+&#"$!"$%  -      -   $ !!#"!#(&()$1,$/,$40+82/:14D>;IC>MGBRJHPGHSJMRKKVPMTPKWSNXTQVOOSMJTNISNFOJ@OK:JG/IG6?>3=:2;520-%+*!#"###!$( )+$(0'*.%(/&+,'+&%*))),*&-+%/,$,''.&-+&(+('*($+)#/+(/(*,')-(,*).()2*-./0+01*35+SSCjbNcP9•{YʧzͨtÇžgÌ¥kÔ®qͦlÏ¥qÔªxÍ£t¼”_¸”YÑ«nÕ­oسmÆ¥WÅ¡VÉ¢]Ú³lå¿uá¼tÕ°jÌ¥`ÈžZ†\ No newline at end of file diff --git a/example/dev/file_grabber/image/img0256.ppm b/example/dev/file_grabber/image/img0256.ppm deleted file mode 100644 index 2393aa9d826..00000000000 --- a/example/dev/file_grabber/image/img0256.ppm +++ /dev/null @@ -1,14 +0,0 @@ -P6 -128 128 -255 -an€`pev‚hrxlqo|zv°¨¤|y|ux„q{…ky„m|„o~„k}‡[o}[mwr„‹“¢ª ¬¸Ÿ­º¢¯¿«¸ÈµÀÓ·ÄÔÁÎÞÈÖáÈ×ßÔâäÞêèáèèïòóíðïëîíïòóôóøúùþöõúô÷øðóôúúüÿÿÿÿÿÿÿÿÿýýýýýýôùùìò÷ÜæìÕâéÐâéÅÚãÂÚâÆàçÀ×ä»Ëá¿ÏçºÊäµÌæ®Éä«Æ߬ÇÝ´Êà·ÆÞ²ÂØ­ÀÕ­À×®ÁÚ±ÄÝ®ÁÚ±ÄÛµÈß²Çâ°Äæ«ÂÞ£½Öž¸Ó¥»Ü®Äã«ÁঽפºÐ¦¾Ó¥ÀÔ¤¿ÑŸ·ÊŸ·Ì¨ÀפºÒ¢±Î¤·Î¡´É›²Ã ·È¤¸Ê§¶Ì£²È¥´Ê£³Ë¢²Ì ³Èš®¾£´Ã¦³Ã °¿­¾™©¼¦²É¦µË—¦¼•¤º”£¹’¡·œ²‡—¨‘ ~Žw‡˜t•q{“jzbvˆ\p‚Xi|TexRawUev]jzN[d`mfs‡ep…ktƒmtyyw¬¦˜}~yqy}jxzi{~k}„p~‹jz‰brƒ^np€‘‹˜¨˜¤²š¨µ¥²Â±ÂÌ°ÃÊ·ÉÓÀÑÝÂÔÞÈÚäÐßåÙäçÞæêáæîäêïèîñçììîñðöùøíðïêíîñðõùùûýýÿøøúöõúðóôùüýîñòïñõçíðÞéêÙëòÇÛëÀÙå¹ÖÞ¼ÕáÆÚì¼Ðà¶ÊÚ¯ÈÔ©ÅЭÆÔ§»Íª½Ö¬ºÞ®ÃÞ¹Ñä´Ìß´Ì߬Ä׬ÄÙ¯ËزÏ×°ÌÛ©Ãܧ¾Ú«¿á·Èé²Áà¬ÁÞ²ÈçªÄÝŸºÐ¢½Ï¤ÀϤ¿Ñ§¿Ô¥»Ñ©¹Ñ¢µÊ¢¹Ê¤¸Ê£´Ç¥¶É¤³Éž®Æ£³Í¤´Î ¯É¥µÏ™¬Åš­Äš­Ä°Ç£³Ë£³Ë ¯Ç–¦¼–©¾›«Á˜§¿’¡·’¢µ¢®ˆ›¢‡™£‡˜§€‘ z‹œt…˜m|’l|fv‰`pƒ^nYh~VeVe{R_sETZamyp|ˆjs‚hu|fvwuzv·²¨|}mzhw{j|k}‡m~k|‹cs„cs„n~ž’£¯—©µ¤µÄ­¾Í³ÃÔ¸ÉÕÂÐÛÁÓÚÂÔÙÈÚßÐâçÕçìÖèíÕãåàèêåîíáèèèííîñòîñòúúüôôöúùþöõúòñöìëðíìñíòòåììàëìÛéëÑâìÅÕëÀÔä¼Óà»ÒßµÌÛ²ÆÖ°ÁÒ²ÆØ·Íã¹Ñä²ÊݵÍä®Ãà«Âܧ¾Ø²Êß´ÊÞ¯ÅÙ¯Â×®ÆÙ¨ÄØ©ÄØ­ÃÛ±Èä­ÃäªÃá«Æá«Æá©ÄߣÁÙ¦ÅÚž½Ò©ÅÛ«ÇÙ£ÀÏ©ÆÕ¥ÁШÄѧÀΨÁÍ›³½¢¶Ä£´Å¡²ÅŸ¯ÇŸ²Ç«¾Ó¢¸Îž´Ì—­Å˜­È™±Æ“¬¼™°Á¡²Å˜¬¾”¨º“§¹”¥¸Œ®®Š›§Ÿ§Š›¥ƒ” ‘yŠ™u‰—j~Žg{‹dxˆbs†]l„Wf~Wf~UdzP\s=JS\lXhydqƒgu‚fs|uzz½¸°€ƒ‚lv~iviw„lz‡o|Œjz‰iyŠ^nm|”~ŽŸžª—§¸¢®Åª¹Ïª¹Ñ¬¼Ï¹ÆØÀÑàÀÔâÀÕàÏáíÊàæÎäèÐãæØèéßííåíïäìîâêìèîñöøüéìíóóóô÷öíðñóøøîóóéôõÝìð×éìÑãèÆØßÈÖãÂÏáÂÎå½Îß´ËؾÒâÂÒå»Ñç·Òí¨ÃÞ¨Á߬Æá«Âܧ¾Ø­ÂݯÄ߯Äá°Åâ±Ãá°Â௾ݮÀÜ®ÃÞ¬ÃÝ¥¿Ø°Êã²Éã²Êá¯ÇÜ¥½Ô§¾Ø¥ºÕ­¿Û§½Õ£»Ò•°Ä–²Ä¸Ê¨¾Ò¦½Î«¿Ï¨¼Ê¤µÄ¡µÃ¤¸Æ¨¼Î±ÄÛŸ²Ç¡²Åœ¯Æ”©Ä ³ÌšªÂ’¡¹š¦¿™¨À¬Æ”£½–¥¿˜§½ ³ ¯¢«Ž£¬„™¤‚” ‘ žsƒ”l}Œev…cw‡cw‰Wh{R_sR_qMZj8BL^kYiz\l{es€iuuy~½¸¸…Šox‡fs|kz€o~„n}ƒn€…l†pn{z‡›Œ˜¯”¡µ ­Á¨µÉ®»Ï²ÂÓ´ÅÔ¶ÇÖ¿ÏÞÌÞêÆØäÀÕà¿ÔßÈÚæÒãïÎáèÐãæØçëÜãêÖáäÞéêçòóåðñÛééÜêêáðíÜëèÑääÂÕÚÏåéÔêîÑæñÇÛíËâñËâñ½Ñã»Ëá·Íã²ÊáªÅÛ­ÇàªÆÚ¥ÂÑžºÎŸ¹Ò¨ÂÛªÄݨÃܬÇà¬ÈÞ«ÇÛ³Ïá°ÍÜ°ÍܬÈÚ¬ÇÛ±Èâ­ÂÝ°ÂÞ¯ÅÝ«ÁÙŸ¶ÐŸ¶Ò¦ÁןºÎ¸Ê¥¾Î¢¸Ì ³Ê¥»Ó¢·Ò¡¹ÌŸ¸Æ©ÀϤ¸Ê¡µÇ¥¶É±Á›²¿›³½²ÇÒ¢¶Ä®Á¡¸Çš³Á˜¬¾ ¯Ç›«¾”¤³•©·‰¢®‰ ¯Š²‡š¯„”ª~’¤{¡z‹ž{ˆœzŠrƒ–p€–ix’dtŠ^o‚XizVfuUfrM^h0>>]m~Vfu\mygu€cpyqxx½¼³…ŠŠpv„ivo~„p…o~†iz†l|iyŠp}‘y†šˆ”«–£· ­Á¥µÈªºÍ­½Î­½Î¸ÈÙ¹ÆعÉÚÀÐá½ÎÝÂÖäÌÞèÆØÝÍááÔèæÖèëÎÜçÏáæÓæéÂÖÖ´ÇÇÃÓÔÔáæâððè÷ôÜðëØìêÂÕÚËÝéÅÙé´ÊÞ³ÉÝÀÓêÄØêÔåö¾Õæ¯ÊܨÄرÍã°ÌÞ®ËØ¿Ûí¬Çà¥ÁתÅÛ¥ÀÔ«ÆÚ¨ÄاÃ×­ÉظÑß¹Õä­ÈÜ¥¿Ø£¼Ú¦½Ù¥ºÕ¨¾Ö¤ºÒ©¿×¥ºÕ±Éࢽј³Ç›¶Ì ·Ñž³Ðš±Í™°ÌŸ·ÌžµÆ±Á¥¶ÇŸ°Ãž­Ã“¤·—¨»Ÿ³Ã£·Ç±Áœ­À™­½›¯½™­¿›«Ã‘¢³—©µ•©·’©º“¤·‹—®Œ˜¯„©¦¥zŠ {Š x‡t€™n}•jz”at‰dxŠ_pƒbr…hu‡U]o29@VfyYix`n{`mr_hgrvn¼¹­†„ly‚jv‚oz‹q|p{gwŠcs‰hyŒm~‘wˆ›€£ŽŸ²œ¬Â›¬¿§·Ê­¾Ï­¾Ï²ÃÒ¹ÊÖ¼ÌÛ¹ÉÚÂÓäÂÖæÌàðÂÖæÀÔä¸ÉÚ·È×»ÌÛËÞåÝïòâô÷åôøÔãéÏÞæÐßå×æêØèççøôÝðõ½Ôá¿ØäÀÙåÄÝéËäòÁÚè¸Ñá¶ÒáªÆÕªÅÛ¯Èæ©ÃÜ­ÅܯÉâ¨Âà©Äß°Êå¬Çâ¨Âà¬Çâ¯Êã©ÄݯÊãªÅÞ®Éâ¯Êã³Íè¨ÂÝ©ÃÞ¨ÂÛ±ÌâªÅÛ¥¼Ö›µÎž¸Ñ¨ÂÛ¥¿Ú›µÐ£½Øž¹Ïœ·Ëž¶ÉŸ²Ç°Å•¨¿›«Ã£²Ìœ«È›­Ë›±É–®Ã–¬À°Å™¬Á”§¼‘¤¹›®Å™­¿–§¸“§¹–©À“£¹œ²ˆ—­™²Ž¤¢}£wŠ¡uˆŸo—i}j~Œd{ˆ_v…`t„\l[h|RZp'1;YgtXew[e}^gv_fopst¸²­…ˆ‰q{…ly‚q~‡p~‹mzŽbs„dx†h|Œp”w‡ƒ’ª‰™¯Š²•¥»¢±É«¼Ï«¿Ï­ÁϲÇÒµÉÙ·ÇÝ·Êß´ÇÞ·Íá·Íá»ÓÝÒèìÌáìÆÚìÈßîÀÙåºÓßÆßëÂÙê¿ÏçÂÒèÏàóÂÙèÀÙåºÖãÀÜî¶ÒáÄÛêÂØìÀÖî»Ñé·Ìç±Éà«ÆÚ«ÆجÇÙ®ÆݯÃã¨ÂÛ£Â׫ÇݪÄÝ«ÅÞ¨ÂÝ©ÅÛ¯ËݤÀÔ¥¿Ø­Çà«ÂÜ¢·Ò±Ãá­ÃâªÃ妿ߥ¾Þ¶Ö›´Ô™´Ï¢¾Ô£¾ÔªÁÛ¨¿Ù µÐ¨»Ô¦¶Ðš¬ÈŸ±Ï°ÉŸ²É¡´ÉŸ¯Å›±ÉžµÑŸ·Î›±Ç–­¾–­¼”«¼¥»¦¼›®ÅšªÂŽµž±Šž®‹Ÿ±†–¬†–¬ˆ˜®„•¨€£€£‚Ž¥{‹žq‚•oƒ•p„–jzfubrŠ[k…VfwNZf1JX$+2u{€dnv_kwZgp]gqlss±³©‚‰…n|~hw}dugx„dq_o‚brŒdtŠk|q„™s‰¡€“ª‹š°‹š°•¤¼œ¬Â±Ã§»Í¨¸Î¤ºÎ¤¿Ñ­ÆÔ®ÅÒ¨ÁÍ«ÄÒ¯Æ×´ÄÚ¶Éà±ÄÝ­ÅܽØî·Òæ¸Ðå»Ñç¿ÒëµÊåµÊç±Èâ´Ëå»Óê¶ÎåµÍâ²ÊݯÇܵËã¶ÎåªÄÝ©ÃÜ°Êå¯Éâ³Íæ±Ëä²Éå®Å᧼٦ÀÛ£¾Ù¦ÄÞ§ÅߧÆÛ¥Ä×¹ÕäÀ×æ³ËÞ®ÆÝ®ÆÙ¹Ðß¹Ïã©¿×£ºÔ¶Ìë¨Áߥ¾Þ¤¾Ù¦Á×¢¼Õ¨¾Ý¢¼Õ¸ÎŸ·Ì ¶Ì˜°Çœ³Í™°Ê™®É›«Ã¤°Ç¢²Èœ¯Æš²Å¬»•­À›®ÇŸ¯ÅŸ¯À˜¨»™¥¾–¥»”£¹‹ž³ƒ›°„š®‡˜«‚“¤ž¯€”¤}‘¡}‘£§yŒ¡pƒ˜s„•t…‘n~m|”iz^o€Wdt7?Q#-5tv|rwdktZdlYfmirq©­§}ƒˆlt†an~_o€]n[kUhZpˆ_u‹fyŽoƒ“p„’xŒš…–§’¢µ” ·‘¡·•¨½°Ç ²Î¡¶ÑžµÏ«ÃÖ¶ÍܱÅÕ³ÃÖ«¿Ñ¯ÅÙªÃÓ±ÍܬÈ×µÎÞ¯ÅݶÇê¸Éì¿ÐóºÎî¶Íé»ÓêºÐä¾Ôê»Ðë±Éà­ÅܲÊá²Éã®ÆÛ³ËÞ±ÉܵË߯ÇÚ¯ÇÜ´Ìã®ÃÞ¯ÇÞ¬ÇÛ¬ÈÜ«ÇÛ®Êà©Ãܤ¿Õ¨ÃײÍßÀØëÂÚï«ÀÛ©¾Ù¦¸ÔµË㤼ӷТ»Ù¥»Ú¤¸Ø¥º×«½Û¨ºØ¨¶Ø£²Ñ¢±Ð¡¶Ó¡¸Ô¡µÕ¡²Õš¬Ê›­É³Ç¢¹È¨»Ð¢±Îœ®Êœ®Ê˜«ÄªºÒœ¬Ä ¯É¤´Î˜¨Â–¦¼›«¼–§ºŠ´ ·Š´„—®‘«„”ª„•¨¥~¥wŠ¡z¦wŽŸr‰–hŽgzfvŒ_n†LWl:=S;@L]_evw€pq~_bnY]lkms«¨©‚‡eqYfv]m~XhyUevTevWh{[ocw‡h|Œk‘v‰ž„”¬³‘¡·“§¹—®½ ¶ÌŸ°Ñš¯ÌŸ´Ñ©»Ù«ºÙ¬»Ø­½×©¼Ó¶ÉÞ¯ÅݬÁÞ¨À׶Îá®ÄØ°ÀÖ®ÄܲÉå³Íè°Éç³Êæ³Èå°Åâ®Ãà¬ÁÜ®ÄܳÎä¸Ôê¸Ïé¸Êè±Èâ¯Êà³Ëà²ÅÜ®ÆÝ©ÃܪÄݨ¿Ù¨¿ÛªÀ߬ÄÙ²ËÙ³ËÞ¹Îé¯Æâ«Ää¯Å䫽۲Çâ®ÃÞ©¾Ù¤¹Ö£»Ò§¿Ô¨¾Ô¨»Ô©¼Ó£¶Ë¥»Ï¡·Í¦¼Ô¢´Ò¡³Ñ ²Ð›°Ë µÐ›±É—­Ã“©½–¬À°Ç¡±Ë¤³Íž©Ç—¦Ã£µÑ–©À”¨º“¦»’¥¼Ž¡¸‘¡¹’¥º‰Ÿ³ˆž²Š´€“¬­€“ª€“¨€”¦‚–¨t‡œpƒœnšj|˜h{’fzŒhxŽ`l‡R^wo{”x„FIFchdv{wjoo[^fjjj¨¢ƒ‡Š`lxR`mVcsTasTauN^qWf|_o‡kz—m€™v‰¢{‹£Ž¤†•­˜§Á¤´Ìœ¬Ä•¨¿³ËŸµÍœ¯È©¼Õ¤¶Ò§¿ÖªÅÛ®ÆÙ²ÉÚ©¿Ó¯ÅÛ§½Ñ®ÅÖ°ÆÚ·Êã²ÊÝ«ÇÖªÆÚªÅÞ¯ÇÞ¶Éâ®ÄܬÂÚ§½Ó¦¼Ò¬ÁܯÀã²Çâ´Ìá®ÄܯÁ߯Äß«ÃÚ¬ÄÛ²Éã³È嫼߫¼Ý©¸×¦µÒ¬»Õ¬»Ú©·Û¯Ä߸Ðå¬Ä׬ÅÕ¤¿Ñ¦Áק¿Ö¦»ÖžµÏ¡¸Ò¢¸Ð®ÁÚ¯ÂÙ¤·Ì§ºÓ£µÓ¡´Ë¤¸È ´ÆŸ²Ç¥¼Í§¾Í¡µÅ—¨¹™­½£·É˜«À˜«Â›®ÃŸ²Çœ¯Ä˜«Â“¦½¢¹¦º§¸‡š¯Œœ¶Š´¢·ˆ›²…˜±‰™³‚‘«€©Š•³€§xˆžvŠšr†”q…•m“j~m}“t‚ˆ’šwƒ~‹x‚Œ5:8KNMkkkvvvccckic¦£™‚†‰]eyO_nMaoMaoOcqO`q_o‚ar…fwŠj~q„™rˆœ|”©‘¤»Ž·¢»’ªÁ“¯¾”°»™¯Ãž­Êš­Æ¤·Î®ÄØ¥»Ï¦¾Ñž¹Íž¹Ï¬Ãߟ¹Ò£½Ö¦ÀÙ®ÅáªÅÛ°ËݳÎà´Ìá´Êà®ÁÚ±Äݪ¼Ø®Åß°Êå­Äà®ÀÞ³Èã¸Ðç±Ãß²À߯¾Ûª½Ö©¿×­ÅܨÀתÂÙ©¾Ù­¼Û«½Û¦ºÚ­ÂÝ´Êâ±ÉÞ¬ÇÙ°ÌÙ¬ÆÏ®ÈѤ»È´Å¤·Î ¸ËžºÌŸºÎ§¿Ö¤¾×¦¿Ý©ÄÚªÂÕ¶ÍÞ¯ÀÓ¹ÊÝ¡±Çš­Â›®Ãš­Â›®Ãš­Âœ¯Æ”ªÀ”ªÀŸµÉ˜®Âš±À—®»’©¸Š ´ˆž² ·ˆž²§º†œ´Œž¼‡™·‡•·…”³}Œ©}©wŠ¡yŒ¡v‰ž{’¡pˆ’uŒ™q…—rƒ”u‚”ž¤´ÇÅÓ‘”¨y€›s€‰-406=9LSOkslqwposkž”‚‡‡]fsO`oG`pHaqI`qMdqYq{_siz‹rƒ–v†œt‡žu‡£€ªŸ¹Ÿ¼ž½’¥¾•¨¿™¯Ã–®Á”¯Á¸Ìœ´Ç›²Ã¤ºÎ¯ÂÙ¯ÂÛ¨ºØª¼Øª¼Ø­¿Ý°¾à¯ÁݱÄÝ·Êã²ÅÞÅØñ°ÃÜ°ÆÞ®Åß°ÊãªÄ߸Ñ慨߭ÄÞ±ÉÞ¯ÇÞªÁÛ§¼×¯Áݦ¾Ó¬ÇÙ¸Óå¬ÄÙ¦¼Ð¯ÂׯÅÝ©½Ý­Ãâ´Êë©ÃÞ¥¿Ø¯Êà±Ìà²ÊÝ«¾Ó¨¾Ô¬ÄÛ£»Ò«ÂܪÄÝ¡»Ô£½Ø«Ä⤾٧¾ÚµÊ竽ۢµÎ¸Ë⤺Ҳ͙¯Å–©¾“¦½•¥¿–ª¼˜¬º—®»“ª·Ž¡¶ž»Ÿ¼Š™¶‘¡»Ÿ¹š­Æ’¤À„š²—¯€“ª‘¡·µ~ªxŠ¦t†¢yŒ¥xˆ {‹£xˆ r‚šp€˜mzŠ€Š”ºÁÊ £«‚‰”u}ly‚,54.76:AAV]Ysyptynœ›’|djxJ[eUoxLfoKcmSgu^o€au…g{‹m‘t…–sƒ™z‰¦‚’¬‘ ºŽµ‘ ¸“£¹­Ã™¯Ã”¯Áš¶Å¹È ¹É©¼Ñ©¼Ó¥µÏ¦¹Ò¦¸Ô¡·Ï«Á×¹É㯺ڱ¿Üª¹Ö­ÀÙ½Óé³Éݪ½Ò¨¾Ò¹Ñä±ÌàªÄÝ­Çà±Èä²ÌåªÆܧÂÛ¤¿Ú§¾Ø­¿Û¥»Ñ§¿Ò²ÊݵÍâ¯ÇÜ®ÄÚ«ÀÛºÎîÁÕõ´Èꦼۢ¼×¨ÂÛ¨ÂÛ«ÃØ«ÁÕ¥½ÐªÅ×®ÆÛ¬ÂÚ©¿×©¼Õ¥ºÕ«ÂÞž¸ÑŸ¹Ò©ÃÜ¥¿Ø˜°Å˜¯À¨»–±Ç˜°Åš­Â˜¨ÀŸ«Æ¡²Åœ±¼¡µÃŸ³Ã˜¨À™§Æ–¥¿‘ ¸œ´œ¶ ·‹¡·‡Ÿ´‚³y§†•¯Šš´…”±}«|Žª{©Ž«w‡¡u„žtƒ›n}•nyŠ“˜¤ÌÏÛ››«ˆ ~‰žv‚Ž5;@.47499DGFdabvsv‰ƒŠ{|…ejvZhsVjxUiwSguRfxVi€au‡cw…tˆ–{ŸŠš°|Š§„—¬‰ ­ˆœª”¥¶•¨½’¨À³É¢µÊ˜®Â•­À•­ÀµÊ¢¼Õ™³Ó•°ËšµÎž¹Ï£»Ð¨¾Ô¬¼Ö¨¾Ô¤¼Ï¢¸Î­¿Û¯ÄßµÊç¹Ðê´Ì㤼ѣ»Ð¨ÃÙ²Ìå©ÃܨÂÝ¥¾Ü¢»Û¨½Ú±ÁÛ¯ÂÙ¬ÂÖ«ÆغÖê®ÊÜ°ÌÛ©ÄئÀÛ »Ô§ÃÙÂÚñ´Æâ¯Äß«ÂÞ§¿Ô¦¿Ï•°Â£¾Ô¤¿Õ¡¼ÒŸ·ÎŸµÍ¥»Ó µÐžµÑ¥»Ú¨ÂÛ¢½Óœ´É›±ÇŸ·Êš²Å¦¼”¤¾šªÄ«»Õœ¬Æ­Ç“£¹”¤·“£¹‘¤»•¥½ž¸Œœ´Ÿµˆž²‰¡¶†¡³…¡°}•ª|‘¬z¦yŒ¡|¢€”¦|¦w†£pœr€p€šm€™o}Š²¸½ÂÉÔ•¨‚¢{‡ uƒAKU4;B/586;;JMNgjkxxzot|dmzXisYnw\m|]m€SgyQjz`wˆh|Žp„–v‰žr…œzŠ¤…˜¯‰Ÿ³£·‘¤¹Š¡²Œ£²œ°Âœ¬Ä–¦À¬Ë¡³Ï³ËŸµË¢¸Î£»Ò¡¸Ò¦¾Ó³Ç¥¾Î¥¾Î£¿ÎªÆÕ¨ÃÕ¨ÀׯÇÞ®ÆÝ­Çâ­Ææ¨Áߦ½ÙªÁÛ¡¸Ò§¾Ø¥¼Ø«¿ß¯½á®ÀÞ¨½Ø¨¿ÙªÄߧÃÙ§ÃÕ¥ÁÕ¨ÄÚ§ÂÛ¢½Ø¥ÁÕ¥ÂѧÄÓ¢¾Ðž¹Ï¦½Ù¡¸Ô§¾Ú¬Ãß«Áाٟ¹Ôœ·Òœ·Ò¤¾×§¿Ö¥¼ÖžµÑŸºÐ£¿ÑŸ»ÈŸ¸Ä¥¾Î£»Ò™±Æš°Ä›®Å¨¸Ò§¹Õ˜ªÈ£»§º‹¤²‹¥®Š¤«ž¶¾‡ ¬ƒŸ®‡ ¬ˆ ªŠž¬Š›¬†™®~‘ª{‘¥|•¥€—¨{Ž£zŠ x‡Ÿp•p•m~‘j{Žs€‰½ÄÄ«°¼Ž‘©ƒŠ£{‡ uƒBP[@JR6ANUUhomqy{eou^jvdqƒdqƒan‚WhyVmz]v„azŠj…—k†šl‚–y‰Ÿ€”¦ƒ—©†œ°ˆž´Š´ ¸š­Â›®Ã˜®Â¡¹Î•­ÂµÊ²Í£´Õ®ÅីӘ¯É™®É¯ÅݯÅÛ©¾Ù­Áᦻ֦¹Ò¨½ÚªÀ᥿ڪÄÝ¥ÀÖ¢½Ó§¿Öª¼Ø©¼Ó£·ÉÁ×ë¯ÇÞ¦½×§¼Ù¯Äß¼Òê¯Æâ­Ãä¯Éç©Æã§Äá©Ãã»Ôò¬Â᧽ܭÁá¬ÁÜ¥»Ñ¥»Ó§¼Ù¥¼Ø¤ºÙ¥¼Ø£ºÖ§½Þ¡¶ÜŸµÖ¢·Ô¨Àפ¿Óš²É¤¶Ò¤·Ðœ¯Æ™¯Å™±È‘©À—­Å§½Ñ¡µÇ™­»Ÿ´¿•®¼¨º§ºŸ²Ç©¿Ó…›±…›¯Š¡²‘¥µ†—¨ˆ™¨‡—¦‡—ª‚‘«‘«€ª†™°|¤x‹ t‡žp„–oƒ“l}ŽiyŠu‡ÌÑϘ©ŒªƒŠ£{…Ÿt€ŒESUO[WPXO4<53862606:4DGDY^\nuugqy[hx\l{YizWh{[nƒ]s‡aw‹i“n„šn‡—x‘‚›«~”ª™®œ²Œ§¹‹¤²‹¡µŽ ¼’¤À¡³Ï ³ÌŸ¯Ç§ºÓ›­Ë§½Õ«ÁÕ ¸ÍšµË¤ÀÔ¤ÀÔ¤ÀÒ¢½Ï¥½Ò¤¶Ò£µÑ¡³Ï§½Õ©¿Õ¡¹Ì¡¹Ì ¸Í¤¹Ô¤¼Ñ¦ÁÓ¥ÁЯËتÆÕ§¿Ô©ÄÖ¯ÌÛ±ÍÜ«ÃÖ±ÊÚ²ËÛ­ÆÖ¤ºÎ¨ÀÕ§¾Ø«¿ßªºâ¤µÚ§¸Û¡·Ö£½Û©Äڵȟ»Ê¡½ÌžºÐ·ÕŸ¹Ò™¯Å“«¾œ·Éž¸Ñ¨È–¯Í—±Ì”¯Å“«À¨½—¯Æ–¬Ä”§ÀŒ¢¸Š ¶¦¼‘¤»Œ£´Œ¥³¤±¤¯…œ©†¬…™«†•­‘¡·…•«‚“¤…—£‰¡«w”œxŒž{‡¢t„œwŠŸt‡œo—m}“n~‘ry‚ÇÄÅ?MRRfmmjux`owVhtVjz`t„fzŒi}n–n‚”vŠšy}‘¡‚˜¬–±ˆž¶˜®Æ™¬Ã—§½”¤º—§¿ ³Ì²Ï—¬É™«Éž´Ì“«À—¯Äž´Ì¡·Ï®ÄܬÄÛ¡¸Ò¡¼Ò¤¿Óœ·ÉžºÉ§½Ñ¬»Õ°¿Ü¨ºØ¨¿Ù£½Ö¦ÀÙªÁÛž´Ì£¶Ï¦¸Ô©»Ù©¿×¹Ïã»×æ¯ÌÙ°ÍܪÆؤÀÔ¦Á׫ÂÜ­¿ÝµÊ娾֦¾ÕŸ·Î µÐ®¿à«½Û­¿Û¦½×©Ãܤ¾Ù¡·Ø•¯È”¯Ãœ¸Ê–²Ä«¿§ÀŽ¨Á“­È˜­Ê–¥Ä•¤Ã“¡Ã—¬É§ÀŠ¥¹˜°Ã«¿Ž©¿„Ÿ¸‡¢½ˆ£¼™²{•®…œ¶†›¶†˜¶…›±{’£‹Ÿ¯‘¢ˆ™¬{Ž£n…–sŠ™k‚“j}”e|d{Šg{‹euˆ\c|CCbqn@:C  -8IX?Sa=Tc>RbHYjQ^nHPb4:H7:F<=FTSZmpxkpz[gsTdseuˆgvŽp€˜sƒ›r‚˜sƒ™|’¦x¥€›­z–¨‚¯‰Ÿµ£¹¢¹¦º’¨¼¥½š¬Ê˜¬Ìž²Ö³Ô¢»Ù¶Ô—°Ð“©Ê˜¬Î”¨È“§Ç•¯È–²Æ—²È¢·Ò²Äॴџ±Í©»×©»×©»× µÐ§¼×¨½Ø¯Äß³Êä®ÅáªÁݬÂá©ÃÞ¬Çà¬ÈÞ«ÇݧÃÙ©ÄÝ¥ÀÙ¤¾×£ºÔ§¹Õ¥¼Ö¢¼Õ®Åߤ¹Ö¥ºÕÃÖ塚զ¸Ô¦¹Ò¤·Îž¶Í–°Ë·ÐŸ¶Ð™±È™¯Çœ´Ë˜²Ëœ¸Î¬À“®Ä’§ÂŽ¦½ƒž´Š¤½§ÃŒ¦¿ˆ¢»…Ÿºˆž½…Ÿº€š³‚œµƒ¶z’©—¯ƒ™±‡š³‰™³}‰¤Žž¶y£sŠ›r†–rƒ–{‡ y…žmy”fvatVi€P`v)8 $:R\IZ6:I5:F8;EOV_gqy_mxYizp€–dwo…›h~”f~“u¤v‘¥y”¨›­x”¦š¬ˆ ³‘©¼‹£¶¦¼–¨Ä›­É¢±Ð ±Ò¤µØ™¯Î”­Ë•®Ì˜®ÍŠ£Á•®Ì´Ð˜­È’ª¿¡¼Î£¾Ò·Ð£»Ò©¿Õ¢¸Î¨¾Ô¬ÄÙ ¸Í¨ÀÕ¥»Ó¥¼Ö¦½Ù¤»Õ¤»Õ¦½Ù§»Ý¯Æâ¯ÇÞ¬ÇݪÅÛ¬Çݤ¾×œ¶Ï¥¿Ø¨ÂÝ¥»ÚªÀߦ¼Û¦½×ž¶ÍŸ·Î¨½Ø µÐ¤¶Ô¤¹Ôž¶Í´ÎŸµÔŸ¶Ò¢·Ôš±Íœ³Ï•¯È‰¤º«¿¸Ê‘¬À—¯Æ’©Ã“ªÆ˜¯Ë‘§ÆŠ¤¿† »˜²†›¶ƒ˜³€•°}•¬„œ³… ´}˜¬|’¨‚’ª}‰¢}„Ÿu…˜tˆ˜t‹œo…™n–tƒ›tƒ›r~—n}—m|™Xk‚M`u@Q`!,  ;L]BSbEWc@Q`?Pa?O`?L`DP\?IO5:D; ' RYY^hr`m}iy‘o‚—m€•uˆxˆžz¤|”§~š®‡©½€Ÿ´… ¶‰¡¶£·“ª» ´Ä£µ”¤º•¨Áš¬Ê™¯Ç—­Ãš°Æ™¯Å–¯¿Ÿ¸Æ¬ÅÓ¢¹Ê¬ÂÖ©¿×¡¹Ð£½Ö¦»Ø¦´Ö ²Î¤·ÎµÈ߶Éâ­ÃÛ°Åà­¿Û¨·ÖªÀߪÄ䨾ߩºß«¼Ý«ºÙ©½Ý¨¾á¤½Ý¡ºØ¥»Ó¬¼Ò¯Â×¥»Ï¦¾Ó£ºÔžµÏ ·Ñ¡¼Ò¢½Ñ§¿Ö¢·Ò¡¸Ò£½Öž¸Ñ•¯Ê—±Ì‘§Æ‘§Æ’¨Ç–­É’§Â‘§¿¢»£»Œ¡¼‘¨Â‰ ºŠ¢¹Ž¦»…›±‡š³„œ³…Ÿ¸›¶~—µ}—·~˜º{”²‚™³…´w£w¡uˆo‚—k~•v‰ q„mƒ›j‚™g}“o‚—h{”`rYk‡Rd€M`wHYlAQb5BT5DLCO[FX_@V\AUcATiDWlGZoAUcCY_HZ_=JO7@?8;8BGEW]`^kr_p_vƒl…‘r‹™vžz’§z”­‚³ƒ›°—¯†•´Žº–¥¿š­Æ˜®ÆŽ¥¿•¬Èš±Ë™±È³Ë ³Ìš²ÇŸºÎ³Ç£´Ç¦¹Ð§¹Õ§½Õ§¿ÖŸ·Ì ¸Í¤ºÐ¢µÌ§ºÓ¤¶Ò¥¼Ø¨Âà¦ÀÙ¬ÄÛ®Äܪ½Ö«ÃÚ¬ÇݪÆÜ°Ëä©Å۸̸Ρ»Ô¡¼Ò¸Ì³ËÞ¾Òä«Áס¸Ô¬ÃÝ®Äܦ¾Õ§¿Öœ¶Ï£½ØªÀߟ³×›´Ô–°Ð˜±Ïœ³ÏžµÑ˜¯Ë–­Çž³Î–«ÆŒ¡¼’§ÂŸ»¥À’§Â‹¡¹‰Ÿµ‰ž¹ŽŸÀ‘¦Á‰ŸµŒ¢¸ƒ™±†œ´Šœ¸…š·‚˜·ƒ˜³‚’¬–¨Ä±x©oŠ q‹¤m‡¢r‡¢w†£m€™i|“fvŒsƒ–gsŽ^fŠ[eˆZd‡M\vIYoFVlAQg@SZARaDYd?T_EZeJ\hI[gO`oG\gG\eDZ`@VZJV5;=KM\ipqz‰„ †‘¤‰•£˜¥Œ•¢–¦|ˆ–|‰™~ˆŽx}tun…€v‚}q„}r‰„xˆ~‘Œ€Œ‡{Ž•“‚’“Ž‚›—†¢Š¢Š¨¢’¥Ÿ§¡‘®©‚¾ðò¡ñõ–òøÿÿ¸ÿÿ¸ÿÿ¸ÿÿ»ÿÿ½ÿÿµõü©ÿÿ±ÿÿ¨ÿÿ¸ÿÿ¼ÿÿ´üÿ¯öü£úÿ¡ÿÿ¨ÿÿ¶ÿÿ¹ÿÿµøû£øü›õøŽúüŒÿÿŸüý¡ôø›þÿ¥ýþžÿÿŸÿÿ ÿÿ÷÷•ÿÿ¡ÿù¡ÿìÇ©\æÄ}ÿÿ¦ÿÿžÿÿÿÿÿø§ÞšaË\?äIKçLJèLFÅ\4òºqÿÿËÿÿÓÿÿÏÿÿÍÿÿÃÿÿ¹ÿÿ»ÿÿ»ÿÿÁÿÿÉÿÿþÄ‘Æӧ㼕۷‘ÒÀšÙħо¨½·¬—óõ´ÿÿÔÿÿÏÿÿÑÿÿÓÿÿÉÿÿ¿ÿÿ·ÿÿ«ÿÿªÿÿ«ÿÿ¨ÿÿ­ÿÿ©ÿÿ¨ÿÿŸÿÿžÿÿÿÿžÿÿ¹°º²æòÞýÿìÿÿ÷ÿÿöÿÿõàã⡨¦Vb`p~~‹˜Š—œ‹•{‡“{†—€‡ruvsto|{r{{k€k„‚qŠ…y‹†zŒ‡}ˆ~‘Š’‹‚™’‹ž—Ž¤š–‹£œ‘©£“¬¤ª¥€ÜÖ¢ÿÿ»ÿÿ¦ÿÿµÿÿ¿ÿÿ½ÿÿÇÿÿ¾ÿÿÃøü­ÿÿ¯ÿÿ¹ÿÿ·ûÿ³üÿ¶öýªûýªÿÿ­ÿÿ¬ÿÿ°ÿÿªþÿŸûÿ˜ÿÿ ÿÿ£ÿÿ£ÿÿžÿÿ˜ÿÿ˜÷ù‹ÿÿ“þþšúöœú÷–ýû“û÷”ÿ÷šÿí™úӌƨ^ÿú®ÿÿªÿÿ ÿÿ˜ðõÿë¢ÏkRØXQèKWâHSâJW¾bOÿôÂÿÿÙÿÿ×ÿÿÙÿÿÛÿÿÑÿÿÇÿÿÅÿÿÃÿÿÇÿÿÍøéÏÁ£¿ÃŸÒÌ¡êÄšáÄ›ßÈžàΞàǜѻ•¿Ä°°ìçÀÿÿâÿÿÕÿÿÏÿÿÉÿÿÀÿÿµÿÿ®ÿÿ«ÿÿ¤ÿÿ¥ÿÿ¡ÿÿšÿÿ•ÿÿ‘ÿÿ”ÿÿ•ÿÿµÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿØßßoy}Š“œ}‰—‰›y€‡inlvvt~wwzvs{ys}w„€{‚w„w‡‚zŒ…~‘Šƒ•Ž‡Ÿ•‹¥™‹§žª¤”­¥´¨´§~ïܨêà£ïé©øù¯öü¬ÿÿ¾ÿÿÀÿÿÁÿÿ·ÿÿ½ÿÿ½ÿÿ½ÿÿÅÿÿÁûÿ³ÿÿ·ÿÿ¶ÿÿµÿÿ­ÿÿ©ýÿ¤ôø—ÿÿ¦ÿÿ¨ÿÿªùýžøüÿÿ ÿÿžÿÿšÿÿ™þÿ—øùö÷Œÿþ‘ùóŒñâƒûçöØŽõè‘ÿÿ¢ÿÿžýÿžþÿ™ÿÿ•÷¿tÓ^8âXIéGSÝLKÒMDÒ†Rÿÿ½ÿÿÉÿÿ×ÿÿ×ÿÿÙÿÿÑÿÿËÿÿÉÿÿÇÿÿÛÿÿðɪÂÈ›ïƛ羗ÝÇžâÅ›ÝÙÙÆœÜÇžÛ»’Í´“»¡Ç¾±¬èé¹ÿÿ×ÿÿÇÿÿ¸ÿÿ®ÿÿ¦ÿÿ¡ÿÿŸÿÿªÿÿ­ÿÿ¤ÿÿ‘ÿÿ†ÿÿ‹ÿÿ†úó£ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŸ¨¥qux‡Œ–ˆ wz„lkpurswrr{vv|wy{wt€{s€{q…€t‡‚xˆzŒ…~—‡—…Ÿ•£ž’¨¦—ª¨±®‹ÈË…ÿÿ¯ÿÿ°ÿÿ¶ÿÿµÿÿ»ÿÿºÿÿ·ÿÿ·ÿÿ¼ýÿ°üÿ¯úÿ«øý©ÿÿ©ÿÿ§ûÿ ÿÿªÿÿ«üÿ¡õüžÿÿ³ÿÿ¶ÿÿ·üÿ¨øÿùÿ”ûÿŽýÿ’üÿ•ýþ—üù˜ïò†úÿÿÿ”ÿÿ–ùóŠüí‰ñæŠèâÿÿ©ëö—÷ÿ›öÿ”ÿþ˜ÿôÜ^ßZUäSRíLSÕOOÆWRÿОÿÿÃÿÿÉÿÿÏÿÿÏÿÿÑÿÿÍÿÿÉÿÿÇÿÿÇÿÿÕÿÿͯšŸ¸“Ͻ™Ûº”ᾗݾ•×½–Ü¿—â˜áÅšáÅ›ßÙÝɥܼœÆ¾¬¥ôò¸ÿÿËÿÿ±ÿÿ¢ÿÿ–ÿÿœÿÿ¨ÿÿ­ÿÿ±ÿÿ¨ÿÿ¡ÿÿšÿÿ‹äÞ‡ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¯¥­yw‚†•vu|vmnwnoypqyqo|qn{vlyvj|zk‚~oŠƒzŠ~‚•‰‹“‹‡˜‘ˆš“Š¡š‘¬¡Œ±¤‚ÝÓ–ìãæãòö§øý§þÿ§ûÿ£ÿÿ¨ÿÿ®ÿÿ½ÿÿ·ÿÿ¼ÿÿ½ÿÿµÿÿ«ÿÿ¨ÿÿ¥üÿŸýÿŸÿÿ¦ÿÿµÿÿ¶ÿÿ³÷üªøÿ ýÿ›ýÿ•þÿúÿõöøø”üøšÿÿ¡þþšüù–õîŽÿø’ÿûäàoþþŒõÿŠïÿŠòÿ‘íù‘ÿøžðÄwËmFãRQäLKéIIÐSCÉoMÿÿÍÿÿÑÿÿÍÿÿËÿÿÏÿÿÓÿÿÑÿÿÏÿÿÉÿÿÅÿÿôåÁßÌ¥Ù¿—â›áÅœà˜ßÄšãÁ˜ÜÀ—×½”ÖÀ–ÝÅžä¾—ßÀ™áÈžç¤ү™®¹±‹ÿÿ¢ÿÿ¬ÿÿ˜ÿÿ–ÿÿ•ÿÿ£ÿÿ°ÿÿ¬ÿÿ¬ÿÿ›ÿÿ„Þ׉ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¤£ª{wqmuvpmvqiupftogwomxpn~sr~sp„vt„|x…~Œ‡†~†{‘‹}˜’„ž•ˆžp¡¥Xóöœÿÿ ÿÿ«ÿÿ°ÿÿ¯ÿÿ³ÿÿ´ÿÿµÿÿ­ÿÿªÿÿ­ÿÿ°õý¡ôýžüÿ¥ÿÿ¨ÿÿ§ÿÿ©ÿÿ²ÿÿ¹ýÿ§õþŸöÿšúÿ–þÿ˜ýÿ•õþ”ýþ¢ùúšøø”ÿÿžÿÿ úû›õñ•óðŠûóˆÿï“ÿâ–ͼkÿÿ­ëõöÿ•ûÿ˜ñÿŽÿç“Þ‡TØbEãMJãMJæNKÅ_Aá­uÿÿÑÿÿÏÿÿÏÿÿÏÿÿÏÿÿÑÿÿÑÿÿÑÿÿÉÿÿÃÿÿ覩ƤËÉ¡ìÉ¢èÈŸãÍ¢ëËœìÇ›çÁ–⹎ڻÛĚᾘÛÂœÛÄŸÛàÙ ֭ž˜Ýßžÿÿ·ÿÿ—ÿÿŽÿÿŠÿÿ”ÿÿŸÿÿ›ÿÿ—ÿÿ¡íç’îá£ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ fdnmmommknlhmifvpm{vn{vlyvl|yo}zpƒ~t‰†zŠˆy…ƒt‰‡x“~˜“€•i»ƒÿÿ³ÿÿ«ÿÿ­ÿÿ©þúžÿúœÿÿ£ÿÿ¢ÿÿ«ÿÿ°ÿÿ±ÿÿºÿÿ¹ÿÿ½ÿÿ±ÿÿ¨ÿÿ¤ÿÿ«ÿÿ®þÿ­ÿÿ¸ÿÿÄÿÿ·ÿÿ¢þÿžôÿ”øÿ—ûÿšÿÿŸÿÿ›öó’íèŒöî‘úï“ÿø“ÿ÷Œÿî‘ð¿tÓºcÿÿ øÿ™úÿŸöÿ‘êì|Ú¢YÜfGßX?èN;äN@äNK¿_EÿÝ®ÿÿÓÿÿÉÿÿÇÿÿÅÿÿÃÿÿÃÿÿÅÿÿÇÿÿÑÿÿÛÿíëÀ˜ÓÇžÞÇœãÈžàÉœÝÌ¢æÉéÈæÀ•Þ¾”ݺ۽•à»“Ḓվ–ÓÄŸÙ½™Ð³¤ ûÿÀÿÿ´ÿÿ‘ÿÿÿÿÿÿœÿÿ¤ÿÿžÿÿ—úö…áÐhÿìªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿéâÛkc_sgiqhkqjnqjjvnjxskwrjvqixskysnyv…zƒ|uƒysŒ|{ƒ|‘ˆ{—cçã—ÿÿ®ÿÿ¤ÿöŸôÞ‘ê݆ïèˆùö•õô•íîŽðñ“åæˆßÞíí”îðëí˜õø ÿÿ¬ÿÿ·ÿÿÄÿÿÃÿÿ¸ÿÿ¯øû¡ÿÿ®ÿÿ¬ÿÿ¯ÿÿ©ÿÿ¥ùû˜öö’õöÿÿœÿÿ›ÿÿžÿøþð…ÿéšâ¦uÛ½uÿÿ¡õÿ—ñÿ–öêŠè¿kÃh=çWZçPVêIRßPLÖWGÄ~Cÿÿµÿÿ½ÿÿÅÿÿÇÿÿËÿÿÉÿÿÇÿÿÁÿÿ½ÿÿÉÿÿÕѸ·ËžáÄšáÅëË ïÆšëÈœíÉîÉžïÅšëÛëÀ˜èÁ›è»•âš従ߺ˜Îµ˜½¯¤„ÿÿºÿÿ£ÿÿ˜ÿÿ™ÿÿ™ÿÿœÿÿœÿÿ£ÿÿ¢ãчáÇ•ýݽÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýúýý÷ÿœ› cgjlihslermerognmbonapmaupfxsi~yo~{o}zn€{s†~|†xŠ€v œnÿÿ°ÿÿ³ÿó ÷è™ûéõì–ÿûÿÿ¤ÿÿ¨ÿÿ§ýÿ ÿÿ¤ÿÿ¦þÿÿÿ§ÿÿ­ÿÿ©ÿÿ®ÿÿ¯üÿ§ýÿªÿÿ°ÿÿ¶ÿÿ®ÿÿ­ÿÿ¤úùžûýšÿÿšÿÿšÿÿ¦ÿÿžÿÿ˜þÿ’íê‚óä~ÿðŒÿä ã…`بhþú óø”õÿ“þØŒÅoEÖ_QèQ`åKVïNWÜPYÒZcú¾šÿÿÍÿÿÍÿÿÏÿÿÏÿÿÑÿÿÇÿÿ¿ÿÿ½ÿÿ½ÿÿÙÿÿ뺡°É¤ÞÆáÇ›êÈœëÌ ñÍ¢î˜áÇœëÈœðÃší¼“èÁšì½—æ¾—ßÙÛÁ¡Ë¿©¾½¶‰ÿÿµÿÿ ÿÿÿÿÿÿŽÿÿŽÿÿ‹ÿÿžÿÿžÎºcùÚ”ÿÞ¶ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŶ½tbxtgprjfpmenmdmlaol`ol`toeurfyvj|zk}{l€{qƒ{w†~lŠ€dǽ†ÿø¥öè–ãЂùë™ÿú¥ÿùžÿûšÿÿ¦ÿý¥ÿÿ¬ÿÿ²ÿÿ¨üü£ûü ÿÿ¬ÿÿ«ÿÿ¯ÿÿµÿÿ¯ÿÿ±ÿÿ©ÿÿ¤úûôø›ÿÿªÿÿªÿÿ¦ÿÿ¡ÿÿžÿÿöö’óöŽô÷ÿÿœÿÿÿÿ ÿù¡ÿÆÚvbÁ‘Qãá{ù÷öô‡ÄŠKÊYIÛWVæM_ëM^óNbÜ[YÏn[ÿÿÃÿÿ¿ÿÿÃÿÿÇÿÿÉÿÿËÿÿÃÿÿ»ÿÿ¹ÿÿ¹ÿÿÑóã»Æ©³¿–ÓÌ£åÉ¢èÊ¢íÉ óÇŸíÉŸèÄ™åÈœëѤøТûÄœìœ濙ÚÚս›Â½ µßÒ®ÿÿÁÿÿ³ÿÿ¥ÿÿ˜ÿÿÿÿÿÿÿÿ§ÿù«ßÅ„ÿà®úÔºÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÂÁÈy{jgfogcnhcoifoidoidskgujgumiuolxrmxqjyrk€ur…ykŽiíØ°õÚžúâ£ÿñ®ÿø¬ýø£ÿÿ¦ÿÿ¥ÿüõå†íÝ€ùèÿöžÿÿ¬ÿÿ§ÿÿ¡ÿÿ¨úÿ£þÿ©ïîžß߈åä‰üþ›ûÿ˜ÿÿ£ÿÿ›þú™ûòœòí‘øó•þû˜ÿÿœÿÿ£ÿÿ øô‘ñêˆø܆ÿã—í”kèe_ÉtLدfÿ؉Â>½_8ÛOVÝLRçQYèPYèKWÏ_Lõ¯€ÿÿÑÿÿÍÿÿÅÿÿ¿ÿÿÃÿÿÇÿÿÇÿÿÉÿÿ¿ÿÿ·ÿÿëŦ¾Ê¨ÓÃÜ»•ÖÇäÅžäÅ çÇ æÈŸãÉŸæÈéÇœëÅšëšåÁœá¾šÜ»—׳›³¥•†ôïªÿÿ¤ÿÿ¥ÿÿ§ÿÿŸÿÿšÿÿ—ÿÿšÿÿžøêàÃoõÈŠòǨÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿª°©ƒˆ}bc\iebga^lcdmhhmjiomiplgrogytlytlysnyvnzwo‚x`›ŠeìÜ¡ÿî ÿ÷žÿü›øø–ÿÿ¡ÿÿ¨øð•õç“õß’ÿöÿÿœÿÿ ÿÿ¢ÿÿ¯ÿÿ¸ÿÿ¹ÿÿ¼ÿÿ¹ÿÿ·ÿÿ²ÿÿªÿýšýù–ýùûù£ýø¡úô÷ò–ÿû›þú—û÷”ÿ÷šüñ™ûð–ÿý¤ÿó©ÿÅ‹ÜnQôdeëfaàbYÙWXÏHVØJ[åPcêVdïYcæR`ÜI[ÀhKÿò¦ÿÿÇÿÿÉÿÿÃÿÿ¿ÿÿ»ÿÿ·ÿÿ½ÿÿÃÿÿ¿ÿÿ»ÿð̺–²Æ ÑÀ–ݽ“ÜÉìÌ¡íÇ èÀ˜ãÄœìÄ›îÅœñÄœìÄœê›ãÂœßÁݼ˜Ö°š­²§’ÿÿ¿ÿÿ’ÿÿšÿÿ¥ÿÿÿÿ”ÿÿ‘ÿÿ˜ÿÿ èÐâ½yöÁ¬ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõ…pfaUh`\—Œ‹ƒrxe\]mhhrliumivpkvrmutkrthyvj|uj„vW¯{øí§ÿþ©ÿÿ¦ÿÿ¤ÿÿ¬ÿÿ½ÿÿºÿí¨õæ›ÿö¥ÿÿªÿÿ­ÿÿ¯ÿÿ³ÿÿ¸ÿÿ¿ÿÿÅÿÿÇÿÿÇÿÿÈÿÿ½ÿÿµÿÿ¾ÿÿµÿÿ«ÿÿªÿÿ¢ÿÿ™ûýšüýŸúùšÿýŸÿÿÿü”ÿóÿìŽÿÍ—î}qá_`óapô`nðWgßK[×DVäP^ó]gíVZô\YàQK×OGé™mÿÿÉÿÿÉÿÿÉÿÿÅÿÿÁÿÿ½ÿÿ¹ÿÿ½ÿÿÃÿÿËÿÿÓÜǾ¾šÏÁÛ¿šá³‘×¹–ßÀéÅŸîÀ˜ã·ÖÄšãÌ¡êË¡êš得ßÅ›äœݼ™Ô²œªÇ¸žÿÿËÿÿžÿÿ§ÿÿ©ÿÿ ÿÿ’ÿÿ”ÿÿ™ÿýžçÄ„å½ó¾¥ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõ÷ýÚÛÖtqea^]kiuÿÿÿøýÿfmmgmdkmcrmernisnnxrmxqjzsj~tl‡zXìÚžÿù°ÿü«ÿÿ±ÿÿ³ÿÿ½ÿÿ½öí—ì܆óê–ÿû«ÿÿ«ÿÿ¨ÿÿ¬ÿÿ®ÿÿ¦þÿ¡øý™ûÿšÿÿ£ÿÿ§øôš÷ñš÷õŸýüªüÿ§ÿÿ²ÿÿ°ÿÿ­ÿÿ±ÿÿ´ÿÿ¬ûüžñì—îà—ÿð ÿù£ÿƘêe`åZZó`gï]aèVZÚIFäTJ÷`ZøVWóQTòMSßWQÒeTÿÚŸÿÿ»ÿÿÁÿÿÉÿÿÉÿÿËÿÿÅÿÿÁÿÿÃÿÿÇÿÿÙÿÿì·›«¿˜à¾—ÝÁ—Þ¸‘׳ŽÕº•Ú¿šßÞãÅžäÄšã¿“â˜áÆœãÀ™ß½–ܽ—Ö¼—Ñ°˜àÝ™ÿÿ¿ÿÿ¢ÿÿ¢ÿÿ¢ÿÿœÿÿ“ÿÿ“ÿÿ–ûî…ÝÀlݹnäºx趚ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÅ»±ÒÊÆunr]Xcnn~ÿÿÿëæób`jfelfk^jrRNP4DA)><+B?7HF5YW<†~Oóä¢÷ï«þþ¹þÿ½ÿÿÂÿÿÂÿÿ²òìšóé˜ÿü¥ÿÿ¦ÿÿªÿÿ¯ÿÿ·ÿÿ»ÿÿ®üüšüüšÿÿ¢ÿÿ¦ÿÿ¤ÿÿªÿÿªÿÿ£ÿüžúö“ôî‰øôšôñ¢ÿÿ±ÿÿ»ÿÿ¸ÿÿµÿÿ¬ÿÿ¤ÿì’ÿÚ†÷œoç]Xè\Wñb^î_]äRVì[Zô`^òUTõLOòKMíFHÔa>àžYÿÿ½ÿÿ½ÿÿÁÿÿÅÿÿÃÿÿÃÿÿÁÿÿÁÿÿ¿ÿÿ½ÿÿÍÿÿÍ«¾–ÎÀ–Ö¿”ݘ߿•Ü»’ÔÙٻ’Ô·‘Ô¿™ÜÁ˜ÜÅœÜÁ™Öº—Ò°’α–Ⱥ¡É¬¥Šöÿ¤ÿÿ¶ÿÿ«ÿÿ¥ÿÿœÿÿ”ÿÿÿÿ•ÿÿ™î×Þ¶xå»yê¼yéµ—ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúùÿ¸µ¸³®®wqlZZXqvvÿÿÿèáåhdjcakknoÿÿÿÿÿÿÿÿÿÿÿÿÿÿõú÷íæàÛìèãÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿðîÝìë×þýéÿÿýÿÿÿÿÿÿÿÿÿÿÿÿîåÖÙØ©öü®ÿÿ¬ÿÿ¡ÿÿ¡ýüþý ýü¡ÿÿ¥üÿ¥õó¦ðêªåâ±äâÃçë¸ñú²õÿ¬÷ÿ£ÿú£ÿò¤È‚U¸D9ÇKAÔQIÅD@ÃCFÖOTÕDNèOUõSXçIOåKTÏnJÿî ÿÿ¿ÿÿ½ÿÿ¹ÿÿ·ÿÿ»ÿÿ¿ÿÿ½ÿÿ½ÿÿ·ÿÿ³ÿÿ¯ÿÿ­ïã—yMzµ‰ÅÁ—×À•Ü¾”Û¹’غ–ص”Ó¹“ÒÀ–ÖǛٻŒË¼ÎÁ˜Õ²¿±•·¼°•ÿÿ¿ÿÿ³ÿÿ£ÿÿžÿÿ˜ÿÿ—ÿÿšÿÿÿü‘ÞÁoåµ€ä·}Ö«lݬ”ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¯°©­©š˜Žrli\Y\€~ˆÿÿÿÅôhe]e`b»»½ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿûöúÿúÿþøÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÌÃÓ¦—®œ¦¢–¬Ê¸Îª“¨‹em˜d_¡>DïZmØPZÑVWÛmÿÿÁÿÿ¿ÿÿ¿ÿÿ·ÿÿ¨ÿÿ¶ÿÿ¿ÿÿ»ÿÿ¹ÿÿ¹ÿÿ¹ÿÿµÿÿ³ÿÿ±ÿÿ¯ùꛤ„[¥…²‡¼½•Ðº–Ø·“Õ·“Õ¹“Ô¿•Õ½”Ö»”Ú»—×¼˜Ö·ž»­œÝØŸÿÿ³ÿÿ«ÿÿ¥ÿÿ ÿÿœÿÿ–ÿÿ‘ÿÿ•üëƒÝÀlÛ°qܱrà³uÞ­“ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¼Ã³‹¤Ÿ“ˆ„fcdVSR‘Žÿÿÿ±°£hedc^iÈÆÐÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÄÕÙc{ÃZ`¿^TÿÖ¢ÿÿ»ÿÿÅÿÿËÿÿÃÿÿ½ÿÿ¹ÿÿ·ÿÿ¹ÿÿ½ÿÿ¹ÿÿ·ÿÿ·ÿÿ¹ÿÿ¹ÿÿ¹ÿÿ¯ÿÿ£ûŒV¥}µŒ¹¿—ÍÀ–Öº‘Ó»’ÖÁ˜Ü»×½•Ò¹•Ê¶œ²² ›ÿý¿ÿÿ©ÿÿ§ÿÿ¡ÿÿ›ÿÿ˜ÿÿ–ÿÿ‘ÿÿ›óÖ‚Ù´nÜ®yⶀ٭wצÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÚßÝorq’Š™”ŠyvuNMTBF@¡§•ÿÿÿ›”fb]da`ÒÏÐìæíññóðóôòïðÍÆÈåáÞòðêõòñýùÿÿÿÿùö÷ÿÿÿÿÿÿÿÿÿùüûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÜéÚg~º^YµlOÿí¨ÿÿ·ÿÿ¿ÿÿÉÿÿ¿ÿÿ·ÿÿ³ÿÿ±ÿÿ·ÿÿ½ÿÿ¹ÿÿ·ÿÿ»ÿÿ¿ÿÿ½ÿÿ»ÿÿ¯ÿÿ¥ÿÿ«ÿÿ¯ÿ󺹕‰c{©¹³ŠÇ·ÏÀ–ØÀ“ØĜټ˜Í²¢·¯‡ÿÿÂÿÿ¥ÿÿ¢ÿÿ¢ÿÿ›ÿÿ“ÿÿ‘ÿÿŽÿÿ‘ãÈoÙ´lÚ¬u׫uÙ¬yТ‹ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÖÛãNQYmkwƒ€|yq_`[8=;8==·»¾ÿÿÿc`aGDCQOKüûòÿýóÿÿÿÿÿÿÿÿÿ«¨©XYR^`T]`M}~g­®•ž…•“v™•w¯«½¹®ªž™„¦£•’~“•‹Œ“‡ž¦¢¤–§£’  Ž‚˜—Œ’‡ƒ|s¥–¬Ÿ–³¦´ª¤±¦¥¬¥ž¹²©ÎÊÅ¿¾Ä¿ÁÉÁÈÉÂÆ¿¶»À¹»ÈÃÅÎÇÇÀ·¸®£¢³¥¥±¥§£š†‚mt`m¯g}TIÚ¨~ÿÿ´ÿÿ¤ÿÿ³ÿÿ·ÿÿ¶ÿÿ±ÿÿ³ÿÿ¯ÿÿ­ÿÿ¬ÿÿ¸ÿÿÁÿÿÅÿÿÉÿÿÃÿÿ¿ÿÿ»ÿÿ¹ÿÿ±ÿÿ­ÿÿ§ÿÿ£ÿÿ¿ëÏ«€bcƒc‰©ˆ··’Ì°Œ¿©†´«˜“ç߬ÿÿÁÿÿŸÿÿÿÿ ÿÿ”ÿÿˆÿÿ…ÿÿ~øêÖ´mà¸x뽆ܰx׫u㲚ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÔÓØFFH^^\qrkqrkhfbJJJ*)015:ÐÖÛÿÿÿ¶º ´·¦·¸±ÿÿÿÿÿÿôôôÿÿÿÿÿÿ¦¤žtshhgZmlX‹‰nœ–tŒ‚[“‹cŸ—qœ”n¡—tž”o –o –qšm¥›x¢˜u§v© t£˜j´¨xª¢q­§u«¤w§v˜c¡–f¤™i¬ p¶«{º¯º±‡ÕÌ«ëçÉìëÓìëÕçæÒäãÏæãÏæãËêèÍéçÊëéÌïëÍüóÔþúÜù÷ÜãàÌ®©kXU¨…Œ©‘zÜÑœÿÿ§ÿÿ•ÿÿšÿÿ¥ÿÿ§ÿÿ©ÿÿ¤ÿÿ¡ÿÿžÿÿ£ÿÿ¤ÿÿ­ÿÿµÿÿ¿ÿÿÅÿÿËÿÿÅÿÿÁÿÿ¹ÿÿ±ÿÿ¯ÿÿªÿÿ–ÿÿ‡ÿÿ¨ÿð«¯{•q¬Ž¨°˜²°©|ÿÿÿÿžÿÿÿÿ–ÿÿžÿÿ™ÿÿ”ÿÿ“ÿÿ‰åÐlæ½tä¸wã³|Ø­rÓ«oÒ¡‰ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÓÑÝEDKVUZ]][kmchib][WBBD$".20:Ü×âòîôfcdQPWfdrÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ­«šš˜{Še“‹c§žr¢™m›d–c˜Žg‘‡`”Šc’ˆc‘‡d”Šg…b”‰i‘†h“ˆh˜Žk”Še™j—Ždœ‘cœe™‹e—Ša›Žc—Ša™‹eœk›Žl¢”wœŒtwlY›•‡ª¥™®©Ÿ¸´£À½§ÆíÍȳÑÌ·ÍȳÕÒ¼ÙØÄÄÀ¯ šŒ¼²¬¥–™L;N…q— ‹—¥‘ÛÒ“ÿÿ™ÿÿœÿÿ™ÿÿ—ÿÿ›ÿÿ£ÿÿÿÿžÿÿÿÿ£ÿÿ­ÿÿ«ÿÿ±ÿÿµÿÿ²ÿÿµÿÿµÿÿ³ÿÿ²ÿÿ²ÿÿ±ÿÿ¬ÿÿ©ÿÿ£ÿÿžÿÿ­ÿöžÍ·|”y^˽xÿÿ°ÿÿ¤ÿÿœÿÿžÿÿÿÿ—ÿÿ’ÿÿ—ÿî‰äÃu꺃巀ܰzݲuܲpß­‘ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿßßáOOOURQ[WTgc`lhe_`[UYS;>?&$+ -<59504|w{ÿÿÿøÿÿÌÕÐÿÿÿÿÿÿš›†‹‡kƒ`‘†f •w˜ŠkbŽ€aŠ_Œ„`Š…`Œ„^‰Z‰\Ša‹‚aŒƒbŒ„`‹ƒ_‰[Œ‚]ˆ€Z‹ƒ]‹ƒ]„zU„Z’‰]…}YtmRTP2nlMæäÉøóÞùöâÿÿîÿÿõÿÿïÿÿîÿÿïÿÿñÿÿòýüïÿÿõÿÿûÿÿùÿÿóý÷é÷òèÛÕÒe[cyk}‡v‡‹u†Ž~m¹®~íë•üÿˆÿÿ‹ÿÿˆÿÿÿÿšÿÿœÿÿ ÿÿ¤ÿÿ§ÿÿ§ÿÿ­ÿÿ¯ÿÿ®ÿÿ­ÿÿ¯ÿÿ­ÿÿ¯ÿÿ¬ÿÿ°ÿÿ±ÿÿ¨ÿÿ¯ÿÿ¯ÿÿ¨ÿÿ£ÿÿšÿÿ‡ÿÿŽÿÿ¢ÿÿ›ÿÿžÿÿ•ÿÿÿÿˆÿÿ‹ÿÿ‘öÔ{߶mä³zã²uæ¶vå·tà´qÙ©ŒÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÒÐÚSSSXZPTUNYWS]YV[URWUOJKD5:6$# 636B=?<7;Ÿ™¢ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ›˜‚Œ…hƒ`‹^ˆz[†{[…z\…|]ƒy]yYyW…{X†xVˆzV‰{UŠ}Y„yYˆ€\‰]‡WŠW‡Wˆ€Z…}YƒxZwTukDRN064#/1'w|zÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúúüýýûÿÿýÿÿùýþùÿÿÿÿÿÿýüÿýýÿúúúñïëíèàŒ€†aMdn\rn_vrdv|n|’‡t·¯|âàŠýý‡ÿÿŠÿÿƒÿÿŒÿÿ—ÿÿ™ÿÿ–ÿÿ—ÿÿ›ÿÿ¦ÿÿ«ÿÿ«ÿÿªÿÿ«ÿÿ¨ÿÿ«ÿÿ«ÿÿ²ÿÿ¢ÿÿ®ÿÿ®ÿÿ¬ÿÿ§ÿÿªÿÿ®ÿÿªÿÿ¥ÿÿ§ÿÿ¥ÿÿœÿÿšÿÿ‘ÿÿ…ÿóˆáÀtã¹uê¹|ë»{æ¶vß²tÙ®sݬ’ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÌ×ØLY^V]]TUPQQOPMNPMNRMQLLJDHB5:6##,'+@3:541'2-!2//,.*,% -(ƒ}†ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿˆ¡€q{Zc\?>9"+%6.,[M[MAbÿùÿÿÿÿÿÿÿÿÿÿÿÿÿžµueTsgL}sN~sSƒw\xlUviYre`fZ`nal~m~{ivp\e¨™|Òƃíé†ÿÿ€þÿzÿÿ{ÿÿ‚ÿÿ„ÿÿ‰ÿÿÿÿÿÿˆÿÿ‚ÿÿÿÿÿÿÿÿ‘ÿÿ•ÿÿ’ÿÿ˜ÿÿ“ÿÿÿÿ‡ÿÿ~ÿÿ„ÿÿ‰ÿÿôÛ†Ó±jæ¸å½æÁ}á»zÞ¶xܵr×­iÒŸ†ÿÿÿÿÿÿ»É?;CKGMNKLLJFHEDB?@?<;=;7971<:4;<5(,$  - 053@C@++)9:5IJCZ\RJI@WVKtshSREIG8ROEXTQURSA@EOTG¶À¡¾È¥Äͨ°¶ÎÒªjoRQTCSUGUWKXZL[^M[]ONMDDC854)('('/.!*):3_R)u^¡”ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿlXJy6½¥2±˜,Žs2F8-]\DªµÿÿÿÿÿÿÿÿÿÿÿçÏèŽw[mMwcAylFˆ€XŒ†R…@zDsgLJDSPFnj[a^RQPGUSMXSSQMS,*6HHHéëß¹¾¯ëðá¿Ç©Òܲž¢ŠZXTXYRVWPXVRYTTSPO]ZYtpkŒ‡}€|mnjYXUI+)#ˆs“ùñÿìï÷ØÚÞ±±³qqJÐÌ€ÿÿ¬üäˆÿîÿúšÿå©‘u_@=%Œ ‰õþòÿÿÿÿÿÿÿÿÿ®¤ˆ¯—p°™o—€Tm_9kbC}vI‘QŒ‡DŽ‡>Ž…K„xOvjQcTNbRQxdkzhem[QŒTĹoêè‚þÿ‚÷ýs÷ÿkÿÿqýÿmüÿröürüÿxÿÿ}ÿÿ~ÿÿ~ÿÿ‡ÿÿÿÿŠÿÿ†ÿÿ|ÿÿzÿÿƒÿÿ|óâzݼpÞ·rÙªnÚ«qâ²}Ý°vÞ³vÖ«nÖ©o·“‘›+*1@?DEECHF@FGB;;934/862-.)783+++#'$#*$#*%%'$$""%"$$&220862B@?:@B8B@:GC@GC@SMJ]YT32)>@69:3  &!#1./B?BJHDBA8CA;DB>HIDVVTGGIJEPTOQWPI>;3#$JEGA4?|r|ÿöÿèÙÜ|jeYNKWRRSQMUSOTUP]^YXVPVSKVRMVQQSNNPKKNLHOMGRUTQUZRWaçëúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿYIU †mçÄ„ÿìÿõ™ÿë™ùæ¡÷êÄÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿçغžx±’b¹˜^Ǧj¸˜YªŒT¬’`¡[u@ƒyD’ˆS~wAzs=Œ„S˜Œa’‡g€nm^V_NRtfftih|mUª–iØÈ€âÔråÛoõìyøíxëßjåà`öùmÿÿyÿÿ{ÿÿyÿÿyÿÿxÿÿqû÷rþîäÇqåº}滀ä¶Û°sÔ©jÈ `ΨiÓ­lä½zç¼›?;AC@A@=<>><===:76B>;@=<444/21    !944!=74F>85PDFE@B::<969<7;521-+%SMJVJLG>A<4;@;=LGGROPRORQRMTVLSTMUSOUSMVULSRISQKQOIMIFLHEMIFNKJLLNCINÐÝæÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöÿ;*9<#]B¯˜éãÓÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿòÖ޼έq¼—Q¹šTǨgÁ£]¸šR¸œZ¾¢i¥\Š{LŠ~S…{TxuDqq;sp;zt@Œ…X˜ŽimaSaQ[qdmrhpjaR„zW·®qúfÔÇláÒpãÙmïìtõ÷uôûnöÿmúÿqúÿoõÿhýüxùè~Ú¾hã»{êćðÉ‘øÑ™ðÇðČ뽆丂ڰ|ש’=>9=>9AB=7<8-42166137333;66""   - -   - -   -52153-HJ@@B8A>6J?><78167031+31+:63HCCSNPQNMOLKOMIQMJQOKOLKLIHLIJTTTNNNJKFLNDHJ@HF@EF?EF?IFEPJQDENÁÆÒÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ×Ëѹ¬µºª¶àÕâÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïܾ”ß¿~âºhÁP·•PƧa¤^­‘Q°’Z½¡hĨoª“e’~\„vYˆ~f‰ƒa‹Š]‘Ž[¢›e ˜p‡}cdZPZPXe[eqcqj_\xp\ª¡u²©eÀ»_ãßlëélðìgòôkóömñøkõüoÿþƒòÜvØ»gÙ±sÔ¬lϧgϧiÓ«oϦmÒ¦p׫uܯ|Þ°—<:4<:6;89030.4-.2,12-:76>9;.+,   -    965fb]ec]STMPLIULMUNNSNNQMJNHEKE@IDMEAIE@GE?EG;DF8DF:AC9AC7EG9GLAFIF>GF’¡¥ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿèéôÌÐÓ«²°ž—‘Œ€¤’vÁžvܳˆÖ§zجtÞ´rÖ°qº–[¶•YÁ dº˜aª‡X·š_Å«fÀ¦c²—Y®’Y¹iµŸd ŒLˆwBoGxgBZI(9*(#5(3\RZh^fxpZ°¨uá܇øôïðröøsÿûŠ÷êÖÁo¹›UÀ¢\¹›UºšWàbãd£dƦeÈ¥eɦf̦iÕ§Ž67200..+,+,'+,%-/%02(12+783BD:SUI5;2! 8>7^`T[]OdcVebXga\YUPd`[a^Vb_U]XPeZY`[S^[QZWMXUKYVJYVJLK>ONAJI:JB>F>:D@;CA;FD@C@?FCBIFGEEG¹¸½ÿÿÿÿÿÿõñùÈÃЪ©® ‹‰…{urPEB6&%+!,#(.&-<6?JGJVVVIIGKHGhb]K>9U@5Šj\±ŒpÁ—oϧrÔ¬l¾˜[µXÀžg¼›fªP·›WʬfÍ®f¼œ[´“Yº›ZʯhÏ°q kȦqÛ¶…ݼ…¸_pY-//YISj^dd[^{tW¼íåžýð¢Ñ€©˜eȯuãÂà½{ݸtß¹|ฃ㽀â½yÝ·vàº{à¸xàµvÕ¤Š*/-%,,$*-%*((,&/,+4-/62-=<1>@4DF<(-)%. NUEZ]LVSISKGVMNZQVYRTZUUZXR\[P[XP[UP^ZU[WRXTOZTO[VLc]O^WL\ULXSKQMJQMJIEBHE=GB6C>4>91?94930.,($$".))=8:F?CF?AJCCG@@JABO=H-%&" 3(5JDKVSV]]]aaafaakcakebkddmjikkiijctsjopiiig]ZY,')+&&700?43M::w]Tž|jº˜{Ážv­‹\¸—`Á¢c²“P«ŒK¸˜YǨiÅ¥i¾žbÁ¡eбrÖ·vÄ¡cÇžgÒ«sܵ}Í«yÀ u“{VZK,]L9mZUdRHcRC€oN”ƒP“}Lº p¶˜`¶–UŸ_Äž_ÄžaϨp׳zضç‘á¸Ý´‰â·è¸©',!$)$&%'('.-$3/*63+;8.971:::$$$&&(bbdYVULHCKE@J?>G@@D?AFCDGDEMHHQJJSMJUMI\TP]RQYQO\UUXTOZYP^[Q\WKTRCWUF`]QYTLYTLRKDOGELCFF@=E?:B?7:90<911,$&#"62/EB:EB6KE@VMPea^nmdrqhLKBVULdaYb^[c\^a\`a[bb[]VMNNHEKEBB<9A898/2.%*% $'$''$#-)$/((/%-2),7/-A2.YC?”xmµ“¯Žjº™b¿Ÿe«ŠP²‘Wº™_äcÆ«b¾£ZÁ¦_ظwͦnÞjÑ«}Ç¥sŤrÀŸh˪pÍ«vÄ¡t¼›f¿ŸeáÁ‡çƌͫt½›iâhÒ²sÛº~ß»‚Ṅ֬zɤn¹™_µ”]­‹V®ŒW¸“_¾•|('&(!&#()+-,#60+70);1)83+862()""#USOLGG8117./:14<38<59;48<79;89>99E<=JB@LA@RJHTNKQMHRNIQPGSRIVULXTOWVKVXJVUHXUKYVL\WOVPK\UUVRMOLBKH@GC>A@7BA6@=3>9/30(+'$(!!% /*"I>=RJHNHEGC@HDAB>9<6182//(*,'+%!'% "+$$)# *$!*##("(!#)"$)$&*'*,*&-,#,*&.)+0))5-+7./6-0:*+>%$dI5žZ«‹`´’c¹—bµ‘X¹™VȪ`ͯe£[À¡YÍ«fصw¾™cÇ¥nͬwήtÑ°tÆ¥kË©rÒ²sÛ¼vÙ¶vÛ²{Æ¡k´’]¶’Yͦlæ¿…èÁ‡Þ´€Ï sÈ k¢fÊ«jѱnÖ¶wß»‚ä» .%&($#"$&)+!/.#0-#1,"5+%7/+811JG?gdXYWQ***##%))),,*,,*&#"+)%.,(0,)1**6//924=66E=;IC>EB:GDD@;@:5>64=720,'+)#%& &#$/+(43&24&46*02&10'-+%-*).+.*&.(%&)%")% (%($!*#'*'*')-**,/,--*)-*).))3*-/+(-,#,*$/+(2)*/ %3 S:,ŒoP­‹^¿ži¼›aŸaÖ°oѬfÞVÇ¢^ׯsÍ©pÀŸmϯuÞ¾ݽ~Áb»›\ϯpÔ±qá»zä¾Ó¬r»—^¾™eßdزsܵ}Åšnµ_°]¹—eÂœnÂœnÆpÓ¦‘-* '&#$&(,. ,+,)+(.+#/-'<:6STOVVT696" $!$ *$!.%(1*,3.0500611>9;D=AJCCIC>PMEMJBPLIRMOTOOXTQa[XaXY\ST[RSUOLXTQVTNRQHPOBPP@QNBFA7E@8B<962-41)/-',-())'!!!! !$$$-.'02&/1'/-'.,((%$*("+*+**)'%)$&))'&+'(,&*+$-+'.))-(,-'0+&*,''-+'-.'-.'-+%/+(0'(. ,;$U;"ŠjJ±gÁ›oÒªwÄœiµZÆžiϧrϧrÁ™fϧrÓ«vË¥hÁœXͨd×°mܵrã»{رw»–b³’VÁ¡^Ô±qÛ´zˤl¿•c²ŠUÃœdÉ¥lÈ£mÇ›ƒ+*!+)%'"$+'$.*%(%'$($+%"1+(F=>SJKH<>1(-+#, !"#%& )+(+/,+301607:57;74=;5AB;?A7DC8QKF[OSYMOWLK[SO\VQ]WR`ZW[VVWRT[WTYSNVRMPLGMGDLCDEA>:;48565/80/4-/3((*% "#! "%'&(&()+!)+!)*%(((((&*'&***)(-('.)'1++-*+&&'"(&")*%**()*#,.$-2')-%+,%,*$,+ +*/)$1%)0 ;(!dI7“qT²cÍ©n½™^¼˜_Æ¢iÌ¥mžeÄ£i˪nË«lϬnѪpÓ°rÔ´sÛ½w×¹q»œ[¹—`Æ¥kÓ¯vݹ~ΨkÀ™_¶ŽY»–`Å jÒ¦Œ%*&',!$&(* (&"($%'*!$6//B>;:125&-+"'% $  -     &#"*##0$(1(+4-15/,<5.>70E;5JB>OFGRLITNKTNIWPIUNGZSL[VNWTLZWM[VLVQGYTJUPHSMHPMEJG?LFAF>04769:JJLfijtyypw~`lxWgv]n[kZj‚Sc{Xh‚brŠjz’o…›rŠŸn†™uŒƒš«‹ž³¢·Ž¡¸‹žµ ºš°Ä˜±¿“ª»™¬Á›²Áš³¿›·Äž¹Ë ¸Í¨»Ô¦¹Ò¯Ë¥½Ô¢½Ó¢½Ó¨¿Ù¨½Øª¼Ø¬ÂÚ¬ÄÛ¬ÄÙ¯ÇܨÀÓ¥¾Î¨Ãո̦¾Õ¥ºÕ¨¾Ô¨¾Ò§¾Ï¦½Î¨¾Ò°ÃܪÁÛ¤¿Ú¤¿Ø§ÃÙ¥ÀÖ¤¼Ó¦¾Õ§¾ØªÂ×¥½Ðœ·É¤¿Ñ ¸Ï¤¸Øª¼Ú¯¾Ý©»Ù£´ÕŸ³ÓŸ³Ó¥½Ô§¿Ò¢¸Î£¶ÏŸ·Ê£¿ÌžºÇœ¸Ç£¿Îž·Ç™±Äœ´Ë—¯Ä¢¸ÌŸµÉ”§¼¢¹’¤À‹£¸Œ¨·¦·¢²È‡›­„›¬„­‚¯… ²ƒž²ƒ›®’§}¥‚’ª’©wŠ£u‡£r m{šs~žh{”d|n€‡ÀÇŪ¯·’¦€ˆžz†Ÿq‚ŽAO\=JO5>=/649<;RUVjlrns{dnx_kwcn`m_l€Xh{Zj€`t†fzŠoƒ•q™k{“xˆ¢|’¨z•§… ²…°ˆŸ°£³œ°À›¯¿™­¿£¶Ë˜¯À ·Èš³Á¡ºÆ­ÅØŸ¶Ð˜­È¬É´ÄÞ²ÂÜ«»Ñ¯ÀѨ¼Î¤·Ì¨¾ÖªÁݧ¾Ú®Â⪼ب¸Òª½Öª½Ö¦¼Ò ¶ÊÀØí±Éाע¼×­Çà¹Ðê¬ÆߪÄÝ°Ëá«ÆÚªÃÓ¬ÃÒ»Óæ¨À×£»Ò«ÂܨÀ×£»Ò¤¼Ñ¥»Ï§¿Ò£¾Ò¢¼ÕŸµÔ¥»Ú£¹Øš´ÍžºÐ¤¿Õ¡¹Ð˜°Å£»Ð£»Î™±Ä™¯Å›­É“©¿˜®Â§½Ñ›±Å˜¯À›²Ã–­¼‘¥µ¦µ ·È¨¿ÎŠž®†šªŒ ²‘¥·„˜ª‡˜«ˆ—­…–©“¥’¥€¥†—ª~¢y‰Ÿu„žn˜l‚–g€d}‹s‚ˆËÐЗœ¦‰Ž£~‰žy…žr€‹EN]RY`LSS6:=76=>@FST]lrwkvyapx\l{\m~\m€Ui{Wn_v‡dxŠm“m“n„˜o‡œx¥‚š¯… ´œ²†¡µŒ§¹Ž©»‘©¾”¯Ãª¾¥½Ò¤ºÒ™¯Çœ®Ê²Ï¡·Ö¡¸Ò–®Ã­ÂݤµÖ µÐ¦¾Ó¡¼Ð©ÄÚªÅÛ£¾Ô¡¹Ì«¿Ñ®ÁÖ¤´Ì©¼Ñ¦¼ÐžµÆª¾Ð­ÀÕ«¾Õ¡·Ï ·Ñ®ÆݵÍâ®ÄܯÁݨ½Ø¬Ãߧ¾Ú¥º×¬ÂÚ°ÃÚ©¿Õ§¿Ô¡¼Î¢¾Í§¿Ò©¿Õ¯ÇÜ¡¹Î¸Ì¥ÀÖ™°Ê±ÑŸµÔž´Õ£ºÖ¤»Õš°È£¶Í¦¹Òœ«È˜¨Â™¨Â˜«Â”ª¾–¯½˜±½Ž§µ§¸œ¯ÄŸ¹•¨¿˜«Â’¥º¡´™­½Œ£°ˆŸ®ƒ—©…œ­‚˜¬z’¥}•ª’§Ž¤…”ª¦xˆ›|Œwˆ™n‚”o•o{”y}ŒÏÊÎbdsƒ©†Ž¤€…˜t€Œnklnkjdb^EEE46:57;CEKZ^amsvhrx[it[lvXiuWgv^narƒbv†i€‘mƒ™m…˜z’¥„š®}¥‚•ªˆ˜®’¥¼Œ¢ºˆ ·ˆ¢»§ÂœµÓ›¶Ìš²Å¢¹Êš®À¥½Ò¥¿Ø¸Î˜³É§¿Ö©»×«ÁÙ¡·Ï¤»ÕžµÑŸ¶ÐŸ´Ï§¹Õ«º×¥µÍ¥¶É¢µÌ§¹×¥º×¨¿Û¦½Ù¯ÆâªÄߦ¿ÝªÄß³Êæ²Çä­¼Û²Äà²Äà®Ãࡵէ¾Ú§¾Ø¨ÂÛ¤¾×Ÿ¹ÒŸ¹Ò¹Ï¢¾Ô¤ÀÔš¶È¹Í¡¼Òž¸Ñ³Ò´Ð–«È§ÁŸ·ÎµÊ§º™¯Ã™¬Ã”ª¾’ª½¨¶•®º—°¾‘©¼‹£º‰Ÿ¾‘¥Å Ã‹ ½Œ£½Ž¦½£¹†œ°‰Ÿ³š¨{—¢‡£°™¬—ª—«ˆž²|¤xˆž{‡ s‚šx‡¡tƒr~™p—l|’ox…ÃÅË:>MELe€ˆž~†šv€Š^[\SSQFFD99932765:<8@HGNa`glqygqy_mx\l{WgzYh€]p…f|i“i“l‚–rˆœu‹Ÿ|’¦}“©}©ƒ™­Š¡²‰¡¶§ÂŽ¨ÁªÃŽ©¿œ´É—¯Ä•­Ä—±ÊœµÓœ·ËœµÃœ´Ç¦»Ö§¿Ö¢½Ó¢½Ó¥½Ô ·Ñš°Ï ·Ó¥¼Ö¨¿Ù¬ÃÝ£½Ö¡»Ô¤¾ÙµË좻۩Â䥾ަ¿Ý¥¼Ö«¾×¯ÁÝ®¿à³Êæ­Çà°Ëߤ¿Ñ¤¿Ñ¥ÀÒªÅÙ¥¿Ø­Ç⨾ݣºÖ µÒ¦»Ö¹Ï礼ӣ»Ò™±ÆµÊš³Ã ¹Ç°Çت½Ò¢¸Îœ³Í˜¯É™®Ë’¨À’¥¼‘§½™¯Å“©½Ÿ³Å—®¿‡ °‹£¶Œ¢¸‹¡¹Œ¡¾Œ¤¹‘ªºƒ™¯‡™µ¡½Ž ¼†™°€”¦ˆœ®„—¬yŸw‹x‰œyˆžw†œwƒšr~•my’kwŽgsŠciw¸·¼FIS.5;Kdjznvz06//4025657;46<57=68>808<9CI;JRS^FZjO`jFSX7?A6;9Ja>O`?SaCWeO`oN_iQ^gCKO;>?7:;BAFVX\imrdjxckt“fw†t…˜k{“j}”wŠ£u‹£yª{•®x’«€š³‚œµŒ¦¿‰£¾Ž¨Á©Â”¯Åž¶Ë³Ë£²ÏŸ±Í›­É—¬Ç—®È¨¾“¯Å›¶Ê—¯Â–¬Â¨ºÖ¤·Ð¢µÎ¤ºÒ§½Õ£»Òž¶Í¨ÂÛŸ¸Ö¥¿Ú¤¾×¥½Ô¥»Ñ¤ºÐ¤·Ð£»Î¤ÀϪÆÕ¬ÅÕ©ÄاÂÛ®Åᨹڟ´Ñ§¾Ø¨ÂÛ¥¿Ø¨ÂÝ¥¾Ü¡»Ôš²É ¸Ë¦½Î¶Æ ¸Ë¥½ÒŸ¶Ð›·ÍŸ¾Óœ¸Ìž¹Ë—²Æš²É”¯Á‡£²“«¾¤·Ð–¬Ä•¬Æ‘©¾‘©¼•­ÀŽ¦»‰¤¸Š¥»›´€šµ™´€šµ{•°€™·‡žº–±|’¨|’¦x‹ yˆžxˆžr…štŠ p†žmƒ™k—o…™i€‘d}‹fRkwKboBT`"/ =KXAR^GWfBRaAN^AR^AR\CRX:DJ29@8;CCIN]cfdnt^lwZkz_v‡]s‡fyp€˜ƒª©„š²„œ³ˆ ·†¡·‚³…´Š ¸Ž¦½œ³Í•¯È•¯È¦½×˜ªÈ™®Ë™®Ë–«Æ™¯Ç‘§¿—­ÅµÌž¶Í˜°Ç¤¼Ó¤¼Ó¨¾Ö«ÃÚ¦½×§½Õ²ÅÞ³ÉᢸЭÅÜ´Îç­Çऻפ¹Ö°¿Þ­¿Ûª½Ö¡·ÏŸ¶Ð¬ÃݪÁÛ­Âß«¼Ý¥¼ØŸ¹Ô¤¾×ªÁÛªÁÝ ¶×œµÓž·Õ¡¸Ò£¶Í°ÃاºÏ›±É“©È—°Î•¯Í”±Î›¸Õ™´Ï¡»Öš´ÍµÌ’ªÁš²É—¯Æ§ÁŠ¡»‹¢¼† ¹† »‡¢¸“«¾‡¢¸‚œ·x’­z‘­z‘«~”¬~•¦‚–¤ƒ—©|¨—­s‰Ÿu¤yªt‰¤o~m€™h{’i—f{–g}•f|”[q‡NavJ[l=KX".< #8HWBT`BT`@R^9JY?P\LZgIWdBN\6CL3=E;CGJOO]eiaks]nxcw‡o†•qŠšt‹œ}£}‘£Œ °‹Ÿ±Š´„š²†›¶‡Ÿ¶‰¡¸¨½™¯Å–¬Ä‘¦Á”©Ä—¬Ç°Ç—§½—®¿•±À“¬¼›¯Á›²Ã ¶Ê¢½Ó¡¼×§ÂÝœ¶Ñž·Õ£¼Ü¤ºÙ§¹×¤¶Ò£¶Ï«ÀÛªÀߪÂÙ²ÈÜ¡¹Ì²Êß­Åܤ»×ªÁÛ¯Æà¦ÀÙ¨ÂÛ©ÄÚ¦Á׬ÇÝ­ÈÞ©ÄÚ«ÆÜ«Ãب»Ð¤·Ìª½Ô©»×¢³Ô¡¶Ó¡¸Ô£½Øž¸Óš³Ñ—­Ð•®Îš´Ò£½Øœ³Ï•¬È’§Ä˜­È–«Æ‘©ÀŒ¤¹Œ¤¹•­ÄŸ·ÎŠ¡»¦¾—§¿†™°‚˜°{“¨w’¦z–¬y”­x”¨~™«u¢rˆ vŽ¥vŽ¥vŽ£—«u‹Ÿl‚˜k~“iycv‹_u‹_udy”^tŠZn€K_oEVe9KW->J"159J[@Td@Td?Sc?PaCTcHYh@R^@Q]O`FWhBSdGXkJZpIYoO^tIZmJ[lFWhBRc=IU:AJ:?GDGOOYc]jzdu†m“n„˜o…›z’¥ƒ›®…›¯€“ªƒ™±‚—²ŠŸº”©Æš±Í“­ÈŒ§À‰¤½“«ÂšªÂŸ¯Å¦¶É¢³Æ¬½Ð¢¶È›®Ã¡´Ë£³Í ¶Ìž¹Í¤¼Ï ³È¢µÌ§¹Õ©»×«½Ù§¼×¨½Ú¬ÂÚ¯ÂׯÂ×°ÃØ®ÄØ®ÆÙ¥ÀÔ¥¿Ø§¿Ö¨»Ô¥ºÕ¦¼Û®Åߦ¾Õ°ÆܱÄÛ³ËÞ¤ÀÒ¥ÁÓ¢½Ñ£»Ð©¿×Ÿ·ÊœµÅŸ»È˜´¿žºÉŸ·ÌŸµËœ¯ÈŸµÍ˜­È‘¨ÂŒ¦¿”®Çœ³Íœ³Ï˜¬Î•®ÌŽ«È‚¸‚œ·ƒ¶˜²ƒ›°…ž®‡Ÿ´ˆŸ¹|“­yª{’¬|“­{’¬|“¯z”¯x’­x’«x§y‘¤tj‚•k™e{“i~™^sŽi{—_r‰\l‚Tg|YlM`uK^sL_tIYoJ`f@H\AQb@TdFZjJ[lIZkIZmF]nA]lB[kDZnFWhDQa;HQ2O^BSfFViKXlJYoQ`xO`sL`pNbpQbqPapM^mFWaÚMMßMQãKTÌ]EÈ|HÿÿÅÿÿÃÿÿÇÿÿËÿÿÅÿÿ¸ÿÿÁÿÿÅÿÿÃÿÿÁÿÿæܵ¹ÑªÉΦãɨÕǮͨ™“åà·ÿÿäÿÿÛÿÿ×ÿÿÕÿÿÏÿÿËÿÿÃÿÿ½ÿÿ·ÿÿ­ÿÿ«ÿÿ«ÿÿ¨ÿÿ«ÿÿ¦ÿÿ¢ÿÿŸÿÿ¢ÿÿ¡ÿÿ¥ÿÿµhu…jz‹euˆj{ŠoxŠ–yŠ–‘˜…”š…”œŠ˜¥Š—§Š•¨{†—|‡˜‰‘u{~qtq~u~{q„u‰„zˆ~‘Œ‚‹†~“Œ…šŒ˜Ž„–~Ÿ—…¥‰ž™‚¤Ÿˆ¤¡¥£”ª£†È»ôð¤òõ‰øþ‘ÿÿ¢ÿÿ¯ÿÿ¸ÿÿ»ÿÿ¹ýÿ°ôö¡ÿÿ´ÿÿ«ÿÿ¿ÿÿÉÿÿ¼úýµòö§ùþªÿÿ²ÿÿ¼ÿÿ±ýÿ¤øý™øø”ö÷Žüþÿÿ ø÷œõ÷’þÿ—úÿ“úÿ‘þÿ•ýÿ”öú‹ÿÿ”ÿú˜ÿðœß´yÑ–xÿè¥úÿ›úÿ™üÿ›ÿø©å¢oÅYEßGTâJWãIVÃZNÜ¡ÿÿÓÿÿÅÿÿÇÿÿÉÿÿÁÿÿ´ÿÿ¹ÿÿ¹ÿÿ¿ÿÿÅÿÿ麢¬Í­ÕÁ—Þ¹ÔÁ˜ÜÈ¡ÙÏ©Ø»£©·­ŠÿüÊÿÿÛÿÿÕÿÿÑÿÿÍÿÿÉÿÿ½ÿÿ¯ÿÿ¨ÿÿ§ÿÿ ÿÿ£ÿÿ§ÿÿ§ÿÿÿÿ—ÿÿ“ÿÿÿÿ¢m~Špj{‡amynrmr…qy}‰•„‘–†–Ž•žŒ– Š“¢x…Ž{ˆ€ˆŒruvytttq€xtƒ{w‡„|ˆ‡|‡„|‹ƒ†‘Š’‹€š‘„¡•‡¥—ŠŸ–‰£œ‘¨¢”­¤•ª¥|àÝ™ÿÿºÿÿ°ÿÿ½ÿÿÄÿÿ½ÿÿ¼üÿ´ÿÿ¼ûÿ«ÿÿªÿÿ³ÿÿ°üÿ°ûÿµóü¥÷ÿŸÿÿ£ÿÿ¥ÿÿ­ÿÿ­øÿ¡üÿ¡ÿÿ¤ÿÿ£ÿÿ¨ÿÿ¨ÿÿ£ÿÿ¡öø“ÿÿ›ÿü™úõ—ùö“ýû•ù÷ûùŒÿíŠÿá‡ÉPõÈŒÿý§öÿ”ôÿ‹ÕèdÿôŠÒ2ÏZ6áIRÞILÞJHÂ_@ÿÛ¡ÿÿ×ÿÿÞÿÿÙÿÿÕÿÿËÿÿÃÿÿ»ÿÿµÿÿÃÿÿÓùãÝÇžÙÅ ÜǦãÁÛÄžÝÄ âÄŸæ¿›Ù·•É¯˜©Ã¶¤õñÅÿÿ×ÿÿÍÿÿÅÿÿ¶ÿÿ²ÿÿ­ÿÿªÿÿ¡ÿÿ¤ÿÿ¨ÿÿ¡ÿÿ”ÿÿ‹ÿÿ–ÿÿý÷ BMÿÿ¬ÿÿÅÿÿÕÿÿ×ÿÿÙÿÿÕÿÿÑÿÿÉÿÿÁÿÿËÿÿ×ɵ¥Å¡Ä›Ѿ“ßÄœçš志âšå›㾔ۿ–ÖÁ˜Ó¼¢¸¼®£õò½ÿÿÃÿÿ»ÿÿ¯ÿÿ ÿÿ˜ÿÿ™ÿÿ¥ÿÿ­ÿÿ¬ÿÿ¢ÿÿžÿÿšÿÿŠíÝ—ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÉÐÄYb]v„†”€—tzmjkupp{ur{ur|uu}wt€xv‚}u‚s‰„x‡€w†}—‡–Œ„›‘‰£œ‘©¤˜ª¥Ž³ª‰ÎÉÿÿ½ÿÿ¹ÿÿºÿÿ»ÿÿÀÿÿ¹ÿÿ³ÿÿ´ÿÿ¹øü­ýÿ´ùý°øü±þÿ«ÿÿ¢ûÿžÿÿ¬ÿÿ¨úþŸòù™ÿÿ­ÿÿ°ÿÿ³úÿ«úü«úú¡úö˜ÿü™þü–þûšøô˜ññÿÿÿÿ›ÿÿ‘øñ}üð{úë‡ïÚˆúò—òö•ûÿ¡õÿûþ’ÿý‰ì©gÜ]OßOPçHW×IZÊL`å Šÿÿ×ÿÿÓÿÿÑÿÿÓÿÿ×ÿÿÑÿÿËÿÿÇÿÿÃÿÿâÿúíµ”´·‘ཕà˜ἕ۽—Ú¾—ÝÁ–⽕㿖éÁ›ê¾˜åÂâßݷ¡¶¼±žëêªÿÿ«ÿÿŸÿÿ‰ÿÿ‘ÿÿ˜ÿÿ¢ÿÿ­ÿÿ¨ÿÿ¦ÿÿŸþÿàÙ‰ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿkq“s~{‰‰mttqnqspotpkuqlysnysnzrnwu„{|ˆ€|‡€wŠ†wŽŒ{’Ž˜‘†›’ƒ¤™ˆ«¢ƒ­¦{ßÖœëà–èâ”÷ö¤ûý¨ÿÿ«þÿ­ÿÿºÿÿ¶ÿÿ½ÿÿ½ÿÿÅÿÿÀÿÿ·ÿÿ©ÿÿ¢ÿÿ£üÿ§üÿ§ÿÿ´ÿÿ¹ÿÿ´þÿ°õþ«øþ£ÿÿ ÿÿ¡ÿÿ¢ÿú¥ôì¡üö¤üû ÿÿ§ÿú üô™úï“ÿ÷’ÿûþð‡ìÝ{ÿÿšåô†ìûòÿ™ÿûüè“ЀTàTQäJSëCZÔOJÀ]<ÿçªÿÿÅÿÿÉÿÿÏÿÿÓÿÿÙÿÿ×ÿÿÕÿÿËÿÿÃÿÿÛëٽȫÂÀ˜ã¿™ãÁ›èÁœã›Ῐཕ㽕དྷÞÇŸê¿—åÁ›åÆ¡èÁß¾šÚ¡’ÏÍ•ÿÿ±ÿÿ„ÿÿ‡ÿÿÿÿ–ÿÿžÿÿ ÿÿ ÿÿžúìŠòÞ ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿw†Ši‚ujrkvnlwomumkumivohwrjvrm}xpxq„}vŒ~Œ‡‹ˆ~‹ˆ|Œ}–‚”‡¢–{­u÷ð¥ÿÿ–ÿÿ¥ÿÿªÿÿ«ÿÿ±ÿÿ°ÿÿ«ÿÿ¯ÿÿµÿÿ²ýÿ¯ñùŸóùžøÿ¡ÿÿ¨ÿÿ¨ÿÿªÿÿ¶ÿÿ½ùÿ­õû­øÿ¤þÿÿÿžÿÿ—ùû–ÿþ¡üøšýù˜ÿÿ›ÿÿ˜üõ“ùì“þî–þí—ÿëžýã ÕÅ}ùò§òûœîÿ•íÿãüÿñî¶kÑiGäJSæIUêGZÍXRÈ}bÿÿÙÿÿÍÿÿÍÿÿÍÿÿËÿÿÉÿÿÉÿÿËÿÿËÿÿÍÿÿòǯ¹Å¥ÏÇŸêÉ¡ïÄ›îÆžìÉžêÛ濗å¸àµŒá¶’帗鸖ܾ˜×ŢۿѾ¬¢êæžÿÿ¯ÿÿÿÿÿÿ”ÿÿ™ÿÿ¡ÿÿ ÿÿ›þü–ÝÔ€üì±ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿy„w_dYqkfvqirmcpkaung|ul|ulytjzr‚|yƒz}Œ€‚}Š€vŒ†v”|˜“~—”a¿¼kÿÿ§ÿÿ¦ÿÿ¨ÿÿ¨ýü¡ÿú¥ÿÿ°ÿÿ²ÿÿ¹ÿÿ·ÿÿ²ÿÿ¶ÿÿµÿÿ³ÿÿ¯ÿÿ±ÿÿ¬ÿÿ«ÿÿ¬ÿÿ¬ÿÿ¶ÿÿ¿ÿÿµÿÿ¨ÿÿ¤ô÷üÿ£üÿ£ÿÿŸÿü’òï‡íæ„÷íŒýî‘ÿ÷˜ÿö”ÿíûÕ{Ó¾\ÿÿ™éï„ñÿ’úÿ”ñþƒÿáŽÕ|S×\MçHSåHTåHVÄWFä¨uÿÿÓÿÿÓÿÿÏÿÿÍÿÿÅÿÿ¿ÿÿÁÿÿÃÿÿÇÿÿÍÿÿôÄ”ÍËžßÇæÄãÅžäÊ¢ðÇ›ñÅœñ½•ì»—괓弙罗佘ݿ™Ú¾œÒº™Èªš‡ÿÿ«ÿÿ§ÿÿ‡ÿÿŽÿÿÿÿ–ÿÿœÿÿÿÿšñÞ‚æÀÿåºÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿqpgmj^pkaqjcrmevqixskwrjwqlzrp|tr€wx„~yƒ~tƒ|uŒ~ƒy•Œ}–’fèæÿÿ®ÿÿ¤ÿö¤øÜšëØŒñã‘üóŸñì—éçìê’æäŽàÚŠìé˜ðíœìë›÷ø¬ÿÿ¸ÿÿÅÿÿÍÿÿÆÿÿ¸þÿ­öü£ÿÿ®ÿÿ¬ÿÿ©ÿÿ¦ÿÿ¥üûœøô–öó’ÿÿŸÿÿ¢ÿýûõúôÿë•ÿݙ̵aÿýšõþ’öÿ—ïøŽïêŒÃƒKÝbQÞSSìN_áKSÜLM¹b/ÿê‡ÿÿ½ÿÿÉÿÿÉÿÿÉÿÿÅÿÿÁÿÿ¿ÿÿ¿ÿÿÇÿÿÑàϾ ÉÆžÙÆšéÇœèÁ—àÁ–åÈœòÆðÄᅵ彛ßÂâ¾—ß¾—ݾ˜Ûº˜Ê¹½¯¥€ÿÿªÿÿ¡ÿÿŽÿÿÿÿÿÿÿÿŒÿÿœÿÿ£ÔÌqåÒ‹óÛ¯ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÙÜÝeinnklskgslevofqlbuphupdwqcxsi}wtytzs€yrƒ|uˆpŒ€i¨kÿÿ´ÿÿ±ÿò›ùë—úé˜øï™ÿú£ÿÿ¢ÿÿ›ÿÿ£ÿÿ¢ÿÿ«ÿÿ­úý¥ÿÿ¯ÿÿµÿÿ±ÿÿ°ÿÿ¬þÿ©ÿÿ°ÿÿµÿÿ¸ÿÿ³ÿÿ´ýý¤õõœúø ÿþ§ÿÿ¦ÿÿ«ÿÿ¤ÿÿŸÿü›ëæŠñä‰ÿóšÿí¨û¸…̪aùõ—õý–ñÿ”ÿó‘ä´`Æd>êT^ãKXêL]ãPYÞRWу]ÿÿÉÿÿÉÿÿËÿÿËÿÿËÿÿÇÿÿÂÿÿ¿ÿÿ½ÿÿ×ÿÿò¾ŸµÌ¤òÉžêÉ›åÅšæÄžíÅŸìÛ澘âÄžëş콗濘࿖ڻ’Ô¾”Ô¼›Èº¢¼¿µÿÿ·ÿÿªÿÿšÿÿ’ÿÿŽÿÿŠÿÿ„ÿÿÿÿ¨ÓÀtöØ þÞ¾ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿÿÿÿÿÿšŽ¤lanrilskiskgoidmifokfuojwsp|wyxx€wxyt€{s‡~oŠ~gÊ¿ÿú¯ðä‘äÔ|õê’ÿú¤þúœþþšÿÿœýÿ–ÿÿ¤ÿÿ©ÿÿ¨ýý¦úý£ÿÿ°ÿÿ°ÿÿ·ÿÿ¾ÿÿ¹ÿÿ¹ÿÿ­ÿÿ¬õú¤ñö úÿ©ÿÿ®ÿÿ«ÿÿ¦ÿÿ¨ÿý¡öò˜ïî“÷õÿÿ¬ÿÿ«ÿÿªÿúŸÿÞ¡ß“tÈbøï›óø”ëýŒú݉¿o:ÔbKíU`áGPíQXâZVÐYKæ§jÿÿ³ÿÿ½ÿÿÇÿÿËÿÿÏÿÿËÿÿÇÿÿ¿ÿÿ¹ÿÿÏÿÿؽ¥«É¡ÜÇáΟïÇœëÇŸíÉ¡ñÊ¡ôÛéÅèÊ¥ìÊ¥ìžàÀšÛÀ›×¾™Ó¼ Àº¦¯ÌÅÿÿ­ÿÿ¥ÿÿŸÿÿšÿÿ™ÿÿ“ÿÿÿÿ™ÿþŽâÒsùÜóѤÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿû¹Ô§`kSmgdngiphomhjlheokfnkcuphwokrkd{qk|unxqƒ|a‹‚VìÛœöÜŽúä—ÿò¦ÿõ¤üù¦ÿÿ£ÿÿœÿú óÝ’é׆øç”ýõœÿÿ£ÿÿ¦ÿÿ¥ÿÿŸüÿ•ýÿšíîàà‰åã–üû§ÿÿ¨ÿÿ²ÿý«úõ ÷ñšòìœõî§üú¤ÿÿžÿÿžÿþ”øõëä‚ðà†ÿç”ÿÏŸâ}r¸Pοpóíˆôô{´{5ÉVDÕRLàJTæMSëMSÛVQÔgZÿôÅÿÿËÿÿÃÿÿ»ÿÿ¿ÿÿÃÿÿÅÿÿÉÿÿ½ÿÿ±ÿÿÞãÁÁŠØ߾˜Û½™ÙÄ âÆŸçÄ â¿žÝÀŸàÄŸäÂäÁ›å¾™Þ½—Ú½™×»˜Ó²˜¾¨•©æà®ÿÿ¦ÿÿ ÿÿžÿÿœÿÿ™ÿÿÿÿŽÿÿšøíŠÝÄqíÃë¿œÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¾±Ÿtjbkdfmfjmellgimhholkolkpliysnvskzwmwtjyvlx_˜‹eëÛ ÿî ÿô¤þ÷§öó üü¥ÿÿ²úó£õè˜ñߎýòšÿÿ£ÿÿ¥ÿÿ£ÿÿ²ÿÿ»ÿÿ·ÿÿ³ÿÿ¯ÿÿ°ÿÿ¬ÿÿŸÿý“ûø’üú’øùŽÿü›úôøó—û÷–ýù–üö‘ûøŽõô‡ù÷ÿÿ›ÿýÿï›ÿ³…ád_ÑqYʃ[ÿ¼ŠÃxAÀW=ÝSWáTVèVXîY^ãIRÈ]DÏWÿÿÇÿÿ¿ÿÿ¿ÿÿ¿ÿÿ¿ÿÿÁÿÿÁÿÿÃÿÿ»ÿÿµÿÿÝ¿¥žÄ¤¿Á˜Ø»•ØÛæÊ£ë›㿗⾓âÆžéÅ çà龞ë½åÀ¡æÀŸÞ·”Ï´š¾³¡®ÿûÉÿÿ¬ÿÿ¦ÿÿŸÿÿ™ÿÿÿÿ‹ÿÿÿÿ›ðÙà¾w뽈ò¿ªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ«¤¦‚‚bafgdgmfhkddnheokfplguphzslwrhwtjwtj|wmuZ®öê§ÿû¦þþ¥ÿÿ¦ÿÿ²ÿÿÁÿÿ¶þî˜ðãŒÿñÿÿ¢ÿÿžÿÿ¢ÿÿ¢ÿÿªÿÿµÿÿ½ÿÿ½ÿÿ¾ÿÿ¿ÿÿµÿÿ®ÿÿ´ÿÿ«ÿÿ›ÿÿ•ÿÿ•ÿþ˜ýú—þúœýú—ÿÿ—ÿÿ›ÿü™ûô’÷íŽÿáÿȇâ|\ç[`ìd^å^QÙOJÖFIÖGSßQfåT\ìXVéSTãGNÅZHÿÉŸÿÿÑÿÿÇÿÿÃÿÿÁÿÿ¿ÿÿ½ÿÿ¿ÿÿÁÿÿÅÿÿÉÿøߺ–·Ç¡Ðš׼–Õ²ŒÍ½–ÜÅèÜ⻒Խ–ÜÂœæÄŸæÁœá¼˜Ø¿™Ø½™×½™×²©°¨„ÿÿÄÿÿ¦ÿÿ¢ÿÿ ÿÿŸÿÿ—ÿÿÿÿÿÿ”èÌxá¼vè¸î»¤ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿž¤}yca[_`GhlBaaBgdPkk[kmaonctogwrfuqbwsbysc…|PëÝ–ÿù¢ÿÿ™ÿÿ¡ÿÿ£ÿÿ±ÿÿ´ùì•îÙ‡õç“ÿû¤ÿÿ§ÿÿ¨ÿÿ¬ÿÿ­ÿÿ¡ÿÿ“÷øüù˜ÿþ¡þü¦ôóŸðò¡ùø¤ýû£ÿÿ¡ÿÿ¦ÿÿ¦ÿÿ¢ÿÿªÿÿ®ÿÿ¨ÿøŸõé–ïà“ÿõžÿÿ¢ÿä¤ÿ¥‚ÜeWí\dòagð`càRWÍAJÞMSô]añX\óU]çSSÜRKÍ~Kÿÿ¯ÿÿÃÿÿÍÿÿÍÿÿÏÿÿÇÿÿ¿ÿÿÃÿÿÉÿÿÑÿÿÙêÔг‹ÃÁ—×”ܽ”Ø´Ò¶’Ò¾˜ÙÄžßÃàßḓؼšÞ¿ã¿žßº–ֳɿϹ¥¥½µ„ÿÿÇÿÿ°ÿÿ ÿÿ”ÿÿŽÿÿŒÿÿÿÿ“ÿõ—ã»ೀ㳋峠ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþíÿؾûuiŠ_`i`cmýÿÿøöÿe^jkfhkh`ljdmkgqoisphxrd~sb›dúì¥þøªÿÿ­ÿÿ²ÿÿ³ÿÿ³ÿÿœ÷ôŠöë†ÿÿ™ÿÿŸÿÿ¤ÿÿ©ÿÿ®ÿÿ¯ÿÿ¨ÿú˜úö“ÿýœÿÿ£ÿÿ§ÿÿ¨ÿÿ¥ÿýœÿû–ùõ’ñíŒøõ”ôó”ÿÿ¥ÿÿ±ÿÿ­ÿÿ©ÿÿ¦ÿþ£ùê‹õÞ{ÿÈ‹ï}fÚ\Sé]bé^`çZZÛOJßPJñ\VïSOïOSëGTßLWÙV`ô¯†ÿÿÃÿÿÅÿÿÉÿÿÅÿÿÃÿÿÁÿÿ¿ÿÿ½ÿÿ½ÿÿÃÿÿÉζŸ»“·Á—Ç–Ô˜ÚÁ—Þ¼•Û½–ܼ˜Ø¯ŒÇ¶’н—Ø¿™Ú»•Ø¸”Ò»˜Ñ³•Ã±”»¯˜áÛ©ÿÿÆÿÿ¡ÿÿÿÿ–ÿÿ’ÿÿ‘ÿÿŽÿÿ‡øÝ}è´|æ¶å¶†å²ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¸Ä¥ÒÖªnn^^YffgrÿÿÿØÞãW^^ddbb\YVVF;.+ÑGDèTTçJMÂVBö»ÿÿÍÿÿÁÿÿµÿÿ©ÿÿ«ÿÿ³ÿÿ·ÿÿ»ÿÿ¹ÿÿ¹ÿÿµÿÿ³ÿÿ±ÿÿ±ÿÿ±Ð½a™€b¡€¢²½¾–Ó»“йн—Ö»•Öº–Öµ‘Óº™Ú¸–ڷʱ´µ²ÿÿªÿÿ¦ÿÿžÿÿœÿÿžÿÿ”ÿÿÿÿÿù™àÆxÞ²zß±zá±|Þ¬™ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¶ÁÒª¯­ŸŒmkeWV[yu{ÿÿÿýÆi`l_[c±°µÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÏgoÓPd·lQÿÿ¶ÿÿËÿÿÉÿÿ·ÿÿ§ÿÿ¥ÿÿ«ÿÿ­ÿÿµÿÿ·ÿÿ¹ÿÿ»ÿÿ¿ÿÿ»ÿÿ¹ÿÿ³ÿÿ­ÿÿ¬òÛ|™yR°„•µ±»“ι‘̵ŒÉ½—Ö¼˜Øµ‘Ï»–Ò¹œÃ±š­ÚÒ£ÿÿ¯ÿÿ¤ÿÿœÿÿ•ÿÿˆÿÿÿÿ~ÿÿ’ÿéŽÕ¸fÙ²mã¹wÜ­qÙ©ŒÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÏÖÔx‰vŸ¤—“‰ƒhaa[U\‡ƒ~ÿÿý°­¡hc[][UÅÅÃÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¹ÀÆhqÉT`ÑŽjÿÿ·ÿÿ¿ÿÿÁÿÿ·ÿÿ­ÿÿ«ÿÿ©ÿÿ¯ÿÿµÿÿ·ÿÿ»ÿÿ¿ÿÿÅÿÿÁÿÿ½ÿÿ·ÿÿ³ÿÿ§ÿÿ›ÿÿ®ÿø»Æ¤”h‡¤~ª­„Á±‰ÄµÊ¹•ÌÁšÐ³˜±¬™úöµÿÿ ÿÿœÿÿ“ÿÿ”ÿÿŠÿÿƒÿÿ€ÿÿ’éÒ~Ö¸kÙ¯mÕ©hÙªlÓ¡…ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïúûdlc’œ›’}vvMHL@BC<õôéûýóÿÿÿÿÿÿÿÿÿ—”JODMTDNVArxR¡£n““h‹‰jŠ‹ižŸ{¬®‡  y““lžœvi™›t——p•’o¨¨¨¨¬®ƒ«­‚¢¢w©§}¤¥u‰X¥¥s®¥yµ­~¼´…·±º¶ˆÈÆžÞÝ»àÞÃÜ×ÄÕйÏ˱ÑͱÑͱÚ׶áß¹ÏÌ«¾º àÜÀãßÁÜغ»´™ Ž„Œlu§‚®‚xÿî©ÿÿ“ÿÿ—ÿÿ§ÿÿ§ÿÿœÿÿ—ÿÿ‘ÿÿ“ÿÿ’ÿÿžÿÿ¨ÿÿ·ÿÿÁÿÿÃÿÿÉÿÿÅÿÿÁÿÿ¿ÿÿ¿ÿÿ»ÿÿ²ÿÿ¤ÿÿ’ÿÿ—ÿÿÿÿ²áÄ¥š{˜}–Ÿ•yÚáŽÿÿ¯ÿÿ’ÿÿ’ÿÿŒÿÿŒÿÿŽÿÿˆÿÿˆóå|Þ¼uâ»vÞ²o×­kÔ¬nΠ…ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøõÿD@HWRRqoitsjmlaWTJ++)./8º¹¾ÿÿÿÀºµ¼µª¹¶®ÿÿÿÿÿûõòêÿÿÿÿÿÿ¡¤¡nrjfhZffT‡ƒi¢”u’…c–‰g•m—“g•mšm¡”n “j™d¤—qŸ•n¡—r¡šmš—d¨¢p§œn­ w­œy¦˜v™‹n¡—t“n¥›t¯¦|·­†Å¸–ÚÑ°íæÉòðÕïîØìëÕîëÕñìÕôìÖòîÒòîÐòîÒ÷ð×øñØõîÕÞÖÀàÕÄ­ ›VFP›Œˆ¤”ƒ×Ôþÿ“ÿÿŸÿÿ ÿÿœÿÿÿÿŸÿÿ›ÿÿ•ÿÿšÿÿ›ÿÿ¡ÿÿ§ÿÿªÿÿ¯ÿÿ±ÿÿ¯ÿÿ»ÿÿ»ÿÿ»ÿÿ±ÿÿ®ÿÿ¬ÿÿ¨ÿÿÿÿ£ÿÿ—ÿÿ‹ÿÿÿìœæÙ€ÿÿ©ÿÿ­ÿÿÿÿ—ÿÿÿÿÿÿÿÿ‘ÿÿŒéÎså¸|á´vÚ­oÞ±sܯsݪ‘ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿñõúBHMPNJg]Spkakgba[XJAB&#$)+/ÎÎÐüùüoloXSW[U\ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ«ªŸ™–‚Œˆn”p§¡ ˜t—Žm–‹m˜Žk†_‘‰aŽ†`Ž‡\’‰]‡]“‰b“‹e‘ˆg—kˆb—i–Œi˜Ži›Žh–Œe“‹c‘‰a’ˆc†e‘‡mvX™‹l›”wŠŠoµ¶ÅɱÈɲÏθÖ×ÂÙÙÇÞßÊÛÜÅÜÝÆæåÏäåÐÑÑ¿±²›¼¾¢Ÿ›ŠXJH—‡ˆ›‡Ž”ˆo¼·~÷÷žÿÿÿÿÿÿŠÿÿÿÿœÿÿÿÿ£ÿÿÿÿšÿÿÿÿ¥ÿÿ«ÿÿ®ÿÿ©ÿÿ¬ÿÿ¯ÿÿ¯ÿÿ±ÿÿ«ÿÿ¯ÿÿ«ÿÿ¢ÿÿ­ÿÿ­ÿÿ¬ÿÿ¥ÿÿŸÿÿŸÿÿšÿÿšÿÿÿÿ›ÿÿ™ÿÿ—ÿÿ‘ÿÿ–ýè„ݽjá³rà´sà³uàµxݵyÖªŽÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüòÿHG\HMWVVXhb]mgbg_]`[[A>A!#"4//00.),)bb`ÿÿÿÿÿÿÑÅôÿÿÿÿÿÿš–‡Žƒp‹f•†g ‘tšŠr‘‚h„fŒa€^Ž_Ž€a†{]‰e‰}bŽ~d‰~`‡a‰ƒcˆ~b‹e…y^‹d~dvXŠ`Žˆhx[a^JA>6adSüÿìÿÿþÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿþýÿÿüÿÿúÿý÷ÿÿüÿÿÿÿÿÿÿÿÿÿþôùõäìáàzdw‡wƒ‰}ƒ…v}†tšŠpÑÁ„ïêþþŠÿÿŒÿÿÿÿ”ÿÿœÿÿœÿÿ–ÿÿ’ÿÿ”ÿÿšÿÿ¡ÿÿ¤ÿÿ§ÿÿ¥ÿÿ¥ÿÿ¡ÿÿ¢ÿÿ¢ÿÿ£ÿÿšÿÿŸÿÿÿÿ˜ÿÿŸÿÿ£ÿÿÿÿ“ÿÿ˜ÿÿšÿÿ˜ÿÿ“ÿÿ•ÿÿÿÿ–óՈ߻pç»vè¹{ã±{ݯx׫sÛ­”ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿêèòLH^TSZSTMVZRY]WVWPXTOLJF965!!#6/1?A=:KDD@;=   #254:84GE?EA83OKFd`[KGDVQQuppXQSOLMTTTSQM93._\HÝÚ¹ÄÁžâàºÀ¿›ÔÒ³——|SRMP?8=048226.-/%01,'$%$$$###"& "'"" %!)%"#5-+>;3GF9@?2FE:PODVSKa]XPLITPKVPK<9:"!(@IF)>2~†sÿÿåàÝÑiiiQOKVSKVRMQMJWSPb\YXSSVSTWRTYPSSLNLGINLHPNHUSOURSMPMBGCÂǸÿÿðÿÿýÿÿÿÿÿÿýÿâš“[èÍ„ÿò¢ÿôÿæÿè“þå­Æ«’ÿôéÿÿÿÿÿÿÿÿÿÿÿÿÓÔ¦ ’\µ–WÀ f³’`§ŽY§‘^•‡SvDŠ…N—•[“”Y‚G…„D¡žZ©¥i•d€p]aLUgR^ubrxhixj]œŒbѽvâÏáÍxêØwïÞtìàiðæc÷ôhùþkûÿqüÿwÿÿyÿÿwþÿsþúsÿì|çÃkä»pã¶xÜ°oÓ§fÉžaͤkÕ¬s仂繠Ž–˜"'%>?:?A7?>1AC7DFIBBYRRC:;:61:<213)*+$RMMWKQF:<=A;;?7?A7>@6:90NM@PP@10'2/.    $!4/3 ?A7@C2jkTZZJ@?6KJ?HG5<:464.3/,2.+952HFBOMIOLKROPPKKTNKUTKOQCJL>LNBUTKTNIRMEOHANHCJEEHEDDDBGGENNLDEP:;Sª¬½ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¢«ª81Íɸÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿíη‹Ò²q¸—[²[ƤoÀžl«Z±”c¼£nêu©“b’€R}U~_ƒX“ŒT‹†M‹†Oª£kª i‹€`naZdXZeXcl_hdW`h[T‰}f£˜fÁ·hèß{êßhíèjòðoïógéñ]ùûtÿû„àÎmѲhʬbȪb̪eШjΨkΧoÓ¬rÛ³wݯ”79=8;<9<;=@=9:523,45.46,24*99;(  - -  - -   -  - 49.,."KJ=<;.46,04.///$%!!&&&589BDHJGHNEFLFCKE@IF>GD5<:451,-'$'#&'"892A?9DC8DC6BA4FE:DA9D>;EABGE8ELZioÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿâå濾ŭ­­›—„~ybUP4$%-19&#ZA3‘s[³’n¿œm̧qÏ©l¼•[´Uže½œb¬‹T¹˜cȪtȪw·™c°X¸˜\ʪiÉ©j¼›_¢hÓ²{Û½…çp°˜[“~>F1 *L<;bWdj`hl`f”‡uµŒÔÅ”¨–\š„KÖ¸‚Ü»„×µ~޺߹|â¼â¼ݺ|Û·|ݳß°ƒÐ¡218446///.+,/(,,'+0*11-3105775HG>STM894==?^[ZXTQ]WT^UVXSSQNM`]\e```^X[]Q_aU]\SZVQ]VV`WXj^`_YTXWNUTIQNDQNFKGBDB=<365(98-74,1/)&#"  1.-A?;A?;CA;BA8@B4EH7CHFCIW™¡ÞÿÿÊáàÈÍÉ–’^QJ.# #""2*1KFJ\YXjhdlmfdf\bdXJI<4/#f\R80,815?43SA>|cU¡€i½œzŸuª‰Wµ“\¢h°V©ŒQ¸œcħjãd»›_¼œbʪnÔ´u¡eßfÑ®pصsȨgŦg˱l»¥\†u6aSn^4dS2[O!\R‘E¸œc¿¢g¹˜^»›aÁ iÁ kË©w×µƒÝ·‰å“޻ŒÞ¹ˆß·„âµ¢4/140--*".)!.' +'$.+.0+-4-/;66@=;@78<6130&'$$%43(GD:GB:JB>L@B/ % B6@WTSa[Xg\Yia_ibbiebiebgeanlhqoklihljda`UXWJJJ:/.%+&(&"(+)33.2:.0@.)bH?š~l»šƒ¬jº›m¼žk­ŒW­Y¹›hÁ¢cƧ_¿XͧhصsÅ£^ÁŸZΩeʨcƦc½žVÊ«aÖ¸kݼnܽuéÉŠëËŒçLjʫj¾Ÿ\¢aЭoß¼|Þ»yÛ¸xÑ®pÅ¡f¼”_´’[ª‰Tª‰T³‘\º‘v.&-+&(*'&)% *%+'$+&(2-/;46<77;87886()$a`UYWHIF:E@6A>4A>4CB9B@D>9D@;@B88=2/5,$+'!'!2.+D?AOLKfgbhj^‰Œy_aUWWUZXTXTQWSPVPMNHEKBC<59/'0$"$**,+ .*',)(-*-.+,2-/6.,7'&6$8#fK7¡a¨ˆ_²‘_¹—h°Ža·—]É©fϯlÄ¡a¼œ[Í®mаm¿šVͪhʧgήkήkÀ¡YË©`Ô²mÛµxÙ³vÞµ|È¢eµ’R¸•SÌ©gá¾|çÄ‚Û¸xɦhȧkÆ¥k˪nÒ±uÕµvÚ·y滚'#)(%('"$&!!)"",(%.*%.-$10'43(52&65(  TMFRJH9031)'9/)7/+5/,611615;468/0<42A63D<8IC@JDAMFFOFGQEGWLIWMGYRK\UN]VO]UQ[VJZVEZXI[XL\WM[TMUNG\RLSKGLFCKEBF@=<;08;*87.0++,(%(""$-0=:IE@GC@MFFUOJ\UL\UL[TK]VM_UMaZQb]U[XPXTO\WOZSJYTHTRCKHLZ^atx}nq{[biTafgnl¥¦Ÿƒ‡ŠflzZft_l~XeuVdqQbnVgvYm{bv„e|‹g’s‰Ÿ€’®Šš°‘ž°“¤·”ª¾ž´Èš°Ä˜®ÄŸ±Í§ºÓ©¹Ó¨¸Ò«»Õ©¹Ó·Æà³ÃÛ°ÀØ©¹ÑºÉã±Àݯ½ß®¿à¯Ãå²Éå¬Æ߯Êà¯ÊÞ¬ÇÛªÂתÁÛ­Áá³Êæ·Ñê¶Ñå±ÌÞ«ÆØ«ÆÚ­ÈÚ«ÆØ®ÄÚ°¿Ü°¿Ü¬»Ú©»Ù¨½Ú«ÂÞ­Æä°Êå´Ëå­ÅÜ©¿×®ÄÚ©¿Ó°ÃÚ°ÀÚ¦»Ö¡·Öž¸Ó£½Ö¤¼Ó¢¸Î¥»Ñ¢µÎ¢¸Î¢¸Î¦¼Ò ³Ìž´Ìž´Ìš°Èž´Ìš°È˜«Ä”§¾›«Á°Ç¯ËŸµË–¬À”§À¤³Ò”£À‘¡»•¤Á’ ¿ ³“¡¬’£¯‹›ª‰š«ˆœ®ƒ—©~’¤€‘¤ƒ¤€‘¤‚•ªv†žsžm}—i|“hxfufu_k„S_vmwzƒ@FI`eexxzjlrWZdgim£ Ÿ‚†‹bhxR^lQapRbqP`qO_pWdx^nhxŽi“q‰œu vŒ ‚•¬“£½¢²Ì¬Æ”¤¾š­Æš°È›±É¦¼Ò ¶Ê§¾Í­ÁÏ®ÂÔ²ÂÚªºÔ°¿Ü¨ºÖ°ÂÞ®ÄÜ°ÆܯÅÛ¯ÂÛ®ÅߨÂÝ­ÈÞ°ËÝ©ÄÖ¦ÁÕ¥¼Ö¢¶Ø©¾Û©¾Ù¬ÄÛ±Ìâ«ÃÚª¼Ø®Àܯ¾Ý°¿Ü·ÇáµÈ᩾٧¿Ö¥½Ò£»Ð¤¼Ó¥½ÔŸ¶Ð¨ÃÙ³ÎâªÆØ¥ÁÓ ¸Ï¬»Ú§½ÕŸºÎ›¶Ìœ¶ÏŸ¶Ð®ÀÜ®ÁÚ¤·Î¤ºÐ ¸Ï›±Å¦ºÌ´Å™¯Ã¡·Ë¤ºÎ ·È‘¨·–­¾³Ç’¨¼–¬À›¯ÁŸ°Á›«Á–¥Â‘¤½£¹¦¾¡½‡š±„—¬†¬‹£­ƒ›¥…™§†šª}‘£¥‡–°Ž¦w†œt„št„œq„™k‘iz‹k{Šo~†…“tƒ‹y‰štƒ‰295ELHgljqvv_cfeee¢ž›ƒˆˆ\fnNZhP\sO_pQapN_pZj€_o‡fum}•q„›n„˜x‘¡Š¢µ…²Œ¢¸’¥¾–©Â™¬Åš°Æš°Ä•®¾œµÅ¬ÂÖ©¹Ó¤ºÐµÊ¡·Ë®ÂÔ ·È¦½Î¦¾Ó¨ÂÛ¬ÂÚ³ÃݶÉâµÇã°ÆÞ©¿Õ«ÁקºÑ­Ã×±ÉÜ­ÅÚ¨ÀׯÅݸÇä°ÂÞ«ÀÛ¦½×¤»Õ§¿Ö«Ãئ¾Ó¦¾Ó¨½Ø­¾ß¨ºØ¨·Ô­ÂݲÉã±ËæªÄâ«ÆܨÀÓªÃÓŸ¶Å˜®Â¤·Ð¡´Í ²Î£µÓ©·Û§¸Ù¦»Ø§¾Ø¥ÀÖµÍ䫾״ÇÞŸ²É›«ÅœªÉ˜¨Àš®À˜«Àš­Ä’¥¾•§Ã°Éœ¬Æ™¯Å–®Ã§ºˆž²†œ²ˆž¶„š°Œ¢¶‡Ÿ²Š¢·ƒ›®€—¨’¥~Š¡z‰¡r‚œzŠ¢w†œ~’¤n…”r‰šq„™s„“t‚œ£¬ÄÅÎŽ”¤ušo~†0478:>POVooqrrrqqqš—˜†Ž^k{QarJ[nJ^nG[kNbt\l„aq‰hxpƒšr…œo…›s‰Ÿ}“«Ž ¼Œ¢º‹£ºŒ¤¹’¨¾“©½•©»–©¾£¶Íž´Ê—¯Æ¡·Í­½Õ®ÁØ£¶Ï¨¾Ò§¾Í¨¾Ò¯ÂÛ¬ÂÚ¯ÇÞ³ËÞ¬ÃÔ¾Ôì°Áâ¯ÅݬÂÖ¯ÇÚ¨ÃÕ³Ïã§ÂÛªÅÛ®ÆݪÅÛ£¾×¡½ÏªÆÓ¤ÀϬÄ׸Ðã«ÃØ£»Ð­ÃÙ¦¾Ó§¿Ô¨ÃׯËá§ÂÛ£½Ø©ÄدËÚ¬ÈÕ¤Àͦ¿Í®ÂÔ£¶Ï«¼Ý®ÀÞ£µÓ¢·Ò¨Àק¿Ò¦¿Ï±Éܨ¾Ô¤·Î¶Æহқ­Éš­Æ–©À‘¥·“§·•©¹’¦¸“ª¹’©¸Œ£²Š¡²¤³‡›©ˆ ª†ž¨–¯»Ž§·‚š­}“©|•¥‰¢®…ž¬vŒ wŠ¡sƒy‰£uƒ x‹¤s‰¡o…›l‚–j|ˆ{ˆ¶ÀÆŸ¤¬ƒŒ™s~“my…/42256>=D\[`potxuv˜‘‘~ˆbgzMZlXi|QbqOamRft[o]t…d{Œi€‘mƒ—n…–u‰›|’¦‰Ÿµˆ ³ˆ ³ˆ µ”©Ä–¬Ä˜«Ä—­Åž´Ìž¶Ë¢½Ñ§½Ó¤´Ì¤·Ð§¹× ¶Ì­ÄÓ´Ìߧ¿Ö¤¿Õ¢¼Õ¨ÂÛ¸Ïë±È䨾ݪÁÛ´Êâ®ÆÛ¬Ä׫ÆÚ¬ÈÞ¯Ëá§ÃÙ¥ÀÖ§¾ØŸºÎ¦ÂÑ¢¾Í¥½Ð¯ÇܲÊá²Êá®ÆݬÄÙµÍâÀØïµÊ秿֞¹Ë¥ÀÒ§¿Ô£¾Ò¥ÀÔ¤¼Ïª¾Ð¯ÅÛ©¾Û«Âܦ½×¸Î¦Áמ¹Íž¶Ë§¿Ô¤¼Ñ•­Â¨¿’¨À˜ªÆ›®Å˜«À˜«À›®Å°Åž¯Â¡²Åœ¬Â•¥»”¤º‘¢³¡°‹Ÿ¯‹Ÿ±Š ´ˆž´…›±ˆ›²z¤}•¨„­~•¦yŸ~Ž¤zŠ ~¥w‡t‡œp„–k‘lz…’šžÇÎÕ™žª†Ž¢~ˆ¤u‚’2=@.68499?DB]`_psr………uy~fkwZfrWhwQbqTduUdzWf€bq‹etŽrƒ–w‹™†¬wŽŸ}•¨‰¡¸‡š±‘ ¸•¥»”¨ºŸ³ÅŸ³Å™¬Á–©Â˜«Âœ¯Æ¥»Ñ™¯Çš°Èž³Î¡·Ï¡·Í¥»Ñ©¼Ó¤ºÐ¥»Ó¡¹Ð¤¿ÕªÄß²Èé¸Ïë²Éã ·Ó¡·Ö©ÃÜ°Ëá¥ÀÖ¦¾Õ¤¿Õ¡»Ô¦ÁשÄÚ«ÃÚ©¾ÙªÂÙ»Óè±Ìà°Ëá©Ãܧ½Ü¢¼×¨ÂÛÁÙî´ÊÞ®ÄÚ©»×¨»Ô¨»Ô–¬Â¢¸Î¥½Ô ·ÑžµÑž´Õ£¹ØŸ³ÓŸ¶Ð¡¼Ò¨ÀÓ§»Í°Å›®Ç³Ë™®É’¤À‘Ÿ¾˜¦Ã©¸Ò—§¿˜¨¾ ³‘¢µ’¥¼¤¿“£½Œ˜±‰™¯‹Ÿ±†®‡Ÿ²ƒš«‡›­€”¦|¤wŽyx‘Ÿ{”¤vŒ¢t†¢q™q€–o€“l}o{‡®´¹ÂÉÔŒ”¦~‹w‡qƒDKV8;C327779KHKdgfszxkvw_ntVho\my]nz]jzTduVfyarƒfzŠp‡˜tŒŸn…–vŠšƒ—¥ŠŸª¡²‘ ¶Š ¶ˆ£¹•°Æ—¯Æ¥À™«Éœ¯È°Ç³Ç ·È ·È¤ºÎ¤ºÐš°È¤ºÎ£·É¤¸Ê­ÀÕ¦¼Ô¨½ÚªÁÝ«ÂÞ®ÃÞ±Äݪ½Ö§¹Õ©¿×Ÿ·Î¦¾Ó¥»Ñ¦¾Õ¤¾×¤¾×£½Ø¥¿Ú¬ÃߦÀÙ¤¿Õ¤¾×¨ÂݦÀÙ¤»Õ¤¾×¤¿Ø¥ÀÙ¢¼Õœ¶Ï¡»Öž¸Ñ£¾Ô¦ÁרÂÛ£¾Ôž¶Íž¶ÍžµÏ¡¼Ò£¾Òž¹ÍµÌž¶Í£»Òœ·Í›¶Ì¥½Ô¡¶Ñ›­Ë¡¯Ó›­É ¶Ì ¸Ë‘©¼‹¢³‘¥µŒ£´¥¹Š¡°´Áƒš©…›¯ˆž´„š²Š¶‹š´‡–°‚‘«€¨}¥€”¦z‹žz‹žs‚˜m|’n}“jziyŒr|„Àï´¾‹“§~‹Ÿv†žsŽ?J]@GR:>C1888?=KRRfjopw€dm|^jxer‚`m}an~[kzXizarƒfwˆk‚“m…šg’sŠ›|“¤‚•ª‡š¯ˆ›°‡š±Ÿ»™¬Ã™­¿šªÀ¦µÏ˜¨Â¢µÎ°É¤´Î®ÄÚž¶É•­À™¯Å®ÅÖ¯ÆÓ¤»Ì«ÁפºÐ£¶Ï¨»Ô«¾×¥ºÕ®Ãਾ֦¹Î©¼ÓªºÔ¨»Ò¡´Ë¾Ôì±È⢼՟¹Ô«Åà¸Ïë­ÄÞ­ÂݯÅÝ®ÄÜ©¿Õ©¿Ó¼Òæ«Áס¹Ð¨¿Ù©ÃÜ¡»Ô¡»Ô£½Ø¢½Ó¡¼Î¡¹Ð¡µÕ¦ºÜ¢µÜœ²Ó ¶Õ¦ºÚ§¸Ùš°È¢¸Ì¡·Íš°È—­Ã˜®Ä’¨À–«Æ¥¾Î˜µ½“­¶±¿™­½‘¥·“¤·¡­ÄªºÒ†›¶„š²‹ž·¢¹„—¬…˜­„—®‚•¬€“ª~‘¦{Ž£†—ª~Ž¡yŠv†œpƒ˜mƒ™h|Žev‡p}‚ÈÍÉ– ¨…‘¨|ˆŸx‚šq}‹GQYT\^PWS5;268,<@:QSWlpulqybox\l{Yix]m~Zk|[o^u†aw‹k•i•l„—q‰œvŸ˜¦†œ°‡™µŒŸ¸Ž¡¸’¥¼“¦½”ªÂ“ªÄ¥»Ó©¹Ó—­Ã”¯Áš³ÃŸ¶Ç ¶Ê–¬Â¬Ä×¢¾ÍµÈ§½Õ¤¹Ô®¿à­¿ÛªºÔ¤ºÒ§¿Ö«ÁÙ¢µÎ¨ºÖ©»Ù²Ï§¾ÚªÁÛ¨¿Ù¢·Ò£µÑ®ÆÛ±ÍܨÃתÁÛ¥¿Ø¨Âݤ¾Ù£¹Ø¦ÀÙ¨ÄئÁ×¥¼Ö¥»Ó¦¹Ò§¼×ªÁÝ­Çà¸Îž¹ÏŸ¹Ò•¯Í•¯Ñ›´ÖŸµØŸ¶Ò¢¸Ð˜°ÇžµÏ¡·Ïš­Æœ«È˜¥Ç–¨Æ“ªÆ“ªÆš¯Ì¢¿‹Ÿ¿—®È‰¡¶“©¿˜«Â’¤ÀŽœ¾š©È‘ ½Š™¶†•²†™²ƒ™¯€¬„Ž±‚­~Ž¦‚•ª}“§rˆœ{Ž£t‡žm€™l|’n~t{„ËËÍhj{†‰ª†Š¨…¡x~ŽskgpmeceYBHA/66388@BFX\ampxeoyXhw\l{XhyWh{Xk€_r‰cu‘i—mƒ›p†œ{‘¥ƒ™­{‘§—«ƒ™­‹¡µŽ¡¶Š ¶Œ¡¼§Áœ³ÍŸ²Ë ¯É¥µÏ˜ªÆªºÔ­¼Ö¦¶Îœ¯Æ¥½Ò£¾Ò¥ÀÔ¡¼Ð¢½Ñ ¸Ïž¶ÍŸ·Î¢¼Õ£½Øœ¶ÑŸ¹Ôž¹ÏŸºÌ ¼Ð¥Á×¥Á׬Æß©Ãܦ½×ªÂ×±ÉܱÉÞ©¿×®ÄÜ°ÃܬÁÜ¢¶Ö§¼×¦¼Ô§¿Ö¤¿Õ¡¹Ì¤»Ê¢¹Ê¥»Ñ§¿Òš³Ã›·ÆŸºÌœ·ËšµËœ·Í“­Æ«Áž¶Í µÒ’£Æš®Î™®Ë–¨Ä˜§Ä’¥¾–¬Ä•­Â¨½‡¢¶‡¢¸Š¥»Œ¤»‹£¸Ž¦¹Œ¥µ¦µ…œ­‹žµ†™°„”¬Ž¡¸—­€–¬‚•¬ˆ›°|¢w‹›wˆ™v‡šx‡Ÿv†žk~—i}l}ŒqxÆÃÆ=AP:Fa~ˆ €…œw~‰[\UNOJEEC7:92484995:8EHGaacmqvgny`ny[myThxVl€[q‡bxh~”k—j‚—q‰ s‹ž{”¢}–¦{‘¥‚˜¬‹žµ‡ž¸Š£Á§ÂŽ¨Ã§Áœ®Ê˜­È•¬È—­Ìž²ÔŸ¶ÒšµË—³É ¼Ò¥¿Ø¥¼Ø£ºÖ¥¼Øœ·Í–±Åœ·Ë£»Ò«ÂÜ­Äࢼա»Ô¢½Ó±Ì⡼ҬÃݧ¾Ú§½Ü¤»×ªÁÝ­ÄàªÀß±Èâ¯ÇܳË⥼֣½Ö¦ÀÛ©ÄÚ¤¿Ñ­ÅÚ§½Õ£ºÔ´Ð¤»Õ¹Î饻Ѥ·Ì˜°Ç›µÐ•®ÌœµÕ¬Æ᥼֟¹Ò—±Ì—±Ê—¯Æ©ÂŽ§Å¨Á’®Â¬À˜³É–±Ç†¡·Š¢¹Š ¸‹¡·Œ¢¸‹¡·¦¾€™©š¦Œ ²‘ ¸„—°€•²ƒ›²€˜­w£xˆ¢v‰ uˆt‡œr…œm€•h{dxˆcxƒbnl´³¨QSW'.3F[fyfsx-3,.5328=28=03;-364;;5<E59<8:>QPUhlqkpx[eoR_odtƒdu†m‘m„“q…•q’£yŒ¡‚˜°{’®ƒ›²‚˜¬£¹Œ¢º£»‘§¿’¥¼šªÀ”§¼ ³Êž´ÌŸ´Ï›°Íœ­Î”©Æ™®Ë–¨Æ”¢Ä•§Ã™¬Å˜®Ä ¶Ì«Á× ³Ìš°È¥»Ó¡¸Ò£ºÖžµÏ¥ºÕ©»×°¿Ü²ÅÞ«ÁÙ¦¾Ñ¬ÅÕ¬ÄÙ®ÃÞ­Äà«Á⦼۪Àߦ½Ù¦»Ø¤¹Ô§¼×¤¹Ö¥¹Ù¬ÁÞ¤¶Ò¤·ÐÂÕע·ÔŸ´Ñ¢·Ôœ³Í–­ÇžµÏ²Í˜­È”©Ä”ªÂ—­ÅµÊ‘¬À«¿¨¿‹¡·†™®Œ¢¸”ªÂ¤¿‰ž»ƒš´…œ¶„š²ƒ–­†™°„—°}§’§‚˜¬—«ˆ›°y‰ŸŽž¶~ªwŠ¡r†˜n„˜rˆ r…šhyŒdwŒ_r‰Xh~O^t&:$ ));K\@PaBOcCP`SanLZgP^kDNV8=BENVXZhh^msfv…m‘i€‘p†œt†¤yŽ©z‘«€—±‰ º€š³œ·‚³‹¡·“©½Ÿ²ÇŠ ¶Š ¸§¼•­Â“«À•­Â—¯Â–®Á‘©¼³ÇªÃÑŸ¸Ä«ÄÒ¦¿Ï ¶Ì§¹×¢¶Ö³Ô›´Ôž¸Ú­Åê±Æ߬ÆߨÀÕ¢¸Ì¨¾Ò­ÃÙ§½Ó¦¼Ò¨¾Ô¨»Ô¥¼Ö£¼Ú£½Öž¹Ï¡¹Î§½Ñ«ÃØ£»Ò¦¾Õ¡·ÏŸ´Ï¦¸Ö¢¸Ð¤ºÐ¥½Ò¸Îž¹Ï¡¼Ò›µÎ’¨Ç—­Ì’¦È¦Å¦Â“­ÈŽ¨ÃŒ¦Á‰¢ÀŒ£¿ŠŸ¼¥½ˆž²‹¡µŒ¢¶ƒ™¯‚˜°„›µ…Ÿº›¶•´}”°˜´|”©šªƒœ¬u w£t‡ mƒ™g}‘rˆœmƒ—l‚–h~”fyŽp”i|‘^tŒWmƒQdyJ]rHXn=Qc/CS-FGE3:A?DLUX`[ho^pz`t„l‚˜o‡œsŽ¤u‘£x•¢ƒœª…™©ƒ—©„—®‹ž³‘¤¹–©¾™¬Á‘¤¹™¬Ã˜°Ã–±Ã™¶Å™¶Å˜±Á¡µÇ±Ã°Å¤¼ÏŸºÎ£¾Ð¥¾Îš²Åž¶ÍžµÏš°Ï£ºÔŸ·Ì£»ÐªÂÙ¦¾ÑªÃÓ­Åئ¾Ó§ÀЮÅÔ¬ÃÔ³ÉÝ®ÄÜ¢·ÔŸ¶Ð¡¸Ò¢½ÑžºÉ®Ç׺Ñ⤼Ѡ·ÑªÅÛ¨ÄØ¡½Ó£½ÖšµË¥½Ò¥ÀÒ˜³ÅšµÉ–°É—²Èš²Çœ´Ç™¯Ã’«»œµÅ“«¾‹¡¹Œ¤¹‰¡¶Œ§¹Žª¹ˆ£µ„œ±„œ±ˆ ·‰£¼‚œ·… »šµ€›±…°„œ±™°~™«x•¢Œ¨ºz”­w’¨p‹¡p‹Ÿo‡œo‡œq‰ h~–iy“at‹n„˜`vŠZm‚Xk‚UhL_tEYkDXfP\?SaDXhEYkGXkJZmJ[jG\gBZbD\dDYbFWcLW5OáFV÷N`×b\Ó’tÿÿ×ÿÿÉÿÿÉÿÿËÿÿ­ÿåÿêjÿÿdÿöyúÇi°•jzt}†Š™}‰ €¥|‹¡r‚˜xˆ yŒ¡|¢vžvŸy£zŠ¤q™jz’o‚™n˜j}”cv^v‹_zŽTrst€—l|‹rƒqƒqƒt†‹~‘”vƒŠtƒ‹zˆ“y‡’{‰”…•——¨³´ž œª¬“ ¥Œ–œŠ‘š‘”•©¥¢³²©º¹®¼¸³Æ¿¿ÌÌÌØÝÝôù÷öû÷ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿéÿÿõÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿôÿÿùÿÿîÿÿãÿÿßÿÿáÿÿàÿÿãÿÿÜÿÿÔÿÿÌÿÿÊÿÿÆÿÿÊÿÿÊÿÿÏýÿ¹ûÿ³þÿ²ÿÿ°ÿÿ²ÿÿ´ÿÿ­ÿÿ«ÿÿ­ÿÿ¥ÿÿ¨ÿÿªüÿŸÿÿŸùÿ–ÿÿšýÿ–ÿÿ—ÿü¨ÿÍ’Ûw^ÓIQâJWìEWæLYãU^Ó…_ÿÿÆÿÿÉÿÿËÿÿÅÿÿÇÿÿÉÿÿËÿÿ¨ÿê~ÿó~ÿýÿÿ‰ÿãq¹¤i€€~…’›vŽ£y‘¦q‰žn‡—wŽvšt‹˜xŒšx‰˜o†“g€Žlƒ”i|‘k~“buŠ^u†^w‡Zvsr‚“m~hz†m~ˆzˆ“}‰•…‹™‰“s€‡u„ˆz‰v…‹x…Ž„Š££¥¦©¨­°¯œ¢§ˆ’œzƒw}|€ƒ­«¥³°¤·´ ½º¦ÓͽÖÕÁåæÑôöèýþùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿñÿÿõÿÿêÿÿôÿÿþÿÿÿÿÿÿÿÿôÿÿâÿÿäÿÿáÿÿÚÿÿÓÿÿÏÿÿ×ÿÿÉÿÿÊÿÿÅÿÿÄÿÿÇÿÿÀÿÿ¼ÿÿÃÿÿÊÿÿÆÿÿ¼ÿÿ¸ÿÿºÿÿµÿÿ³ÿÿ³ÿÿ¯ýÿ ÿÿ­ÿÿ¦ÿÿ¡ÿÿ¨ÿÿ¢þÿŸùÿ˜ÿÿŸÿü£ÿæŸÚ€\ÍFIáNWæGVçEUéBTÖQJÊdFÿߪÿÿÑÿÿÑÿÿÑÿÿËÿÿÇÿÿÃÿÿÁÿÿÁÿÿÁÿúŽÿêsÿêsÿú‚ÿÿ†ÿÞf«”N|xg€†‰t„šyŠz‹žz‹žyˆžxˆžv‰žr…œo‚›m€•n‚”k‘g{fzŒi|‘avk{Šk{Œht‹p}uƒw…’y‡”sŽs~{‡“vƒŒvƒŒp|ˆƒ•§­²¢ª¬©´µ™—~Šˆ‚‰‡‹‹‹”Ž‰´¥Ÿ±§Ÿ¤–¬¥š¹°£À·¨èÜÎøïàðêÚðëáýùöÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿãÿÿäÿÿÞÿÿèÿÿòÿÿêÿÿôÿÿôÿÿôÿÿèÿÿæÿÿìÿÿäÿÿÕÿÿÐÿÿÕÿÿÒÿÿÊÿÿÐÿÿÅÿÿ¿ÿÿºÿÿ»ÿÿ·ÿÿÁÿÿ¿ÿÿºñø¥ÿÿ¸ÿÿ°ýÿ£ùÿÿÿ¦ùÿœþÿ¡ÿÿ¦ÿÿ²ÿÿ¬úþÿÿ¤ÿÿ¢ÿÍ’ÙdNÙTKåPUÜFNÜFPãJPçGKÊVG×mÿÿÓÿÿÇÿÿÉÿÿÍÿÿËÿÿËÿÿÅÿÿ¿ÿÿÃÿÿÇÿÿËÿÿÏÿÿ´õì†þé|ÿï~ÿÿŒÿéu¶œY‹~n‰Œz‹žuˆr…žq„™u‰›mƒ—mƒ™l‚˜mƒ›k~“v‡˜m~‘ds‰_q}iqƒoz‹kxˆp|Šs|‹|„–~†šozly‹~‹›wƒ‘t‚s‚Š•¢§¢ª¬¢­°£­³Žš˜~‹‚£¬ £¥™ž›¬£–¦œ’¢˜¤š’¯¢›¼²ª¶¯¦¹²§Ç¾±ÚÑÂæÞÌïêàü÷÷ûø÷ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöÿÿèÿÿàÿÿÚÿÿìÿÿîÿÿêÿÿêÿÿÞÿÿÞÿÿÛÿÿÜÿÿÖÿÿÛÿÿåÿÿæÿÿÙÿÿÉÿÿËÿÿÅÿÿÆÿÿ¾ÿÿ³ÿÿ®üþ«ÿÿ«ùÿžÿÿ¦ÿÿªÿÿ­ÿÿ¢úþŸÿÿªÿÿ­ÿÿ­÷ûž÷ú¢ÿÿ¥ÿú›ÿé§òjÞcTäQXßLSÝJSÛEOÜDQãITàCMÃ\DüËÿÿÓÿÿ×ÿÿÍÿÿÅÿÿ¿ÿÿ¹ÿÿ¹ÿÿ´ÿÿ·ÿÿ·ÿÿÅÿÿÑÿÿÑÿÿÓÿÿÍÿÿ´÷æÿãÿðŠÿñ|»¢Z‹|f†‡‚z‡—r‚“l}k‘r†˜mƒ—l‚še}g€lƒ’au…]x|gt„iv†ju†o|Œo|Œ|Š—y‡”k|ˆiz†p€t•t…‘|Ž“¢³¯œ¬¢¨´°™¡£†Ž‰Ÿ¤¤•”™ œ¤Ÿ—™–Š˜–‡›–Š¥›•±ª¡¬¥š³­¹´ŸÁ¼§ÓË·ÞÖÀàÕÀäÛÌìâÜìèåÿÿÿÿÿÿÿÿÿýÿíÿÿöÿÿúÿÿúÿÿðÿÿèÿÿîÿÿòÿÿâÿÿïÿÿçÿÿãÿÿÒùÿ³üÿ¼ÿÿÞÿÿàÿÿÖÿÿÒÿÿÌÿÿÅÿÿÅÿÿÇÿÿÊÿÿ½ÿÿ±ÿÿ¨ÿÿ©ÿÿ«ÿÿ®ÿÿ±óõ øÿÿÿ þÿ›úÿ•ÿÿœÿÿœÿÿ¦ÿÜŒÚzQë^^äTUáOSÞKTÜHVÙFQßISÜIPÙIL¼iHÿÿ¼ÿÿÏÿÿÍÿÿÃÿÿ¹ÿÿ·ÿÿµÿÿµÿÿ¹ÿÿµÿÿ±ÿÿ¶ÿÿ½ÿÿÁÿÿÅÿÿÉÿÿÏÿÿÍÿÿÍûòŽÿò|ÿõÿåp°‘GŽ|`‚„xn„Šq†‘wˆ›oƒ•f|i“fyŽaw‹i“f„epƒgsjw€o}ˆrn‰q„‹r„‹o~†o}ˆs€u†œ£ª±¢¦©¬±¹–¡…‰Ž•••–š’Œ‘„¦¥š¤”œ—‹š—‹ ›ª ˜£œ‘§¢–ª¦—¨¤“¶±žÎƲÖ˸ÔÇ·ÔÇ·ÒÄ·Ô˾éäÚùöâýûÞÿÿüÿÿÿÿÿüÿÿøÿÿëÿÿ×ûýÖûýÝÿÿöÿÿôÿÿîÿÿåÿÿÕÿÿÉÿÿÑÿÿ×ÿÿÓÿÿÌÿÿÄÿÿÓÿÿÎÿÿ¾ÿÿÁÿÿÒÿÿÊýÿ·ÿÿ·ÿÿ¯ÿÿ³ÿÿºÿÿÀÿÿ´ÿÿ¤ýÿœþÿŸùúœþýžÿýœÿÝ“Û†UßlXçT]âRSàQMàPSëWeãPYáKS×FL×KPÞŒoÿÿ×ÿÿÕÿÿÓÿÿÇÿÿºÿÿ´ÿÿ°ÿÿ±ÿÿ­ÿÿ¯ÿÿ¯ÿÿ°ÿÿ³ÿÿºÿÿÅÿÿÇÿÿËÿÿËÿÿËÿÿ»ÿÿ«ÿÿÿÞsÿíÿ똯 sqoiy…r‚‘o€“k~—gz“i|•k~•n–i~‡apver{js‚oz‹p}‘p|“v€šv‚™m|’n~s‚Šv…ž©‘£ª”¦«‘£¨„“›…’™˜Ÿ¨‘’›•˜¡šœž“’Ÿ•¢™Œ¦¤š ™ ›“¦¡—ª£˜©¢—°©žÀº¬Æ½®Ê®ÏįÕ˱áÕºÛÙ±þÿÏÿÿÝÿÿÏÿÿÖÿÿòÿÿãÿÿóÿÿôÿÿòÿÿðÿÿåÿÿÚÿÿÖÿÿÒÿÿÙÿÿ×ÿÿÉÿÿÉÿÿÏÿÿÎÿÿÇÿÿÀÿÿ¼ÿÿ¹ÿÿ°þÿ«øý©ÿÿ°ÿÿ¹ùü¤ÿÿªÿÿ´ÿÿ­ÿÿ¡ÿÿœÿÿœÿÿ˜ÿþ“ÿõ‘ú°pøx\ë_XëQ^êSYêTUçPTæLUäJSäJUÑHIÍTKþ¼ÿÿËÿÿÑÿÿÙÿÿÏÿÿÇÿÿ½ÿÿ¯ÿÿ±ÿÿ¹ÿÿ½ÿÿ¿ÿÿ½ÿÿ»ÿÿ¸ÿÿ¹ÿÿ½ÿÿÁÿÿÃÿÿÅÿÿÉÿÿÏÿÿÅÿÿ½ÿÿ§ÿïwüßyÿáóÙ–»¯€|k`dsgtˆez•d|‘ayŒazgt†iyŠjz‹hyŠj~Žrƒ’vƒ“t†’nƒŽj|†n‰z‰‘”¡ªš£— ­‘ž§„‘š——Ÿ£Ž–›–Š—”ˆ™•†›’…¡›£œ‘ ™Ž£œ‘«¦š¬©Ÿ¨£—©£•°§˜½° Æ¹§Ôı×Ë°ÒÈ¥ÐÊ–ÿÿÃÿÿÁÿÿÑÿÿæÿÿòÿÿðÿÿðÿÿéÿÿÔÿÿÑÿÿÚÿÿÙÿÿÍÿÿÎÿÿÆÿÿÃÿÿÎÿÿÜÿÿÚÿÿÌÿÿÄÿÿ»ÿÿ¿ÿÿ¾ÿÿ³þÿ©ÿÿ§ÿÿ³ÿÿ²üÿ¨ýÿ§ÿÿ¨ÿÿ¤ÿÿ¥ÿÿœÿÿ™öú‹ÿôžÿâ£îŒpîbiàRWëY]ð[`îV_ïX\êRQäLMãJNÍJDÍ`SÿäºÿÿÕÿÿÙÿÿÞÿÿ×ÿÿÑÿÿÉÿÿÁÿÿ½ÿÿ¹ÿÿ»ÿÿ¿ÿÿÃÿÿÇÿÿËÿÿÏÿÿÉÿÿÃÿÿÇÿÿËÿÿËÿÿÍÿÿÍÿÿÍÿÿ¿ÿÿ±ÿÿ¯ÿÿ™üæ~üÞÿç“ûâ˜Â¶††ƒodgfbj|`osf}Œkqƒfx„l~Šm‰pƒŠs†l}‡o~†|†Ž‡‘™™£­•Ÿ©ž§´…™€Š”‰——¢‹‘Š—™‹•”‡™”ˆ•„˜“‡š–‡›•‡›”‰ ™¥ž“«¤™¬¥š®¤œ°§š¹­ŸÂ·¦½²ŸÄº É¾ ßÚ±ÿÿæÿÿÜÿÿàÿÿÛÿÿÇÿÿÍÿþÁøúÃÿÿÙÿÿéÿÿäÿÿÒÿÿÆÿÿÀüÿ·ÿÿÎÿÿÚÿÿÍÿÿËýÿ¹ÿÿÁÿÿ¿ÿÿ´ÿÿ°ÿÿµÿÿ´ÿÿ¹ÿÿ·ÿÿ´ÿÿ¶ÿÿºÿÿ²ÿÿ±þÿ¥ÿÿ¨ÿÿ§úü—ÿõ¢ÿºxë|dçReèU`ôbfõ^dóW^ñVXíPOæLGÝF>ÄV4ωNÿÿÏÿÿÓÿÿ×ÿÿÛÿÿÛÿÿÞÿÿÙÿÿ×ÿÿÑÿÿÍÿÿÇÿÿÃÿÿÇÿÿÍÿÿÍÿÿÍÿÿÉÿÿÅÿÿÇÿÿÉÿÿÇÿÿÇÿÿÁÿÿ½ÿÿÁÿÿÇÿÿÉÿÿËÿÿÁÿÿ·ÿþñÝ„øá‚ÿë‰þå™×Á‹¦‹rgu‚ew~fx}gy€j{‡m~Šq‚Žrƒky„lz‡w‚•Ž—¦”›¦›¨­™¬¬ƒ’–}Š“‡Ž•“•›Šˆ„›”‰”ƒ•†˜‘†¡”‹ž•ˆž•ˆ–‹¤”§ •ª£˜¯©›°§š© ‘­¡“º±¢¹°¡¹³‘º´‚óó®ÿÿ²ÿÿ¿ÿÿÉÿÿÌÿÿèÿÿìÿÿìÿÿáÿÿÛÿÿÔÿÿÎÿÿÕÿÿçÿÿàÿÿÙÿÿ×ÿÿ×ÿÿÖÿÿßÿÿÍÿÿÉÿÿÄÿÿ·ÿÿºÿÿÀÿÿ¶ÿÿºÿÿ¹ÿÿ·ÿÿ·ÿÿ·ÿÿ°ÿÿ«ÿÿ¥üÿ™ûý˜úú˜ÿì¤ùœrés`ì_aç\^áW[ê]_ìW\êSYäHOáHNàHQÃ_M鸋ÿÿâÿÿæÿÿæÿÿèÿÿæÿÿäÿÿâÿÿâÿÿàÿÿÞÿÿÛÿÿÛÿÿÓÿÿÍÿÿÃÿÿºÿÿ»ÿÿ½ÿÿ·ÿÿ¯ÿÿµÿÿ»ÿÿ¹ÿÿ·ÿÿµÿÿµÿÿ¹ÿÿ¿ÿÿÅÿÿÍÿÿÃÿÿ³ÿÿ¥üñŽùë‡ÿóÿí°cxƒcw…hyŒj{Œqpzˆ“k|ˆk{Šm{ˆ}‰•Š”ž—œ¦œ£¬”›¦‚‰”€†”‘–‰‰‡‰†~˜’„•„•’ˆ™•†¡›‹ ›ˆ ˜†ž˜ˆ¤’¦¢“¢ž§£’­©˜¬§”­¥“¼±ž»®š·®À¹ŽÿÿÕÿÿÒÿÿÜÿÿæÿÿàÿÿÚÿÿÒÿÿËýýÇÿÿ×ÿÿäÿÿàÿÿÔÿÿÃÿÿ¾ÿÿ¼ÿÿÅÿÿÈÿÿÅÿÿÇÿÿÁÿÿ¹ÿÿ¿ÿÿÁÿÿ¾ÿÿ¾ÿÿÄÿÿ¶ÿÿ³ÿÿ¯ÿÿ«ýÿ¢ÿÿ¨ÿÿ©ûÿœýÿœÿû˜ÿþžÿá¦ò|kåueÛsbõoÿÀzãwNé[RéSRëMSàJKÜKJ¹]Fÿé¼ÿÿàÿÿâÿÿæÿÿêÿÿèÿÿæÿÿæÿÿæÿÿâÿÿàÿÿâÿÿæÿÿàÿÿÛÿÿÏÿÿÃÿÿ´ÿÿ¤ÿÿ¥ÿÿ¨ÿÿ¯ÿÿµÿÿ¯ÿÿ«ÿÿ©ÿÿ­ÿÿ±ÿÿµÿÿµÿÿ·ÿÿ»ÿÿ½ÿÿµÿÿ¯ÿÿñè„ïæ¢o|Œl|gvŽixŽsƒ–k‘tŠžn…”j~Œj{‡…‘‰—¢‹™¦¨‰˜ ‚‘—‹˜Ÿ• ¡{„‡ˆ‹„{‹†z’›•‡ —Š œ‹ ž¦£¬¤’®¨š¤Ÿ•¤Ÿ•¨¡š¬¥š°§šµ©´¥¯¤‘ÕγÿÿçÿÿÓÿÿÀÿÿÃÿÿ¿ÿÿÕÿÿÑÿÿÓÿÿÄÿÿÀÿÿºõû­þÿºüÿ½ÿÿ¾ÿÿÆÿÿÆÿÿÈÿÿ³ÿÿ®ÿÿ¯ÿÿ¸ÿÿ¹ÿÿ²üÿ°ýÿ³ÿÿÀÿÿ¿ÿÿ³üÿ¦ùÿ›ÿÿžÿÿ˜óÿ‚ùÿúÿ—ÿÿ™ÿú‘ÿÌŠárZÓ†[ñÆ‹ÿû²ÿ÷£Õ†Wâ]VçVUéKQØICÒSC¿xFÿÿÈÿÿÓÿÿÞÿÿÙÿÿ×ÿÿ×ÿÿ×ÿÿ×ÿÿ×ÿÿ×ÿÿÙÿÿàÿÿæÿÿæÿÿèÿÿâÿÿÞÿÿÉÿÿµÿÿ¯ÿÿ§ÿÿªÿÿ±ÿÿ³ÿÿ¯ÿÿ¬ÿÿ±ÿÿ¯ÿÿ±ÿÿ©ÿÿ¦ÿÿ¥ÿÿ¤ÿÿ¨ÿÿ«ÿÿ¯ÿÿ¬ñì©iyˆj{‡ct€fwƒo|Œo|Œs€t…‘p‹z‰Š—œ‰˜œˆ—Ÿ¦…—¡~“Œ—š“˜–„€{ˆ€Œ‚|Œ…~‘‰…šŠž‘Š£™¡›©£“¬¦–¯©™ª¤–£œ‘¨¡˜©£•¬£”®¦·­“º·„úþ³ÿÿÁÿÿ¾ÿÿÉÿÿÎÿÿÇÿÿÁÿÿ»úÿ­ýÿ°ÿÿ²ÿÿÄÿÿÒÿÿÐÿÿ¿ÿÿµÿÿ³þÿ¯ÿÿ¯ÿÿ´ÿÿÃÿÿ¾ÿÿ¶þÿ¦ÿÿŸþÿŸÿÿ°þÿ¥ýÿ¨ÿÿ¦ÿÿ§üÿ™òù‡úÿÿÿ–ÿÿ˜ÿÿ›ÿþ•ÿõ’üƈ؀jݯxÿÿ°ÿþ«ÿö¨Ü‡_åZZæQVéJWØLSËRTÝzÿÿÑÿÿ×ÿÿÞÿÿÓÿÿÉÿÿÇÿÿÇÿÿÅÿÿÅÿÿÉÿÿÏÿÿÓÿÿ×ÿÿÙÿÿÞÿÿÞÿÿàÿÿÕÿÿÍÿÿÅÿÿ½ÿÿ³ÿÿ¬ÿÿ«ÿÿ¬ÿÿ°ÿÿ°ÿÿ§ÿÿ©ÿÿ¥ÿÿ¤ÿÿ«ÿÿ¯ÿÿ«ÿÿ­ÿÿ®ÿÿ°ÿÿ¼ixŽfzŠaz†f~ˆewj|†pqƒŠyˆŒŒ“Œ’ Ž—ƒ’š‚›v„‘u‰ˆ•‡ˆƒ†‚q‰y‘ˆyŠ†wŽ‹‹’‹„˜Œ£ŸŽ¥Ÿª¡’«¥•¬¦˜§ •¨¡š­£™²¦˜­¢µ©ŽÅÁ…þþ¥ÿÿ³ÿÿÌÿÿÐÿÿÓÿÿÃüý±ÿÿ¶ÿÿÄÿÿÁÿÿºÿÿºþÿ°õý£øÿ¡ùþªÿÿÁÿÿÂÿÿ¾ÿÿ¸ÿÿ°ùÿ§öþ¤ÿÿ²ÿÿµÿÿ¬ÿÿ¨ùþšÿÿ¢ÿÿ£ÿÿ¥ûü ÿÿ¦ÿÿ¤üÿ›÷úÿÿ•ÿýŸÿî£Ù¯iϤeÿö¡ÿÿœÿÿ¢ÿó¢Ó~VâYZãPWèIX×LYÄO[ÿŦÿÿÑÿÿÑÿÿÑÿÿÇÿÿ½ÿÿ½ÿÿ¿ÿÿÁÿÿÃÿÿËÿÿÕðæÁÿïìÿÿþÿÿðÿÿæÿÿÞÿÿÛÿÿÙÿÿÓÿÿÏÿÿÅÿÿºÿÿ²ÿÿ«ÿÿ«ÿÿ®ÿÿ¨ÿÿ«ÿÿ©ÿÿ§ÿÿ­ÿÿ®ÿÿªÿÿ¯ÿÿµÿÿµÿÿ¼kwk{Žiz‰hyˆjz‹iyˆo}Štƒ‹x…Š}Šw‰€Š”…Žz†”}Šš„‘š‘˜Ÿ}‚~ƒw„ƒv…ƒt‹‡x‘Š†~š†¥œ¥œ¨›’¦œ’ ™Ž ™Ž¥›‘¥Ÿ‘¥Ÿ¬¥Šµ«ˆÝ×¥ÿÿÌÿÿÏÿÿÌÿÿÄÿÿ³ñö¢ÿÿ°ÿÿ½ÿÿÑÿÿÐÿÿÉÿÿ¹üÿ¬þÿ«ÿÿ²ÿÿ´ÿÿ³úÿ§ÿÿª÷ûžÿÿ£ÿÿ®ÿÿ·ÿÿªþÿ¡øý™úÿ™ÿÿ¢ÿÿ¬ÿÿ¦øý—úü—ÿÿŸýý™ÿÿýû‘ÿÿÿûÿÛ’ÉžTþÜ“ÿøŸùÿ–ÿø›ÿã“ÆpH×MSÙFQéI[ÑSS¾dSÿ÷ÄÿÿËÿÿÏÿÿÓÿÿÉÿÿ¾ÿÿ¿ÿÿ¿ÿÿÁÿÿÃÿÿîø×éj™¸ŒÛ·•Ç¿§¿úìêÿÿúÿÿèÿÿ×ÿÿÓÿÿÏÿÿËÿÿÇÿÿÃÿÿ¿ÿÿµÿÿ±ÿÿ®ÿÿ´ÿÿ¬ÿÿ­ÿÿ¬ÿÿ£ÿÿÿÿ ÿÿ¤ÿÿ©ÿÿ»kwmzŒgu‚hp‚hkƒnvŒq|‘zˆ•€’™Š›¥‡•¢Œš¥ˆ–¡}‹˜xƒ”†~ƒƒyzu„wƒ‚uƒ‚uŠ‡{“Ž‚š“ˆ•‹ƒ˜Ž„¤˜Œ¢–ŠŸ“‡”‡—‰¡›£¤ ¨¤“¬¤Žµ¦Œöî½ûù°çèœöú­øý«ÿÿ·ÿÿ¼ÿÿ¾ÿÿÂÿÿÃúÿ²ïöŸ÷ÿ¥ÿÿ¬ÿÿ¸ÿÿÀÿÿµûÿ©íö—ÿÿ¥ÿÿ¶ÿÿ¬ÿÿªûú¦õö˜÷ú’ÿÿŸÿÿ¤ÿÿ£ÿÿ¥óø”ýÿ˜ÿÿŸÿÿžêå‡øí•üò‘ÿûÿè’æœ\פaÿö¯ÿþ¥òû‘ÿþžÿÎ{Æe<ÜJNàJTåJZÎTYÐxtÿÿâÿÿÍÿÿËÿÿËÿÿÃÿÿµÿÿ½ÿÿ¿ÿÿ¿ÿÿÁÿÿô˧ÊÌ¥Û¾”ݸ’Óʧ⿧Á¦—“ÀºšÿÿÒÿÿÙÿÿÕÿÿÓÿÿÑÿÿÉÿÿÁÿÿ»ÿÿ³ÿÿ±ÿÿ³ÿÿ©ÿÿ§ÿÿ§ÿÿÿÿ™ÿÿšÿÿœÿÿ›ÿý¾fs‡iyˆdum{ˆs{|ˆ–|ˆ–~Œ™‚ƒ”ž…—ž‰—¢Š•¦zˆ•|Š—~‰Œw|xquo}{u{wr‚|y‡|Œ‡‘‹†„…’Š†šŠš†”‹|œ“„¤˜Œ¢™Œ¤ž¥Ÿ‘¨¢”¬§‚ý‚óñ¨íïœîõžÿÿµÿÿ´ÿÿ³ÿÿµÿÿºÿÿ±òù¢ÿÿ±ÿÿ§ÿÿ¶ÿÿ¿ÿÿ´ùÿ­ðøžùÿ üÿ¡ÿÿ°ÿÿ°þÿ¯úú£úùœöö”üú”ÿÿ¢üøžôó–þÿ¡ýÿœþþšÿÿ—ÿý“óð†ÿÿ—ÿú•ÿðõɆԎkÿßšÿýœýÿšüÿ›ÿ÷¡è®fÃ[9àIOãKTàHU¾X=ì´sÿÿÍÿÿÑÿÿÏÿÿÏÿÿÇÿÿ¿ÿÿ½ÿÿ»ÿÿ½ÿÿ¿ÿÿÚ¿ž°È¢ÎËåÁ–Ý—ÞÈä͢鿛δ˜¸·¨¢ãá·ÿÿáÿÿ×ÿÿÉÿÿ½ÿÿ²ÿÿ³ÿÿ¬ÿÿ­ÿÿŸÿÿÿÿ¥ÿÿ£ÿÿ™ÿÿ˜ÿÿœÿÿ’ùñ¦l|‹m~Šn|‰pz‹šxŠ–yŠ–~›„‘¡…“ ˆ–¡‰—¤…’¢{‰–{‡•„Œsssyttvw|uu‚{}„ˆ„Š„‚‰„|Š‡}˜“‡œ˜‰Ÿ›Œ›—ˆ¢œŽ©¡¯¤‘«£{ÚÖšÿÿ¹ÿÿ­ÿÿ·ÿÿ»ÿÿ½ÿÿÂÿÿºÿÿ¼úÿ§ÿÿ§ÿÿ¯ÿÿ¯þÿ­þÿ²õû¢úþŸÿÿ¡ÿÿ¤ÿÿ«ÿÿ©ýÿ¤ûÿžÿÿ¤ÿÿ§ÿÿªÿÿ¤ÿÿ ÿýŸôô’ÿÿÿýœýøšû÷”ÿù”þô•ÿóšÿìÿå…â·c× Zÿôšÿÿ›ùÿ™éõÿî¦ÑŠeÇZMßIUÜGZÜF`¹_Nÿî²ÿÿÕÿÿÕÿÿÑÿÿÏÿÿÉÿÿÅÿÿÁÿÿ¿ÿÿÇÿÿÏæÏÂÊ£ÔϦáÅ—ßÇ›çÄ™êÇæÈžâÃຖز“Ľ¡Á¹§¢ÑÉ¡ÿÿÑÿÿÅÿÿ»ÿÿ°ÿÿ¥ÿÿŸÿÿ•ÿÿ•ÿÿÿÿžÿÿ˜ÿÿ™ÿÿ—ÿÿéàŠoƒ‘fy€\nqDTS/;7+73?KG[ho~‰œƒ‘žŠ™¡ˆ—–|‹}Šx€‚mpoxuv~wyzuu{wt}zpp…€t†|t…q‹…uŽ‡|”†›”‰¢™Œ¤žŽ©£“¬¤Ž®¤ˆ²¦vïÞîã™ñë›øú§óü©ÿÿµÿÿ±ÿÿ·ÿÿ¶ÿÿ¼ÿÿÀÿÿ¿ÿÿÄÿÿ¼ùÿ«ÿÿ±ÿÿ¯ÿÿ®ÿÿªþÿ§üÿ£òú•ÿÿžÿÿ¨ÿÿ­ùø¦û÷«ýû¥ÿÿ¦ÿÿ£ÿÿÿÿúõ—ûô’ÿù•ûð‹óåüâ„ÿè‘̧_ÿÞ¤ÿÿ«õÿ–öÿêõ}ÿãžÍeTÓSTßFXÙFXÒFZ¿lTÿÿÇÿÿÏÿÿÏÿÿÑÿÿÕÿÿÏÿÿËÿÿÇÿÿÃÿÿÑÿÿàŦ¬Â•ØÀ–ÚÁ–ß¾“Ü¿“ß¾”ØÁ—×ÆœàÅšãØá—àÈŸßßֹ£¯ÖË­ÿÿÇÿÿ´ÿÿ¡ÿÿ‹ÿÿ’ÿÿ˜ÿÿ ÿÿ©ÿÿ£ÿÿ¡ÿÿ›ÿÿÞÓ7H@‚Œ‚ÆËÀùûñÿÿÿÿÿÿÿÿÿÿÿûÑÖÔž§¦lwxp}„zˆ•Œ•…—v{{mkgusmwtlyvn|vq~xs~vtzo†n‰…t‡‚vŠ…{‘Œ„Œ„—“Ž ›“©¢™©¤±ªÇɆÿÿ®ÿÿ®ÿÿ±ÿÿµÿÿ½ÿÿ¸ÿÿ³ÿÿ¬ÿÿ¬ûÿ©ùÿ¯öþ®öü°þÿ±ÿÿ«üÿ£ÿÿªÿÿ¨üÿŸñø˜ÿÿ­ÿÿ°ÿÿ²ýÿªøû£úûýú™þúžþù¤üú¢öõšîóúÿ™ÿÿ¡ÿý¡ûð”þëüã—÷×›ÔÇwÿÿ ùÿ™ôÿ•ôÿŠùÿ„ôÀvÑbJÙTKäKQÓPJÄTFæ®qÿÿ·ÿÿ»ÿÿÁÿÿÉÿÿÑÿÿÑÿÿÓÿÿÇÿÿ½ÿÿÓÿýѸ£ª¼—Ó»•Ö½–ÜÀšÝÀšÛ½—Ú¿•Ü½’Þ¾‘åÅšëÁ–å¿šááå ֻ™Â¡}ËÉ|ÿÿ­ÿÿÿÿÿÿ•ÿÿ›ÿÿ¦ÿÿŸÿÿšÿÿ—öù†çá‘ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¢©²GWjuƒŽ~‰Œqvrsriroewpgxqjzrp{upysn}xpƒ|s†xˆ€|‹„{‘‹}’‹€•Ž‡˜‘ˆ ™Ž« ‹±¢…ÚÑ”èäŠæåˆùúšúÿŸýÿ¥ùÿ£ÿÿ®þÿ®ÿÿ½ÿÿ»ÿÿÃÿÿÃÿÿ»ÿÿµÿÿ³ÿÿ©úÿ£ûÿ¡ÿÿ¦ÿÿ²ÿÿ°ÿÿ°øù«ûý¨ÿÿ¦ÿÿ ÿÿšüÿ•óñ‰úø’þûšÿÿžýý™úöœôíýõšÿù–ÿô’òßÿÿ•åø‚ðÿðÿûü‘ÿñÚ“aÖVWÚOQãJNÏOP½VRÿß³ÿÿËÿÿËÿÿÍÿÿÍÿÿÏÿÿÑÿÿÕÿÿÍÿÿÅÿÿîçÊÖƤÍÇ æÞåÂœéÅëÆ›ê›ãÀ™ß¼•ÝµØ˜á—޿™Ü¼˜ÚÅ¡ßàۼ©©ÑГÿÿ¸ÿÿ“ÿÿÿÿ”ÿÿ˜ÿÿ£ÿÿ ÿÿœÿÿ›äÒüéµÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿèùñ`mdx€wlriopisqkuojtogwpiwpgyrg}vkxoƒ~t‡‚z‹†|Œ‡{ˆ}“‰–€”‡ž™r Ÿ]ô÷Ÿÿÿ™ÿÿ£ÿÿ¤ÿÿ§ÿÿ«ÿÿ³ÿÿ±ÿÿ«ÿÿ©ÿÿ«ÿÿ«ð÷ ðø¨õþ©ýÿ«üÿ¨ÿÿ«ÿÿ³ÿÿ¼ûÿ©ïùŸôÿžûÿŸÿÿ úÿ•øý—þý øù’úùŠÿÿ“ÿÿ“ùö“óî”öî‘ûï‘ÿî™ÿâ˜åÓ‰àØýÿªèù‘ßö…âþ…øö‰øÒvÌqDÞNQßJMçKPÏYFÆvLÿÿÏÿÿÏÿÿÏÿÿÑÿÿÑÿÿÑÿÿÑÿÿÑÿÿËÿÿÇÿÿðά¼É¢ÑÉšêÈìÁ›êÆžìÉžíÈœèÁ“ݾ“ܻܸ‘×»•Ø¸’ÑÁ™Ö¿Ñ¸šÈ®¢–ãç£ÿÿ¸ÿÿ“ÿÿ“ÿÿÿÿ˜ÿÿ ÿÿ¡ÿÿ¡ñî„ÖÍiþí¬ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿpkaic`rintmmrlioidungxsgywhvvf{zmzyl~{q…‚zŠ„‡‚z‹†|’‹‚œ’Š–ŒrÁµŠÿý¼ÿÿ³ÿÿµÿÿ°þø¦þø¦ÿÿ¦ÿÿÿÿªÿÿ¯ÿÿ°ÿÿ¹ÿÿ¶ÿÿ·ÿÿ°ÿÿ«ÿÿ©ÿÿ¯ÿÿ¬üÿ§ÿÿ°ÿÿ¶ÿÿ·ÿÿ®ÿÿªùù¢ûù¡ÿü¥ÿÿ¢ÿù˜úï“ïâ‹ùé“ûé–ÿõÿñ•ÿí”ùÕêÑzýí•ïò†íÿ‚ôÿîþ‹ÿí›ÜbÑaQßLWÜHVßG[ÅZHÜŸfÿÿËÿÿÉÿÿËÿÿÏÿÿÍÿÿËÿÿÉÿÿÉÿÿËÿÿÍÿÿ軣»Å£ÕÇœèÅžæÉ¢êÅžæÅšæ—ãÉ鿘޿›ÝÂ⼖࿛ݽšÕ»™Ï¸–ʱ –þþ·ÿÿ¸ÿÿŽÿÿ’ÿÿÿÿÿÿ“ÿÿ¢ÿÿ«çÝÛÈ–ùß¿ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿñõÛXUKrflphfpkcrkbyogxqhxqhvqgurhwtj~yo…€v‚}u€{q…€tŠ†uŠu–’dæä›ÿÿ±ÿÿ§ÿô¢ôÞ“êÜŠñè’ûöœöò˜êéŒîíçæ‰ÞÝ€êéŠïîëìŽööÿÿ¬ÿÿ¼ÿÿÃÿÿºÿÿ­ÿÿŸõù˜ÿÿ¬ÿÿªÿÿ¨ÿÿ¢ÿÿžýþ—÷õöôŒÿÿ—ÿÿžÿÿ ÿ÷˜üï”ÿì”ÿïÔ¼`ÿòŽòö…òÿ‹öÿŽïò†ÚªhÍfP×YNæPQÞKRÝKX¾_KüÏœÿÿÍÿÿÃÿÿÃÿÿÅÿÿ¿ÿÿ»ÿÿ½ÿÿÁÿÿÏÿÿÞïÓØÇšß¾”Ý¿—åÌ¢ëÅ›ßÊŸæÈœèÀ˜ãÅŸéÄã¿–Ú›áÁ›å¹’Ø¿–ÚÀœÓÁ¡Ë²¢‘ÿÿ¸ÿÿµÿÿ˜ÿÿ—ÿÿšÿÿ•ÿÿ’ÿÿœÿÿ¡åÑ|ëËŒõЭÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿìëâjfWqm^ql`qlbrlgqkfqkfuojuojxrm~vrzr}zp}zr€|w„u‡€užpÿÿµÿÿ´ÿò›øç”ûé˜úíÿúªÿÿ©ÿÿ¤ÿÿ§ÿÿŸÿÿ¨ÿÿ¬þÿ£þÿ§ÿÿ¯ÿÿªÿÿ«ÿÿ¯üÿ§øÿ¦ÿÿªÿÿ²ÿÿ­ÿÿ©þÿŸõô—ûû—ÿÿ˜ÿÿ™ÿÿ ÿÿœÿÿ˜þÿ˜êäîâÿðŸÿö§ÿå›Ã§Súï“÷ÿ”éÿ‡ïð‡ð×€ÄuFâ]XÞQQãKTÜOOÖQLÅvEÿÿ¯ÿÿÃÿÿÉÿÿËÿÿÏÿÿÇÿÿ¿ÿÿ»ÿÿ·ÿÿÅÿÿÓŬ§É ÛÆÝˤêÄãÇæ—ãƛ꼕ÝÂâÄãΤíË¡êÄ™åÁ—໑ظ–Ƚ¤Ã¶¬‡ÿÿ²ÿÿ«ÿÿ¢ÿÿœÿÿšÿÿ“ÿÿÿÿ™ÿÿ”àÉjõ·ýÓ«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¥¥•ifZpkamj`mlalkbmidnkcrmewql{ur|xs|zt~zwxxƒn„€bž†ÿø¤ïâ’áσùê›ÿö§ÿù¨ÿû«ÿÿ«ýþ¢ÿÿ¨ÿÿ«þÿ¡üû ÷÷žÿÿµÿÿ®ÿÿ±ÿÿ¸ÿÿµÿÿ·ÿÿ³ÿÿ¬øö ôòšÿý¥ÿÿ§ÿÿ¨ÿÿ¤ÿÿ¢ÿþ›öòõòöö”ÿÿ£ÿÿ¤ÿÿ¤ÿüÿë–í¼q¶–CíÜ‚õ÷”ãùüï–ÌšRÃdBçY`ãQUèQUßSXÙV^Ì„bÿÿËÿÿÉÿÿÇÿÿËÿÿÏÿÿÉÿÿÃÿÿ¿ÿÿ»ÿÿÑÿÿÝÁŸ¯Êœæ¿–Ú´ŽÍßῙãÄœçÇœëÅëÅŸîÀëŸíÀ龘⾙޿™Ü¸–ʱ”»Åºœÿÿ»ÿÿ°ÿÿ­ÿÿ¦ÿÿŸÿÿ’ÿÿÿÿ˜ÿü‘åÈvýϘóŬÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùøýÿÿÿÖÝägnlhldikalialianhcnjenjgunnwnspkknlfwtl|wm€xf‹|fçÔ¢ôÛùä”ÿïœÿøžýù›þþœÿÿ¡ÿú›õáˆæÕ}øæ“þòŸÿý«ÿÿ©ÿÿ¢ÿÿ¢úÿ›ýþ¢ïì›ßÜ‹ÝÚ‰úú¡ýþ ÿÿ¦ÿÿ™ýõ˜ûîžóí˜õð›úùœÿÿ›ÿÿ¡ÿÿŸûô”ïã…ðá„üìÿÞšû«¼„PÛ»èã…îÿƒàÀo´^>Ê[FÖODÞPEéRJÚYDÉ^@ÿÜÿÿ¿ÿÿÅÿÿËÿÿËÿÿËÿÿÉÿÿÇÿÿ½ÿÿµÿÿËïå°¼¦¤ÁšÐ½˜ÔÂœßÂâÅ çÁœá¸‘×ÄŸäÁœáÄãÉžåÇäÅ›âÅŸâ¼–Ù¸›Ä³°Ýקÿÿ¯ÿÿ§ÿÿ¥ÿÿŸÿÿ˜ÿÿÿÿˆÿÿ”ÿñ†ÝÀjê¾}캜ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿìõÙ—€feXhg^gdclggnehrilthlwlk|qnytlutivuhyyi€wV›ŠWçÙ’ýð™ÿ÷œþùøô–þýžÿÿ¤øô‘ôéïÝŒþó™ÿþ›ÿÿ ÿÿ ÿÿ§ÿÿ­ÿÿ°ÿÿ¶ÿÿ²ÿÿµÿÿ¬ÿÿ¥üþúú†ýû“úöœÿù§ýï¦ùî¤ÿö¬ÿö þô•üõ•úó“ùò’ÿþŸÿû—ÿù’ÿÕŒî‡^ÈyF¼„GÿØ‹ìÈp¹i4ÑRBÛSMåSWéQZçHWÊPLÅpYÿÿÎÿÿÁÿÿÃÿÿÇÿÿÃÿÿ¿ÿÿ¿ÿÿÁÿÿ½ÿÿ»ÿÿâΰ­¿œ¸Â™ÖÀ–ؾ“ÚÅ›âÇä˜áºÛ·ŒØÆ›çÉžêÈœëÀ–ß¾—ÝÀšÛ¿™Ø¶ž¶©‘óï£ÿÿ–ÿÿ–ÿÿ¡ÿÿœÿÿ—ÿÿ‹ÿÿ‰ÿÿ•ïà|Û¿kã¹wë¹›ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿîÝÓ¨˜—gU`pdhkebmgbnhcnjeokhspftrcvsgvqixskysnuZ¾¬|öí«þû¬ýý¦ÿÿ¥ÿÿ¬ÿÿ¹ÿÿ²þìžðâþòÿÿ£ÿÿŸÿÿ¤ÿÿ¥ÿÿ¬ÿÿ±ÿÿºÿÿ¸ÿÿ»ÿÿ»ÿÿµÿÿ¯ÿÿ¸ÿÿ¯ÿÿ¦ÿÿ«ÿÿ¦ÿûúùšûú÷ö—ÿüžÿÿ¡ÿùŸþñ˜ûê”üâ”üבÿ¾ÜmUÚiYØc[ÕbPÆT8ËKBÛMVãUZéY\ëX_áITÄXDë¨uÿÿÍÿÿÉÿÿÅÿÿÁÿÿ½ÿÿ¹ÿÿ¿ÿÿÇÿÿÉÿÿÍÿÿõ»œ´Ã¢Ïº™Úµ”Ó°ŒÌ±Ï¾™ÞÂâÁœãÂ仓޽•à—ãš录ීӻ˜Ñ¸¡¶­Ÿ”ÿÿ»ÿÿ ÿÿ™ÿÿ”ÿÿŽÿÿŠÿÿ‹ÿÿÿÿ™çÐ|Þ¼sæ¹}궚ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÏÌÍ®«¬]Z[ec_ea\LKBcbWlkbmkenmdnmbrqfspfwrfzsh„zWèØýö¨ÿþ¡ÿÿ¨ÿÿ­ÿÿ´ÿÿ´ûî“ïÖöé’ÿû¦ÿÿ¦ÿÿ¤ÿÿ¦ÿÿ¤ÿÿ ýý›õô—ü÷ ÿü¢ÿû¡ôï“óî’øô˜ÿû¡ýþ ÿÿªÿÿªÿÿªÿÿªÿÿ­ÿÿ¥úú–ñìïà‘þó›ÿÿ ÿò—ÿâð˜hâ]Vîccï\eéX`ÖHOÓFHé]ZñZ^ôS\íPZâHUÇjGÿñžÿÿ¿ÿÿ¿ÿÿÇÿÿÑÿÿËÿÿÇÿÿÃÿÿÁÿÿÅÿÿËÿ÷Þ¤…¨¾ÌÁÛ¿›Ûº–Ø´“Ô´–Ö¼›Ú»—×½˜Ý»•â¾˜â¾—ß¿™Ü¾•Õ´‘ʳ—˵ ®¹ª”ÿÿÊÿÿ£ÿÿ›ÿÿ“ÿÿŠÿÿ‡ÿÿŒÿÿÿ÷’ߺtÛ¶rÞ¶và±ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÃÐÅ°·«YXM^aPnt`ƼÆz`ˆn`phd_kjamlaonapn_sr\xv[—^øè¢ýø¡ÿÿŸÿÿ¨ÿÿ­ÿÿµÿÿ¯øð—÷æÿû ÿÿ¢ÿÿ¥ÿÿ¨ÿÿ­ÿÿ­ÿÿ¦ýú—ùö•ÿüžÿÿ¤þÿ¡ÿÿ£ÿÿ¡ÿü™ýú”úô÷ì‰úò•öñšýý¤ÿÿ±ÿÿµÿÿµÿÿ¯ÿý«öí™ïáýÑŒÿÀ‰ÙpVáW]è_`ê__ÛRHÔJ6ìZNóXVðPRíGPÝFJÚQPׇ]ÿÿÁÿÿÃÿÿÁÿÿÅÿÿËÿÿÅÿÿÁÿÿ¿ÿÿ½ÿÿ½ÿÿ¿ÿí¿¢‚†¤ »ŽÏ¼“ÐĜٻ•Ô»•Ö½™Û¶‘ֱѸ—ؽ™ÛěߴŠÊ½‘Ï¿—Ò´‘ʱžžÏÍ“ÿÿ¿ÿÿžÿÿ–ÿÿŽÿÿÿÿÿÿÿÿùç„à¹tâ¸vä·yä²–ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ½šã¹¬ÔPU_V[e”—£ÿÿÿ‡„ƒec_gc``\W^[Sif^ojbrl^zo^¸«€þî¨ÿý­ÿÿ®ÿÿ§ÿÿ¦üÿŸÿÿªÿÿ©õè‘íåŠÿÿ£ÿÿ­ÿÿ²ÿÿµÿÿ³ÿý¥ûð˜éáˆÿù¢ÿÿ¢ÿÿ™ÿÿžÿþŸÿÿþÿ™ÿÿ™ÿÿ•üý–üøšóï‘íèŠø÷šÿÿ¬ÿÿ¨ÿÿ ÿÿ¢ÿÿ¦ÿò§ÿ»‚ÒeCãXNë_Zë[\ÝMNéYZîY\åIPéKSèDQÕRLÈcOÿÚ—ÿÿ¯ÿÿ·ÿÿ¿ÿÿ½ÿÿ»ÿÿ»ÿÿ»ÿÿ»ÿÿ»ÿÿ»ÿÿ»ÿÿ¯ÿÿ•·ª\™|_ €´É¶ÏÀšÝ»’Ô¼’Ò¼–Õ¶•Ô»—Õ»•Ô»•Ö¼–Ù»—Õ¸˜Ð« çî—ÿÿ¸ÿÿ¢ÿÿœÿÿšÿÿ•ÿÿ’ÿÿ‘ÿÿŒîÜyݶsߺrÖ²eÚ­ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿêöÓ·Ç„¢^YY^Zbª¤¸ÿÿÿx†_bcd^[wq~leOE-GEE>QF¶§zι‘ȼ‘áݱîìÍïïÝèèØüùíÿÿðÿûÞÝÛ³áá¯øøÍÿÿäÿÿñÿÿùîìÝ·³¤«©èåŸúù¥ÿÿ¢ÿÿÿÿ™ÿÿ¤ÿÿ³ÿÿ»ÿÿÅÿÿÁÿÿ¶öü¬ðô©éç¯ÝÕ±áÞ­éë­ìç®êà«ÿݦÍYžM(©E3¬K:§G:ž<0ªE:¨7.¹<7ç\\äHOËXDÒ†VÿÿËÿÿÃÿÿ½ÿÿ·ÿÿ­ÿÿ±ÿÿµÿÿ»ÿÿ¹ÿÿ¹ÿÿ»ÿÿ½ÿÿ¹ÿÿµÿÿ¯ÿÿ«ÕÎnœˆA €t´ˆ¶´ŒÂ»’Ô½—Ú¸‘×·“Õ½™Ûº–ؾ˜Û»™Ï½Ç¸©“ÿÿµÿÿ°ÿÿ¡ÿÿ–ÿÿŽÿÿ…ÿÿƒÿÿ‰ÿÿåÊoÞ±uÜ°oÞ²oß­‘ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¾­¾Í¸Ô“Š˜[Z_UW]¯°»ÿÿÿu~yVb`LWZ¢¬¤ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿáêÞ°·«°²¨ÈÉÂÒÒÐ×ÔÓÚÕ×ââäæèîÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÝ›¸Õo„ÛRa²]DçÇ„ÿÿÄÿÿÃÿÿ½ÿÿ·ÿÿ±ÿÿ±ÿÿ³ÿÿ¶ÿÿ¹ÿÿ»ÿÿ¿ÿÿÃÿÿÁÿÿ¿ÿÿµÿÿ­ÿÿ£ÿÿ›ÿÿˆ¼©;›~O§}²Š°²ŠÇ¶ŽË¾•Õº‘ÑÀ—Ù»šÉ´˜¸¿µÿÿ­ÿÿ¤ÿÿ—ÿÿ•ÿÿ–ÿÿŒÿÿ„ÿÿ„ÿ÷~Ù»Zß²hãµrÚ«qÙ¦ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿìÿž”³¤¡²}|ƒ[[YVWRÁ¿¹ÿÿÿ{sz`]`uxyÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿßéÖ€‹ÐUa³jEÿæ’ÿÿ¸ÿÿ¿ÿÿ¹ÿÿµÿÿ³ÿÿ±ÿÿ±ÿÿ±ÿÿµÿÿ¹ÿÿ½ÿÿÃÿÿ¿ÿÿ½ÿÿµÿÿ­ÿÿ£ÿÿ”ÿÿ‘ÿÿÿÿµÿíº¦ƒxxNn—p¡«‚Æ»’Ô²‰Ë§‰µ¬•¯æß²ÿÿ«ÿÿ˜ÿÿ˜ÿÿ™ÿÿ˜ÿÿÿÿ‰ÿÿŒóàr×¹\Ú¯g׫jÙªpІÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿtƒ ’œ›–ŒtooPLTMMMÌÍÈôôòVST[^]nusÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýþÿÞéÌ‹¡Ân»Q`¦mCÿú–ÿÿ¯ÿÿ½ÿÿ¸ÿÿ¯ÿÿ«ÿÿ³ÿÿ«ÿÿ§ÿÿ©ÿÿ®ÿÿµÿÿ»ÿÿ½ÿÿÁÿÿ½ÿÿ»ÿÿ·ÿÿ³ÿÿ±ÿÿ±ÿÿ ÿÿ‘ÿÿ§ÿÿ¯ÿò¹¦…~n€¦ƒ±¯–£¹¨—ÿÿ·ÿÿ¡ÿÿ›ÿÿœÿÿšÿÿ˜ÿÿ’ÿÿ“ÿÿ–âÆrÛºnæ¼z׬mØ­rß®”ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿx„€hwb’˜„Œ‰uca[=;EEHIàäÞÝâ×JOBSZL‹’„üÿúúúüÿÿÿÿÿÿÿýÿC2U$2#-#'&$&%'&!#9-/:+2,*7%;0$8&1@3<%.6TCvUGibShUJYJAM\R\SCM‚rs“€{¢“‹§š‘§›¢–Š§¢–·¹¯ÅÈż¾ÂÀÀÀÃÁ½¼º´¶²­¹·¨ÊDZËÉ®°®‘®®ÅŦƤ¼°—ž‰~ˆim¤|ƒ¡o{ѹ‹ÿÿŸÿÿ¡ÿÿ¤ÿÿ®ÿÿ¯ÿÿªÿÿ©ÿÿ¦ÿÿ¤ÿÿ¢ÿÿ£ÿÿ®ÿÿµÿÿºÿÿÃÿÿ¿ÿÿÁÿÿ»ÿÿµÿÿµÿÿ´ÿÿ¯ÿÿ§ÿÿŸÿÿ›ÿÿ›ÿÿ•ÿÿ©òˤ°—_¼±iÿÿ³ÿÿœÿÿšÿÿ—ÿÿšÿÿ“ÿÿ˜ÿÿ”ÿðã¼uã¸yß±zÖªrÒ©p΢†ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ|ƒƒHF@~uh‚}qrqhLLJ107EGMúþÿÞãáƒ}xzpµ²¨ÿÿÿÿü÷ÿÿÿÿÿÿÿÿÿfg`nmbfcWmkLœm¬¦v£˜h§œj¤™g­¡q³ w¥˜m°¤{£™r¤œv®¤©œx±¤‚©š}²¤‡µªŒ¯¥~´¬}¯¥€ž’w¢˜u¦s§ s°ªz·±º²Ä½’éá½ñîÍïïÒëíÍêìÌééÌìèÎðìÒõñ×õóÖðîÏûùÚýûÞüúÛ÷öÔÔξ‚svo\^«”—¸«‚öïÿÿÿÿ™ÿÿšÿÿŸÿÿ¡ÿÿ¥ÿÿ›ÿÿžÿÿ¡ÿÿ§ÿÿ§ÿÿ¥ÿÿ«ÿÿ¯ÿÿªÿÿ­ÿÿ©ÿÿ£ÿÿ¥ÿÿ¦ÿÿ§ÿÿ¦ÿÿÿÿ¦ÿÿ¤ÿÿŸÿÿ—ÿÿ“ÿÿ’ÿÿ“ÿÿ™ÿÿÿÿ™ÿÿ“ÿÿ’ÿÿ‹ÿÿÿÿðÛ{å»uß´uتsܱvÛ°sÛªÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿorz5>9ef_slctocfaU>9;(#2B@JÿÿÿÛÔÖ¤–”Œ…‡ÆÁÌÿÿÿöóëøöòÿÿÿüÿøw|oonalfX€zZ•f–aˆ|S–Œe•g‘‡b’…a’…c•†g–ˆf”†d™‹l”†i›Žj—Š_™ŒcœŽh—‰c¡“mœi†_š‘g”‹a’ˆa™Œh£•o£“k¯œ…‰pk–„±§¡¹²§À¼«ÌɵÔϼÛÕÅÞÕÈÙÔ¿ÚؽáàÊßÝÎ¥©“£ª¯²ŸcbYi`ažŒ—•ƒ|žŽtÜÔ’þÿ–ÿÿ’ÿÿŒÿÿÿÿ–ÿÿ›ÿÿžÿÿŸÿÿÿÿŸÿÿ ÿÿ¢ÿÿ©ÿÿ¦ÿÿ¥ÿÿ¨ÿÿ«ÿÿ«ÿÿ­ÿÿ¨ÿÿ«ÿÿœÿÿ¡ÿÿœÿÿ˜ÿÿ™ÿÿžÿÿ ÿÿ¡ÿÿ˜ÿÿ˜ÿÿ”ÿÿŽÿÿŒÿÿÿÿŒÿø†àÃmÞ±wà³wâ³uå¶zà°yÖ£Žÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿuv˜:=IUYSbc\kja^_XQRM15/ # A<>ãÓÝ…{>9Z 0¦Ÿ«ÿÿÿÿÿÿÿÿÿÿÿÿûýñ“}•“v™Žn¢˜q³ª~Ÿ˜m˜“j–Žf–Œg–Œi–ˆi‘„b“…a’…a†c’ˆa‘ˆ^“‰d’‡g…b’…aŽ_“…f’ˆa‡Q˜e’…c‰ephVFC+™™|âáÉôðßüúéÿÿôÿÿöÿÿõÿÿ÷ÿÿúÿÿûýùöþúõÿÿûÿÿþÿÿöÿÿðüôàõèã·¥°jWi”}—Šw‹†sƒ‹zp¯¡ÜÓöóÿÿÿÿˆÿÿ‡ÿÿŠÿÿ‰ÿÿ‰ÿÿÿÿÿÿ•ÿÿžÿÿ£ÿÿ¨ÿÿ§ÿÿ§ÿÿŸÿÿ–ÿÿ™ÿÿ–ÿÿ˜ÿÿ¢ÿÿœÿÿžÿÿ ÿÿ ÿÿœÿÿ™ÿÿ•ÿÿ’ÿÿÿÿ‡ÿÿ‰ÿÿÿÿ’úè‡Ù»næ¸å·€á³|ݯzÚ©yݬ–ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿogzD<^SQ]X\Thj`dcZ_`YLPJ-2.   34/:63HHH¶¸¼ÿÿÿÚÙ·÷óâÿÿÿõîã…€iŒ‚hbŠ|_…wZ…zZ„yY…zZ‚wWtT‚wY„yY…zZ„{\„z`„z`„z`‰€_ˆ€Z‰YˆU†}SŒY…{V|rO…z\i]FGA3.))032ÆÍÍÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýýûô÷ôþÿþÿÿüÿý÷þþüÿÿÿýýý÷÷÷õóïôïçëãáÑÅËYLUm`kueovdoxeuh€ycq„lt¤–wÉÄôô’ÿÿ…ÿÿ‡ÿÿ†ÿÿ„ÿÿÿÿ™ÿÿ›ÿÿ—ÿÿ‘ÿÿ‘ÿÿÿÿÿÿ–ÿÿ’ÿÿ†ÿÿŠÿÿ‹ÿÿŽÿÿ’ÿÿÿÿÿÿÿÿÿÿŽÿÿ‹ÿÿ‡ÿÿÿÿƒÿÿÿÿ„ãÎlÓ·eÛµvÖ®rÖ¨sÛ¯w×®uÚ¬“ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿqgaGBFSQ_QPWYVWTUPTUNPQJFD>/-';74:7/JG?àÚÕÿÿÿÿÿÿÿÿÿÿÿÿäâÜ…rŠ…nŒ‚fˆ€\…~S…}U„zW„|V€{T€{V‚yXySwPwR„yY„zW…{Xˆ~[ƒxX‚}X~|T~|V{[zvXd`FHC01*/*"/)&969¾¿Èÿÿÿüþÿùûÿýÿÿùüûÿÿýéå℆KDFSOU—”—ïêìÿÿÿûûû÷÷÷øõöçåáÝÙÔqigwhkxlpuks{ou‚sx…u…r‚€p|ueqˆzm¬žzÐÇ…ñéŽúõ‰õóvúüzöþwÿÿ‚ÿÿ„ÿÿˆÿÿŠÿÿŽÿÿŽÿÿˆÿÿÿÿ‡ÿÿˆÿÿ‡ÿÿ…ÿÿˆÿÿˆÿÿÿÿ“ÿÿŽÿÿ‡ÿÿ‚ÿÿÿÿÿÿ}þð…ܽuÕ¯nÙ®sÒ§jÙ®qØ­pÙ®qÖ¥‹ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿppnLD@[SQULMSLLRMOLJFNMDLHCJAB.))30/1+(3*-ƒs¡Ž ¾¦¾Ë¹ÄÜÎΰ¡¦„t€}wrxxfst_ut`ts]sr\rq[qnZonZom\pmYvq\qlYsm]pjZqh[ypawn_vs_qr[ttYnjN_\H@;1/, -*+'")$(?=GÉËÚÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÔ³ÕdSbsqma_[USOM=WM0gÿþÿÿÿÿÿÿÿÿÿÿÿÿýñðç‚}urdb~okƒql‡upŒzw~‰yz‚svzntwmuxmz`QVƒpp´¦€ÝÒˆóïŒÿÿ‹ÿÿƒùÿ~ÿÿ†ÿÿŒÿÿ‹ÿÿƒÿÿýÿrýÿrÿÿÿÿÿÿ„ÿÿƒÿÿ€ÿÿŒÿÿ‘ÿÿ‹ÿÿ…ÿÿ€ÿÿ…ÿÿ†ÿúzñÚwâ¸rå»yåºä·{ã²wá¯yÜ©xÑ‹ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ{{y=:9SNPPMPNJPGDGB?@>?:BD:DHB //-PMN,,*JJHJKDKJAE@6:0(d_Uvskif^b_W^`TY^QZYP[UR[URXROVPMRLIOKFSQKSQKXTQWRRXQS[TVcZ]b\Y[WRPOF<;221$///-.(+&,(%??=½ÀÁÿÿÿÿÿÿÿÿÿÿÿÿþÿÿ^cxrs^WS-*(%81&`R`sc}ÿÿÿÿÿÿÿÿÿÿÿÿùó㟔yjPrN‹€R‚R”‰Y„wSsdLpbUeWUe\]c[bnfmndn^T^]R_—ŒyË¿èá‘ÿþÿÿ‹íòqüÿ{ÿÿ}ÿÿ~ûÿw÷ýsøþtýÿzÿÿ}ÿÿyÿÿrÿÿxÿÿ}ÿÿ€ÿÿÿÿ|ÿÿÿÿˆûí„ãÊwÓ°rÕ¯rФlÕ©qÚ¬wØ©y߯‡ã± ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿLPS,31KPLLLJNNPHGNDDFEECBF>?D7>E9&.'   - $#(]XZSNNB==FCB]Z[XTQUPHnhewnqXQQVRO_]W^_XXZP$& 54+(#/,$ONESPHTNIVPKXRMLFCOFGGA>:6153-+)# $$)(+&1, 930_ZZ¿ÂÿÿÿÿÿÿÿÿÿÿÿÿÁÍ¢6I¹À<ÿýMóë^¡“*"LIAa\R÷ðåÿÿÿÿÿÿÁ¾¿¡˜™ ’…—…i€qTyjM€sO‘ˆ\’Š[‰PŽ†^¥œ}…qyri`XTi]_sgm€s~~orhYSre?®£]ÛÐvòæxýø|ùûtøûtùüuüÿxúývõ÷wììsóöqÿÿ{ÿÿ|ÿÿ{ÿÿ}ÿÿyÿÿzÿÿxÿý|úìÛ¿kÔ¬nÕ©qß°~ݯzãµ~ÙªxÖ¦|Ê—‰ÿÿÿÿÿÿÿÿÿÿÿÿOKc47ADKKEJFFGBFD@D==>99944<:6@A<591'+#&+ *,"  $'("" %#@@0DC-JE9TIHaYWnefVMNWNOIFG EA>¸°õéíνΞ–’×Ö¾}}kXWNWUQXSUZSU[RWZSWVOSVROVSKVRM_ZZjdaped`URA635-++$$A6E¹¥ÇùïÿëæóÒÈÒ¬—£viÿåÃÿìžþïyþë{ÿï…óÖ§vR^_SWåñïÿÿÿÿÿÿÿÿÿüôÞ¥”o¹Ÿm¦ŽbsQjMn_G~tO‡Vƒ~G‡ƒGƒ}I|sG“‡\¥˜o•†nuc\`OUs_vtdpsgiwjX„vR¹§kßÇvêÚ{èÛpðèpûõs÷íqâÖ_çã`ýÿsþÿxÿÿ}ÿÿ}ÿÿÿÿ|üÿpüúyúìÜÀjà¸xê‚éÁß´wÙ¬rÏ£kÑ¥oΠ‡ÿÿÿÿÿÿõ÷û45>66FHDLSLNLIL>=B99;967521/-)31-/-)(& (& ()")*#'+#&""A>6FA9NI?TOEXRMcZ]UOLTQI<;0#%IC>B17zmxÿöÿä×àxdiSJMWSYTOOTNISOL^Y[WTSRONSNPWNSSNPNKLLIHNLHTPMXQQRMMA>?DAB¨¥¨¼»²ìêÙüúÝÿÿåÙÌŽßËvÿô˜ÿø˜þé‰ÿéŠÿæ˜ôÔ˜|jÿÿÿÿÿÿÿÿÿÿÿÿÿÿþ§›pµš^À¢j²‘\¦U­˜b¨•c„rF€tB†N¢œ^˜Uƒ@ˆƒJž™b šf”j›nxj]aPXvfpxkvncbm`W˜ŽiƼ}Ì¿sÏ¿gÛÌoéÚxæÝnòïuõ÷uôúpöþlûÿmûÿo÷ÿmÿþ÷ÞwÜ¿kݺzÔ±qÏ©lÆžbÑ¥mÖ®rã»溠ÿÿÿÔÕÞ%(064>C?854521523//-&'"&%&#"%!'!""" +'$63+WTJC@6C@6GD62@;3MH>ROGQOIQPGVSKRQFSRGUTKQOIQMHSMJQKFNHCLHCMIDNHENEFIDH>9=TLU5/84/:A@G  &' /0)GEAEG=DF8HE;E=9EA?88:046*02&1/)611GDEOLOPNJOLDOLDRLGSOJQMJNKLLHPQQSOOMLMHJKDJI@JG?KF>JB>KE@RLGEEE:?G?FQ÷ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÓÓî". - 5#WLKëåîÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿåϮصw¹™Z±TÁ¡e¿¢gªŽU®’^»Ÿkŧt³™gŸ‡Y€Xˆ}]ƒ`”‡c›b™Xš”Y¬¦h°¤yžŽv|k_`POVGJI:ATELgWah\NŒ„`ÌÄ}÷é…ôëzíækæà^íçaÿútÿÿzûé†Ô³wϬnË¥h˨hË«hÉ©hË«lЫu׬€Ü¯š'271:@;;=;7?=9>?:783<;2VSI41)5/,   -   -  +,%64.%!LHEEA>nkcHE9C@6KGBHG>FE:EB6?:.73.0+-$$$!&$+.-;;=GGEPNHQMHQKHLGGKFHOJJMHHIH?GG7HE;MGDLFALD@LDBNEHLFMB@L:?Gèóöÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¶´¾–‘œ¶¯½ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøèÐع‰Û»|ʦ[¯F¸˜W¼›_°‹U§…Pµ“dÅ¥kÁ¡`°V§ˆX¤Œ`—„]†wX‚ua‡|kvipf^eZWNBD>1::168/4))@2BdW`i]awmU°¥sßÖ€ûó{øöyøùyøð…é؅ʱgÚ·wÚ¶{Û¶€Ú³{ܳ|Û´zÔ®qΨkÇ fÆš‚92B;7=9:5:;4:<2220218145.10777.)+    -  -    #&'@<9TJBTMDE@6A@5FHGF;HE;FE:DC:DC:D@;D@;EA>EA>JEEBDJ=AP7AKÓâêÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùÙͨrØ­rã³sܯsÀ”\¹‘\Àžlº—h©†Y¹˜cƦlãi³“Y²‘\º˜iÄ¥w¸šnž…`ŒuY†qV„nX„nVv^GmWCN:*( 8+6_Q_fXfeWe}qc¿³ŠéÛ¥ûç§Å°u–€M¯”X¹™Vº—UÁ›ZÅždÆžkË£nˤlË£nÌ¢pÒ£‘56?5::4954:1.5),-&0++/*,807;89450 - - -   %#'%(& PLGia]h`\ld`b^[`]\^YY\UU[WTXVPPLGRLIQKFOHAGD8BB2@@0;8,43*,)(##%$+( 950C<7VXL<;./1%  ;:1\WO[VNg_[b_W>@4LK@if\cbW_^Ua_Y`\Y\ZV\ZVZYPedY\[RYUPYUPXRMQMHLJDGD6;72>99615.))'# "#""-+'?=7A>6C@8IC>IDWTWfcbfaab[[950JG=[VV6.7;/1J85v^Tž~p¼œ~Å£v°U·”RÀ _²‘U«‹J»˜VƦgÁ¡gº™bº™dǦoЯuÁŸh½›f˪pÖµyƤm nȧkÒ¯m×·tбpµž\¥‘Q©”V»Ÿfƨpʨs½›d¸–_¿fÞhžęoÖ²yÙµ|æÁຌݸ‡Úµà¶ 0.:329/.3),-'*)&)&(+(-0----30/>:7QOKBB@#(&'$%_]YVRMTPKOIFVROYWSYXOZYN\[R][W`^X_\T]ZP^[QYXO\ZT^\V^ZUWUOVTNa_YYWQXWNROGOKFLEED@=C?:@?4:<.46,.,(& '!%"#442B==H?@KCAJB>A+<- .#"LDMZUWca[fd^fd`hg^hg\gfYkk[rthqrklmfjkflmfab[CH=',(,$++)-.)-.);1)]H=”|i·™®dºš^¼\«ŒF­ŽM¹™]Á¢aÁ¡^¼œ]Ä gÔ°wÆ¡k¼›aÊ©mǦoâp¾žbǨbѲlصs×µpâ½wæÁ}ã½|ΨkÀ™aàbÒ¯oÞ»{ß¼|Ù¶vЭmƦe¸˜Y´”U­ŒP«ŠNµ”X¸”s2+73/7*).+++((&((&)))---111775<98C@A1.1OLO\ZVKJ?C@8JB@MGBJFAJG?NIAQLDUMIXRM\VQYVNWVKYVLZUK]ZP]ZP[XN_\TYUPYUR[WRYVNYVN`[SXUKROEJG;GE6BA6CA;<;0<:+/.%*'(%"#*+$=B5GI=SRGacWotgjlbNLH_`Yikafk`cg_\]VZXRZYPKJ?=;5.)+$*+$*/$(,&,,,),).1.3/,8-,6'!;&aG,~P©ˆQ²’Qµ–U«ŒM´•RÁ£]Ë«jÁš`½™^É¥jÓ¯t¾šaɧpÌ«yÌ­nÌ®d¼žVĤaÖ¶sÚ·uÙ¶tÝ·vÆ£a³N·”Rʧeà¾yèÃÜ·sͨdÁ¡^À¡`È©fѱnÖ³sܵ{东)*#&*$#(& %!!&"#&#+('/**6//<61<7-781&+'SXMZYLLG=A63>567-5=68;74=88948@<9A>4EALI?ROGUOJYTJ\UJ[WHZXI_\T^Y[WTSZXTVTNYVNXWNSUKJODKOGRPJG?=D?7>9-;50926/,-///)))# # !!#$$&,*&63)30&2/'-+%+('))'**()*%(& (',+"(&"+&*+)%.-$*+$(,&'+#'+#,+"/*"-* -,!,+-*.*%/(*+"%*"6$T;+ƒiKªŠcºšo̪{¼›d­ŒP¢_ʨa̪e¿œ\ͪlرwȤk»™dȧmÓ°rÚ´wàµzÕ®v¸–a³’XàbÔ²kÖ²eÇ¢^¸‘Y°‰QÀ™aÊ£kÈŸh”{!%$( "& !"%"!(& -*".+!-(.+#/+&0,'@<7gdcaac222 "$!)"$( #$()$,)!2/#84#=9*>9/@;3C=8D@=IFEJFANIAVPM]TW[RSZRP\WO]ZP`]U_[V]YT[UP]ZRVSKZUMTLHMGBKE@GA>>7773040+2,'3+'-*"#%!"# !  !$!)# .(%/((/'%1&%/)$,*$+)#-)&,'),&--&&.&"/)$/)$+'"+'$+$$/&+0'(0($,*$(,$&*$**(+,'()$+)#)% 2&>'cI0qN­dʨy·–_·—[ĤaȦ_¿œZÄcÏ©jͨdÍ«fÌ©gÔ±qÙ³vàº}Ù³v¼™[¸˜YĤaѯh×µlͨ`¾›[°‹W·’\ÅhÍ¡‰('*("'$%!!& '+&()%"*("(* *,",*$42.OLK^_Z9:5 !!!"""&&((((.+*1/+40+43*98/?>5@<7GE?NLFPLGZRPYSNXTOWTLZWM]ZR]WT_YV\VSXROWOMXRMTPKQMHKGDMH@H>4E@6>:586211/+,'*($%!##%#$"'# +)#,*$(& (&"'+##) #(*)-+'.)-*'(%%%'%!+'"+'$)$$*+&'-$&,#(,$&+'(--*-,///11/2/.OR?jbN_L7”z\ÀœyÆ£tÁšbÄ¡cͪjÆ£eʦkʪkĤe¸˜U¹šRÏ­dÔ°eÔ¯iÆ _Ã^È¡gÓ°rÛ¸x×´vÍ©p¿›b»–`¶™z \ No newline at end of file diff --git a/example/dev/file_grabber/image/img0259.ppm b/example/dev/file_grabber/image/img0259.ppm deleted file mode 100644 index e8f11a3e5fd..00000000000 --- a/example/dev/file_grabber/image/img0259.ppm +++ /dev/null @@ -1,21 +0,0 @@ -P6 -128 128 -255 -\mw_pzdr}gqyhmusss©¢›~~€pv„my…ky„ky†mzŒk{Œ^nYixm}ŒŠ›¥™«²›¬¶ ®»¨µÅ±¼Ï´ÁÓºÊÛÂÓßÅÓÞÐÝäÜäèßåèëíñìðóèìïíòòïôôõøùóóõôôöïìïöööÿÿÿÿÿÿÿÿÿýüÿûùÿöøþëíóàèìÑáâÏÞæÉÖæÁÒãÅÙë¿Óã·ËÙ¹ÍݸÈÞ·Ç߶Åâ¯ÁÝ®ÀܲÄà²Á଻ӯ¼Ð­¼Ò¯¿Ù­¿Û­¿Ý®ÀܲÄà¯Äß®Åá¦ÀÙ¡¼Ò·Ð¤»×­Ä৽ܡºØ¶Ö¥»Ú§¹×¥½Ô¸Ìž¶Ë¥»Ñ¢¹Ê›²¿žµÂŸ³Áš®¾°Å¡µÅ¤¶ÂŸ°Á¢±Ç£³Æ ­Á °Ã›¬¿ž­Ã¥±Ê ¬Å›§Â—¦¾ž®Æ¡²Å”¤³Ÿ®“ °¡­ˆ¦…—¡~›{Œ˜u…”q’m}hyŠbs‚\myZhuTeqOamPblXjtObb]lr_qx_p|et|fsznus¡£™}‚€qxirit…hvo~„hwbp}^k{mzŒ„’Ÿ•¡­™¨°Ÿ±¸¯¾Æ±½É±Â̸ÍÖ½ÓÙÂØÜÌÞãÔáèÙäçÞæèãêêçììæêíêìòõ÷ýíìóéëñêìòôöü÷ùÿöøüôóøîðôõùþêðóèîñåñïÙêæÙëîÊÛçÀÒÞ¼ÐÞ½ÑßÂÖæ¹Ïã³Éá¬ÄÙ¦ÁÓ©¿Ó¦µÍª¹Ñ¬»Ó©¿Ó±ÍܯÌÛ°ÍܧÇÕ£ÂÓªÊدÌÙ­ÉØ«Áק¿Ô§¿Ö¬ÇÛ¦ÁÓ¡¼Î¬ÇÙ©¿Õ¥µÏŸ´Ï¤»×¥ºÕ¨ºÖ¤·Ì¦·È¢³Ä¤µÆ¤µÆ¡²ÃŸ°ÃŸ¯Å™­¿œ°À£´Ç¢±Ç¥´ÊŸ«Â›ªÂš©Æ›«Å ¯Ç ¯Ç¢®É˜¤¿–¢½˜©¼”¨¶¤¯Œ¡¬Œ¡ª†›¤…—£‰–¨Ž {ˆšvƒ•n{jz‹euˆ`pƒ^kWhyQesVgxS`tJW`_jly‹eu„hwhrxnsq®ª¥ƒ‡Šlu‚eq}jv‚lx„nz†ky†_o~Zkzi}‹w‰•ž«•¦°¢³½ª¼Æ­¿É±ÅÓ¼Ðâ¿ÐáÂÏáÃÔàÉÛåÑäéÔæéÒáåÙãéâíîÝéçàéæçîìéîìô÷øñôõùùûòõöñõøæêíéíðìòõäìðÜéîØçíÐâéÄÖà½ÒÛ¹ÑÛ·ÏÙ²ÊÔ°ÄÒ°ÁÒ¯Â×µÊå³Îâ«ÇÙ¬ÈÚ©ÄؤÀÒ¢¾Ð®ÊÜ®ÊÜ«ÇÔ«ÅΪÆÓ§ÃÕ¤ÀÒ¤ÀÒ©ÅצÁÕ©ÄÚ¬Ãݨ¿Ù¬ÁܨºÖ¬»Ø µÐ§¾Ø¬ÁÜ©¸×«½Ù¦¹Ò§½Ó¡·Í¦¼Ð ´Æ±Ã¡´Éœ°Àœ­¼œ­¼ªºË¥¶É­Å˜¨ÀšªÂ¬Ä˜¤½™¨À¢±ËšªÂ•¥½‘¡´–£µžªŠ›¥ˆ™¥‰™ª‰š©~’ {›y‹•y‰˜nz‘bq‰fuct‡XlzUiwSguQbuKZr?MX[kzXhw`m}fszltvoro³¯ªƒˆ†jw|gtyiv}kz‚n|‰fwgy€]o{h|Œwˆ™‹˜ª˜¥µ ®»§¸Â¨»Âª»Ê²Á×¼ÌÛÁÓÚÀÒÙÍßæÇÜåÉãìËàéÒäëÛêîàëìåíñâåíéíòñõøèííîóññööæêíñööíòòçðïÜèæÒåãÌâäÄ×ÜÅÔÜÁÏÜÂÏáºËÞ°ÆܹÑæ½ÕêµÍâ¸Ðå¨Ã×¥ÀÖ¬ÄÛ©¿×¡¼Ð©ÅפÀÒ©Å׬ÇÛ®ÄÜ«ÁÕª¾Ð¨¿Ð©ÀѪÂÕ¤¿Ó«ÆÚªÅÙ«ÃÖ°ÆÚ¥½Ò§¿ÖŸ·Î§¾Ø¤¼Ó ¶Î—¯Â—°À˜´Ã¡¼Î§ºÏ¬¸Ñ¦¹Îž·Çš¶Ãœ¸Ã¢ºÂ³ÆÍŸ³Á°Ç˜«Ä–¨Äœ¯È–¦ÀŒ£´Ž§³’¦¶™©¼’¢µ’¡·•¦¹ŽŸ°‹Ÿ­‹£­Šœ¨‡”¤ž|Œ›~Ž¡v‚›kz’dtŒdtŒcrŠVf|L_tO_pMXi@GRZf}Xew[iveowlrwrrp¸³«ƒ‡Šmy‡cnit‡mx‹ozjz‹g{iyixq”†–¥ ¯œ­¼¢·Â§¼Å­¾Í±ÁÔµÅÖ½ÊÜÉÙèÉÙè¾ÓÞ»ÓÛÄÚàÎáæÉÜßÎââÕèëÒäéÑãæ×æêáïñäïòÙçéØèéØëëÕèèÎàãÄÓÛËÝçÐçôÌäîÈàêÉáëÌáì¾Òà¶ÊÜ°ÆÚ­ÅܦÀÙ«Åà¦ÁÓ¢¾É›·Ä¸Ê¤¿Ñ¤¿Ñ¦ÁÕ¬ÃݪÁÛªÁݲÍá¬ÈתÆÕ¯ÇÚ¨Ã׫ÅÞ§ÃרÅÔªÆÓ«ÂÑŸ¸È›¶È¦¾Ñ¤·ÌŸµÍ ·Óž¶Íš²Å ¹Éž·Ç ¹ÉŸµÉ¥¼É§½ÃŸ·¿žµÂ™°¿š®Àš®¼³ÅÑ¢¶Ä›¯Áœ¯Ä¡±Ë–¦¾œ¬Ä—¨»’¢±”¤·‘¸œ²ˆ™¬ˆœ¬~•¤|“¢{ŸyŠw†žv†žq™j}”fy_r‰^nˆTg|OcuP`sPXn6:I\f€Xey]jzfszepqjpiµ²¨‡ŽŽlz‡fsƒnyŒozozfv‡g{fwŠl{‘q‚““¡¡±—¨»±Á¢¶Ä«¼Í®ºÑµÁص¿ÙµÁÚ¼Ëã½Îß½ÒÝËÝéÄÑáÈÙãÑãêÕçîÊØãÊÜãÍàç¾ÑÖ¯ÂǼÎÑÓâæàðñæöõÝððØëð½ÕÝÀÜçÁÞæ¶ÐÙ®ÈѵÍ×ÀØâÊáî¿Øæ­ÉØ©ÄرÈä¬ÇÛ®ËÚ¼Ùæ«ÇÔ§ÀЬÂÖ¨¾Ô¬ÂÚ¥½Ô£¾Ô©ÄÖ¶Òá·ÒäªÅÙ¥¿Ø¢»Ù¡¼Ò£»Î§¿ÒŸµÉ¥¾ÎŸ»È«ÇÔŸ»È—¯Âš°ÈµÌµÌ—²Ä“¯¾›·Ä›·Ä™²¾š±¾™­½›«ÁŸµ”¤¼œ°Â ´Ä¡²ÅžªÁ›ªÂž®È›ªÄ¨Æ“¤·¤¯–§¸” ·‘¢µ˜©†š¬}Ž¡xŒœyv†œz†¡z†¡s~œjz’cv‹\o„cs‹\p‚_sƒl|‹T_p5?GWdxZezbj€bkx`hlhmi²´ª‡ŽŒlv|gt}oz‹o|Œjz‹eu„`pfwˆk|q…•z‘ž‡›©˜©º–ªº ´Ä©¼Ñ¨»Ô°ÄÖµÉ×·ËݳÃÛ¿ÏçÂÑëÎÚñÆÑæÄÏäºÅÚ·ÂÕ»ÆÙÊØãÛíðÞðóáðôÐâéÊÛçÌÝçÑãêÒäéàïõÝïù½ÑáºÑà»ÒãÀÙçÇãðÀÛí´ÌãµÍä¬ÁܬÁܲÄ⥽ԥÀÔ¨ÄÚ¥ÀÛ¤¿Ú©Äß«ÅÞ¨¿Ù¬ÄÙ¯ÇÚ¬ÄÙ­ÃÛ¬Æß«ÆáªÅÞ±Ëä¥ÀÔ¦ÁÓ¤¼Ñ²Äà­Âݤ¹Ô ¶Î¤·Ð©¿Õ©¿ÓŸµË¤¹Ô¤ºÎ´Ãš±À±Á›®Ã•¨Á–©Âž®Èœ«È›¨Ê›©Æœ«Ã™¨¾œ¬¿–ª¼‘¨¹¤µ•©»–§¶–§³¡²‘¤¹‘¤¹Žž¶ƒ–«‡›­|¢|¤{Ž£v‰žt…˜n~fwŠk{‘cw‡_sbs†^jƒ[g~R]r)3=^bs[aq\dv[dq[eminl®«£‰ŽŽn{„kz‚o}ˆn|‰ly‹br…etŒiyl|’oƒ•| „˜¨†š¬¡±›¯¿¤»Ì§½Ñ©½Ï°ÁÔ¯ÃÕ­ÄÕ³ÌÚ­ÆÔ·ËÙ½ÊÚ¼Í×ÑãèÎßëÊ×ëÉÖêÇÔè¼ÌßÆÖìÂØì¸ÐãºÓãÇÞí¿Øæ¼Õå¸Ñá¿Øè¶ÍÜÅÙéÀÙç¹Õâ³Ðß±Íß«ÇÛªÅÛ¨ÃרÀÕ«Âܨ¼Ü¦½Ù¤»×¨¿Ù§¼×«ÂܦÀÛ¤¾×ªÄݤ¾×£½ØªÂÙ¬Âؤ·Ð°¾Ý®ÀÜ«ÀÛ¥ºÕ¦¸Ö µÐ™°Ê•¯È›¶Ï ¼Ò£¿Õ¢¾Ò—³ÇžºÉŸ¸Æ—®¿­Åš®À›²Á›²Ã˜«Àœ¯Æœ®Ê›±Å™°¿•©»•¥½“¦»¡³Œ£´‘¨¹”«º‡›«‰š«‹˜ª‰™ª‡—ª’¥†—ª‚‘§|ˆ£{Š¢}¥zŠ¢q€˜k{“o—iy“craq‰Xh~WdtS\i3;?gt}TckVem^kt[dqfmm«­¡Œ•’o~†gx‚fw†fw†bs„_q}hz„g|…h}ˆlƒ’tŠž˜©ˆœ®¡±’¦¶›¯¿Ÿ³Ã±Á¨¹Ê¥¶É¬¼Ò°ÄÖ²ÉØ´ÇܶÅâºÉãÃÏê´Çà®ÆÝ°ÆÚ»Ïá¹Ïã¹Ïå´Ìã¸Òë¿×î»Îç½Óë·Íå»Óè¿×ê´ËܹÍß²ÈÜ­ÅܬÇÝ®Éâ«Æß²Íæ¥ÀÒ§À̬ÅÕ®ÆÝ©ÃܬÆá½×ð²Íã­ÅÚ¾Ôè­ÃÙ¨½Ø¨½Ø¦¸Ôª½Ô±ÄÙ®ÁبºÖ«ÀÛ©¾Ù¥º×«¿ß ¶Õ£¹Ú£½Ø¦ÀÙŸ¹Ò¡¸Ò¨¾Ö©¼Õ ²Î¥´Ó¡³ÑŸ´Ñ¢µÎ¤³ËŸ¯Ç­Å›¯Á˜¬¼‘§»¥½¦¾“¦¿‘§½£¹‘¤¹Ÿµ µŠ²Šž°Œ®†–©Œ˜¯’¥~’¤yŸ€¦y¡y’¢~•¤p„’fwˆiyŒk|dxŠau…Zn~Vhr>MQ"-.wzygosYhpZgl]eihmi¦¨žŠ‘mzdudu†du†`pƒ]m€br…_pƒfwŠktˆ˜¡Œ™«œ²Ÿ¹˜¨¾œ­¾¤µÈ¦µÍ¥µÏ£µÓ©»×®ÁÚªºÔ­¸Ö±ÀݱÃß²Èà®ÆÝ«ÃغÐæ¹Ïã·ÍáºÐæ»Ñé´Êâ²Èà²ÈÞ´Êà¹ÏåµËã´Êà­ÃÙ®ÆÛ¯ÇÞ²Íã©ÄÚ¥ÀÖ¯ÇÞ®ÄܶÉâ·Êá°ÃجÄÙ¤¿Õ£¾Ô¦¾Õ§¿Ö¦¾Õ§¿Ö§¿Ö¶ÌâÃÖí°ÆÞ­ÂÝ­ÂݵÇãºÏꧼנµÒ³Çç«ÀÛ§½Ó¦¼Ò¦¼Ò§ºÓ¬»Ú«»Õ£³Ë ³Ê¡´Í—­Ãš°Æ™¯Å™¬Åœ¬Ä¬ÂŸ°Ã›¯¿œ°Â•¨½–¬À—­Ã˜«À›ªÀ”¥¸“¤·’¦¸£µˆœ¬‡›«„—¬ƒ–¯’©‡š¯‚’¨~£~Ž¤{‹¡w‹m‘oƒ“o€‘kg|‡iz‰`mXctK[?LU7BE.9:1:9BNL`ljix|bsYizam„`p^n}WhyVi~[rƒax‰h~’n„šh~–r‡¢z¦}“§„š®ˆ›°ˆ›²ŒŸ¸˜«Ä™¬Å–©À£¶Íš­Ä ³Ì›±Å›²Ã®ÅÖŸµÉ”¯Á“¯Á¨ÄÚ­Ç⤼ӫÁÕ¤·Ì£³É§½Ó¨À×£¾Ô¦ÀÙ¡¼ÒŸ·Ì¤¼Ó¦½×¥¿Øœ¶Ï¸ÐçµË᣻Ҡ·Ó¨À׸Ðå¬ÄÙ­ÃÛ¯ÇÞ¬ÄÛ¬ÂÚ§ºÓ½Óé¨ÀÓ¢½Ó¥¾Ü©ÃÜ£»Ò¡¹Ð£ºÔ¢¼Õ·ÒŸ¹Ô¶ÔŸ¹ÔŸ¹Ô™´Í¹Ï¡¼Õ¤½Û–°ËŸ¶Ð¡¼Ò–±Ç—¯Ä™¬Á”§¾–©Â¤·Ð¡´Í”ªÀ³Éš°Æ¢¹“§¹›¬½°ÁЊš©‰š©‰š©£±„˜¨ƒ—§‚–¨€”¤“£~’¤|¦‚•ª£vŠœtˆšp„”o€‘j{ŒjzqxƒÄÄÆ¥§¶‰«~ˆ¢z†Ÿp~‰IRMRZSTZQ8;86688;58B59>DFJ]^gqqdjz`k|ZgyXg}Yl`x‹c{Ži“h€•m…œqŒžz–¥|”§ƒ–­‚–¨¡°ˆ™ªž± µ”§¾’¨¾˜®Ä™¯Å™¯Å”ªÀ˜«Â—­Á›²Ã´Å¤ºÎ¦¾Õœ¶ÑŸ¹Ô¥¿Ú¡»ÔŸ¶Ð™±ÈŸ·Ì¤¼Ó¨½Ú¬Ãߤ»×¥¼Ö£ºÔ£½ÖªÄÝŸ¹Ò¤¾Ù¡»Ô¦Á׫ÇÖªÃÏ£¿Ì¡¼Î¨ÀÕ§½ÕªÂÙ¨¿Ù¥ÀÔ·Óâ´ÍÝ­Ãק¿Ò¤¼Ïœ´É¤¼Ó«ÃتÂÕœ·Íœ¶Ô£½ÛªÈ™´Ï”®É—±ÌžµÑœ³Í–®Å‘§¿Ž¡ºŒ¤»•±ÇŒ¨¾Ž©¿—²ÈªÃŽ¥¿ŠŸº‡Ÿ¶š®‚±Ž¦»‚˜¬Ž¡¶…›¯—¬—­~‘ª‚•¬‚•¬}¥v‰žrˆœs‰r†–†˜¤p„”f|h{brŠ\av_Wj†‰Š   ###/:;.9:9DG:GNTZDYbObgFVW6AB3::28=GJTejtjqzZiqN`lbt€cumo†•lƒ’oƒ•z¦yŽ©€˜¯x“©—ª†š¬Œ£´‹£¶Œ¤¹¥½§º’«»•­À™±Èœ´ÉŸ·Ìš²Ç–¬Â–¬Â™¯Ç–¬Ä‘§¿’¨À–¬Ä“«À—²Ä©ÄÖž¶É™¯Ç¦´Ö¡¶Ó¡»Ö›µÎ¥¼Ö¦¼Òª¾Ð²ÅÜ­¿Û¨½Ú§»Û«ÂÜ­ÅÜ«ÆÜ©ÄÚ¡½Ó¤¿Ø¥ÀÖ¦¼Ô¤¼Ñ¢½ÑžºÎ¡½Ñ«Çٸʠ¸Í½Ï뫾ס´Íž´Ì ¸Ï›µÎ‘«Æœ³Ï®Ïœ®Ì”¦Â˜®Æ•­Â›¶È“®À’«»¤µŒ¥µƒž°‡¤³ª·Œ¨·‰Ÿ³ƒž²‚¶‚³™°„œ³„š²y‘¨|”«}•¨˜©†œ°uˆŸ†™°€¨v† ržpƒšq„™r…šiy‘fwŠeu†[lxTbm"/8! Ob?Sa?T_MbkObiK]bBQU2=@38@9:GMPXcinblrXgor€‹fsƒq‚‘i}i}wˆ›{Ž§y­–°z•«™°…›³‹¡·Š ¶Œ¢¸“¦¿–¬Âœ´Çž¶Í µÒ•¬Æ—®È’ªÁ–®ÅŽ¦½“©Á›±É™®ÉŠ¡»žµÏ¤¼ÏŸ¶Å¤»Ì¤ºÎ¤ºÐ¢´Ð­ÂÝ¡¶Ó¡¸ÒŸ¶Ð¡¹Ð¥»Ñ µÐ¤¸Ø¥¹Ù¨¹Ú­ÂݬÂÚªÂÙ¨À׬Æß ºØœ¶Ñ¤»×¤¿Õ¢¾Ò£¿Ó¤¿Õ£»Ò›°Ëž³Î§¹ÕŸ±Í¡³Ï£ºÔ›µÐ˜²ÍžµÑ²Ï£²Ñ›­ÉŸ±Í›®ÇŽž¸Ž¡º£¶Ï”ªÀ–®Ã§º’©º—°ÀŒ¤·‹¡µŠ²‚š¯~˜±³~š°z•«–±†›¶€’®~‘¨|¢yŸsƒ™u‹¡n…Ÿt‰¤pœpƒœj}”n˜m€—dwŒg{YmM^qGWf+8 =H]AN`HUg>K[>K[>LYDR_DQZAKS5DFHLX]ebitZgwcs‰o•t„šp„–xŒžy…™©ˆž²…›³ƒ™±…—³„š²‰¡¸‹£º™°Ê’©Å‘¥Å–«Æ–¬Ä›±Ç‘§½–©À˜¨Â˜§Ä›¨Êœ®ÌŸ´Ñ¡¸Ò¡»Ô¥¿Ø ·Ó³Ò£¹ÜŸ¸ØœµÓ ·Ó¡¶Ñ¦¼Ò®ÁÖ­ÀÕ¶ÆÞ¤·Ì®ÅÖ®ÆÙ¤¼Ñ§¿Ô­ÃÛ¨¾Ö§½Õ«ÁÕ§¾Í©ÀÑ­ÃÙªÂÙ©ÃܦÀÛ¤½Û·Ò¦½×¤»ÕžµÏ·Ò¶Ô£½Ø·Ðœ¶Ï•¬È•¬Æ›°Ë¦½×œ¶Ï“¬Ê¦É”¨È–¨Æ“ªÆ‰¢ÀŠ¤¿Ž¨ÁµÊ¥¹Ž¡¶›ªÀ‚’¬„–´}’­uŒ¦}”°~’´{­€–®xŠ¦s vˆ¤vŒ¤vŒ¢~‘¦uŠ¥l€¤g|™cvat^mŠZoŠcz”YqˆSiMduCWe9NW,?D!538G_BReAQbARa>ABUUU_gk^pw]qg}“o‡šsŒœw¡}§…˜±†˜´€–¬˜¨ˆ ª“¦­–®¸’«¹‹£¶’ªÁ˜®Æœ®Êœ¯Æ¡±Ç›®ÃŸµÉ›±Ç™¯Ç¡¹ÐŸ¹Ò£¾Ô¤¿Õ¸Ìœ´É³ÉŸ¯Ç£¶Í¡·Ï¡·Ï«¾×¦¾Ñ¥ÁΫÇÒ¦¿Ë¥ÁЩÄبÃÙ­ÄÞ­ÅÜ¡·ÏµÌ ·Ñ¡¹Ð ¶Ì¬ÃÒÀØऽ˞¹Ï£¿ÕªÆÜ ¼Ò¤¿Õœ³Í¡¶Ó©¾Û™®Ë™¯Î”­Í”­Í™¯Ðœ³Ï–®Å©Â–¯Í‘«Æ† ¹Œ¦¿‰ ºŠ¥»¨¼ˆ£·‚³„œ±ˆ›²¢½†šº‡ž¸‚š±ƒ›²„›µƒš¶•·~—µx“®‰£¾•´w‹«rƒ¤sˆ¥qˆ¢n†›r‰ši“h{”_r‹q›at‰YmTk|RizL`pHYhCTe?Ob?PZ>QXCSbBNeFViHYjHYhM_kGXgK[lGYe>TZ;MT8EN8=GA?IMT]Ygrbt€hŽl…•m…šv’¡~š¥‚¯yª€˜¯}•ª†œ²¢¹™°Ê©Ç‹¦¿ˆ¤¸«½“©½œ¯Æ£³Í›®Å£¶Í¡´Ë™¬Å¯ËŸ°Ñ ±Ò ±Ò¤¹ÔŸµÍŸµÉ£·É¥½Ð£¾Ô¢½Ö£½ÛªÂÙ«¿Ñ®ÅÖ®ÅÖ¬Ä×­ÅÚ¦¾Ñ¥¾Î¥¾Î¡¹Ì¡¼Ò¡»Ö©ÄÝ¡¼Õ«ÆÚ«ÃÖ°Ëݤ¿Ó¤¿Ó ¸Ï¡¸Ò¦¼ÛŸ¶Ð™¯Ç ¶ÌŸ²Çž¶Ëœ·ÍµÌ›®Çš¬Ê›¬ÏŽ¥ÁŠ¥»ª¾—²Æ˜³Ç–®Ã“«À–®Ãƒ›°™°„œ³™°€—±˜´‚œµ… ¶y”ªx©v‘¥y”¦x“§z‘«zª}­yŒ¥wŠŸu‹¡x§h€—k™f|g~`t†jyds‰]l„Udz[k~P_uKZtN^vGWmJ`f;IT@Q]?P_EZeF[dF[dF[dH]hFZhEYiHYlCTcFWcG;@HXZ`hrzq‚Žn‚o†—w¡yŒ¥{“¨~™«„œ±ƒ™±ƒ›²‡Ÿ¶§¼Ž¦»•±¾Œª²­¸©¸ª¼•°Ä•­À›¯Á›²ÃŸ¶Ç™±Ä™±Æš²É›°Í«ÀÝ©¾Ûž¶Í£»Ðœ·Ë›¶Ê¦½× ±Ò¯Áߧ¹Õ¦¼Ô©¿×ªÂÙªÅÛ¥ÀÖ£ºÔ ·ÑŸ´Ï¡¸Ò¤»Õ¡·ÖŸµØž´Õ³Ò—±Ê£¾Ò¨¾Ô¥µÏ µÐ¶ÔŸ¶Ð¡´Ë ³È©¹Ï¤·ÌŸ²É”ªÂ›°Íœ³Í¡¼Òœ·Í’©Ã“ªÄœ³Í˜°Ç“«Â¨¿–«Æ‰Ÿ¾}“¶€—±‹¡µŠ¢·™°z¦}£—­{–¬w“§z–ª„œ±…•­wŒ§z¯ƒš´z’©sŽ¢qŒžjƒ“g{‹h|Žjz’hxŽixŽct…Zn|QhyYo…Ui{TevOcsCZiE^aK_?PcATiHYlHXkO_pYixXizObwZn€VgxUfyUe{QeuJ_j7ER59JQ]ibt{yŽ™p‡˜…ž®{“¦}“§}§ƒ™±…š·Š¢¹œ°Œ¢¸–¦ÀšªÄž®È”ªÀ•°Âš¶Å•®¾“¯¾”¯Áž¶Ë›®Ç˜­È´Ð˜³É–±Åž¶Ë¡´Í¤·Ì¤¸Ê›±Åž¶ËŸ·Ìž¶ËªÂÙ¥¼Ö ¸ÍžµÆ©¼Ñ­½Õª½Ôª½Ôž´È§¿Ò¤¿Ñ¢½Ï¨ÃÕ¥½Ò³Éß²Åܧ½Óš²Ç¨½˜°Çž¶Íž³Î£»Ð›¶È–±ÃšµÉ“®Âš²É–­Ç“©È›µÐš´Íž¹ÏŽ©¿Ž¦½–¬ÄµÌªÀ¡¹Ì›²Á‘©¼š°†¢¶‹§»†¢¶‡¢¸€›±‚™³™°}•¬‚š±yªwŒ©‰—¹‰½oˆ¦x’­{’®vŽ¥w¡rˆœm€—f|’g}“h{iyjz’ds\nŠYk‰Zj„Ye|Ue{Sf{F^fBRcBSdK_oJ^lM^mUgsbsXizRezZm‚Xk€Uh}\l„`t†PgtI[g>JVTbmrƒ|žwŽvy•¢—ª}“«…´ƒ›²ƒž²… ²‰¤¸–®Å—¯Ä–¬Â‘©¼Ÿ·Ê‘©¼¦¼•­Â˜³ÉžµÏ¯Í—®È›¶Ì—²Ä¬»™±Ä™¬ÅŸµË¢¸Ì¡ºÊš³Ã¡¹Ì£»Ò¸Î£¾Ô§¿Ô±ÄÙ°Ãت½Ô§ºÓ¦¸Ô¤ºÐ­ÄÕ«ÂÑ¥¼Ëš³ÃŽ©½“«À˜®Æ¡¹Î¬ÇÙ¯ËÝ¥ÁÓœ¸Ê¡¼Ð¡¼Î¹Èš¶È™µÉ›·Í©Äß›¶ÑªÈªÈ–°Î“®ÉªÃŒ¤»˜®Ä½Ó뗬Ǔ«À¨¸Ž¦¹Ž¦»ˆ£·©½ˆ£¹„›µ|”«z¨€˜­€›¯™²€–µvŒ«‚–¶s‰¨rˆ§sˆ¥r„¢u‹£y¥l„™e}”e}l…•ax‰at‰dw]l‹apbp’\j‡ZfUe}Sf}JbjAUgDZnJ`vJ]rN_rSj{Sl|Rk{Rh|Wn\p€Zn~Zn~Xl~QawQawVe}brŠo—xˆ¢„“°yŒ¥—¯…›³„™´Š¶ˆ—¯‹žµ‹¡¹§¼«¿’ª¿˜«Ä˜ªÆ›­Ë™«Ç•§Ã•¨ÁŸ²Ë¢¸Ð¢·Ò›±É˜®Æ™¯Ç¢µÎ ²Îœ­Î›°Ë¡·Ï¤ºÐ¨¾Ò¢¸ÌŸ²Ç¢µÌ°É™¬Ã¢µÊ¯ÂׯÂÙ©¼Ó¦¶Ð–©Àž´È©¿Ó®ÄØ­ÃפºÐ¤¼Ñ¦¾Õ¥ÀÔ¢¾Ò›¶Ê¯ÅÝ´Ì㚲ɕ°Ä¸Ì¤¿Õ¢¼Õ˜°Ç™¬Ã•­Ä–±Ì›¶Ï•°É‘«ÆŽ¤Ã“­È’­ÈŽ¨Á¨¿Œ¤»‹¢¼Œ§»Žª¼¨¼Š¢¹‰¡¸ˆ¸}•¬{“ªx“©x’«x“©y‘¦s‹ s‹¢x§r‰£o„Ÿm|›u‹£j…™j†šgƒ—d“bxZm†\kˆ^mŠft‘_r‹^tŠSk~Yq„Xn„SfL^jDXfFZhN_pL`rL_tSgyVgx\m~`pbs‚bv„[o}\p€RixRkyXqdzŽh{o—y‰£}Œ©r…ž|¨…›³‚™³†œ´µ‹žµ£¹¨»Ž¦¹’ª½“«À“«Â–«Æ˜®ÆŸ²Ë›®Ç¤´Î ²Îš¯ÌŸ¶Ð—®È¤¼Ñ§½Ñ¤ºÎ§½Ñ±ÊÚ¦ÂѯÈØ©½Ï¨»Ð¨¸Ð¯¿×±ÀÚ§¶ÐŸ®È¥µÍ«»Óª½Ô®ÄÜ«ÆÚ§ÃÕªÇÖ©ÅÒ¨Ãס·Ö¡¼Ò¢¾Ð¶Òä­ÈÚ¤ÁО»È›·ÉšµË•±Ç•±ÇšµË˜¯É–®Å£»‹£º‰¤º˜³ÅŒ¥µ—­Ã“¥Á”¦Ä˜©Ê‘¢ÃžÀŸ½‹¹ƒ›²‡¢¸ˆ ·ˆž¶„œ³‰¡¸†¡·ˆ¢»z”­~˜±{•®v§v‘§rŽ¤sŽ¤w¥vŽ¥d•kƒšsˆ£m…œl„›g~˜h}šax’_wŽbxat`sŠ[n…Zj‚VeWf€Ra{UgqAVa?WaLdnQhuJapUiyWh{]m€`man€an€[l}Vj|Sgy[oduˆiyŒm}y‰œyŒ¡x¥z¦}©~‘¨†™°†œ²‡Ÿ´‹£¸‘©¾™¯Å’¥¾œ¯È ³Ì›®Ç£²Ï¡´Ëœ¯Ä£¶Ë£¶ÍªºÔ°¾Ý¯½ß£±×§¸Ù©»Ù¤ºÒ©¿Õ°ÄÒ¸ËжÇÖ¬»Ó¤´Ì¤·Ð¥½Ò£¾Ò¯Êà«ÂÞ¥¼Ø¨¿ÛŸºÐ¢½ÏŸºÎ£¾Ô£»Ð§ºÑ¨¾Ö¤¹Ö¦ÀÙ¤¿Ø´Ïã­ÅØ¡¼Î¡¼ÎŸ·Ì›±Éž¶Í¢½Ó—²ÈšµË™¯Å¢²Ê¡´Í™«Ç™®É¦½ÙŽ¨Á‘¬Â«ÁªÀ©Â‰£¾‡žºŒ¾‹Ÿ¿‰Ÿ¾ˆŸ»¦ÀŒ£½„™´€–®‰Ÿ·‰ º—¶z”¯}˜±y•«sŽ¢p‹¡qˆ¤|”«y‘¦n†›s‹¢mˆžk…žb~”gƒ™[w‹Zu‰Zp„iy_o…_o…\l‚[j€Xh€Vi‚Ukq=Vd@]eMjpZrzSeqYnyXlz[o}[oVkv]oyZlxVfwVgx\p€[r`y‰cŒk‡”t~”¨}–¦šª„š®‡š³‚˜®ƒ›°„œ¯“«¾‘©¼›±Çž´Ê›®Å±ÃŸ³Ã£·Ç¨¹Ì ³È³É¦¹Ð¨¸Ò¦¹Î›²Ã¥½Ç·ÐÓ´ÉÒ±ÂÓ­ÁÓ¥»Ñ£»Ò›µÎ¤¿Õ¦¾Ó¤»Ì®ÂÒ«ÁÕ®ÅߪÅÛ¶Òè¥ÀÖ¤»Õ¥ºÕ©»×¨»Ô¨»Ô ¶Î¦½×¤¼Ó ¸Ï¥½Ô¥½Ô£»Òž³Î›°Ë–¨Æ–©Âª½Ò ¶Ì—¯Æ•±ÅŠ©º«¿›¶Ì•°Æ•°Æ–­Ç¤Á‘¨Â‰¡¸«Á‡¡º‡žº‹Ÿ¿‰ž»¥Â§Á…Ÿ¸‰¤½… ¹… »‚›¹† »…Ÿ¸œ²ƒ›°x“©tŽ©q‰ i•{“¦ƒœ¬rˆœr…žl‚šh~–awdy”]xŽ^zZu‰^tŠ`t†_p\l}an‚Zk~Uh}LejFYnL`rRfx]qƒYlVm~WnXo€Vi~VjzThvUiw[l}Ylaw]t…d|†kƒnƒŽvŠ˜“£…œ­†œ°ƒ™­’©‡š¯‘¥·Š ´‹£¸¦¾™«É¯Ëš¬È¡´Ë§»Í©ºÍ­ºÎ¨µÇ©¶È®½Ó©¸Õ ¯ÅŸ¬¼¶ÃÓ¯ºÍªºÍ¨»Ò¥¼Í©ÀÏ®ÅÖ·ÍᢽϠ¼Ð¡¼Î«ÂÓ¥½Ð§¿Ô«ÆÚ²Í㤿բ½Ó¡¼Ð¥ÀÔªÄݪÀß©¾Û¢´Ð¢µÎ¡´Í§¹Õ¦µÔ¦¸Öš®Î˜¯É˜°Ç™±Æ¥»Ï¥½Ð¸Ì›·Ë•±Ç¬Àš¶Ê•´ÉŒªÂ”®Ç˜ªÆ‘¨Â… »Œ¦¿‘©À’¨¾Žž¶ˆž¶‹¢¼¥À“¢¿‘¦ÃŒ¢Á‰¤ºƒž°~š®€œ²y•«w’¨qŒ¢qˆ¢vŒ¢n–uˆuˆn„šf|”f~“c~_{ŠcŽa|Ž]xŒYq†Ylƒcv‹\l‚\m€du†Tj~Og~KfjM]uVi~Qew[lVfyYiz\l{Zk~Xh‚Yh€]i‚^ncs„iz‹i}h|Œkd{ˆk‚u‰™£„•¦‰š«…™«†œ°Š¡°‘¦±‘¥µ ¸”ª¾–®Á´Å©½Í©ºÉ­½Ì´ÄÓ«»Ì«·Î´½Ü¤´Ì³ÇŸ¶Ç›¯¿¢¹È²ËÙ¦¾Ó¥¼Ø¬ÃݬÃÝ¥ÀÒ¨ÄѦÂϨÁÑ«Á×±Ã߯ÂÛ§ºÓ¨¾Ô¨¾Ò¢¸Î¦¼Ô¬ÂÚÀÓì­¿Û©¸×©¼Õ›®Å¢µÎ¤³Ð¢´Ò¡µÕ¤¸Øœ­Ð¬Ë¢±Ë°ÀÚ¤´Î˜ªÆ›­Ë¥¹Ù›¯Ñ’©Å–­ÇŠ¤½©Â‘¬ÂŽ©¿Š¥»‰¡¸Ÿ»Ÿ¬Î¨·ÖŸ½Ÿ»‘£¿‰ž¹€—³…›º‰ŸÀ†Ÿ¿ˆ¡Ã˜¶{•®€›±™®z’§tŒ¡{‘§€ªtŠ n†™r‹›n‡—l…•h€“f~•ez—dz’_r‰]p‡[kƒ]p…Yl_s…Zn~Vo}LhwHfgVcsWgvQbsXhyXey]j~`mcrˆ^nˆTj‚Rj[nƒp€‘kz’iw–k{‘m~i}‹m‘q…—~‘¦}“§…›±ƒ–«Š›®Š›®’¢µš«¾’¦¸“ª·˜°º™­»¡²Å°ÇŸ±Ïœ®Ê°É«ÁÙ§½Õ¢¸Ð©¾Ù¤»Ì£¸Ã»ÐÛ±ÅÓ¨ÁÏ£¿Î«ÆÚªÁݨ¿Ù­Âݨ¾Ö¥»Ñ¬ÂÖ°ÆÚ²Èà¯Áߪ¼Ø¯¾Û°ÂÞ«ÀÛ£ºÔ¯Æâ­ÂݲÁÞ°Á⧸ݤ¹Ö¤ºÒ§½Óž´Êž¶ËŸ·Î¥ºÕ¥³Õ˜¬Ì•®Î¥Ä”¨È”©Ä›®Çš©Æ–¤Ã“¢¿“¢¿“©Áª¾›¶Ê¨½ˆ¤¸‹ª¿“®Ä¡½‡Ÿ¶ˆ£¹‚³š°‰ º•µ—¶—¸‚˜·‚–¶ˆœ¼ƒ”µ~®}­y‹§t‡ qƒŸrƒ¤v‹¦w¥u‹£nšh}˜ax”^tŒiy‘at‰]p…Xn„]rZp†j~YoƒMcyLajRfvRgrNclYouUkqUju[l}dxˆ_s…\p‚[ofzŒk~“j~q…—o€“u…˜p€–m}•{‘¥€™©€™©€—¨†š¨†—¡‹™¦›¬”¡µ’¡»–¦À˜¨Â˜¨Àž®ÄŸ³Å¤¸Ê¡´É ³Ì©¹Ó§³Î¦µÏ°¾Û°ÀÚ«»Õ®ÀÞ®¿â¨½Ú±Èâ²Çâ³Â᫽ۨºØ­ÀÙ«»Ñ©¼Ó²Èà¶ÌâµËá²Êá±Èâ­ÃÛ±ÁÙ¢¸ÎŸ·Ì§¿Ô¦¾Ó¬ÁÜ°Áâ«ÀÛ§½ÕµÍà­ÆÖ£¿Î›·Æ¤½Í©½Ï›±Å˜®ÄŸ·Ê›¶È–®Ã’¤À’¤À˜§Æ˜ªÈš¬Ê’©ÅŒ¥Ã’®Ä‹§¹Œ§»Œ¡¼‹£º§¼ª¼‡¤³”±À‡¢´Œ§¹… ²~™«{“¨…°—ª~™­{–¬vŽ£w£x¥x¥s‹žp†šq‰žhƒ™g–j}–e}’a|_wŠ_r‡duˆ^nWhyar…g{‹[o}RfvQawJ\fQesOirOltSlx[o[oarƒ_pdu†ct…_pƒduˆjyk{Žy†šn~r‚“k{Œm}Žx‰œ{Ž¥„›¬|“¢ƒš©‚–¦“¤·–¢¹”¤·‘¢µ£´Å£´Å¡±Ç£²Ï¤´Î£³Ë¦¶Ð¬»Ú°ÀÚ¥µÍ­¾Ñ²ÃÔ­¾Ï¤µÈ¢²È«»Õ²ÂÚ·Ç߬¼Ô¥µÏ°ÃÜ®ÁÚ©¼Óª½Ô¯ÂÛ·Æã´Çà¶Ìâ³Éá¯Áݪ½Ô±Å×¼Ðà¹ÍÛ·Ê᪻ܫÀÛž¶Í§¿Ö¬ÁÜ©»×«¹Ö«»Ó§ºÏ«ÄÔ¨ÄÓ›·Ä–¯½š²ÅŸ¶Ð¦»Ö•§ÃŸ·Ì¨º“®ÂªÀªÀ“®Ä‘©À‰ž¹¤Á¡ÁˆŸ¹†¡µŒ¤·¥¹“«À‰£¼¨½¢·’¥¾‚‘°©~Ž¦w‰¥x‰ªz¬wŒ§vŒ¤w¥u lˆ—h€“g}•i|“sƒ™r…šm€•m}“bq‰eu]p‰Vl‚Vl‚dzŽZp„Tk|QewOeiPapTitYny^p|ct€_p|eu„du„bs‚fzˆ`t„g{jzq€–x‚šk{Žp’psƒ’x‰˜…–§…™§€• Œ ®ˆœ¬“¤·‘ ¶ ³‘¥·•©»‘¤¹œ¬Ä«ºÔ­¼Ô§¶Î°¿ÙºÅå©·Ô¦µÒºÊâ·Çݬ¼Ò°ÀÖ«¾Õ»Îç°Ãܯ¿Ù­ÀÙ¬ÁܱÄÛ´ÄÚ½Îá»Ìß»Îã³ÉßµË߶ÍÞ¸Ëà·Çß²ÅÚ±ÄÙ¯ÃÕ´ÈØ´Êà­Áá³È婾٨¾Ö«ÁÙ®Äܤ¶Ò«¾×°ÃÚ¨¿Ð ·Æ¤»Ê›¯¿ ·È¢¸Ì˜®Ä›®Ç™±È‘¬Â¥ÀÒ¹Õ䪼•°Ä§¾‹¹–¨Æ–§È‰¡¸¨º… ´‰¡¸“«ÂŽ¦½ˆž²‡›­„—®ˆ—´…—³ƒ•±ƒ˜³–²y¬yŽ«x©t‹¥sŽ¤p‹¡o‡œp†œh€“h€“l‚–m€—pƒœfx–k•f}ŠZsXqKdtOg|WmQdyG]cSalXixYm\p€au…\p~dx†fx„^o{bseu„hu…fq‚q|v€˜r“n~{‹œ†–©£Šš°†š¬‰ ¯ˆœ¬“¤µ ³“£¹‘¢µ–§º™­¿¡´É¡´É«»Ñ®½Ó°¼Õ¯»Ö®¹Ù¨´Ï«·Ð±ÀÖ«»Ñª½Ò²ÅÜ°ÃØ·Êß°Ãب¸Î¬½Ð§·Ê®ÂÒ½ÔáÍáñÏàóÀÓè¾ÔìµËá®ÄÚ­Ã׶ÍÞµÉÙ³ÄÕ±Å×±ÄÛ®ÆÝ¥¿Ú«Áà¬À⨽ڦ¸Ô©¼Õ¦¶Ð¥µÏ›©Æ¢²Ê¢³Æ¡·ÍžµÏžµÏ˜­Ê•­Äœ´É™±Ä”ª¾£¶Í•¤Á‘¦Á˜¯É˜³ÉŽ©¿¨½’¥¼”§¾–¦À‰Ÿµˆ µ‹£¸ˆž´ˆ µ…´ƒš´ˆž½ˆº‡–µ…šµ€—±s‹¢q‰žs‹¢z‘­y“¬y”ªq‰œp‡˜o…™j}”m€™m›hz–ix•brˆhyŠiy‘]kŠXfƒXcWe‚We‚O`o^k{Yixcs‚fx„ewƒ`q}[hx[lx_pzdv‚h|ŠfzŠhxŽx‰œw‡˜r‚•wƒš‚Ž¥{…Ž¢ˆ˜«Šš­‘ ¶°Žž¯Žž¯°‘¢µ•©»“§¹¤µÈ¬¼Í²¿Ïª»Ê§¾Í©ÀÑ­Ã׶Ìà½Óé°ÆÚ­ÄÕ­ÄÓ³Ê×­ÄÑ®ÅÒ°ÇدÂÛºÐæµÍàÇßéÌßâ¸ËÒ¹ÊÙ½Ñá¼Ïä¹ÍßÂÓæ¶ÊÚµÉÙ³ÊÛ°ÆÚ´Êà°ÆÞ¸Ëä«»Õ³ÃÝ°¾Û´Ã௾ۧ¹×¥¹Ù¡¸Ò¦¾Óž¶Ë¢¸Î ¸Í—¯Æœ´Ë™¯Ç˜®Ä¡´Ë ¶Ì˜®Æ¦¾¥À’ªÁ«¿“®ÂŽ¦½Œ£¿¥Æ¦Â¥À‹ »Ÿ»Ž¡¸Šž°ˆž´ˆŸ»‚™µ„š¹‚œ·~˜³„Ÿ¸~™²sŽ¤u¤vŽ¥s‰¡y¥|’¨rˆœq…—n†™c~”f“i…”i€s„“rƒ–jz”dtŠbs†^o€\m~Xi|brˆRhnZgyVfu_pbs‚arƒZkzbt€dy‚dz€nƒŽq…—o€q‚Žs„w‡–t„“zŠ›ž}Šš‚“¤€“¨…˜¯Š¶Š²‘¢³¡°Žž­œ­¼™­»Ÿ³Ã¨¼Î¨¼Î©¹Ï¤·Ì§½Ó°ÇرÅÕ°ÁÒªºÍ²ÃÒºÌظÈÙ´À׬¼Ï¥¶Éª¾Ð®ÂÔ¹Íß·ËÝ¿ÐãÀÏåÁÑäÃÓæ»ËÜÈØé¿ÐßÁÓßÃÓäÄÐçÂÒê¶Éâ¹Ìå´Çà·Çß±ÀسÃÛ¶Éà©ÀѬÅÓ§¾Í©½Ï¦ºÌ£¶Ë ³È¨»Ð®ÁØ ³Ì ³Ìš­Æ“¦½•¨½°Åœ¬Ä–©À”ªÂ§¼™±Æ–¬Â‘¤»¨¿Œ¦¿¨¾Ž¦»•­Â¡¹Ð–®ÅŠŸºŠ¡»§ÁŠ¡»„™¶€•²}’¯}”®€—±{’¬~“°z‘­xŽ­yŽ«w‰§r„ o‚›n„šf|g’h€•g}“k{•fygzbv†k|‹\p~_sƒev‡`pTgnZhu^o{hz†dtƒo|ŽmzŠnyŠk|ˆewƒkj~Žq‚Žv‚Žv„{Œ˜€‘›€‘›‰š¦‡”¤‡—¦‡˜©ŽŸ² ¶¡±Œ ®¡«˜§­­¾È¤µÄ¦·Æ­¾Í«ÂϦ¿Í«ÄÔ¬ÂÖ°ÇزÆت¾Ì®ÃβÆÔºËÜ·Îß³Îà¶ÍÚ´ÆзÌײÉؽÒÝ¿ÐÚÇÙàÇÙà»ÍÙÀÑä·ËÛ»Ïß¹ÍݽÎá¿ÏåÅÕïÁÑéÆÕí¼Ïæ´Êâ²ÊÝ«ÄÒ¯Æ×°ÃØ°ÃÚ³Âß±ÄÛ¡µÇ¡¸Ç§¾Í ·Æ«¿Ñ¤·ÌŸ²Ë¡´Ë›®Å™¬Á˜¨¾™¬Ã—¬Ç“©¿–¬À•¨½˜¨À™¬Ãš­Ä£¹¦¼¤¿‘¥Å”ªÂ¦º—¯ÄŒ§½‡¢¶”¯Á“°¿ˆ¥´… ²™°~”¬}«{‘°w²v¯z¯sŠ¤u‹¡u¢n†kƒ˜h~”i—k}›dv’gz“n˜fyŽ]p…aq‡aq‡Yh€\k…`k‰Ufr_o€eu†jzgw†t‚w„”kxŠm~Ši{…k}„o~†v„w…’qxˆ›yŠzŠ ƒ“¦‡”¨‰•¬Š–±“ ´›¨¸•¥´•¥´•¦°¢´»´ÆÐ¥·Ã¦¶Å­¸Ë²¿Ñ·ÄعÅÜ´¾Ú´ÁÕ°¾Ë¶ÃÓ·ÄÖ¹ÆÚ¾ÊãÁÐèÂÑëÃÒê»ÊâÆÚè½ÖÛÂÚâ½ÔáÀÔâÈÙêÃØãÏäíÉÞéÀÔäÉÝëÑæñÉàíÁØçÀ×èÅØïºÐä¶Ìà¶Ïß¹Òâ´ËÚºËÜ´ÅسÃÛ«»ÓªºÔ ³Ì§ºÓ¥»Ñ ¸Í™²Â¶Ä—­Á™¬Åœ¯È¡³Ï’ª¿•°Âž¹ËŸ·Êš²Çœ´Ë•­Ä–®Åœ´Ë“ªÄŽ©¿¬Â“­ÆŒ¡¾„˜¸‰Á£ÅŽŸÂŒ¡¼‰¡¶†¡µ‚ž´‚³zªz‘«x«tŒ£x¥sŽ sŽ o‹Ÿlˆžmˆœn†›kƒšg|—bw’f{–dzŽj~Ž_v…]t…Zq‚YlTj~Vl€SlqeuˆjzgwŠivŠu}“p{Žkxˆo}Šr€‹m~ˆqƒy‹—|Œ›zŠ™{ˆšy‰˜yŠ™‘€’ž‡—¦‰”§‹˜ª—§º•¥¸™¥¼ž«¿£®Á°»Ì©µÃ¬ºÇ­ºÊ±ÂÎÀÑÛ²ÃͲÀÍ·ÄÔ¿Êß¾ËÛÂÐݽÊÚºÇÙÁÏÜÉÖßÉÕáÁÌÝÌÙéÌÜëÍÝìÌÙéÑÜíÖÞòÒÚîÕÚïØãøÏÛôÑÞòÇÔæÑÞðÑÜñÐÜóÇÓìÀÏå¾Îä¹ÊÛ¿Ðß¿Óá·ÎÛ°ÇÖ¶Ìà­ÁÓ«»Î¬¼ÒªºÒ§ºÑ§½Ó™±È¡¸Ô¥»Ó ³Ê›®Ç”¦Â¨¿•°Æ—²Æ“®À“«¾”ªÀ˜®Æ—¬É—¯Æ•­Â–®Ã•­Â“®ÄŽ¨Á‰¥»’®Ä… ¶Š¢¹ˆ ·‚—²„œ³€›¯™¬‚•ª—«|”©vŽ¥z¬r‰£sŠ¤m‡ o‰¢s‹ n…–l‚–mƒ›i~™fw˜]s‹e{`vŠ_u‰YoƒYo…^v‹Sk€Qjog|…hz„gx„n‹k|ˆl}‰n{‹sƒ’r‚‘t…‘x‰“t…{‰–}ˆ™„Œ ƒ¤{Š¢€¦~’¤†šª„˜¦¬“ž±™¦¶›«º¤²¿¨±¾ª¶Ä©´Ç­¸Ë¯ºÍ±¼Í½Å×¼ÇؼÉÛ¹ÆØÀÍáÀÍá¼ÉݾËßÉÖêÈÕçÌÙëÐàóÁÐæÇØëÌÝîÐáíÕáíÜêìæõðÚåæÜãìÔÞæÛåï×ãïßíúÙçòÑßêËÙæÎÛëËØêÀÍáÀÍáÅÑèÄÕæÊÞì½Îß»ËÞÄÕè¸ÉÜ®ÂÔ²ÅÚ¬ÂÚ¡¶Ó›°Íž²Ò¡µÕ®Ï¯Ë—§Á—§Á˜§Ä›ªÂ›§¾ž­Å–¥Â™«Ç•§Å¡¿‘£Á‘¦Ã’©Å’§Â”¤¾’§Âš±Í¤ÁŒ›º‡™·ŠœºŒŸ¶…™«ˆœ®‰š­‡š¯}§{‘§y§tŠ¢v‰¢o‚›o‚›pƒ˜vŠœv†žs~œoz˜lw—cqao‘es•hv˜^l‹bm‹dr_mŠWgxh|Šk|‹r‘o|Žn{n‹m‰u…”vƒ—{ˆš}ˆ™t‚|Š•w…’„ }Šš{ˆ˜ž€‘ ‰š¦“Ÿ­—£¯’žªŸ­¸ž¯¹Ÿ°º¢°»©·Â¦²À«¹Ä²À˲ÀË·ÅлÉÖ¾ËݹÉØÃÔàÀÐß¾ÎßÅÖàÉØÞÄÑØÇÑÙÓÝåËÕÝÑÚçÖÛîÒÛèÚäîàçîåëîåëðëðøëñöãéîæîðàìêÒààÒáåÑàæÊØãÂÓß½ÎߺËÚÁÑàÅÕëÊÜø»Îå»ËáºÊà·ÇݳÊÛ¯ÈÖ¨¾Ò£¶Ï¡´ËŸ¯Åœ¯Æ›°Ë³Éš°Ä—¯ÄŒ¤»¦¼œ¯Æ¬¼Ô—¦À”¤¾•¥¿¢»•§ÃŒ¡¼‘¨Â’¨À’¥¾ ¹Œ›¸Œž¼€‘´…š·…šµ£»Š´Š ¶ˆž¶„œ±}˜ª™®†œ´zªy­nƒžv‰ }£z‰Ÿp€škz™buŽ`vŒe{“gy—dz’g}“cvdr‘`n‹Yh‚Vhtn~‘m}Œn‹n‹q‚Žs„p€sƒ”t„—p}z†”w…’|™~Ž€¡wˆ”|Š•€Ž™Œš¥‘Ÿ¬—¤´’Ÿ¯–£³›¨¸œ§¸˜¨·ž¯À±ÃÏ©ºÄ°¾É·ÀͶÃ̼ÉÒ½ÊÓÁÍÙ½É×ÇÏã¾ÉÚÈÔâÌØäÕßéØßèÚßçäéñáäìâæéæéèæêäæçàïðëñîíððòèêðïõúßçëãêñàçðÓÝåÙæïÑßêÎÜéÂÓâ»ÏáÉÝíÇÛëµÉ׺ÌعÊÙ³Ä׳ÌÚ£ÀÍ­ÆÖ¿Òé²ÅÞ¬»Ø¤¶Ò£µÑ¦¾Õœ·Í¸Ê¶Æ¨¾Òž®Æ’¥¼“©Áœ´Ë§ÁŽ ¼–¤Ã•¤Ã”¢ÄŸ¾˜§Æ“¨Å“­È§Á¦¾‹£¸•°ÄŠ¢·‰Ÿµ›±É…š·–±‹ž·‚•®‚‘®}’­z”­z‘«v‹¦f•i…—rŸh€“h€—jf|’q…—q„›_qdz’e{“at_o‰_o‡Wg}`v|r€‹o}Šn{‹qu…”s„“o€t…”v‡˜q{‡•|Š—~Ž}Ž~žœƒ‘œ‡•¢Ž™ªŒ˜¦“Ÿ­‘ŸªŒ›£•¢«›¤±«¶£´À¤µ¿¬ºÅ³ÁÌ·ÅÒ¹ÇÒºÇпÌÓÅÏ×¾ÇÖÌÔêÍÕéÔÙîàéøÞèòàçîäêïåëîíñôîòõôöúïôçÿÿïþÿêïïßåæßêìðêîñíóöëóõãëíÜçêÞèîàêòÑÚçËÙæËÜíËßíÅÙç¿Ðß¿ÏÞ¾Ïà¹Íß®ÅÔ³ÌرÊÖ°ÇÖ®ÅÔ¯ÃÕ§»Í§ºÏ¦¼ÐŸ·Ì¸Ê–²Á—®¿¬Â›«Á™¬Á“©½—­Ã”§À–¤Ã”£Â•£Å¡¿’¤À¥½“©Á¡½•¤Ãˆž¶Œ§»ˆ£µˆ£µŠ¥·†¡³—ª€“ª‘£¿›¿{’®z–¬ƒž²x¥v‘§™´pŠ¥k… iƒžiƒžf~“lƒ”s‰Ÿcu“btgz“eu\kƒ]mƒ[k]sym{ˆo}Šhu…m}Œt…–vˆ”s…rƒ’w‡š{‹žŽ¢u…–q’{ˆ˜Œ…“ „’…“ Š—©‹˜¨‘Ÿ¬‘Ÿª–¤¯”¢­—£±£¯»¦²¾¦´Á­ºÊ²À˶Ã̾ÍÕÁÐØÈÕÜÎØÞÔÞæÛäñÞèðÝèëåíïèìïôùùíðñòñöû÷ÿòïðù÷ñÿÿæÿÿìÿÿçÿÿóÿÿúÿÿóôòáõôëïòñðóûêòöâíðÚçîØæñÐÞéÓáîÌÜëÁÒãÅÖåÇ×æ¿ÏÞÇ×è¸ÈÙ²ÂÕ°ÁÔ­½Óª¾Ð©½Ï²ÆÔª¼Æ¨¹Ê¦¶Îœ¯ÆŸ²Ë°ÉŸ¯É­Å­Ã«¾Ó¦¼Ò‘§»›®Ã£µ‘¥·¨¹Ì©¸Î“£½œ®Ì–¥Ä•¢Ä”£À™¬Å¥½„™´ƒ™±†œ´ƒ›°€˜­™®„š°|”©€˜­¨¾qŒ¥rŽ¤qŒ rˆœwˆ›n„šk‚œi~™m|›m|™ix’aq‹et‘av‘]tŽZp†Vi~Rgpj{Šl}Œiz‰t„“vƒ“rƒr…Œqƒrƒ’t…”x‰štˆ–r†”uŠ•}™š…“ž‡• ªž©ž©’ ­”¡±’ ­Ÿ­º¦µ½©¶»©¸¾¶Å͵ÂɼÆÌ¿ÌÑÃÐÕÎÚØ×ÞÚÞååÞäéáçêèìïíðñööøðóôõ÷ûöøüÿÿÿïòñúÿùÿÿøÿÿîÿÿáÿÿÑÿÿâÿÿãÿÿàÿÿÙÿÿÚÿÿØòöÞêíêêñïâîìÙçéÓâêÊÜãÈÙãÆ×áÈÖá¿ÏÞÀÑä¹Íß´ÇÜÂÖè¶ÇØ«¿Ï©½Ï§»Ë ´Ä±ÁŸ³Ã“¦»˜¨Âš­Ä˜«À˜¯À’«»©¹’ª½¨½”©Ä‘§¿Ž¡º£¹’ª¿–®Ã£»Œ£½Ž¥Á‰¤ºƒž°‰¡´¥¹‹¡µˆž´ˆž´‡š±„š°‚š¯™®…›³ƒ™±x‹¤vŽ¥w’¨x§p†žvˆ¤t£o~qƒŸnšiy‘aw`w‘b}h„‘Vo}Ui{Ukomx‰p}qn~p}s„Žs…Œu†’u‚”vƒ“{ˆ˜v‡–r‰˜vŠ˜{‹š~™†˜ˆš¡Œš¥…”œ’¡§“ ©¢¨¸¡©»ž©¼¨³Ä¬¸Æ´À̺ÄιÃÍ¿ÉÓÆÐÖËÖ×ÔàÞãìëåììåéìêìðòîôöõúöõü÷ûÿúÿÿýÿÿÿÿÿøüÿºÂƬµÿÿäÿÿßÿÿÜÿÿîÿÿúÿÿéÿÿåÿÿÙÿÿÌÿÿÊýÿÊÿÿÞÿÿæêëä×ÛêÒÞêÉÚæÌÝçËÙäºÌÖ¶ËÖ·ÈÙ³ÂزÃÖ¯ÃÕ¦¼Ð¢¸Î¦¹Î©¹Ï©¹Ï¥µË¥µÏ—¦Åš­Æ ³Êš°Ä‘©¼”ª¾›®Å ³Ì‘£Á•¬ÆŽ©¿¨¼•­À’¨¼ ¶”¨º“ª¹£·Ž ¼Œ¢º†œ²ƒ™¯‚˜®ŒŸ´Šš°„š®{–ª{“¨|’ª}“«y§u¤s‹¢q‰ t‰¤r‡¢i~›k™o‚™k—h~”d{Œbv„dwŒfu’ZlˆVh„[o}o{‡us~n{‹l|‹xˆ—u…”u…”w‡˜y‰š}Šž~‹|‰›€~‹›…”œ†“˜Š— ‰•£‚ˆ–£‘Ÿ¬”¢¯š¨µ¢®¼«ºÂ°¿Å¼Ì˺ÉÄÍÙÕÃÌÉËÒÒÙÝâêìðóò÷òôøðòöõúúúÿÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷„e–˜qÿÿíÿÿïÿÿõÿÿöÿÿòÿÿæÿÿêÿÿçÿÿâÿÿÖÿÿËÿÿÉÿÿ¿ÿÿÆÿÿÍïñÊÝÜÈÍÐÍÑÕäÆÏܾÊÖ½ËظÈ×·ËÙµÎÚ©ÀϧºÏ¨¾Ò¨ÀÕ¶Î᧾Ϧ¾Ó’©Å´Î ·Ñ˜°Ç’¨¾£»¢´ÒŽ¡º’¥º”§¾“¦¿”ªÂ§¾Ž¦½‰¡¸Š¢¹…´¦À±Ñ‰½‚–¶ˆº„™´€˜¯}˜®z•©—¬€˜¯–±‚•®}¥uˆ¡r‡¤r‡¤p„¤lƒŸlƒŸo…q„™g€k‡–e^v‰_wŒ\sYo‡Yl…bt€m|‚p‹t„“t†’p‚Œx‰“v„p‹w‰•|Š—€‰˜›Žž‚Ÿ€‡•¢…“ž‡•¢ˆ•¥ª“¡®’ «™¨°š©¯¡®³§´¹­ºÁµÂǾÈÎÍÚßÉÖÝÍÖÕèîåô÷ôûøûýúûÿÿÿþþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïíûie}ÏÌÍÿÿÿÿÿÿÿÿÿÿÿøÿÿéÿÿöÿÿùÿÿøÿÿðÿÿòÿÿåÿÿæÿÿÞÿÿØÿÿÌÿÿÃÿÿÃýÿ·íõ©Ýâ±Ê˶½ÄÀ½É×¼ÉÙÁÑ⬽ΡµÅ§»Íª½Ò°Åª½Ô³É™¯Åš°Æ–¬Ä“«À“«À£·¥¶É”¤¼œ¹Ž ¼“¥Ã‘¦Ã‹ ½ˆœ¼¡Å…›º€—³¢½”§À‚—²ƒ—·…œ¸‚™µ‚™³‚™³}”°•¶|°‚³†•´~¬u‹£vŒ¤vŒ¤t‰¤q‰ o‡œn„˜wŠŸo‚™hw”cv`vŽaw]p‡`sˆaq‡]pwmy…s~xƒ˜s~uy‡”v„‘l}‰z‹—‘˜€•{Š’}‹˜ž{Œ†—¨‚“¤‘ˆ™£Ÿ§™£«’¡© ª—©® ³³¤´µª´º¿ÆÍÑÖàÏÕÚÔØÛâåæïïñúùþÿþÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÖ˶?) -XQ$ïö»ÿÿòÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÿÿôÿÿãÿÿÜÿÿÛÿÿÐÿÿ¼ÿÿÇÿÿ¾ÿÿÁÿÿ¹ÿÿÀÿÿ¾õú³ÙßÀà··µ¬¶¼«¼Í¨¼Î¢µÌ¢µÌ­½Õ¡´Ë™¯Å™¬Ã—§¿—§½–¥» ¶£³Ëœ¬Æ–¤Ã¡½–¬Ä¨½Š¢·‹¡·ŒŸ¶–±•µ‹ ½Ž ¾–¨Äˆš¶ƒ˜³~“®€˜¯™°~™­œ®~™«|”©}•ªvŽ¥|’¨~‘¨w¡rˆœo…™l‚˜pƒœm|™mct•`udzeubn‡\k…bqŽ]r}gwˆm}Žw„–k|ˆl~ˆrƒw…’u†’€Ÿš~•yŠ”zŠ™}Šš„Œžˆ”¢ˆ”¢‚ŽšŽ—¤’›¨”š¨“Ÿ«”¥¯›©´ ¬¸©¶¿®¸À»ÂÉÇÍÒ×ÜÚàäÞäçäññóúúúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïÿÿÙ—™fÔË¡ÿÿöÿÿÿÿÿðÿÿîÿÿêÿÿâýÿßÿÿøÿÿôÿÿéÿÿèÿÿØÿÿ×ÿÿÕÿÿÇÿÿÀÿÿ»ÿÿ¶ÿÿ¿ÿÿ·ÿÿ¿ÿÿÅÿÿÌÿÿÁ×ÝžÁȹÀ©®°Á§®Ç®¸Û£¶Ï ¹É›²ÃšªÀ–¦¾”£À—§Á¦µÍ£³Í’¤ÀŸ»¡½™¬Å”§ÀŠ´¢·‡Ÿ´}˜®‰¡¸„š²—­‚•¬‚˜®~”ª{–¨y•§y–£›¦Š£³‚•¬~”¨}–¦y’¢—ªqŒžoŠžk†šg”n˜m|–jy“lz—i{—ez—^sŽat[q‰[q‰_x}s~“p}‘u„šl|n{p€wˆ”t†‚”žš~Œ—y‡’{‡“{ˆ‘{ˆ™ƒŽ¡ƒ„š‹—£‰•¡˜¥¬ «®¢¬² §²°ºÂ°ºÀµ½¿ÆÍÍÞãßîòêîñîýýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿÿôÿÿðÿÿäýþÎÿÿÙÿÿáÿÿÖÿÿ×ÿÿÖÿÿÕÿÿÙÿÿÓÿÿ×ÿÿÍÿÿÐÿÿÉÿÿÃÿÿÁÿÿºÿÿ»ÿÿ¯ÿÿµÿÿ½ÿÿÀñò¦ÀÄ…®±ž¥•¦±Â¥µÆ™­¿“§¹”¨º”§¾¢´Ð¡³Ï’¤ÀŽ¥¿ˆ¢½‰ º¦¾‰Ÿ·Ÿ»†œ´ƒ›²‰ŸµŽ¡¶—­†œ´„š°‚˜®„œ¯˜¨|”©|‘¬|’¨yŒ¡}¥}¥v‡šx‰˜m„“qŠšo‡škƒ˜e€–d~—j‚™pƒšh~”f~“h~–cu‘cv_s…aw{p€‘jz‰s€o}Šn|‰sŒ}‹–v„‘ƒ ‚Ÿ€Ÿu‚’uƒ}Œ”}Š‘€—‚ƒ™‹•‘ž§™§™¥š¤®¥¬³¦¬¯­µ·°»¼¿ÈÅÒØÑéïèÿÿÿùüùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïÿÿñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿîÿÿÞÝàš¤«VÿÿÈÿÿèÿÿÚÿÿÞÿÿßÿÿåÿÿ×ÿÿÝÿÿÉÿÿÃÿÿÆÿÿ¿ÿÿÇÿÿÒÿÿËÿÿÈÿÿÈÿÿ¿ÿÿ»ýÿ°þÿªÿÿ¦ÿÿ²ÐΡ¡m¤¤‰ž£Ÿ“ž±•¥¶”¥¸±Ã“§¹“«¾‰¤¸Š ¶Œœ´Šš´œ»Œ›¸œ¹‡š±ˆœ®Šž°‡˜«†™°†˜´€–¬˜©~’¤‘¤|‹¡~§y‡¤y‡¦‘©yŸo†•t›s‹žm…œj‚™l„›e€–e—l‡›kƒ˜d|‘]s‰[q…`vŠbw€s‚˜m}n{l|‹n~s…‘xŠ”z‹•‚…“ ƒ‘žy‡’w…{Š’~‹’~“~•‡–žŒ™¢’Ÿ¨•¢«œ¨´’ž¬š¤®©°·¥°³²½¾ÄÐÌÖßÚéîêÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿõÿÿòÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷ÿÿïÿúâÿÿúÿÿõÿÿêÿÿÚÿÿÑÿÿØÿÿÖÿÿÍÿÿÇÿÿÊÿÿÊÿÿ¾ÿÿÉÿÿÏÿÿÀÿÿ½ýÿµÿÿºÿÿ·ÿÿ´ÿÿ³ÿÿ®ÿÿ¦ÿÿ¬ÿÿ¤ÿÿ¹ÿÿÍåß¿–—’€Š¡´”«º©·ˆ£µ… ¶‘©¾ ·‹žµ‹ž·‡š±•¥½†™®‚•ª‡›­Šž°Œ ²€“¨€¦‡–¬„•¨}ŽŸwˆ›{Š¢zŠ¤}Œ«~‘ªu‹¡o†—vœuŽžk†˜m‰˜t›g€i“h€“t¡j‚•h{e{bxŒXntn~qn{k{Šm‹t„“Šy†˜{‹œzŒ˜yŒ“}‹–ˆ—{‡“}‹–“š}—Œ›£š¤ §°§¬´¤«´ §²£¨²°³½²¹Â±¾Ç·ÁÉÍÔÝðôùÿüÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿêÿÿÿÿÿÿÿÿÿÿÿôÿÿðÿÿèÿÿåÿÿÚÿÿÜÿÿÜÿÿÇÿÿÐÿÿÔÿÿÈÿÿÇÿÿÄþÿ´ÿÿÀÿÿ¸üÿ«ÿÿ°ÿÿ´ÿÿµÿÿ³ÿÿ³ÿÿ­ÿÿªÿÿªÿÿ©ÿÿ­ÿÿ­üþ©ÿÿ¤ÿÿÿý²÷éÃÈdz„‡™ž‰¡«’¤§’žšŸ”‘»–•Á£¤¬’–vpmjvpu…†{™yŽ™ˆŸ¬…™©¥}¥„—®‚•ªv‰žu‹ŸvŒ |’¦s‰n„šuŠ¥v§rŒ¥k†šg€n…–k{‘iy‘q€i|“d{Œg{dtŠ\nxo|cs„k|‹m~m~vˆ”{Œ˜|Ž•|Ž“y‹’w…yˆtŠtˆvƒŠ…Œ•“Ÿ™ž¨œ£¬š¤¬œ¦®œ£ª¦«³±·¼¸¼Á¹¿ÂºÃÂÂÊÁçìÝñöëûûùÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÿÿïÿÿåÿÿáÿÿÕÿÿÔÿÿÚÿÿÕÿÿÙÿÿÓÿÿÃÿÿÁÿÿÃÿÿÀÿÿ±üÿ­ÿÿÀÿÿ²ùÿ¥ÿÿ¬ÿÿ³ÿÿ´ÿÿ´ÿÿ¬ÿÿ¤ÿÿ¨ÿÿ©ÿÿ¡ÿÿªÿÿ¨ÿÿ¦ÿÿ¢ÿÿ›ÿÿžÿüÿë©ñÌ©Ü¥lì¥Vÿ½hÿÊpÿçsÿìaÿéXÿô[ýÙÇ«•­©šƒ—‡š¡~Ž¤‚•ªy£—ªr¡t£qŒ t£oŠ n†{Ž§vŒ¢s‰Ÿv‰¢o~n gx›k€›f~‘`x‹_wŠ`vŠ`sˆ_x}ozgr…p{q|u€“zˆ•y‡’z‰‘{ŠŒ“|†wƒmy‡oyƒy€‡Œ”˜Ÿ¥ª—ž§Œ’ Ž˜ “¡£˜¦¨š¨ªš¨ª©¶»ºÃÂÉÏÈËÎÍêæìêêê÷ûõÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùÿÿüÿÿþÿÿúÿÿÿÿÿëÿÿøÿÿüÿÿøÿÿêÿÿäÿÿãÿÿðÿÿîÿÿèÿÿãÿÿÓÿÿÌÿÿÉÿÿ¸ÿÿ¾ÿÿÃÿÿ¹ÿÿ¶ÿÿ°ÿÿÀÿÿ±ÿÿ²ÿÿ±ÿÿ³ÿÿ¬ÿÿªþÿ§ÿÿ¦ÿÿ°ÿÿ±ÿÿªÿÿ¨ÿÿ©ÿÿ®ÿÿªúÿ™ÿÿ¡ÿÿžç¥gË[FÖVOð_iÄfMÿߢÿÿÏÿÿËÿÿ½ÿÿ“ÿéoÿñkÿú{ÿêtÏ·x‰ƒ~{† €”¤x‘¡x‘¡s‰q‰ s¨sŽ¤sŽ¢t£vŽ£z’¥n‡—l…•d|kƒ–g”d|“[p‹_u_r‹]u}l|hvƒw„‹x…Šs~u„Š|—€Ž™ˆ•x„’vƒ“s„s…zˆ“ƒŒ™—¡§—£¡Ž™š—ž–¤¢©²£«¯£¦ ¦©¦ª­®´·½ÃÆÐ×ÓåëâîôíÓØÔýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿôÿÿúÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿóÿÿêÿÿåÿÿæÿÿäÿÿàÿÿåÿÿæÿÿ×ÿÿÃÿÿÈÿÿÆÿÿ¸ÿÿ½ÿÿÁÿÿ¼ÿÿ¸ÿÿ·ÿÿ®ÿÿ±ÿÿ¹ÿÿ¾ÿÿ²ÿÿ«ÿÿ¯ÿÿ®ÿÿªÿÿ©ûÿšÿÿ—ÿÿŸÿÿ¨ÿþÿÿ¥ÿÉÎbLÑICëGTáSXÔ[YÿÇ›ÿÿËÿÿÍÿÿËÿÿÍÿÿÍÿÿÃÿÿžÿç}ÿî€ÿÿˆÿû|ðч¨Œx‚}}z‹žz‘¢x£kƒ˜q‰ tŒ£yŽ©wŒ§w‰§y¥vŸj…—b~”j…™j‚—g”ay]s‹cvYm{s€’mzŠrt‚s‹v„€Ž›šv…tƒ‹{‡“v„{‰–~‹’Œ”–­±¶œš¤ ¥­“ §ˆ•œˆ’œ‹šž§³°±¼¶±¼»²¾À´ÇÉ¿×ØÓöóöùòþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿíÿÿóÿÿÿÿÿÿÿÿÿÿÿÿÿÿíÿÿçÿÿïÿÿëÿÿÞÿÿÝÿÿáÿÿßÿÿâÿÿÞÿÿÙÿÿÌÿÿÌÿÿÈÿÿÊÿÿÅÿÿÇþÿµÿÿ´þÿ±ÿÿ²ÿÿ¯ÿÿ´þÿ®þÿ°ÿÿ³þÿ­þÿ©ýÿ¦þÿ£ÿÿ£úþŸüÿ£ÿú¡ÿù¨ÿÑßtbÌMKßK[âIYäETÌ]EÞš_ÿÿÍÿÿÑÿÿÓÿÿÕÿÿÕÿÿÕÿÿÓÿÿÑÿÿÅÿú›ÿå€ÿïˆÿý|ÿÿmóÙt¨b„mxŠ‘}Žt„špƒšt‰¤s‰ŸsŠ›vŒ uˆ¡pƒšj}’i|“i|•g|—_v’^vbxŽ[pyo€plz‡n|‡{ˆ‘|…’‡—‡—w}xz†”wƒ‘w‚“‰“˜ ¤¤°®£¯«˜§¢‰˜•{‹Œo~„y|}±¦¥¸­¬·¬«¹²©ÏÉ»ØÔÅãßÐõòèýûõÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿýÿæÿÿíÿÿßÿÿîÿÿùÿÿþÿÿÿÿÿòÿÿæÿÿãÿÿÜÿÿÒÿÿÒÿÿÈÿÿÕÿÿÇÿÿÊÿÿÅÿÿÅÿÿÃÿÿ¶ÿÿ¹ÿÿÅÿÿÉÿÿÆÿÿ¼ÿÿ³ÿÿ¹ÿÿ´ÿÿ®ÿÿ¬ÿÿ­üÿ¡ÿÿ¬ÿÿªÿÿ¦ÿÿ¯ÿÿªÿÿ¥üýÿÿ£ÿõ§ÿ¯vÇU9æOSãLPáHNàJTÚFTÅiRÿê¬ÿÿÓÿÿÓÿÿÑÿÿÑÿÿËÿÿÇÿÿËÿÿÏÿÿÏÿÿÏÿÿÅÿÿÿíÿærÿórÿÿrÿÚz°ˆX‹~ju‚‹x‰•z‹žw‹v‰žr†˜tˆšt‡œsƒk—kƒ–k•dwŽawez•_tk|‹k{Šgt„o|Œu€“xƒ”wƒ‘t‚n|‡z‰‘vƒŒu„Šo~„ˆª©°£¦®¬±»™Ÿ}Ž‹…‡„Œ®¥–²©š¥œ­£™µª§¼³¦ÞÖÂöñÞðêÚíêÞù÷ñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿöÿÿäÿÿèÿÿêÿÿèÿÿöÿÿôÿÿòÿÿîÿÿæÿÿçÿÿâÿÿÕÿÿËÿÿÏÿÿÒÿÿÏÿÿÚÿÿÒÿÿÇÿÿÁÿÿÀÿÿ¼ÿÿÁÿÿÅÿÿÂõú¨÷üªþÿ«ÿÿ¨üÿŸÿÿ¦ýþžÿÿ¥ÿÿ¦ÿÿ¯ÿÿ©üþ™ÿÿ¢ÿø›û«rÓWDÞUKáKLÜCGèKUÛNNÑSLЊ[ÿÿÅÿÿÉÿÿÏÿÿÏÿÿÏÿÿÇÿÿÁÿÿ½ÿÿ·ÿÿÁÿÿÇÿÿÉÿÿÍÿÿÉÿÿÅÿ÷Žÿèpÿïrÿösÿä{¶•G”‡aƒ‰Œzˆ“rˆœo…™tŠžj‚—l„›j‚™h€—h~”uˆŸm€—buŒas}gr…oz‹lx†m{ˆr€uƒŽ{ˆ‘p}†lx„zˆ“w…v„r€‹¢£¬«¦¥§­°™˜~‡„¡¦¢¦§¢™•¬¡ž¤”ŸšŽ›Œ¦¤•´²£´¯£·±£Ä¸ª×̹åÚÅíåÓý÷éüøóÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþÿÿôÿÿëÿÿãÿÿÕÿÿÝÿÿèÿÿæÿÿîÿÿâÿÿÝÿÿÚÿÿßÿÿÕÿÿ×ÿÿÙÿÿèÿÿæÿÿÕÿÿÑÿÿÏÿÿÕÿÿÆÿÿ¿ÿÿ¶þÿ«þÿ§üÿ¡ÿÿ¨ÿÿ°ÿÿ²ÿÿ©ùÿ¢ÿÿ¨ÿÿ©ÿÿªùÿœñù”ÿÿ¨ÿô¤ÿã¬æƒgØ_RÞQQÚNKÜMIàJGåHGÓJ@ÎXG÷»ˆÿÿËÿÿÍÿÿÏÿÿÇÿÿ¿ÿÿµÿÿ­ÿÿ¯ÿÿ±ÿÿ²ÿÿµÿÿ¿ÿÿÉÿÿÍÿÿÑÿÿÏÿÿÏÿÿµúñ‰ÿïuÿüoÿá|»SŠ{aw„‹rƒj}’e{n†™jƒ“lƒ”dzf{–l„›d|“^v~gt†gu€hw}p|ˆrzŒz†’{ˆo~†j{‡n‹p}uƒzˆ•›©¶œ¨¶¡°¸–¥«…’™…Œ•ž££™—“£ž–¥›‘œ—‹—”ˆ›—†¢Š°­™ª§“°¬›±­žÂº¨Ï®ÝѺâÖ¿æÛÆçßÍíèÞÿþþÿÿÿÿÿÿûÿùÿÿòÿÿóÿÿ÷ÿÿòÿÿìÿÿðÿÿôÿÿáÿÿèÿÿåÿÿÞÿÿÙýÿ¹ùüÀÿÿãÿÿèÿÿÝÿÿÔÿÿÎÿÿËÿÿÅÿÿÂÿÿÃÿÿ»ÿÿ¹ÿÿ­ÿÿ§ÿÿ©þÿ£ÿÿ©ò÷“øý—ÿÿŸÿÿœùÿ’ÿÿ˜ÿÿžÿÿ®ÿÝ¢àz\ê]]áSXàN[ãPYÞHPâKOâJKÏQHÉeSÿë¾ÿÿ×ÿÿÓÿÿÏÿÿÁÿÿ²ÿÿ®ÿÿ«ÿÿ®ÿÿµÿÿµÿÿµÿÿ±ÿÿ¯ÿÿ¹ÿÿÃÿÿÅÿÿÇÿÿËÿÿÑÿÿÁüþùêtÿñtÿÞ‚½X‹y[r{xs…ˆtŒ–jƒ‘d|‘h~”gz“buŒj}’j€†al}eq}ivnz†s~p|Šuo~†k}„n|‰q|t‘|‰™ž°·”¦©¦¸½ˆ—Ÿ~‹’—ž•™œŽ¤ ¥ž—˜š•¡š¦Ž¢œŽ©¤˜§¢–ª£šµ¬É¼¨ÔdzÑÄ°ÑIJÑÄ´Óʽæá×íïáñùæÿÿùÿÿöÿÿöÿÿöÿÿéÿÿÒÿÿÖôò×ÿÿöÿÿúÿÿòÿÿãÿÿÕÿÿÃÿÿËÿÿ×ÿÿÔÿÿÇÿÿ¾ÿÿÈÿÿÌÿÿÃÿÿ·ÿÿÅÿÿÂÿÿ²ÿÿ³ÿÿ¬ÿÿ«ÿÿªÿÿ¸ÿÿ±üÿ£úÿŸüÿùÿ–ýÿ”þÿÿéœâ‰`ãmZëY[ìY`æS^æS^æP\âJSßFLÌXIÔƒaÿÿ×ÿÿÑÿÿÍÿÿËÿÿ½ÿÿ¯ÿÿ¥ÿÿ¡ÿÿ§ÿÿ³ÿÿµÿÿ·ÿÿ³ÿÿ±ÿÿ·ÿÿ½ÿÿÁÿÿÇÿÿËÿÿÑÿÿÅÿÿ»ÿÿ±ÿÿ üâ{ÿÞˆÿéŸÌ¶{€xbqu„o|Œj}’fyfu’m}—m}•h}†_o~`phu‡k{Šl|‹n‹t‚v‚s{p{Žs€”t‚›™§©•Ÿ¥˜¥®ˆ“¤ˆ‘ —›ª’–™‹ œ— ™’œ•Œ –Ž£™‘¥›“–ž—¥ž•«¤™¬¢˜³¦Ÿº°¦Æ½°ÉÁ¯ÐÅ°×͵ßÕ»ßÛ¯úø¾ÿÿÙÿÿÆÿÿÌÿÿãÿÿÙÿÿêÿÿðÿÿðÿÿîÿÿæÿÿßÿÿÜÿÿØÿÿâÿÿâÿÿÜÿÿÕÿÿÍÿÿÒÿÿÉÿÿÅÿÿ¼ÿÿ¾ÿÿºÿÿ±öû¥ÿÿ«ÿÿ²ùÿ øÿŸÿÿ«ÿÿ§ùÿ™üÿ—ÿÿ˜ÿÿ˜ÿý“ÿõ˜þ¿‚í~aÛ_Gç]Iì_Që[SèWRçSSáLQÚBMÁUAëªyÿÿÕÿÿÕÿÿ×ÿÿÙÿÿÏÿÿÅÿÿ½ÿÿ·ÿÿ·ÿÿ¸ÿÿ»ÿÿ½ÿÿ¹ÿÿ·ÿÿ·ÿÿ¹ÿÿ¹ÿÿ¹ÿÿ»ÿÿ¿ÿÿÅÿÿËÿÿÇÿÿÅÿÿ·ÿÿ©ÿÿ•ÿævúßâÅv”‡ebcngpgvŒk{‘eucxƒgt†fs…ly‹kxˆo|Œp}t‘u‚’t‘k|ˆm~Šs…Œ‘ ¦Œ™ž–¡¤‘ž¥†’ž”Ÿœ¨’’”–”›” ‘‰Ÿ’‰šˆ–¡š‘ž—Œ¥ž“«¥—­¤—¨¢”©¢—®¨š¸²¤¿º£ÊæÓÉ­ÒÆ­ÉÅ™ÿÿÆþÿÅÿÿÌÿÿâÿÿìÿÿìÿÿêÿÿäÿÿÏÿÿÒÿÿÚÿÿÝÿÿÔÿÿÏÿÿ½ÿÿ¼ÿÿËÿÿÔÿÿÏÿÿÅÿÿÁÿÿ»ÿÿ½ÿÿ½ÿÿ·üÿ®úÿ¬ÿÿ«ÿÿ¥÷ÿ›ýÿŸÿÿ ÿÿ£ÿÿ¦þÿþÿ›óüÿùÿ÷•ò›hídcâXUì`]ða_ð\\íWVæKIáKJÕDCºa:ÿä˜ÿÿÏÿÿ×ÿÿÙÿÿÛÿÿÛÿÿÞÿÿÙÿÿÕÿÿÍÿÿÅÿÿ¿ÿÿ»ÿÿ¿ÿÿÅÿÿÉÿÿÍÿÿÅÿÿ½ÿÿÃÿÿÉÿÿËÿÿÏÿÿËÿÿÉÿÿÉÿÿËÿÿÃÿÿ»ÿÿ¸ÿ÷•òÙ†í͌ϸ‡™Škje]cgxanuly‹kxˆt‘gw†j{Œm}Žo|Žt‚o{‡l{ƒ{Š–”£©š ¤©±Š—ƒˆ‰››‘Šœ•Œ•„—•†“„•ˆ™”Œ›“›”ž— ›¦¤•¨¥™§¤šª¥™°©ž½·§¾¶¤Ã¹¡Ë¼¢ØÓ¬ÿÿèÿÿàÿÿæÿÿÞÿÿÊÿÿÈÿÿ¼÷ù¸ÿÿÍÿÿÝÿÿàÿÿÎÿÿÅÿÿ½øþ®ÿÿÂÿÿÍÿÿÁÿÿÃÿÿ°ÿÿ·ÿÿ¸þÿ²ÿÿ²ÿÿ¹ÿÿ´ÿÿ¶ÿÿ±ÿÿ£ÿÿ¦ÿÿ­ÿÿ©ÿÿ¬ÿÿ ÿÿÿÿ§üý¡ÿó¤ÿÕ‘ä‚^é]Zê^[ócdò`bîW]íS\çHWàJTÜNUÏ|fÿÿàÿÿèÿÿðÿÿìÿÿêÿÿäÿÿàÿÿàÿÿàÿÿÛÿÿ×ÿÿÍÿÿÅÿÿÅÿÿÇÿÿÅÿÿÅÿÿ¿ÿÿ»ÿÿ»ÿÿ½ÿÿ½ÿÿ½ÿÿ½ÿÿ½ÿÿ½ÿÿ¿ÿÿÅÿÿÍÿÿÇÿÿÁÿÿ±ÿÿ•ÿõ†ÿå‡ÿå•áÍŠ°“tcrŠcs‰buŠcw‡j{Šk|‹qr‚‘ivˆiw„vƒŒŠ™¡‰š¤–§³ž®½‚›|‰†”•ˆ…y˜|•y–‘z•}š”†›•‡œ’ˆš”† šŒ¤žŽ¨¢’²ª˜²§”« ­ Žº­›»®œº±’¹²‡íé¨ÿÿ¬ÿÿ½ÿÿÉùûÈÿÿéÿÿêÿÿêÿÿâÿÿÙÿÿÍÿÿ¾ÿÿÂÿÿÑÿÿÎÿÿÆÿÿÅÿÿÄÿÿÅÿÿÎÿÿÂÿÿÃÿÿÁÿÿ²ÿÿ¶ÿÿ¿ÿÿµÿÿ®ÿÿ³ÿÿ¶ÿÿ±ÿÿ¨ÿÿ¤ÿÿ¢ÿÿ¤þÿŸþÿ™ûü“ÿð¥ÿ¹‹æzdìehæacéghê^cíU^ìR[çHSÛNPÌOL彩ÿÿÑÿÿÛÿÿæÿÿæÿÿæÿÿàÿÿÛÿÿÛÿÿÛÿÿàÿÿæÿÿâÿÿÞÿÿÙÿÿÕÿÿÇÿÿ»ÿÿ³ÿÿ¬ÿÿ­ÿÿ¯ÿÿ²ÿÿ³ÿÿ²ÿÿ¯ÿÿ±ÿÿ¶ÿÿ·ÿÿ¹ÿÿµÿÿ³ÿÿ³ÿÿ°ÿÿ§ÿÿ“þò‚õÞ{ÿå«fv…ewexi{‚r€‹p‡|‰’p~‰iz†iz„{‰”ˆ—ŸŽ›¢—¦®ª}Œ”|‰‰’‘ŠŽ†ƒw’ƒŒ‚—’Šš“Š¤š šŒž˜ˆœ˜‡¢ž¦¢“£œ‘¥Ÿ‘¬¦˜°¨–¯¢»®žº¬Ÿ·­“¹±ÿÿÏÿÿÔÿÿ×ÿÿÛÿÿÞÿÿÛÿÿÑÿÿÉùÿ½ÿÿÄÿÿ×ÿÿÜÿÿÕÿÿÅÿÿºÿÿ´ÿÿ½ÿÿÅÿÿÁÿÿÉÿÿÄÿÿ»ÿÿÁÿÿÂÿÿ¾ÿÿ·ÿÿÂÿÿÀÿÿ¶ÿÿ¬ÿÿªÿÿ¡ÿÿ¡ÿÿ¤üÿ—ýý™ýú”ÿÿ™ÿð¨ö˜q×YÜ‹dÿѤÿС×pZçY^éTYçIOÑPL¿ZOÿÛ©ÿÿÉÿÿÏÿÿÕÿÿÕÿÿ×ÿÿÙÿÿÛÿÿàÿÿäÿÿâÿÿàÿÿäÿÿèÿÿäÿÿâÿÿÕÿÿËÿÿ¿ÿÿ±ÿÿªÿÿ¤ÿÿ­ÿÿ¸ÿÿ·ÿÿ±ÿÿ³ÿÿµÿÿµÿÿ³ÿÿ±ÿÿ­ÿÿ±ÿÿ±ÿÿ±ÿÿ­ÿÿ°ÿÿ£íÞžiyˆl}‰fwfxu„Œr{…v–nyŽmy‡ƒ™Œ™žŒ—˜‘¡¢ˆšŸ‘’Š•–ššŠ„Œ†x‡sŽ†r“‹y›’…“ž—Ž ›¤¡¦£‹ª§¨£Œ£ž‹ª –¬£”®¦’³«•´©”³©‚ÍÃŒÿÿÙÿÿÑÿÿ½ÿÿ¿þÿ¾ÿÿÕÿÿ×ÿÿäÿÿËÿÿ¾ÿÿ¹úù©ÿÿ¶úü¹ÿÿÁÿÿÆÿÿÇÿÿÈÿÿ¶þÿ­ýÿ±ÿÿ¸ÿÿ·ÿÿ¯ÿÿªÿÿ¯ÿÿ½ÿÿ¿ÿÿ¸ÿÿ´øû£ÿÿ®ÿÿ¨üü˜ýý›þýžÿÿŸÿø“ÿߙ߃]Ì“[ýçœÿû®ÿßÑoKìV`çOXäGQÌRLÈo[ÿþÈÿÿÉÿÿÅÿÿÃÿÿÅÿÿÉÿÿÍÿÿÓÿÿÏÿÿËÿÿÑÿÿ×ÿÿÛÿÿàÿÿâÿÿäÿÿâÿÿâÿÿ×ÿÿÍÿÿ¿ÿÿ¯ÿÿ¯ÿÿ²ÿÿ¹ÿÿ¿ÿÿÁÿÿ»ÿÿ»ÿÿ·ÿÿ­ÿÿ¤ÿÿ¯ÿÿ±ÿÿ´ÿÿ³ÿÿ·ÿÿ¯ùò«iz‰j{Šdu„dum{ˆn|‡r€‹s‚Šr‰v…‹˜¡‰•¡ˆ”¢Žš¨ˆ”¢}‰•‡‘›•šš„y‹†|Œ‚zŽ„z“†}™Œƒ‡¢™Š¤œŠ§Ÿ­¤•®¨˜©£•£ Œ¥¤Ž¨¥‘­¤•¯£—¶§Ÿ¶¬ôíÀÿÿÑÿÿÀÿÿÇÿÿÒÿÿÌÿÿÂÿÿ¾úÿ°øÿ¨þÿ«ÿÿ¿ÿÿÉÿÿÍÿÿÀÿÿ¶ÿÿ´ÿÿ²ùÿ«þÿ°ÿÿ¹ÿÿ½ÿÿ·ÿÿªÿÿ¨þÿ¥ÿÿ´ÿÿ£ÿÿœýþžÿÿ­ÿÿ¥îïõú–þÿ¡ÿÿŸÿÿŸÿÿšÿõ‹ÿä“Ê‘[íË‚ÿÿ¤ÿù¦ÿÖÒjHëTZéPVçJTÇXEØ—hÿÿÓÿÿÑÿÿÑÿÿÑÿÿÍÿÿÉÿÿÇÿÿÇÿÿÇÿÿÉÿÿ×ÿÿãÿÿÞÿÿøÿÿîÿÿäÿÿàÿÿÛÿÿ×ÿÿÓÿÿÍÿÿÇÿÿ¿ÿÿµÿÿ³ÿÿµÿÿ¹ÿÿ³ÿÿ´ÿÿ³ÿÿ¬ÿÿ«ÿÿ±ÿÿ¯ÿÿ¤ÿÿ£ÿÿ©ÿÿ¢ÿùµhxŽhyŒduˆhyˆgx„j{…r€‹s‚Šw†ŒŒ‘•™…Œ•‡‹šƒ‰™}…—|†Ž…‘†‹‹‚‚‰…‚‹†~Š…}‡‚ˆ~Ž‡|š”†¤žŽ¦«ž—ª£˜©¤˜¨¤“§¢ª¥¬§¨¤ˆ²«Ž¹¶öô§ùý®ÿÿÆÿÿÐÿÿÜÿÿÆþÿ³úþ¯ÿÿ¿ÿÿÀÿÿºÿÿÀÿÿ¸úü§ýý¤÷ú¢ÿÿ³ÿÿ¾ÿÿ¿ÿÿ»ÿÿ¶üÿ©øüŸþÿ¥ÿÿ®ÿÿ¤ÿÿŸúÿ“þÿ™ÿÿÿÿŸùû˜þÿÿÿŸÿÿ÷úŽüÿÿý™ÿñ™éÃwÚ­oÿö£ûÿšÿõŸÿÄËeEáNUáKUäJW½Z>æ¸sÿÿËÿÿÏÿÿÍÿÿÍÿÿÅÿÿ¿ÿÿÇÿÿÏÿÿÍÿÿÍÿÿü£}¥ˆd‰•t˜Æ±¿ÿÿúÿÿöÿÿâÿÿÛÿÿÕÿÿÑÿÿÏÿÿËÿÿÇÿÿ»ÿÿ­ÿÿ«ÿÿ±ÿÿ¯ÿÿ±ÿÿªÿÿ¬ÿÿ­ÿÿžÿÿÿÿ¤ÿÿ©ÿÿ¬ÿüºiyˆl|jziyˆky„ky„o{‰sŒr„‹|‹“s|‰|…’ƒŒ™{‡•{ˆ˜Ž•›œ~ƒ‚x…‚zˆ€|‹„y’Œ|‰yŠt˜‚£™£™¦œ’¢œŽ¡›‹ž˜ˆ¥œ¥œ¦Ž¬¤Ž²¨ŽÑΛÿÿ¿ÿÿÌÿÿÌÿÿÈüÿºëñ¡ýÿ®ÿÿÀÿÿ×ÿÿÜÿÿÔÿÿÂþÿ­ýÿ¬ÿÿ¯ÿÿ¶ÿÿºýÿ¬ÿÿ«öü£ùþªÿÿ¯ÿÿ°ÿÿ¥ýÿ öÿøÿ‡üÿ•ÿÿªÿÿ§üþ›öù‘ÿÿ™ûü“ÿÿ™úû”ÿþ˜ÿû¥ÿï®Ì³kõæ™ûú›äò€ÿø£ä¤lÁX>ØFJÞQQÚQP¿lFÿð¦ÿÿÉÿÿËÿÿÇÿÿÃÿÿ¼ÿÿ¸ÿÿ½ÿÿÃÿÿÏÿÿÞúèÜáÈÌ¥ÙºÐÆ¡ÛÁŸÕ¦®Ñ»Ìÿÿ÷ÿÿìÿÿÛÿÿËÿÿËÿÿËÿÿ¿ÿÿµÿÿ­ÿÿ¨ÿÿ§ÿÿ¨ÿÿ£ÿÿ¤ÿÿÿÿŽÿÿŽÿÿÿÿÿÿ‘ý÷ fv…jz‹er†dtƒfwƒlz‡qz‰zˆ“‘˜Š—žŽ•œŒ–ž‹˜¡~‹’w„‹z…ˆyƒtwt~zu‚}u„}vŠ…yŒ{”‹•Ž…¡”¢˜Ž›•‡š”„œ–† šŠ¦§ž‘ª –«¤‰­¦{ïëªÿÿ­ìï—ðöõü§þÿ´ÿÿ¸ÿÿ½ÿÿÅÿÿÎþÿÂîõ®öü¬õû¢ÿÿ·ÿÿÅÿÿÄÿÿ¸éð›üÿ©ÿÿ½ÿÿ¸ÿÿ²ýü¨õö–óöŒÿÿ•ÿÿœÿÿžÿÿ¥óõ’ùû–ÿÿžÿÿžíî‡òðˆôñ‹ÿú˜ÿî™é¼tÙÀmÿÿ§ÿÿýÿ’ÿöŸØ‡GË[5âOHÞSIÙRGËKÿÿ¸ÿÿÉÿÿÓÿÿËÿÿÅÿÿ¿ÿÿ¹ÿÿ½ÿÿÁÿÿÍÿÿÙν±Ê¨ÑÆŸÓ»’Ͻ”ÔÀšÝʤåɣ⪓¨§šˆîç¼ÿÿÙÿÿ×ÿÿÕÿÿÉÿÿ¹ÿÿ³ÿÿ®ÿÿ§ÿÿ¤ÿÿžÿÿŸÿÿÿÿŽÿÿÿÿ‘ÿÿ•ÿÿŒóë¢jr†gw†`t‚hz†n‹t…‘z‡—~‹›Ž ‡”¦ˆ•§†’ —¡|†|†€‡Žx~ƒmpm}zp}zn€~o‡ƒt‡yŒ}‹†z‘Œ€•„”Ž€‡z›“ ˜„ž™†¢œŽ¤ž¥Ÿ‘®¥†½²‚êæšìî‰îðÿÿ§ÿÿ­ÿÿ³ÿÿ·ÿÿ¾ýÿ±óý£ÿÿ¬÷ÿŸÿÿ±ÿÿ½ÿÿ¶üÿ²ñùŸöÿžøÿ¢ÿÿ²ÿÿµÿÿ´ùü¢ùû˜ðó‹õö‹ÿÿ ýû¥÷øšøý™ûþ”ÿÿ‘ÿÿ“ÿý“óñ‡ÿÿ—ÿú”ÿö”þÞÑ c÷âúÿ›ùÿ›üÿžÿæ–Ís=ÎY7àLAÔM@ÐUFë§yÿÿÏÿÿÕÿÿÞÿÿÓÿÿËÿÿÅÿÿ¿ÿÿÁÿÿÅÿÿÙÿÿ㿤¯Ò­éÈŸáÇœãØßÆ›âÅšãǛ翙ܧ†Ã±™ºµ¦«ÊĤÿÿËÿÿÉÿÿ½ÿÿ±ÿÿ¬ÿÿ¦ÿÿ¡ÿÿžÿÿ§ÿÿ¥ÿÿ˜ÿÿ”ÿÿ˜ÿÿ“ÿÿ‡àÕ‹nz‘n~‘k|l}v†œy‰œ{ˆš}‹˜…’›ƒ™ˆ” ˆ–£‘ zˆ“z‡‡‹qvvstm}xl|wmxq…~u‡€uŠ…{‰„|‰†|‹ˆ|ŒŠ{‘~š˜‡™Š˜–…›Š¥Ÿ‘®¡˜«œ‚Ô–ÿÿÁÿÿ²ÿÿ¹ÿÿ¼ÿÿ¸ÿÿ¸ÿÿ³ÿÿ»üÿ§ýÿ ÿÿ¬ÿÿ²ÿÿ¶ÿÿºöû§öýŸùÿžÿÿ ÿÿ«ÿÿªüÿ£üÿ£þÿ›ÿÿ”ÿÿÿÿžÿÿ ÿþ£÷ö—üü˜ÿý—ý÷’üö‘ýö”úôý÷ÿñùá…óÓ€Ö«cÿú›øÿðú‰åî‚ûÍŒÄ_KÕUNãFPÑNFÆ]CÿØŸÿÿÇÿÿÏÿÿ×ÿÿÕÿÿÓÿÿËÿÿÃÿÿÁÿÿÁÿÿÛöãʹš®¿•×Á˜Ü½“Ú¿™Ü·‘Ô½–ܘá›á›ᾘÙÀ›×Á¤É´®Å¼ÿÿ½ÿÿ¿ÿÿªÿÿ—ÿÿ’ÿÿ’ÿÿ˜ÿÿ¤ÿÿ¯ÿÿ¨ÿÿ¡ÿÿœÿú”Ùȇq|nyŒq|mxcm‡al}lv~‰‘‹•Ÿ†œ‹”£‰•£Œ}Š‘|ŠŠzƒ€jmjtunzwoyvlzwm}zr„~y„u…€t…€vŠ…}Œ‡}’ƒ˜“‰œ•Œ¡Ž§¤§¢­¢‘«¥uâÞ’çæ’îï“÷÷ ÷ö¦ÿÿµüÿ®ÿÿºÿÿ¼ÿÿ¸ÿÿ·ÿÿ¶ÿÿ¹ÿÿ¸úÿ®þÿ¨ÿÿ¦ÿÿªÿÿ©ýÿ¨ýÿ¬òù—ýÿ˜ÿÿžÿÿ¤úùšúùžýý›ÿÿ™ÿÿšÿÿœÿÿüõ•øîÿô–þï’ôá…õÜ…ÿê—ÖÂiõëŒÿÿžõÿ“üÿ‹ÿÿƒâŸ_ÙXTÛPRáITÇVHÄvSÿÿÈÿÿÅÿÿÍÿÿÕÿÿÓÿÿÓÿÿÏÿÿÍÿÿÉÿÿÇÿÿèθ²»›¶»’Ï¿—Ô½—Ö¾˜Û¾—ß½˜ß·’Ùº•Ü¼—Þœ潗äÁœãƟ廟Á¨•—¸°ÿÿ¥ÿÿ¢ÿÿŽÿÿŽÿÿ‘ÿÿšÿÿ¥ÿÿ›ÿÿ•ÿÿ”ûèzñÜžGQW186‡‹ƒµ¹³ÌÌÊÓÖÕÏÔÔÉÎÌ¢§¥_gilv|‹“}†“…™†–z~mjisrivvfutiyupzvq}wt}zr€t„u†‚s‰…v‘~“Ž‚š“ŠŸ›Œ¤ ª¢Ž³¦’Ľ’ÿÿÉÿÿ¾ÿÿ´ÿÿµÿÿ»ÿÿ·ÿÿµÿÿ²ÿÿ¶ýÿ²øûµûÿ±ðù¢üÿ¢þÿ›öÿ•ÿÿ¡ÿÿ¦þÿ£ó÷–ÿÿ¤ÿÿ­ÿÿ³ÿÿ°õöªûû¢ùö“ýú’ÿû’ÿü–ûö˜ñî‹üý–ÿÿ›ÿþ›ûï‘üè‘÷àŒþá”ìß÷ù¨÷ÿ£òÿ›û÷–ÿêÐMßWOßNKãGLÀSB樂ÿÿÓÿÿÉÿÿËÿÿÍÿÿÑÿÿÕÿÿÓÿÿÑÿÿÍÿÿÉÿÿ÷Ê£Ò˦âÁ›èÂœéÄžíÛæÄšã¾—ß½•à´ŽØ»•ßÂä»–ÛÂœßÇßÄ ÕÁ¤ËªŸüÿ¡ÿÿ¡ÿÿÿÿ’ÿÿšÿÿÿÿ ÿÿœÿÿ–ÿþ”ÛÐxûî²ÝßÓÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ÷÷ùr|‚H]fy‡’…”tv|olktpkuphurjurjyvnwtlzwm€{q„w†~|Šƒ|ˆ’Ž“~—“‚›—ˆ¦Ÿ‚¯£zÐƉìß“åÞôñ¢þý­þÿ¯øþ¥þÿ¨üÿ¤ÿÿ®ÿÿ®ÿÿ·ÿÿ¸ÿÿ«ÿÿ®ÿÿ·ÿÿ°þÿ«øÿ¦ÿÿ­ÿÿµÿÿ¯ÿÿ²÷ø¬ùû¦üÿ¡ÿÿ¡ÿÿ¡þýžöò–÷õûùŒÿþ–ÿû˜ÿø˜÷êÿð–ÿóšÿöšïëþÿæó„æù…êÿ‹ÿö’ðÀnÌlCÝMPÛOLÜRM¼f<ÿã–ÿÿÇÿÿËÿÿÉÿÿÇÿÿÍÿÿÓÿÿÕÿÿ×ÿÿÓÿÿÏúê׿ÄÄ¢ÖÄŸäÄåÅšéÉžêÇœèÀ˜æ¹‘áµ’Û°‘Ö³”Ùµ’Û¼•Û˜ÚÄÕ¾›Ë¸©ÿÿ¯ÿÿžÿÿÿÿ‘ÿÿ“ÿÿ—ÿÿ–ÿÿ˜ÿÿ’éÜÛ¿†þå¾ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÌÐÈZ^c{|povokhwppulosjmvmrsnnsqmyxo|yoytˆ|€Š„‰†~‹†|Ž‡|“Ž‚˜“‰›—{Ÿ˜kíëžÿÿœÿÿ¥ÿÿ¦ÿÿ¨ÿÿ­ÿÿ¬ÿÿ¦ÿÿ§ÿÿ«ÿÿ¨ÿÿ¤óúšðö›øÿ¡ûÿ¢üÿ¥ÿÿ©ÿÿ±ÿÿ»üÿ°òúªõü§ùÿ¦ÿÿ¦þÿŸøý™üýùõ™ûóšÿûÿÿüøšöð™õé”þì™ýêŽÿê†çÛ{ðëõÿ•éÿ‹ìÿŠäû}þãŠÚ‹ZÐ`KãMWØLSÕPT¿tKÿÿ¶ÿÿÉÿÿÏÿÿËÿÿÉÿÿÉÿÿÉÿÿÇÿÿÇÿÿÑÿÿÞÙÀ¿É¡ÜÇžÞÅ›âÇäÇœãÆáÆáŜ࿖ڿ˜Þ½˜ß¼—Ü»•Ø¿–ÖĘԽ—È·•¼Ãµ˜ÿÿÁÿÿ¢ÿÿ‘ÿÿ‘ÿÿÿÿ•ÿÿ™ÿÿ¢ÿÿ™ÎÌ_íä€ûë§ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿíéÿe^‡gbqoldtogrjfniaqldxrmyspwsnyxo{zo€}s„ƒxˆ‡|ƒ‚u„ƒvŽŠ{—Žši·­nÿþ¯ÿÿ¨ÿÿ®ÿÿªýùŸùõ›ÿÿ£ýþžÿÿ¯ÿÿ²ÿÿ°ÿÿ¯ÿÿ°ÿÿ¶ÿÿ³ÿÿ°ÿÿ°ÿÿ³ÿÿµûý¨ÿÿ°ÿÿ¸ÿÿ·ÿÿ³ÿÿ¬úú£õùšùþšÿÿœÿÿ•ôñ‰éæ€ôê‰÷æŒÿò˜ÿð—ÿï™ô׈ëÜ}ûùŠìóïÿŒ÷ÿñï…î¶uØiTØXQãMYÖORÊPLÚ•jÿÿÇÿÿÇÿÿÉÿÿÃÿÿ½ÿÿÁÿÿÇÿÿÇÿÿÇÿÿ×ÿÿãÂ¥±Æá˜ÚΡäÉŸá˜ÜÅžæ½—æÃêÄœçÀ˜ãÀ•áÁ–徒濔࿕ÜÁŸÑ¼ ¾ÊÀÿÿ¿ÿÿ¦ÿÿ“ÿÿ–ÿÿ–ÿÿ’ÿÿ‘ÿÿ ÿÿžÍÃdíÚŒõÛ«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÜ×öFHWdjmjjlpikqjjulmuqltsjsrgsrguti{xn‚w~zw€zu†{xˆ~x…}’fÔØ‹ÿÿ«ÿÿœÿùŸöÝ“é؇ôé‘þú—úûñò‰ñò‹ìëŒâ݆èæŽñï—ååŒñôšûþ¦ÿÿ´ÿÿÅÿÿÅÿÿ½ÿÿ°õú¤ÿÿ°ÿÿ¨ÿÿ¥ÿÿŸÿÿžúü™ôó–ñîÿü™ÿÿ™ÿÿ•ÿúÿôÿð”ÿí›äÔ|ïëòý’ðÿ‘îì„ïÔ{ÆuEâXSàQMãMNÓVFÉdAÿ΋ÿÿ½ÿÿÅÿÿÍÿÿÉÿÿÅÿÿ¿ÿÿ»ÿÿ¿ÿÿÃÿÿÛùçÉ¿ ¶ÊŸèÌ¥ëÞãŸèÀëÁžì¼–彚æÀæÅŸéÛ濚ߺ–Ø»—×»—׶œÀ¸¤­ÝÕ¢ÿÿ¯ÿÿ¡ÿÿ™ÿÿ”ÿÿ–ÿÿ’ÿÿ“ÿÿ¢ÿúÚ¿töÏ—óʯÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ×ÜØ_ddiigplgplgqkhpjgqjjplirplvrm~vr}zr|{p}zryu‰w‹}ršiÿóµÿÿ¿ÿî§øæšùè—öë“úõ™ÿÿ¥ÿÿ¬ÿÿ®ÿÿ¦ÿÿ¢ÿÿüÿŸþÿ«ÿÿ«üÿ¥ÿÿ¦ÿÿ¥þÿ©öû§ýÿ¨ÿÿ²ÿÿ°ÿÿ±ÿÿ£÷÷“úú˜ÿþŸÿÿ ÿÿ¥ÿÿ¤ÿÿ›ÿÿ›ïë‘äàúñ‹ÿ÷ÿí Ü¿pðâôù“êÿˆüìÒ–XÉcCæVWßNMçQRÌWOÄn^ÿûÄÿÿÅÿÿÅÿÿÇÿÿÉÿÿÍÿÿÅÿÿ¿ÿÿ¹ÿÿ³ÿÿäàÀËŤȻ—×¼–ÙÁ—àÄãÅ åÆ ãÆßÃœâÃêÄžèÁœã¿˜ÞÀ–ݾ˜Û»—׫“°©œ•îî§ÿÿ›ÿÿšÿÿœÿÿ™ÿÿ”ÿÿ‹ÿÿ‰ÿÿ•üïÝÁhôȇÿÏ°ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿŸ›£hehlginggqhiphfphfpjgokhtpk{vnzwmzyn~yqƒxwƒyq‰}q¹­„ûðªîÞ˜ãψöå”ÿ÷œÿùœþúžÿÿ¥ÿú£ÿÿ§ÿÿ¬ýý¤÷øœîñ—ÿÿ²þÿ«ÿÿµÿÿ¶ÿÿ¯ÿÿ¯ÿÿ¨ÿÿ õûðöùþšýþžÿÿ¤ÿÿ¡ÿÿ ÿÿ™öó÷ô‘ðïÿþŸÿÿªÿÿ¥ÿÿšÿí›ûÊ£[ãÕƒóõìÿ‰íÍz¹e8Î_LÛOVãRXèQWÉ]Ié§{ÿÿÏÿÿÅÿÿÅÿÿÅÿÿÇÿÿËÿÿÇÿÿÃÿÿ½ÿÿ¹ÿÿÛ¿¥§Å¤ÆÄ›ßÄšáÆšæÇæÜ俘ÞÁ—ÞÀ™ß¾™à¿šáÃç¿šá½–ÞÜ⻕ظœ¼µ¢¢ÿÿÄÿÿœÿÿÿÿœÿÿ–ÿÿŒÿÿ‹ÿÿÿÿšñÚ‚èÆ}ûÍ–óÀ©ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüùüÿÿÿóæáwlinefkgdmkekjali_mj`ojboldsojpmerogtshutiwa‰{YÝÇ–øÙšøß—ÿîÿö£ùó¡ÿü§ÿÿ«ÿú§ðÝçÖƒôäŽÿõ–ÿþ™ÿÿžÿÿÿÿžýÿšÿþŸñí“åãÖÕƒöôžýø¡ÿÿ¬ÿÿ¤ú÷‘üó‹öïôï“ùõ—ÿü›ÿÿžÿÿ›üöõì„ìá|úë‰ÿÝÿÅŒÁ‰JÏ¥_óÞ~êæqµw5ÎUHÕOMãPYåR[ßIUÅaOÿÕ¥ÿÿÓÿÿËÿÿÇÿÿÃÿÿ¿ÿÿ½ÿÿÅÿÿÍÿÿÇÿÿÁûé˹•¸ÅžÒÀ–Ú»‘ÓËžáÆßÀšÛ½—ؽ”ÖÂœßÉ¢èÄŸä¾™Þ¾˜Ùě۾šØ¸—Ô±Ÿ¬¶³ÿÿÄÿÿžÿÿšÿÿ˜ÿÿ”ÿÿ”ÿÿÿÿ’ÿÿ–êÒväÀsê»赜ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿùïÿ—”§actecmidfnggofgqjjojlomiutkwsnwqnvrmyvn~v`Ž€\äÔ™ýì›þòÿû¡÷ö—ýÿœÿÿ¥øó™ôçŽóÜ„üðÿÿ›ÿÿÿÿœÿÿ¦ÿÿ±ÿÿµÿÿ¼ÿÿ¶ÿÿ´ÿÿ§ÿÿŸÿÿ“üú’üúýüüù–øó™õí’ÿôšýù–ù÷úøøõóïŒÿúŸÿûÿù›ÿÜôfÈyJ¿wUê¢uÁxC½T7ÛRQâWWì\_ßVUÓOLËSÿÿ´ÿÿÅÿÿËÿÿÇÿÿÃÿÿ½ÿÿ¹ÿÿ¿ÿÿÇÿÿËÿÿÏÜ˼ Ҿ›Ô»—Ù²‘Ю̻—ל߽›áºšå»˜ä»•â¿šáÀ™ß¿™Ø½˜Ò»˜Ñ¾›Ôµ¡¨Ã¾•ÿÿÇÿÿ¨ÿÿ¡ÿÿœÿÿ–ÿÿÿÿÿÿ—ÿü—ؽrÜ·så¶zé´›ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿé÷×›¥†`aHggWiebhf`kjamkenlhnlfrqhuojxmlwrjvsg|tP±¡iòê¡ÿú¥þü¦þþ§ÿÿ¨ÿÿ²ÿÿ«ÿï’ñá‡ÿðšÿÿ£ÿÿ¤ÿÿ£ÿÿ£ÿÿªÿÿ±ÿÿ¹ÿÿ¼ÿÿ¹ÿÿµÿÿ´ÿÿ³ÿÿ±ÿÿ¦ÿÿ›ÿÿšÿÿŸÿþ£ûüžùýœ÷ù”ûü•ÿý—ÿù˜ýó”ûî“ûåŠùÚ€ÿÉã€dÜiWåb\ßZQÓLA×L@í^Qñ\VôWZÛQLÓZOõ³wÿÿ³ÿÿ»ÿÿÃÿÿÁÿÿÁÿÿ¹ÿÿ³ÿÿ½ÿÿÉÿÿÑÿÿÛÁ«¥¹’ÛÑÀ˜Õ»•Ô¶Ñ·‘Ò¾•ÙÀ—ÙÀ—ÙÀšÙ»•ÔĞݽ—ؾ™Õº’ͯýžÑ±¢žÖלÿÿÁÿÿ¢ÿÿžÿÿšÿÿ“ÿÿ‘ÿÿ–ÿÿ™ûëŒÝ»và¸xã¶z泚ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿåî಴¨a\Tea\^ZW=;5\[RlkbljdmlcmlaspfvqgvofzpjƒvTÛËŽÿ÷°ÿù«ÿÿ¯þÿ¬ÿÿ±ÿÿµÿ÷žëÙˆñåÿù¢ÿÿ¦ÿÿ¤ÿÿ¥ÿÿ§ÿÿ ÿý—õöøù’ýþ—þû˜ñð‘ìëóô–ùýž÷ú ÿÿ²ÿÿ°ÿÿªÿÿ©ÿÿ¦ÿÿ£üûœóí–ìß‘÷ë˜ÿý¥ÿòŸÿæ™ÿ°‡Ý__ëfjðbkàT[ÓIMì[ZõYUðQNíHJÖU@ÌnGÿå ÿÿ½ÿÿÃÿÿÉÿÿÅÿÿÁÿÿ½ÿÿ»ÿÿ½ÿÿÁÿÿËÿÿѱ—Ž³Œ»º“ɼ—Ó¿™Ø½—ع“Ô¾•Ù¸’Õ°‰Ï¸‘×¼•ÛÀšÛ¸“ϳ˽šÕ¶”ȱ¿­ öú­ÿÿ»ÿÿ¥ÿÿžÿÿ›ÿÿ˜ÿÿ˜ÿÿšÿÿ˜íÚ~ß¹xÛ³uÞ³x߯’ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÙÒÞ©£ª]X\`YiypŒééçx‚cdfXhcgjgfklgmlctoevrcxrb„Zðâøñ¨ÿþ±ÿÿ²ÿÿ³ÿÿ²ÿÿ¦ùòôä…ÿøœÿÿ¥ÿÿ§ÿÿ«ÿÿ±ÿÿ³ÿÿ¬ÿöœûó˜ýøœÿÿ ÿÿÿÿ¢ÿÿ¥ÿýŸÿúšÿø–õïŠóîöð™üú¢ÿÿ¬ÿÿ­ÿÿ¦ÿÿ¡ÿÿýó”òá‰ùÓ‡ÿÑâ‚hàWfë`ké]dàT]çXdçQ[èKUéJUäBNÎ[Gé¤pÿÿÅÿÿ¹ÿÿ»ÿÿ½ÿÿ»ÿÿ»ÿÿ½ÿÿ¿ÿÿ½ÿÿ½ÿÿµÿÿ¯ÿÿ®Æµ_œ}hžrœ²Š¾»’Ò¼–Ù¼”ß»–Ý»–Û·’Ù¸Û¼•Ýº×¼–Ùº–ÖºžÎµ À´¯Šÿÿ²ÿÿªÿÿÿÿ—ÿÿ—ÿÿ–ÿÿ•ÿÿ™ÿÿ“áÊtà·~à¸|â·zⲕÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÛ¼—Ô¾º\Ol]WiŠ‹”ÿÿÿ†žaejfd`TVLBG8QTC^^LheOpfN¦–nÿê±ÿö°ÿÿ±ÿÿ°ÿÿµöü¬ÿÿ¶ÿÿµïêàÜ€ø÷šÿÿ®ÿÿºÿÿÂûÿÂêì«ØÔ•ÄÂyðíœÿÿ¦ÿÿœÿÿŸýþžÿÿŸÿÿÿÿžÿÿ ûú›úø ôñ çã™óó®÷ú¾ûÿ¹ùÿ±øÿ¬÷ü¦ÿî¨ÿË–™O-—5'š:+“6&,"•/+–"*ÈEYÛU^ØMOÄpAÿõ—ÿÿ¹ÿÿ»ÿÿ·ÿÿ³ÿÿ¶ÿÿ»ÿÿ½ÿÿ¿ÿÿ¿ÿÿ¿ÿÿ¹ÿÿµÿÿ³ÿÿ±ÿÿµãØu«“i¢{Š­ˆ­¹‘κ‘Ѿ•Ù¸’Ѷ“̼™Ô¼–Õ¼–×¼–Ù¹ŸÇ³ °ÒÉÿÿµÿÿªÿÿ¤ÿÿ¢ÿÿÿÿ‘ÿÿ‰ÿÿ”ÿú”ÝÀsݳݱ{Ù¬rÙ¨ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ“«µ©´·ZVS]Z]“‘ÿÿÿ„ƒŠ^]d_^e £ äéܱ°£›–ŠysesgY¶¬”Ë¡ÅÁ¥æåÑÿÿõÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿúùîðîßÿÿ÷ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÝìÃâí¼÷ùÂö÷ÉõòÏïïÔòòâõôçùøïòïîØÔÚÄÉÅÁËÁÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿê÷Éh‚ÐfsÌUYÕ“gÿÿ²ÿÿ¿ÿÿÁÿÿ¹ÿÿ±ÿÿ¯ÿÿ±ÿÿµÿÿ¿ÿÿ½ÿÿ½ÿÿ·ÿÿ±ÿÿ³ÿÿ·ÿÿ±ÿÿ­ÿÿ©ÿÿŽ¾°^§‹e¨ˆŒ°‰º³ŒÀ³ŒÄ¼—Ó¼–׺–ؾ™Þ¸žÂ°œ¡éã¯ÿÿ²ÿÿ¤ÿÿ•ÿÿ–ÿÿ‘ÿÿÿÿˆÿÿ’ûé†Ô»fÕ¶pÖ´mÙ²mÚ­ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÜպ͹•¡–ƒ_\]YVWŸšžÿÿÿ‹•eZk`Ud©¢°ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿíª¼Âtx·\Tè¹ÿÿ«ÿÿ·ÿÿ½ÿÿ¹ÿÿ·ÿÿ³ÿÿ¯ÿÿ¯ÿÿ±ÿÿ³ÿÿ·ÿÿ·ÿÿ¹ÿÿ·ÿÿµÿÿ³ÿÿ³ÿÿ¯ÿÿ©ÿÿ¤ÿÿÿÿ¸¨I‹oIsˆª‚¨¸Ê´ŒÇ¯ŠÄª•¡±«‰ÿÿ²ÿÿŽÿÿ‘ÿÿ˜ÿÿšÿÿ˜ÿÿ”ÿÿ“ÿÿ”êÓtÖºaײcܵnÛ°sÕ¨Šÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþýÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¼ª·»¤¹ƒŒ][WXVR¦¤ ÿÿÿ|‚{X][hjnÿÿÿÿÿÿÿÿÿüþÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿüÓãÒ‰ºlp¯ZPðȈÿÿžÿÿ¯ÿÿ³ÿÿ²ÿÿ±ÿÿ±ÿÿ­ÿÿ«ÿÿ«ÿÿ®ÿÿ¹ÿÿ»ÿÿ½ÿÿ»ÿÿ»ÿÿ¹ÿÿ·ÿÿ³ÿÿ±ÿÿ§ÿÿžÿÿšÿÿŸÿÿ¿ÿê¿¡wm†ª…¯²Ç°š¦É¾ ÿÿÅÿÿ”ÿÿšÿÿžÿÿœÿÿ˜ÿÿ‘ÿÿ‘ÿûŒÖ»bÚ·gÙ­hÕ«iѦkÍŸ„ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¢“ц…ž—Ÿ˜uxuPMPIIG­®§ÿÿþdf\WXSiikûþÿÿÿÿùûÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþóôïæçâêèäÚÕÕÉÂIJ¦¬™‰Šœ‰†ÑÀÏ>2Sj_w(/ -  K88:#$M9@>+;TBMnZatelš– ”šœ”«Ÿ¥·®³²¨°²§´Ã¹Á×ËÏÕÉË·¬«Ä¿·ÐÍÃÍÌ¿¹¸«ŸŒŒkt£~v²‰pÿõ­ÿÿ™ÿÿšÿÿ¥ÿÿ«ÿÿ­ÿÿ¨ÿÿ¢ÿÿŸÿÿšÿÿ¥ÿÿ³ÿÿ¹ÿÿ½ÿÿ¿ÿÿÁÿÿÁÿÿÃÿÿ¿ÿÿ»ÿÿ´ÿÿ«ÿÿ¦ÿÿ£ÿÿœÿÿÿÿ«ÿÿ±ôØ¡¡yp„n=æáŠÿÿ³ÿÿ ÿÿžÿÿšÿÿ˜ÿÿ•ÿÿ–ÿÿóä~Ô³gܶlè»sÜ°kÑ¥bÝ­ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¼¿ÓT_pŠŽ‘‹hf`???@@@¾¾¾ýýÿSRYVUZ~ÿÿÿü÷÷ÿÿÿÿÿÿÿÿÿJOK/2398?EF?wzgŽx…ƒh~|_‹o¢ž€¨¥„”’u•’|••x‘’n££z’f©¨y¯¯{±®{»³‚³¬»³µ°‰›–o£šp°¤v°¤yº­‡¼°‡½±†Æ¼™ìâÈùïÕùïÕîçÌêæÌêåÎêåÐòêÔüïÛûñÙõîÓÿüÛþûØöóÒéåÉ»²¥l]`‚r°£ìèžÿÿ”ÿÿžÿÿ›ÿÿ ÿÿ¦ÿÿ§ÿÿ ÿÿ›ÿÿŸÿÿ£ÿÿ©ÿÿ¥ÿÿ§ÿÿ±ÿÿ¸ÿÿ·ÿÿ¿ÿÿ·ÿÿ¯ÿÿ¯ÿÿ±ÿÿ°ÿÿ¨ÿÿŸÿÿ¢ÿÿŸÿÿ–ÿÿˆÿÿ}ÿÿ„ÿÿ˜ÿÿœÿÿ¡ÿÿÿÿ˜ÿÿ“ÿÿ†ÿÿÿÿˆâÌqÞ¶zâ·zÞ±sתnÓ¤jЈÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÕØì=@Aqqa„s€vnYRR6/;:5DÐÊÞÿÿÿ’•¡°²¤ÿÿÿýüïøùòÿÿÿÿÿÿosvkogggWqoT˜n¡—r”‡^ “m –qŸ•n ”kši¢”u˜Žk›‘lž—lš”dŸ—o™oŸ—s¢˜s¡•l¨˜n£•q–‡jŸ’p˜Žg˜e”j© t´«¾´…g¡•z¹ª”¹®™¾¶¢ËÇ­ÑͱÚÓºàÕÀÝÕÁàÛÈìçÒçâͱ©“´§“¥“fP^w¢‡œŠlÓË„ÿýšÿÿ‰ÿÿÿÿÿÿ’ÿÿœÿÿšÿÿ—ÿÿ›ÿÿžÿÿ ÿÿ§ÿÿ²ÿÿ¹ÿÿ¯ÿÿªÿÿ§ÿÿ¢ÿÿ£ÿÿ¡ÿÿ¦ÿÿ¥ÿÿ•ÿÿ¡ÿÿ¡ÿÿ¢ÿÿœÿÿ›ÿÿ ÿÿ ÿÿžÿÿœÿÿ˜ÿÿÿÿÿÿŠÿÿÿñ„ßÃoä¼€Þ¶xÙ®qÛ°sܯuØ¥Žÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¿ÄÎ#09Y\]rkdwrjke`HED')-()4ÝÚíûùÿ—–{yƒ˜§ÿÿÿùõòùö÷ÿÿÿÿÿÿ„ˆ‚~|kx[…`£–k›f’…_–Œg‘‰eŽ†`“‰b†ZˆY“Š`…`–Œg†c—j–‹k’ˆe—h’ˆa–‰cšg‚^™j†cƒh‚ua_\FŒ’~ÉͳÝÝÀððÓýýàÿÿåþýåýþçÿÿíÿÿñýüïýÿñÿÿ÷ÿÿùÿÿóüûçõðÙçáÜž—§{nyš†zvy¤–pÕÎ~óðýÿ‰ÿÿˆÿÿ‡ÿÿÿÿ™ÿÿ›ÿÿ›ÿÿ–ÿÿ•ÿÿšÿÿŸÿÿ ÿÿ£ÿÿÿÿ—ÿÿŸÿÿ§ÿÿÿÿ’ÿÿ–ÿÿ˜ÿÿÿÿ ÿÿ ÿÿœÿÿÿÿ¡ÿÿœÿÿ™ÿÿÿÿ‹ÿÿ‰ÿÿŠÿÿ‘ô܂׶hÝ°rÛ³wÛ³~Ú³yزsÕ©ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÌÈâ47CMVU_c]liajd_`XV@;?&$0'$'™“”ˆœA+Y&5vu|ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿˆ€“‹w’‡i™jª¡u™h’ˆe„f„m‚b‹Z‹‚X‰€V‡Y‡~]‰€a‰}b‰€aˆ^ˆ€\‹\ˆ~W‰X„y[|l[}l€p_bUEA5)4/#Êɾÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿþúøòÿÿøÿÿ÷úûôýû÷ÿþþýûõöøîîíàíéÚèã×¼·­XLN|jw€o~}l}~nxptŽ~k¯ŸwÙÒ‡ñò‡üÿ‰ÿÿ†ÿÿˆÿÿ†ÿÿ“ÿÿ˜ÿÿ•ÿÿšÿÿ—ÿÿšÿÿšÿÿ—ÿÿ‘ÿÿÿÿŒÿÿŠÿÿÿÿ—ÿÿ–ÿÿ–ÿÿ˜ÿÿœÿÿ™ÿÿ™ÿÿ‘ÿÿ‰ÿÿƒÿÿ~ÿÿ‚ÿÿ†ÿøŒÜÃwÕ¶näºxä¹zàµzÛ°uتsÜ«“ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¾·»>,DSKRZXRfg`de^ab]UUS779# -,'2@;HKGO˜”šÿÿÿïÿöãîáÿÿÿÿÿô‹†o‡hŽ€ZŠ}W…{T†|W…zZ„{\‚{^€~X}}R}S‚zR„zUˆz[„y[ˆ|a‰€aƒzY‡~]„yY†}Sˆ€O„|VyoW_WA@8&0,+(65*ÂÁ¶ÿÿÿÿûÿüøþÿÿÿÿýþÿÿÿðé願™nehkbg˜““òóîÿÿÿÿÿÿÿÿÿÿûûëåàÚÓÊd]Vk`]pedsgi|mrƒrz…u€o€yfh|n¶§zØËñêˆýü†õù÷ý‚÷ÿ|ÿÿÿÿ‰ÿÿ‹ÿÿÿÿ‹ÿÿ‰ÿÿˆÿÿ‚ÿÿ~ÿÿ‡ÿÿ…ÿÿ‰ÿÿ‹ÿÿÿÿ–ÿÿ•ÿÿ“ÿÿ‰ÿÿƒÿÿ€ÿÿ}ÿÿƒÿÿúí×¹lضoÚ²tÖ®rÒ©pׯoÕ®iØ­ŒÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÀ½³>99YQZTOOYXO\[RXTOXTOHDA4101119:5AB=±¯«ÿÿÿÿÿÿÿÿÿÿÿÿÿÿø‡u€lŽ~hˆyc…yb‚x^w]z_{tY}y]zvZ~w\‚x`w]‚v[‚yZ€wV~xXxtX{_{tY|vV}uQolKLJ/50.%,%.&"<:6ÃÈÄÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÏßÅafWpjg_Z\RLU:??GSOûÿüÿÿÿÿÿÿÿÿÿòïðïçå{os{kwxlrvmp~ux†z€‡{rw€pz}jzq`ho[`‚rZ³¤sØÎ}ðéyÿÿˆÿÿ†úÿ}ÿÿ‚ÿÿ…ÿÿ…ÿÿ†ÿÿ†ÿÿ{ýÿsÿÿzÿÿ€ÿÿ~ÿÿ{ÿÿ~ÿÿ„ÿÿ‡ÿÿ…ÿÿ„ÿÿ|ÿÿÿÿƒÿÿ‰ÿø€êÓ}Õ­zÓ«vÔ­uΨkÖ®pÕ­mÖ¯lاÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ½½¿9:3SWOMQKOOMSPSLHNPLTMMMGHA23,))+76;#!+=:K74ELFXhaoŽƒ‹ƒztd|vhuncqk]oiYjeYga\d`[b^[d^Yc[WaYUbZVa[Va[V`[Sd]Tg`Yg\Yh`\g_[b\WQMJ>;31, /* .' -'")$$=@A¶»Ãÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ|a_n[WN-1* % 34/PVd\kfÿÿÿÿÿÿÿÿÿøöðûöì†}aTOvh]q`€p_qb~pc~ogrhbia_pgltftrdrkZim^XuĹ‚èâ‹þü’ÿÿõýtûÿrÿÿyÿÿ}ýÿrúÿløÿjÿÿsÿÿwÿÿ|ÿÿyÿÿ{ÿÿzÿÿ{ÿÿ~ÿÿ~ÿÿzÿÿzÿÿþñÙ½dß²vçº~è¹ä·yÞ´rݳo׫hÏŸ€ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÓØÖ:;4TQGROGPLGKHG@?DE@BJB@IFGEGK"''&#&KEN/,/OLKJI@KJ=JI>@?6]\Syupec]ca]\^T\^P\[NROCTOGRIJQJJLEEMIFTPKSQKVTNUSMWUOZYPXWNXWNGE?632'"&*##1&%3)#0&3%2!F<6¶²¸ÿÿÿÿÿÿÿÿÿÿÿÿáì¹Wa­¦2Ư#й?´š59$L?/TFVÑÃòÿÿÿüõ÷×Ðм¹‡~q€q[}rR‚yOŠ„Pš–Z‹OŒ†KˆSl`EfXKudhrcho`gscowdvjXe{jr«š‡ÔÀ•õåÿõ’öñƒ÷ö€ýþƒýÿüÿzúüsôöqóñtÿÿ{ÿÿ|ÿÿvÿÿwÿÿwÿÿsÿÿyÿÿwþù{ûç€Ï±b×®wÙ­wÒ¤oÒ£qØ©yÔ«tÚ´wݱ—ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¬±± NOJRLGTMMSJOE@BC@AD?AF=BGDG8:>  TVZ_c]783'!(O89§—²´¨ÿÿÿÿÿÿôôäÊÈ©DöÖƒÿë‹ÿüÿì†ÿâ„ÿêr6iXIÿõÿÿÿÿÿÿÿÿÿÿû÷殟…©nƒnQxeNtjCŒŠR’ŽO˜U“R”Œ[‰Zˆ|c‹~lwi^gWVlWc~ly„s‚wfjq_Z|[·¥kÒÄråÚsíævîçsý÷~üõxíæiÜÕZôömÿÿsÿÿwÿÿyÿÿvÿÿrÿÿwþÿtÿýöå{׺hÙ­wÕ©sÜ®yݱ{Þ±~Õ«wÒªuËœˆÿÿÿÿÿÿÿÿÿÿÿÿŸ¢ª'+0DHKGJGIGAHEFB>F@;=<6373.A?9:90/.#.-$3/*(## (',. !&9>3EF?KJAPMEYSPjafXQSVQSGIM#-3<0˜¢ƒúýØ°®„––yÈʼ{€|SXbTV\XTZSOUXR[YTXXQSTPMROGTQGZWMddThkXTQEA:35..+%,&wpiumk”™×ÈÂÿëÙÿóÈÿï¬ÿì úæ‘úæÿéŒ÷êšËƃƒ…\ÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ±›ƒÂ¤z´™n™~U‘|TƒsKrf8‡|L…|B~v2‰AŠ†>‘ŒG•ŒM±¤hª—c‰y_cRVYLWocyugwtboseXŸ’nÒʼnÜÊ|ÙÉqÝÎoåØoïârìæmóõsôúpøÿnýÿqþÿnþÿpÿÿrÿûïч߹xà²}ê¼…è»Þ³vÙ®qË cΣhÌ ˆÿÿÿÿÿÿÿÿÿ‹‰“+%7BAFFGBFFDBBB@=<;669463-44/34/3.*'+( *("*+&*'(##% '$;80D@=OIDWPI[TMdZTTLHVPM@=>%>D=:D1[YJÿðæçà×tupHLFOSMQTUPNXPPPZ[TXYTOOMUSOTPKQMJOJLLIJNKLQOKTPKOPKBEDEJFüÿýÿÿÿÿÿÿÿÿÿÿÿÿÿÿðÀ«kÿêŸÿù£ÿì‘ÿëûä¢úá¼ÿóèÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿ¼®²›hÀ¤k¼œ`¬‘U´›c¾¨u¦”f„w>„Cœ”Kž—Iˆƒ>{y?‡ƒD‹…EŒƒI •`¬Ÿ}†ui^NOjWivfrthni_Ue[CŠƒX¸²tºs¼¯aÑÈdìänîìkñójòõlðölóùqüÿ~ÿùÞÁrÛ¼tܶwصu˨jŸaÌ¥kͦlÝ´{áµ™ÿÿÿÿÿÿMSc)+1C=:E@@WRTAAA5:8/21111),-$&*$$&&#$'""' # #"!("#&'23.SPFHE9DA5HE;OLDPNHQOK64085442.,*$LHCSKIG?;>62=66JDKPMPNNNOOOSPQSRISQBROGSNNRPLMNINLHLHEKGDLGGJFCKGBBBB<=F9:EãäñÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿïäÄO0k8.Ï£‰ìȞ̵™ÿøêÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÞÔ­³›^²˜UƨbÃ¥_¹™Vµ˜]À£r¸¡pª“g~M„|IŒ‰VŠ‰Zƒ…Gƒ8„ˆ9„2Œ?¯«c¥lƒw^g]U[Q[XKV`O^bV\bWV{rQ²©jæÛÿó|ìâfíægëçbíìdÿÿ~ÿÿ‰õæ„Þ¿wæÃêÉõÏ’îȉëÅ„ä¿{Þ¼wÒ¯mÑ©‰ÿÿÿNPa%-A:=E@>:?=9A>=:;45:/02(.-$A>=$%  "!# -  $".,&;93HJ>EG9VVFEC2=<1KHG?=9;9368,13%/1%54+@B6IK?NM@QNBNMDQOKNOHKOGHLDJKDSTMOPKJKDJLBGHAGDCFCBE@BJFCOKFFFF<=F46GÄÆãÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÙÐѶ¯¯ÕÐÐÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿÿøÛØ·…Ä£i·‘RÄ¡aãb°Tª‰Rºš`ǧm¹d§ŽY‡Vœˆ]‚`Šj‰i–”l¢žp¨¢n™‘kˆ|ecUJL;?PAH:,:4&6\N`j^dlb\˜cÖÌ{òìƒöôuðñqöøxüó‹ðÞ˵lÊ­pË«hΩaË©`Í«dÆ£a˨j̨mÕ­xÜ°˜LA>,''98===?;;=>><:;67;3ae]67020,%%#    - -    # :5 OMG@>8]][JMNHEDMECMDEJAFD??=;78621/+$$"#&'---:78GC@RKDRJFPGHNHEJDALHCLKBIH?FD>GE?GEAIGCGDCFCBHEDHDJCKH@TNKVMPQLNPMNMHJLEGGBB>9986054)1/))$&")$(502D==JD?NG>KF5:8253--+''%! &&$31-C=:C<;B>9D@;C?BBBBB@@@>E;C…nÿÿÿÿÿÿÿÿÿêê辿¸£¢™‡„|xqjJB>3*+8/0H<@]TUic`d`]fb_RLITKLv`\…bY«…p½•sÈ¢vϧt»–b®ŒZ»še¾h­ŒU²‘Zȧm̨o¼›a²‘W³“YÀŸhƦlµ•Yº™]Ьqݺ|ͧj¼šUЮeÏ°hÍ®kµ`•N|k8|m/63'-.)!% %'VS=WWGacY]_UGHAC@6jdVhcW_\Tc^Tc\Q_[L_[L]VMj_\d\X\VSXUMVSIQPELK@HE;HA:D>;<57>77=453.2($,$ &0&0=8:>?8>@6A@5DB?4,5B68H93jUJŽqd´’~¿š€¬‰c±`¾h´”Z¦†Lµ•[Á¡g¡g·–_º™dãiϯpÀŸc½˜bɤnÖ®{Ê¥qÁœhÈ£m˦pÑ­rÖ³uß¹|èÀ„îȇðË…Ù¶tŸaµ•V¶•YºšY½šX½œbÇ¥xΫղŠß¼’ÞºÚ´†Û±‚㶣10'23,01,,-()*%'+%(+(+.+,,,31->91TQIJI@+/)  STOWUQUSONLHRPLYVU][WXVR[WR]VOd_W`]UZVQa[X_YVa[Xa]X^[SYTL]VO`ZU[UR\UURILPKKHFBC@?B=??<;97345./1'$%!500<9:B?BC?ED=IA=CDABca]ea\lhcC?91C@840+!??=^\XMIFCA;DC:IGAGDCIFENKLPLIVOHXSK\VQYSP[RS\VQWTL]ZRZWO]ZR]ZR[WR[URZVS]XXXVRYWSXVRPNJLJDDC:=?5DF<;<5672-.'*) $")#*?4AICLDCHTTTUSOLHEGA>@996/30)++$$' "'%"%$*&"*& )%"%$$$&#")%"-'$,#$0))-((,),1-51-50*37,+1R<$‘vM£†Wª‰T¸—b«ŠX°Z¾hɧrÞj½œbǦjÒ²q»›XǧdÉ©fˬfЮg [Áž^Ñ®lÜ·sÙ´pÛµtɦh±Xµ”ZÅ¡hݶ|龃ݵyˤjÇ¡dÅŸ`ɦdÏ­hÖ°qܳzà´œ+,%*+&%%%%%%'$%$$"()$*+$-/%98/<61<77,'+A>=^Y[TOO>8582/7./<42?43=51=80?:0F?6J@:QCAODARJFOIDRLGTPMVSTWUOYXMYXM]\SZYNWVI^\M]WG\VH]VKSLA]SKVLFQFCOGCG?;C<1@7(71#5.%/)$(##!  *'(63466633320,2,'.*'-((,(%+'")&'$'$'#"#!$!#&%'*+***.))-+'*+$-.)/,-,,*,,*.(%6((3$'4#+6#L5$eE§‡\¶—i·•fºš`É©hÌ©gÀšYÅŸ`Ϩn̨o»–`Ì©kݺxß¼zÄž]·‘R̦iÔ®oß¹xâ½yÕ°j¾™U¼–WÁ›^Ò«qÙµ|ÄŸiµZ°‹U·”V¾›Y½šX½šZË¢…#'! $"%""!""$%%'($*-*)/,$21(42,/3+(0'68.XYT==?((*'$'(##*$!*##/&)/(*0)+2,'50$73$=9(=8.?96E>>G@DLIJJJJQNOTOQSQKVUJWVKYXO_\Ra\P]XP_YVWSNXVPYVJVP@VP@SM?RN=GC2FB3C>442,111//////*'(' "!!#$",+"21(/-'1/+.,&*("(',)('%&!#'#) %+"$( (,&))'*+&,*&-+%,)!+)%**,-*)/)$1,$/*".(%/(*/ %, 8" N5)~aB¨†W¹˜^Ë¥fàb°ŒQº™]ȧkͪlÁ›^ͨdÔ­f˦`ÁœXʨcѯjÖ±mä¼|Ö¯u»–b®S¼›_Ò¯qÕ¯rʤg¾•\¯ˆN¾—]È¢cÉ¡aÅ›w###"""$!"!# #'$#,(%-*"-(/, 2/#11!66&GG7feX;74!$#'"$)"$+&(-(,/**3/,952;74=;7?<;@=MF=IC@?7>95;2161.13.0,''&"$!  !$!)*#)&('+*)&,%-(-( )&('&(',',!)*%(&"+%"($!-((+&&,'',*&,*&*($+('(,&'-$)*#.(#3&;&Z?+‹kO«ˆ`Í¥r¿—d¼”aÆ ą]ÁœTÄZͨdͪhЭmͧjÑ®nÒ¯mÝ·vÛ³u¼˜]´’]¢cίiÖ¶ųm¿›bµZ·XÃœbËŸƒ$("&' '$$%+&-( *$*##(& *,"21&ID:ic`JAF) #   ! !# % ,#&-&(0)-4//3/*71.=45B;?@9EICJQJLQLNWRTTPMWTLXSK\UN]XP\WO]XP[UPVRMVTNTQITOGRMEKC?LFCA<6?;,94(6/(-'$*#%&!#  #$&&$))+(',('.&)(#'()$*'&)))(+,)))(%$(&"+'$'%+)#-+%,(#*'&+(++(),)(,*$/.%/.%31+GC@h[RWC5‰kSšxÆ r¿›bÅ¢bÍ«fʧeÈ¢eÏ©jʤeº—W³“TʧeÒ­gÕ¯nÈ¢e¾šaÞjÏ«pÚ·wÙ¶tϬjà^º—U´˜t \ No newline at end of file From a312ea2cc53328015b1791edca6df27bf2767262 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 17:14:20 +0100 Subject: [PATCH 053/267] removed (from documentation etc.) any reference to `grabberDual` and `remote_grabber` devices --- .ci/initial-cache.gh.linux.cmake | 5 +-- doc/module_devices/note_devices.dox | 2 +- doc/module_executables/cmd_yarpdev.dox | 2 +- .../userlib/fake_grabber/CMakeLists.txt | 2 +- src/devices/README.md | 31 ++++++++++++------- src/devices/fakeFrameGrabber/CMakeLists.txt | 11 +------ src/devices/fakebot/fakebot.example.ini | 2 +- src/devices/ffmpeg/CMakeLists.txt | 2 +- .../frameGrabberCropper/CMakeLists.txt | 2 +- src/devices/opencv/CMakeLists.txt | 2 +- src/devices/usbCamera/CMakeLists.txt | 4 +-- .../fakeFrameGrabber/fakeFrameGrabber.xml | 4 +-- tests/devices/grabber_basic.ini | 2 +- 13 files changed, 35 insertions(+), 36 deletions(-) diff --git a/.ci/initial-cache.gh.linux.cmake b/.ci/initial-cache.gh.linux.cmake index b1cf74d92f4..a6a3e2f8d4c 100644 --- a/.ci/initial-cache.gh.linux.cmake +++ b/.ci/initial-cache.gh.linux.cmake @@ -37,6 +37,8 @@ set(ENABLE_yarpmod_fakeMotionControl ON CACHE BOOL "") set(ENABLE_yarpmod_fakeAnalogSensor ON CACHE BOOL "") set(ENABLE_yarpmod_fakeBattery ON CACHE BOOL "") set(ENABLE_yarpmod_fakeIMU ON CACHE BOOL "") +set(ENABLE_yarpmod_frameGrabberCropper ON CACHE BOOL "") + set(ENABLE_yarpmod_SerialServoBoard ON CACHE BOOL "") set(ENABLE_yarpmod_ffmpeg_grabber ON CACHE BOOL "") set(ENABLE_yarpmod_ffmpeg_writer ON CACHE BOOL "") @@ -90,8 +92,8 @@ set(ENABLE_yarpmod_pipe ON CACHE BOOL "") set(ENABLE_yarpmod_serial ON CACHE BOOL "") set(ENABLE_yarpmod_fakeMotor ON CACHE BOOL "") set(ENABLE_yarpmod_test_motor ON CACHE BOOL "") -set(ENABLE_yarpmod_remote_grabber ON CACHE BOOL "") set(ENABLE_yarpmod_frameGrabber_nwc_yarp ON CACHE BOOL "") +set(ENABLE_yarpmod_frameGrabber_nws_yarp ON CACHE BOOL "") set(ENABLE_yarpmod_remote_controlboard ON CACHE BOOL "") set(ENABLE_yarpmod_analogsensorclient ON CACHE BOOL "") set(ENABLE_yarpmod_analogServer ON CACHE BOOL "") @@ -104,7 +106,6 @@ set(ENABLE_yarpmod_controlboardremapper ON CACHE BOOL "") set(ENABLE_yarpmod_remotecontrolboardremapper ON CACHE BOOL "") set(ENABLE_yarpmod_robotDescriptionClient ON CACHE BOOL "") set(ENABLE_yarpmod_robotDescriptionServer ON CACHE BOOL "") -set(ENABLE_yarpmod_grabberDual ON CACHE BOOL "") set(ENABLE_yarpmod_JoypadControlClient ON CACHE BOOL "") set(ENABLE_yarpmod_JoypadControlServer ON CACHE BOOL "") set(ENABLE_yarpmod_portaudio OFF CACHE BOOL "") diff --git a/doc/module_devices/note_devices.dox b/doc/module_devices/note_devices.dox index ca6226fd870..b10dc07f3ff 100644 --- a/doc/module_devices/note_devices.dox +++ b/doc/module_devices/note_devices.dox @@ -319,7 +319,7 @@ we do: Once we've reached this point, some fun things become possible. For example: \code - Property config("(device grabberDual) (subdevice fakey) (w 640) (h 480)"); + Property config("(device frameGrabber_nws_yarp) (subdevice fakey) (w 640) (h 480)"); PolyDriver dd(config); ... \endcode diff --git a/doc/module_executables/cmd_yarpdev.dox b/doc/module_executables/cmd_yarpdev.dox index 71615289e40..592213a0e32 100644 --- a/doc/module_executables/cmd_yarpdev.dox +++ b/doc/module_executables/cmd_yarpdev.dox @@ -106,7 +106,7 @@ $ yarpdev --device fakeFrameGrabber --period 0.5 --width 640 --height 480 \endverbatim was automatically expanded to: \verbatim -$ yarpdev --device grabberDual --subdevice fakeFrameGrabber --period 0.5 --width 640 --height 480 +$ yarpdev --device frameGrabber_nws_yarp --subdevice fakeFrameGrabber --period 0.5 --width 640 --height 480 \endverbatim \section yarpdev_verbose yarpdev --verbose --device DEVICENAME ... diff --git a/example/plugin/userlib/fake_grabber/CMakeLists.txt b/example/plugin/userlib/fake_grabber/CMakeLists.txt index 2f51a5c57f5..a4805b0e930 100644 --- a/example/plugin/userlib/fake_grabber/CMakeLists.txt +++ b/example/plugin/userlib/fake_grabber/CMakeLists.txt @@ -14,7 +14,7 @@ yarp_prepare_plugin(fake_grabber CATEGORY device TYPE FakeFrameGrabber INCLUDE FakeFrameGrabber.h - EXTRA_CONFIG WRAPPER=grabberDual + EXTRA_CONFIG WRAPPER=frameGrabber_nws_yarp ) if(NOT SKIP_fake_grabber) diff --git a/src/devices/README.md b/src/devices/README.md index 0789a30a9c7..4573c211193 100644 --- a/src/devices/README.md +++ b/src/devices/README.md @@ -47,9 +47,10 @@ The tables shown hereunder report all the information needed to understand the f * ![#ffff00](https://via.placeholder.com/15/ffff00/000000?text=+) controlboardremapper * ![#ffff00](https://via.placeholder.com/15/ffff00/000000?text=+) remotecontrolboardremapper -* ControlBoardWrapper - * ![#cc6600](https://via.placeholder.com/15/cc6600/000000?text=+) *controlboardwrapper2* +* controlBoard_nws_yarp * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) controlBoard_nws_yarp + +* controlBoard_nws_ros * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) controlBoard_nws_ros * DeviceGroup @@ -74,8 +75,10 @@ The tables shown hereunder report all the information needed to understand the f * RGBDSensorClient * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **RGBDSensorClient** -* RGBDSensorWrapper +* rgbdSensor_nws_ros * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) rgbdSensor_nws_ros + +* rgbdSensor_nws_yarp * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) rgbdSensor_nws_yarp * Rangefinder2DClient @@ -90,9 +93,15 @@ The tables shown hereunder report all the information needed to understand the f * RemoteControlBoard * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **remote_controlboard** -* RemoteFrameGrabber +* frameGrabber_nwc_yarp * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nwc_yarp +* frameGrabber_nws_yarp + * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nws_yarp + +* frameGrabber_nws_ros + * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nws_ros + * RobotDescriptionClient * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) **robotDescriptionClient** @@ -108,11 +117,6 @@ The tables shown hereunder report all the information needed to understand the f * ServerFrameGrabber * ![#882200](https://via.placeholder.com/15/882200/000000?text=+) ~~grabber~~ -* ServerFrameGrabberDual - * ![#cc6600](https://via.placeholder.com/15/cc6600/000000?text=+) *grabberDual* - * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nws_yarp - * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) frameGrabber_nws_ros - * ServerSerial * ![#ffff00](https://via.placeholder.com/15/ffff00/000000?text=+) serial @@ -155,7 +159,6 @@ The tables shown hereunder report all the information needed to understand the f * fakeFrameGrabber * ![#ffff00](https://via.placeholder.com/15/ffff00/000000?text=+) fakeFrameGrabber - * ![#cc6600](https://via.placeholder.com/15/cc6600/000000?text=+) *test_grabber* * fakeIMU * ![#ffff00](https://via.placeholder.com/15/ffff00/000000?text=+) fakeIMU @@ -238,15 +241,19 @@ The tables shown hereunder report all the information needed to understand the f * localization2DClient * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) localization2D_nwc_yarp -* localization2DServer +* localization2D_nws_yarp * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) localization2D_nws_yarp + +* localization2D_nws_ros * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) localization2D_nws_ros * map2DClient * ![#00ff00](https://via.placeholder.com/15/00ff00/000000?text=+) map2D_nwc_yarp -* map2DServer +* map2D_nws_yarp * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) map2D_nws_yarp + +* map2D_nws_ros * ![#00ffff](https://via.placeholder.com/15/00ffff/000000?text=+) map2D_nws_ros * map2DStorage diff --git a/src/devices/fakeFrameGrabber/CMakeLists.txt b/src/devices/fakeFrameGrabber/CMakeLists.txt index 446414a74a0..2a6c453c056 100644 --- a/src/devices/fakeFrameGrabber/CMakeLists.txt +++ b/src/devices/fakeFrameGrabber/CMakeLists.txt @@ -6,19 +6,10 @@ yarp_prepare_plugin(fakeFrameGrabber TYPE FakeFrameGrabber INCLUDE FakeFrameGrabber.h EXTRA_CONFIG - WRAPPER=grabberDual + WRAPPER=frameGrabber_nws_yarp DEFAULT ON ) -yarp_prepare_plugin(test_grabber - CATEGORY device - TYPE TestFrameGrabber - INCLUDE FakeFrameGrabber.h - EXTRA_CONFIG - WRAPPER=grabberDual - DEFAULT OFF - DEPENDS "NOT YARP_NO_DEPRECATED") # DEPRECATED Since YARP 3.5 - if(ENABLE_fakeFrameGrabber) yarp_add_plugin(yarp_fakeFrameGrabber) diff --git a/src/devices/fakebot/fakebot.example.ini b/src/devices/fakebot/fakebot.example.ini index c1a6dca774e..00836c81e2f 100644 --- a/src/devices/fakebot/fakebot.example.ini +++ b/src/devices/fakebot/fakebot.example.ini @@ -9,7 +9,7 @@ sx 1.0 sy 1.0 [part grab] -device grabberDual +device frameGrabber_nws_yarp subdevice robot name /fakebot/camera diff --git a/src/devices/ffmpeg/CMakeLists.txt b/src/devices/ffmpeg/CMakeLists.txt index a0b090d50c7..e79f9fae6a6 100644 --- a/src/devices/ffmpeg/CMakeLists.txt +++ b/src/devices/ffmpeg/CMakeLists.txt @@ -7,7 +7,7 @@ yarp_prepare_plugin(ffmpeg_grabber TYPE FfmpegGrabber INCLUDE FfmpegGrabber.h EXTRA_CONFIG - WRAPPER=grabberDual + WRAPPER=frameGrabber_nws_yarp DEPENDS "YARP_HAS_FFMPEG;FFMPEG_avcodec_FOUND;FFMPEG_avformat_FOUND;FFMPEG_avdevice_FOUND;FFMPEG_avutil_FOUND;FFMPEG_swscale_FOUND" ) diff --git a/src/devices/frameGrabberCropper/CMakeLists.txt b/src/devices/frameGrabberCropper/CMakeLists.txt index 32ed7ea6119..c8ffd4f5606 100644 --- a/src/devices/frameGrabberCropper/CMakeLists.txt +++ b/src/devices/frameGrabberCropper/CMakeLists.txt @@ -6,7 +6,7 @@ yarp_prepare_plugin(frameGrabberCropper TYPE FrameGrabberCropper INCLUDE frameGrabberCropper.h EXTRA_CONFIG - WRAPPER=grabberDual + WRAPPER=frameGrabber_nws_yarp DEFAULT ON ) diff --git a/src/devices/opencv/CMakeLists.txt b/src/devices/opencv/CMakeLists.txt index c2f2c39a371..dda0100a1fc 100644 --- a/src/devices/opencv/CMakeLists.txt +++ b/src/devices/opencv/CMakeLists.txt @@ -7,7 +7,7 @@ yarp_prepare_plugin(opencv_grabber TYPE OpenCVGrabber INCLUDE OpenCVGrabber.h EXTRA_CONFIG - WRAPPER=grabberDual + WRAPPER=frameGrabber_nws_yarp DEPENDS "YARP_HAS_OpenCV" ) diff --git a/src/devices/usbCamera/CMakeLists.txt b/src/devices/usbCamera/CMakeLists.txt index 443e707fbe2..28a4f166325 100644 --- a/src/devices/usbCamera/CMakeLists.txt +++ b/src/devices/usbCamera/CMakeLists.txt @@ -6,7 +6,7 @@ yarp_prepare_plugin(usbCamera TYPE USBCameraDriverRgb INCLUDE common/USBcamera.h EXTRA_CONFIG - WRAPPER=grabberDual + WRAPPER=frameGrabber_nws_yarp DEPENDS "UNIX;NOT APPLE;YARP_HAS_Libv4l2;YARP_HAS_Libv4lconvert;YARP_HAS_OpenCV" ) @@ -15,7 +15,7 @@ yarp_prepare_plugin(usbCameraRaw TYPE USBCameraDriverRaw INCLUDE common/USBcamera.h EXTRA_CONFIG - WRAPPER=grabberDual + WRAPPER=frameGrabber_nws_yarp DEPENDS "UNIX;NOT APPLE;YARP_HAS_Libv4l2;YARP_HAS_Libv4lconvert;YARP_HAS_OpenCV" ) diff --git a/src/yarprobotinterface/tests/fakeFrameGrabber/fakeFrameGrabber.xml b/src/yarprobotinterface/tests/fakeFrameGrabber/fakeFrameGrabber.xml index 0b67c7801cb..a707ba3b397 100644 --- a/src/yarprobotinterface/tests/fakeFrameGrabber/fakeFrameGrabber.xml +++ b/src/yarprobotinterface/tests/fakeFrameGrabber/fakeFrameGrabber.xml @@ -22,7 +22,7 @@ grid - + /left 33 @@ -31,7 +31,7 @@ - --> + /right 33 diff --git a/tests/devices/grabber_basic.ini b/tests/devices/grabber_basic.ini index 69d561045f3..4ea31e223b3 100644 --- a/tests/devices/grabber_basic.ini +++ b/tests/devices/grabber_basic.ini @@ -1,5 +1,5 @@ # start up a network wrapper around a fakeFrameGrabber -device grabberDual +device frameGrabber_nws_yarp subdevice fakeFrameGrabber width 640 height 480 From 023097c876111d39019baa1be014b2f2977498be Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 20:19:41 +0100 Subject: [PATCH 054/267] added changelog --- doc/release/master/device_dualGrabber_removed.md | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 doc/release/master/device_dualGrabber_removed.md diff --git a/doc/release/master/device_dualGrabber_removed.md b/doc/release/master/device_dualGrabber_removed.md new file mode 100644 index 00000000000..4df0bc34db6 --- /dev/null +++ b/doc/release/master/device_dualGrabber_removed.md @@ -0,0 +1,6 @@ +device_dualGrabber_removed {#master} +----------- + +### `Devices` + +* device `dualGrabber` and device `remote_grabber`, previously deprecated, have been removed. From d60e55810c9a6c9ec6ae2d628c0d479ae38fda15 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 20:26:10 +0100 Subject: [PATCH 055/267] fixed race condition in FakeMotionControl --- src/devices/fakeMotionControl/fakeMotionControl.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/devices/fakeMotionControl/fakeMotionControl.cpp b/src/devices/fakeMotionControl/fakeMotionControl.cpp index 04e21fcda8c..57a06cfeefa 100644 --- a/src/devices/fakeMotionControl/fakeMotionControl.cpp +++ b/src/devices/fakeMotionControl/fakeMotionControl.cpp @@ -35,6 +35,8 @@ YARP_LOG_COMPONENT(FAKEMOTIONCONTROL, "yarp.device.fakeMotionControl") void FakeMotionControl::run() { + std::lock_guard lock(_mutex); + for (int i=0;i <_njoints ;i++) { if (_controlModes[i] == VOCAB_CM_VELOCITY) @@ -1476,6 +1478,10 @@ bool FakeMotionControl::fromConfig(yarp::os::Searchable &config) bool FakeMotionControl::close() { + std::lock_guard lock(_mutex); + + this->yarp::os::PeriodicThread::stop(); + yCTrace(FAKEMOTIONCONTROL) << " close()"; ImplementControlMode::uninitialize(); From 1e843f498b3f6111071eea288e99b1efe4bd0420 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 20:34:46 +0100 Subject: [PATCH 056/267] TO BE REVERTED: temporary disabled frameTransformClient frameTransformServer transformClient transformServer tests --- src/devices/frameTransformClient/CMakeLists.txt | 6 +++--- src/devices/frameTransformServer/CMakeLists.txt | 6 +++--- src/devices/transformClient/CMakeLists.txt | 6 +++--- src/devices/transformServer/CMakeLists.txt | 6 +++--- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/devices/frameTransformClient/CMakeLists.txt b/src/devices/frameTransformClient/CMakeLists.txt index b3c2a8f5506..b083392e534 100644 --- a/src/devices/frameTransformClient/CMakeLists.txt +++ b/src/devices/frameTransformClient/CMakeLists.txt @@ -66,8 +66,8 @@ if(NOT SKIP_frameTransformClient) set_property(TARGET yarp_frameTransformClient PROPERTY FOLDER "Plugins/Device") - if(YARP_COMPILE_TESTS) - add_subdirectory(tests) - endif() +# if(YARP_COMPILE_TESTS) +# add_subdirectory(tests) +# endif() endif() diff --git a/src/devices/frameTransformServer/CMakeLists.txt b/src/devices/frameTransformServer/CMakeLists.txt index 21f559977fa..67638190284 100644 --- a/src/devices/frameTransformServer/CMakeLists.txt +++ b/src/devices/frameTransformServer/CMakeLists.txt @@ -60,8 +60,8 @@ if(NOT SKIP_frameTransformServer) set_property(TARGET yarp_frameTransformServer PROPERTY FOLDER "Plugins/Device") - if(YARP_COMPILE_TESTS) - add_subdirectory(tests) - endif() +# if(YARP_COMPILE_TESTS) +# add_subdirectory(tests) +# endif() endif() diff --git a/src/devices/transformClient/CMakeLists.txt b/src/devices/transformClient/CMakeLists.txt index e786be42cb5..d79c74a5d21 100644 --- a/src/devices/transformClient/CMakeLists.txt +++ b/src/devices/transformClient/CMakeLists.txt @@ -45,8 +45,8 @@ if(NOT SKIP_transformClient) set_property(TARGET yarp_transformClient PROPERTY FOLDER "Plugins/Device") - if(YARP_COMPILE_TESTS) - add_subdirectory(tests) - endif() +# if(YARP_COMPILE_TESTS) +# add_subdirectory(tests) +# endif() endif() diff --git a/src/devices/transformServer/CMakeLists.txt b/src/devices/transformServer/CMakeLists.txt index 662aec4bdf4..367a1e76b82 100644 --- a/src/devices/transformServer/CMakeLists.txt +++ b/src/devices/transformServer/CMakeLists.txt @@ -47,8 +47,8 @@ if(NOT SKIP_transformServer) set_property(TARGET yarp_transformServer PROPERTY FOLDER "Plugins/Device") - if(YARP_COMPILE_TESTS) - add_subdirectory(tests) - endif() +# if(YARP_COMPILE_TESTS) +# add_subdirectory(tests) +# endif() endif() From 6eb66a9835a981df9a3ff06891e33985dd08b9e8 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 21:43:49 +0100 Subject: [PATCH 057/267] `depthCamera` device renamed to `openNI2DepthCamera` --- src/devices/CMakeLists.txt | 2 +- .../CMakeLists.txt | 20 +++++++++---------- .../depthCameraDriver.cpp | 0 .../depthCameraDriver.h | 0 4 files changed, 11 insertions(+), 11 deletions(-) rename src/devices/{depthCamera => openNI2DepthCamera}/CMakeLists.txt (64%) rename src/devices/{depthCamera => openNI2DepthCamera}/depthCameraDriver.cpp (100%) rename src/devices/{depthCamera => openNI2DepthCamera}/depthCameraDriver.h (100%) diff --git a/src/devices/CMakeLists.txt b/src/devices/CMakeLists.txt index 0c4d1a8b79c..1bca7d002a9 100644 --- a/src/devices/CMakeLists.txt +++ b/src/devices/CMakeLists.txt @@ -14,7 +14,7 @@ yarp_begin_plugin_library(yarpmod add_subdirectory(audioRecorderWrapper) add_subdirectory(audioFromFileDevice) add_subdirectory(audioToFileDevice) - add_subdirectory(depthCamera) + add_subdirectory(openNI2DepthCamera) add_subdirectory(fakeDepthCamera) add_subdirectory(fakebot) add_subdirectory(fakeMotionControl) diff --git a/src/devices/depthCamera/CMakeLists.txt b/src/devices/openNI2DepthCamera/CMakeLists.txt similarity index 64% rename from src/devices/depthCamera/CMakeLists.txt rename to src/devices/openNI2DepthCamera/CMakeLists.txt index 1300525fc64..7309f84e986 100644 --- a/src/devices/depthCamera/CMakeLists.txt +++ b/src/devices/openNI2DepthCamera/CMakeLists.txt @@ -1,25 +1,25 @@ # SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) # SPDX-License-Identifier: BSD-3-Clause -yarp_prepare_plugin(depthCamera +yarp_prepare_plugin(openNI2DepthCamera CATEGORY device TYPE depthCameraDriver INCLUDE depthCameraDriver.h EXTRA_CONFIG - WRAPPER=RGBDSensorWrapper + WRAPPER=rgbdSensor_nws_yarp DEPENDS "YARP_HAS_OpenNI2" ) -if(ENABLE_depthCamera) - yarp_add_plugin(yarp_depthCamera) +if(ENABLE_openNI2DepthCamera) + yarp_add_plugin(yarp_openNI2DepthCamera) - target_sources(yarp_depthCamera + target_sources(yarp_openNI2DepthCamera PRIVATE depthCameraDriver.cpp depthCameraDriver.h ) - target_link_libraries(yarp_depthCamera + target_link_libraries(yarp_openNI2DepthCamera PRIVATE YARP::YARP_os YARP::YARP_sig @@ -31,12 +31,12 @@ if(ENABLE_depthCamera) YARP_dev ) - target_include_directories(yarp_depthCamera SYSTEM PRIVATE ${OpenNI2_INCLUDE_DIRS}) - target_link_libraries(yarp_depthCamera PRIVATE ${OpenNI2_LIBRARIES}) + target_include_directories(yarp_openNI2DepthCamera SYSTEM PRIVATE ${OpenNI2_INCLUDE_DIRS}) + target_link_libraries(yarp_openNI2DepthCamera PRIVATE ${OpenNI2_LIBRARIES}) # list(APPEND YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS OpenNI2) (not using targets) yarp_install( - TARGETS yarp_depthCamera + TARGETS yarp_openNI2DepthCamera EXPORT YARP_${YARP_PLUGIN_MASTER} COMPONENT ${YARP_PLUGIN_MASTER} LIBRARY DESTINATION ${YARP_DYNAMIC_PLUGINS_INSTALL_DIR} @@ -46,5 +46,5 @@ if(ENABLE_depthCamera) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) - set_property(TARGET yarp_depthCamera PROPERTY FOLDER "Plugins/Device") + set_property(TARGET yarp_openNI2DepthCamera PROPERTY FOLDER "Plugins/Device") endif() diff --git a/src/devices/depthCamera/depthCameraDriver.cpp b/src/devices/openNI2DepthCamera/depthCameraDriver.cpp similarity index 100% rename from src/devices/depthCamera/depthCameraDriver.cpp rename to src/devices/openNI2DepthCamera/depthCameraDriver.cpp diff --git a/src/devices/depthCamera/depthCameraDriver.h b/src/devices/openNI2DepthCamera/depthCameraDriver.h similarity index 100% rename from src/devices/depthCamera/depthCameraDriver.h rename to src/devices/openNI2DepthCamera/depthCameraDriver.h From ca6a7dcbc36552ed0c5ce2442190b15ab3b7d5c9 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 21:45:05 +0100 Subject: [PATCH 058/267] added tests for `fakeDepthCamera` device --- src/devices/fakeDepthCamera/CMakeLists.txt | 5 ++ .../fakeDepthCamera/tests/CMakeLists.txt | 41 +++++++++++++++ .../tests/fakeDepthCameraTest.cpp | 51 +++++++++++++++++++ src/libYARP_dev/src/CMakeLists.txt | 4 ++ .../src/yarp/dev/tests/IRGBDSensorTest.cpp | 6 +++ .../src/yarp/dev/tests/IRGBDSensorTest.h | 30 +++++++++++ 6 files changed, 137 insertions(+) create mode 100644 src/devices/fakeDepthCamera/tests/CMakeLists.txt create mode 100644 src/devices/fakeDepthCamera/tests/fakeDepthCameraTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.cpp create mode 100644 src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.h diff --git a/src/devices/fakeDepthCamera/CMakeLists.txt b/src/devices/fakeDepthCamera/CMakeLists.txt index b7a4249cb3a..c8d4f6ded2f 100644 --- a/src/devices/fakeDepthCamera/CMakeLists.txt +++ b/src/devices/fakeDepthCamera/CMakeLists.txt @@ -42,4 +42,9 @@ if(ENABLE_fakeDepthCamera) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_fakeDepthCamera PROPERTY FOLDER "Plugins/Device/Fake") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/fakeDepthCamera/tests/CMakeLists.txt b/src/devices/fakeDepthCamera/tests/CMakeLists.txt new file mode 100644 index 00000000000..bf48028f38c --- /dev/null +++ b/src/devices/fakeDepthCamera/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_fakeDepthCamera) + +target_sources(harness_dev_fakeDepthCamera + PRIVATE + fakeDepthCameraTest.cpp +) + +target_link_libraries(harness_dev_fakeDepthCamera + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_fakeDepthCamera PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_fakeDepthCamera) diff --git a/src/devices/fakeDepthCamera/tests/fakeDepthCameraTest.cpp b/src/devices/fakeDepthCamera/tests/fakeDepthCameraTest.cpp new file mode 100644 index 00000000000..9e38ad2c33e --- /dev/null +++ b/src/devices/fakeDepthCamera/tests/fakeDepthCameraTest.cpp @@ -0,0 +1,51 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +using namespace yarp::os; +using namespace yarp::dev; +using namespace yarp::sig; + + +TEST_CASE("dev::fakeDepthCameraTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeDepthCamera", "device"); + + Network::setLocalMode(true); + + SECTION("Test the IFrameGrabberImage interface") + { + // Open the device + PolyDriver dd; + Property p; + p.put("device", "fakeDepthCamera"); + REQUIRE(dd.open(p)); + + // Get the IFrameGrabberImage interface + IRGBDSensor* irgbd = nullptr; + REQUIRE(dd.view(irgbd)); + + yarp::dev::tests::exec_iRGBDSensor_test_1(irgbd); + + // Close the device + CHECK(dd.close()); + } + + Network::setLocalMode(false); +} diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index 8af4eec60c3..26a7ad79b73 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -422,6 +422,8 @@ target_sources(YARP_dev_tests yarp/dev/tests/IAxisInfoTest.h yarp/dev/tests/IOrientationSensorsTest.cpp yarp/dev/tests/IOrientationSensorsTest.h + yarp/dev/tests/IRGBDSensorTest.cpp + yarp/dev/tests/IRGBDSensorTest.h ) else() target_sources(YARP_dev_tests @@ -434,6 +436,8 @@ target_sources(YARP_dev_tests yarp/dev/tests/ITorqueControlTest.h yarp/dev/tests/IAxisInfoTest.cpp yarp/dev/tests/IAxisInfoTest.h + yarp/dev/tests/IRGBDSensorTest.cpp + yarp/dev/tests/IRGBDSensorTest.h ) endif() diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.cpp b/src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.cpp new file mode 100644 index 00000000000..8c1b8351ef5 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.cpp @@ -0,0 +1,6 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "IRGBDSensorTest.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.h b/src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.h new file mode 100644 index 00000000000..3863e4b0f32 --- /dev/null +++ b/src/libYARP_dev/src/yarp/dev/tests/IRGBDSensorTest.h @@ -0,0 +1,30 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef IRGBDSENSORTEST_H +#define IRGBDSENSORTEST_H + +#include +#include + +using namespace yarp::dev; +using namespace yarp::os; + +namespace yarp::dev::tests +{ + inline void exec_iRGBDSensor_test_1(IRGBDSensor* irgbd) + { + REQUIRE(irgbd != nullptr); + + int w=0; + int h=0; + w = irgbd->getDepthWidth(); + h = irgbd->getDepthHeight(); + CHECK(w > 0); + CHECK(h > 0); + } +} + +#endif From e2a1bc631da1f7edb21ba1ffb5d0fce14f481e2c Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 21:46:04 +0100 Subject: [PATCH 059/267] Added some extra info messages to some tests, hopefully fixing some valgrind failures --- .../tests/Rangefinder2DClientTest.cpp | 8 ++++++++ .../tests/Rangefinder2D_nwc_yarpTest.cpp | 11 +++++++++++ .../tests/MultipleAnalogSensorsClientTest.cpp | 12 +++++++++++- 3 files changed, 30 insertions(+), 1 deletion(-) diff --git a/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp b/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp index 234e9716999..61e918ff92d 100644 --- a/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp +++ b/src/devices/Rangefinder2DClient/tests/Rangefinder2DClientTest.cpp @@ -68,9 +68,17 @@ TEST_CASE("dev::Rangefinder2DClientTest", "[yarp::dev]") //Close all polydrivers and check CHECK(ddnwc.close()); yarp::os::Time::delay(0.1); + INFO("Rangefinder2DClient closed"); + CHECK(ddnws.close()); yarp::os::Time::delay(0.1); + INFO("rangefinder2D_nws_yarp closed"); + CHECK(ddlas.close()); + yarp::os::Time::delay(0.1); + INFO("fakeLaser closed"); + + INFO("Test complete"); } Network::setLocalMode(false); diff --git a/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp b/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp index cd50048ab94..4bce9114e03 100644 --- a/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp +++ b/src/devices/Rangefinder2D_nwc_yarp/tests/Rangefinder2D_nwc_yarpTest.cpp @@ -52,6 +52,9 @@ TEST_CASE("dev::rangefinder2D_nwc_yarp", "[yarp::dev]") bool result_att = ww_nws->attach(&ddlas); REQUIRE(result_att); } + //wait some time + yarp::os::Time::delay(0.1); + //create the client { Property pnwc_cfg; @@ -68,9 +71,17 @@ TEST_CASE("dev::rangefinder2D_nwc_yarp", "[yarp::dev]") //Close all polydrivers and check CHECK(ddnwc.close()); yarp::os::Time::delay(0.1); + INFO("rangefinder2D_nwc_yarp closed"); + CHECK(ddnws.close()); yarp::os::Time::delay(0.1); + INFO("rangefinder2D_nws_yarp closed"); + CHECK(ddlas.close()); + yarp::os::Time::delay(0.1); + INFO("fakeLaser closed"); + + INFO("Test complete"); } Network::setLocalMode(false); diff --git a/src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp b/src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp index 6bd6ef99737..ba8f99f5cee 100644 --- a/src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp +++ b/src/devices/multipleanalogsensorsclient/tests/MultipleAnalogSensorsClientTest.cpp @@ -22,7 +22,7 @@ using namespace yarp::os; using namespace yarp::dev; -TEST_CASE("dev::MultipleAnalogSensorsInterfacesTest", "[yarp::dev]") +TEST_CASE("dev::MultipleAnalogSensorsClientTest", "[yarp::dev]") { YARP_REQUIRE_PLUGIN("fakeIMU", "device"); YARP_REQUIRE_PLUGIN("multipleanalogsensorsserver", "device"); @@ -87,9 +87,19 @@ TEST_CASE("dev::MultipleAnalogSensorsInterfacesTest", "[yarp::dev]") // Close devices client.close(); + INFO("multipleanalogsensorsclient closed"); + yarp::os::Time::delay(0.1); + iwrap->detachAll(); wrapper.close(); + INFO("multipleanalogsensorsserver closed"); + yarp::os::Time::delay(0.1); + imuSensor.close(); + INFO("fakeIMU closed"); + yarp::os::Time::delay(0.1); + + INFO("Test complete"); } Network::setLocalMode(false); From 9e085fd1aafaaf64d64d124d84190ff625c34b40 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 29 Nov 2022 22:20:18 +0100 Subject: [PATCH 060/267] added tests for rgbdSensor_nws_yarp and RGBDSensorClient devices --- src/devices/RGBDSensorClient/CMakeLists.txt | 5 + .../RGBDSensorClient/tests/CMakeLists.txt | 41 +++++++++ .../tests/RGBDSensorClientTest.cpp | 91 +++++++++++++++++++ .../RGBDSensor_nws_yarp/CMakeLists.txt | 5 + .../RGBDSensor_nws_yarp/tests/CMakeLists.txt | 53 +++++++++++ .../tests/RGBDSensor_nws_yarpTest.cpp | 43 +++++++++ 6 files changed, 238 insertions(+) create mode 100644 src/devices/RGBDSensorClient/tests/CMakeLists.txt create mode 100644 src/devices/RGBDSensorClient/tests/RGBDSensorClientTest.cpp create mode 100644 src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt create mode 100644 src/devices/RGBDSensor_nws_yarp/tests/RGBDSensor_nws_yarpTest.cpp diff --git a/src/devices/RGBDSensorClient/CMakeLists.txt b/src/devices/RGBDSensorClient/CMakeLists.txt index 02e9ca5a37e..ef5da194c55 100644 --- a/src/devices/RGBDSensorClient/CMakeLists.txt +++ b/src/devices/RGBDSensorClient/CMakeLists.txt @@ -48,4 +48,9 @@ if(NOT SKIP_RGBDSensorClient) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_RGBDSensorClient PROPERTY FOLDER "Plugins/Device") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/RGBDSensorClient/tests/CMakeLists.txt b/src/devices/RGBDSensorClient/tests/CMakeLists.txt new file mode 100644 index 00000000000..287fc31096e --- /dev/null +++ b/src/devices/RGBDSensorClient/tests/CMakeLists.txt @@ -0,0 +1,41 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_RGBDSensorClient) + +target_sources(harness_dev_RGBDSensorClient + PRIVATE + RGBDSensorClientTest.cpp +) + +target_link_libraries(harness_dev_RGBDSensorClient + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +set_property(TARGET harness_dev_RGBDSensorClient PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_RGBDSensorClient) diff --git a/src/devices/RGBDSensorClient/tests/RGBDSensorClientTest.cpp b/src/devices/RGBDSensorClient/tests/RGBDSensorClientTest.cpp new file mode 100644 index 00000000000..b2bff6fd7b8 --- /dev/null +++ b/src/devices/RGBDSensorClient/tests/RGBDSensorClientTest.cpp @@ -0,0 +1,91 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::RGBDSensorClientTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeDepthCamera", "device"); + YARP_REQUIRE_PLUGIN("rgbdSensor_nws_yarp", "device"); + YARP_REQUIRE_PLUGIN("RGBDSensorClient", "device"); + + Network::setLocalMode(true); + + SECTION("Checking RGBDSensorClient device") + { + PolyDriver dddepth; + PolyDriver ddnws; + PolyDriver ddnwc; + IRGBDSensor* irgbd = nullptr; + + ////////"Checking opening polydriver" + { + Property pdepth_cfg; + pdepth_cfg.put("device", "fakeDepthCamera"); + REQUIRE(dddepth.open(pdepth_cfg)); + } + { + Property pnws_cfg; + pnws_cfg.put("device", "rgbdSensor_nws_yarp"); + pnws_cfg.put("name", "/rgbd_nws"); + REQUIRE(ddnws.open(pnws_cfg)); + } + + //attach the nws to the fakeDepthCamera device + {yarp::dev::WrapperSingle* ww_nws; ddnws.view(ww_nws); + bool result_att = ww_nws->attach(&dddepth); + REQUIRE(result_att); } + + //wait some time + yarp::os::Time::delay(0.1); + + //create the client + { + Property pnwc_cfg; + pnwc_cfg.put("device", "RGBDSensorClient"); + pnwc_cfg.put("localImagePort", "/rgbd_nwc/rgbImage:i"); + pnwc_cfg.put("remoteImagePort", "/rgbd_nws/rgbImage:o"); + + pnwc_cfg.put("localDepthPort", "/rgbd_nwc/depthImage:i"); + pnwc_cfg.put("remoteDepthPort", "/rgbd_nws/depthImage:o"); + + pnwc_cfg.put("localRpcPort", "/rgbd_nwc/rpc:o"); + pnwc_cfg.put("remoteRpcPort", "/rgbd_nws/rpc:i"); + REQUIRE(ddnwc.open(pnwc_cfg)); + } + REQUIRE(ddnwc.view(irgbd)); + + //execute tests + yarp::dev::tests::exec_iRGBDSensor_test_1(irgbd); + + //Close all polydrivers and check + CHECK(ddnwc.close()); + yarp::os::Time::delay(0.1); + INFO("RGBDSensorClient closed"); + + CHECK(ddnws.close()); + yarp::os::Time::delay(0.1); + INFO("rgbdSensor_nws_yarp closed"); + + CHECK(dddepth.close()); + yarp::os::Time::delay(0.1); + INFO("fakeDepthCamera closed"); + + INFO("Test complete"); + } + + Network::setLocalMode(false); +} diff --git a/src/devices/RGBDSensor_nws_yarp/CMakeLists.txt b/src/devices/RGBDSensor_nws_yarp/CMakeLists.txt index 164512edf8c..b824359b33f 100644 --- a/src/devices/RGBDSensor_nws_yarp/CMakeLists.txt +++ b/src/devices/RGBDSensor_nws_yarp/CMakeLists.txt @@ -48,4 +48,9 @@ if(NOT SKIP_rgbdSensor_nws_yarp) set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE) set_property(TARGET yarp_rgbdSensor_nws_yarp PROPERTY FOLDER "Plugins/Device/NWS") + + if(YARP_COMPILE_TESTS) + add_subdirectory(tests) + endif() + endif() diff --git a/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt b/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt new file mode 100644 index 00000000000..d8c95931f47 --- /dev/null +++ b/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt @@ -0,0 +1,53 @@ +# SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) +# SPDX-License-Identifier: BSD-3-Clause + +######################################################################### +# Wrapper for the catch_discover_tests that also enables colors, and sets +# the TIMEOUT and SKIP_RETURN_CODE test properties. +include(Catch) +function(yarp_catch_discover_tests _target) + # Workaround to force catch_discover_tests to run tests under valgrind + set_property(TARGET ${_target} PROPERTY CROSSCOMPILING_EMULATOR "${YARP_TEST_LAUNCHER}") + catch_discover_tests( + ${_target} + EXTRA_ARGS "-s" "--use-colour" "yes" + PROPERTIES + TIMEOUT ${YARP_TEST_TIMEOUT} + SKIP_RETURN_CODE 254 + ) +endfunction() +######################################################################### + +find_package(YARP::YARP_dev_tests) + +add_executable(harness_dev_RGBDSensor_nws_yarp) + +target_sources(harness_dev_RGBDSensor_nws_yarp + PRIVATE + RGBDSensor_nws_yarpTest.cpp +) + +target_link_libraries(harness_dev_RGBDSensor_nws_yarp + PRIVATE + YARP_harness + YARP::YARP_os + YARP::YARP_sig + YARP::YARP_dev + YARP::YARP_dev_tests +) + +if(TARGET YARP::YARP_math) + target_link_libraries(harness_dev_RGBDSensor_nws_yarp + PRIVATE + YARP::YARP_math + ) +else() + set(_disabled_files + Rangefinder2D_nws_yarpTest.cpp + ) + set_source_files_properties(${_disabled_files} PROPERTIES HEADER_FILE_ONLY ON) +endif() + +set_property(TARGET harness_dev_RGBDSensor_nws_yarp PROPERTY FOLDER "Test") + +yarp_catch_discover_tests(harness_dev_RGBDSensor_nws_yarp) diff --git a/src/devices/RGBDSensor_nws_yarp/tests/RGBDSensor_nws_yarpTest.cpp b/src/devices/RGBDSensor_nws_yarp/tests/RGBDSensor_nws_yarpTest.cpp new file mode 100644 index 00000000000..2907d067c9c --- /dev/null +++ b/src/devices/RGBDSensor_nws_yarp/tests/RGBDSensor_nws_yarpTest.cpp @@ -0,0 +1,43 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include +#include +#include +#include + +#include +#include + +using namespace yarp::dev; +using namespace yarp::sig; +using namespace yarp::os; + +TEST_CASE("dev::Rangefinder2D_nws_yarpTest", "[yarp::dev]") +{ + YARP_REQUIRE_PLUGIN("fakeDepthCamera", "device"); + YARP_REQUIRE_PLUGIN("rgbdSensor_nws_yarp", "device"); + + Network::setLocalMode(true); + + SECTION("Checking rgbdSensor_nws_yarp device") + { + PolyDriver nws_driver; + + ////////"Checking opening polydriver" + { + Property nws_cfg; + nws_cfg.put("device", "rgbdSensor_nws_yarp"); + nws_cfg.put("name", "/rgbd_nws"); + REQUIRE(nws_driver.open(nws_cfg)); + } + + //Close all polydrivers and check + CHECK(nws_driver.close()); + } + + Network::setLocalMode(false); +} From e79a057f30ddcf90c670eead3ceee2637d441daf Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 30 Nov 2022 14:26:09 +0100 Subject: [PATCH 061/267] Improved thrift generator in order to handle default values of the variables declared inside a .thrift file. --- doc/release/master/improved_thrift_gen.md | 6 ++++++ src/yarpidl_thrift/src/t_yarp_generator.cc | 25 +++++++++++++++++----- 2 files changed, 26 insertions(+), 5 deletions(-) create mode 100644 doc/release/master/improved_thrift_gen.md diff --git a/doc/release/master/improved_thrift_gen.md b/doc/release/master/improved_thrift_gen.md new file mode 100644 index 00000000000..8502d5e7849 --- /dev/null +++ b/doc/release/master/improved_thrift_gen.md @@ -0,0 +1,6 @@ +improved_thrift_gen {#master} +----------- + +### `yarpidl_thrift` + +* Improved thrift generator in order to handle default values of the variables declared inside a .thrift file. diff --git a/src/yarpidl_thrift/src/t_yarp_generator.cc b/src/yarpidl_thrift/src/t_yarp_generator.cc index 48f06f630bb..6cda209dfb6 100644 --- a/src/yarpidl_thrift/src/t_yarp_generator.cc +++ b/src/yarpidl_thrift/src/t_yarp_generator.cc @@ -1763,7 +1763,6 @@ std::string t_yarp_generator::declare_field(t_field* tfield, result += prefix; result += tfield->get_name(); - if (init) { t_type* type = get_true_type(tfield->get_type()); @@ -1773,19 +1772,35 @@ std::string t_yarp_generator::declare_field(t_field* tfield, case t_base_type::TYPE_VOID: break; case t_base_type::TYPE_STRING: - result += "{}"; + if (tfield->get_value()) + result += "{\""+tfield->get_value()->get_string()+"\"}"; + else + result += "{}"; break; case t_base_type::TYPE_BOOL: - result += "{false}"; + if (tfield->get_value()) + { + int b=tfield->get_value()->get_integer(); + if (b==1) {result += "{true}";} + else {result += "{false}";} + } + else + result += "{false}"; break; case t_base_type::TYPE_I8: case t_base_type::TYPE_I16: case t_base_type::TYPE_I32: case t_base_type::TYPE_I64: - result += "{0}"; + if (tfield->get_value()) + result += "{"+ std::to_string(tfield->get_value()->get_integer())+"}"; + else + result += "{0}"; break; case t_base_type::TYPE_DOUBLE: - result += "{0.0}"; + if (tfield->get_value()) + result += "{"+ std::to_string(tfield->get_value()->get_double())+"}"; + else + result += "{0.0}"; break; default: throw "compiler error: no C++ initializer for base type " + t_base_type::t_base_name(tbase); From 76fe34dfd5bb6b07557a816116cf48ae35a0e279 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 30 Nov 2022 14:35:14 +0100 Subject: [PATCH 062/267] - Improved tests for IRangefinder2D - Fixed issue in LaserScan2D.thrift --- src/libYARP_dev/src/idl/LaserScan2D.thrift | 3 +- .../src/yarp/dev/tests/IRangefinder2DTest.h | 40 +++++++++++++------ 2 files changed, 29 insertions(+), 14 deletions(-) diff --git a/src/libYARP_dev/src/idl/LaserScan2D.thrift b/src/libYARP_dev/src/idl/LaserScan2D.thrift index 3bc580b501a..9d50ded0614 100644 --- a/src/libYARP_dev/src/idl/LaserScan2D.thrift +++ b/src/libYARP_dev/src/idl/LaserScan2D.thrift @@ -29,7 +29,8 @@ struct LaserScan2D /** the scan data, measured in [m]. The angular increment of each ray is obtained by (angle_max-angle_min)/num_of_elements. Invalid data are represented as std::inf. */ 5: YarpVector scans; - 6: i32 status; + /** the status of the device. See yarp::dev::IRangefinder2D::Device_status. The default value is DEVICE_TIMEOUT. */ + 6: i32 status=3; } ( yarp.api.include = "yarp/dev/api.h" diff --git a/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h index c77d1f39a47..82f357ab03a 100644 --- a/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h +++ b/src/libYARP_dev/src/yarp/dev/tests/IRangefinder2DTest.h @@ -21,6 +21,16 @@ namespace yarp::dev::tests bool b; + yarp::dev::IRangefinder2D::Device_status status; + for (size_t counter = 0; counter<10; counter++) + { + b = irf->getDeviceStatus(status); + CHECK(b); + if (status == yarp::dev::IRangefinder2D::Device_status::DEVICE_OK_IN_USE) break; + yarp::os::Time::delay(0.5); + } + CHECK(status == yarp::dev::IRangefinder2D::Device_status::DEVICE_OK_IN_USE); + std::string info; b = irf->getDeviceInfo(info); CHECK(b); @@ -31,11 +41,6 @@ namespace yarp::dev::tests CHECK(b); CHECK(scanrate==0.02); - yarp::dev::IRangefinder2D::Device_status status; - b = irf->getDeviceStatus(status); - CHECK(b); - CHECK(status== yarp::dev::IRangefinder2D::Device_status::DEVICE_OK_IN_USE); - double hstep; b = irf->getHorizontalResolution(hstep); CHECK(b); @@ -53,14 +58,23 @@ namespace yarp::dev::tests CHECK(b); CHECK(timestamp != 0); CHECK(las.size() == 360); - {double r,t; - las[0].get_polar(r, t); - CHECK(r == 0.5); - CHECK(t == 0);} - {double x,y; - las[0].get_cartesian(x, y); - CHECK(x == 0.5); - CHECK(y == 0);} + + //check the measurement values. + //REQUIRE is needed to prevent segfault if nothing is received. + { + REQUIRE(las.size() > 0); + double r,t; + las[0].get_polar(r, t); + CHECK(r == 0.5); + CHECK(t == 0); + } + { + REQUIRE(las.size() > 0); + double x,y; + las[0].get_cartesian(x, y); + CHECK(x == 0.5); + CHECK(y == 0); + } } } From b46623ba7b4c1e96e861adb8751ba049949c03cc Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 14 Dec 2022 14:58:02 +0100 Subject: [PATCH 063/267] Added check if getImage() method fails --- .../FrameGrabber_nws_yarp.cpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.cpp b/src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.cpp index 58828870b7d..2a89bafbb24 100644 --- a/src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.cpp +++ b/src/devices/frameGrabber_nws_yarp/FrameGrabber_nws_yarp.cpp @@ -266,19 +266,23 @@ void FrameGrabber_nws_yarp::run() if (cap == COLOR) { if (iFrameGrabberImage != nullptr) { - iFrameGrabberImage->getImage(*img); - flex_i.swap(*img); + if (iFrameGrabberImage->getImage(*img)) + {flex_i.swap(*img);} + else + {yCError(FRAMEGRABBER_NWS_YARP) << "Image not captured (getImage failed). Check hardware configuration.";} } else { - yCError(FRAMEGRABBER_NWS_YARP) << "Image not captured.. check hardware configuration"; + yCError(FRAMEGRABBER_NWS_YARP) << "Image not captured (invalid interface). Check hw/sw configuration."; } } if (cap == RAW) { if (iFrameGrabberImageRaw != nullptr) { - iFrameGrabberImageRaw->getImage(*img_Raw); - flex_i.swap(*img_Raw); + if (iFrameGrabberImageRaw->getImage(*img_Raw)) + {flex_i.swap(*img_Raw);} + else + {yCError(FRAMEGRABBER_NWS_YARP) << "Image not captured (getImage failed). Check hardware configuration.";} } else { - yCError(FRAMEGRABBER_NWS_YARP) << "Image not captured.. check hardware configuration"; + yCError(FRAMEGRABBER_NWS_YARP) << "Image not captured (invalid interface). Check hw/sw configuration."; } } From e9627ef2ce08c8f93a3bb7b74e28daa0a8053969 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 15 Dec 2022 13:23:34 +0100 Subject: [PATCH 064/267] Added visualization of motor position when a joint is in hardware fault --- .../master/yarpmotorgui_hwfault_motorpos.md | 6 ++++ src/yarpmotorgui/jointitem.cpp | 19 ++++++++++++ src/yarpmotorgui/jointitem.ui | 30 +++++++++++++++++-- 3 files changed, 52 insertions(+), 3 deletions(-) create mode 100644 doc/release/master/yarpmotorgui_hwfault_motorpos.md diff --git a/doc/release/master/yarpmotorgui_hwfault_motorpos.md b/doc/release/master/yarpmotorgui_hwfault_motorpos.md new file mode 100644 index 00000000000..001410fb9e1 --- /dev/null +++ b/doc/release/master/yarpmotorgui_hwfault_motorpos.md @@ -0,0 +1,6 @@ +yarpmotorgui_hwfault_motorpos {#master} +----------- + +### `yarpmotorgui` + +* Added visualization of motor position when a joint is in hardware fault diff --git a/src/yarpmotorgui/jointitem.cpp b/src/yarpmotorgui/jointitem.cpp index 514ef00406b..3f525e7bbd3 100644 --- a/src/yarpmotorgui/jointitem.cpp +++ b/src/yarpmotorgui/jointitem.cpp @@ -596,6 +596,9 @@ void JointItem::setUnits(yarp::dev::JointTypeEnum t) ui->labelVelocityposUnits->setText(pos_metric_revolute); ui->labelFaultposUnits->setText(pos_metric_revolute); + //ui->labelIdleMotorPosUnits->setText(pos_metric_revolute); + //ui->labelFaultMotorPosUnits->setText(pos_metric_revolute); + ui->labelIdletrqUnits->setText(trq_metric_revolute); ui->labelPositiontrqUnits->setText(trq_metric_revolute); ui->labelPositionDirtrqUnits->setText(trq_metric_revolute); @@ -635,6 +638,9 @@ void JointItem::setUnits(yarp::dev::JointTypeEnum t) ui->labelVelocityposUnits->setText(pos_metric_prism); ui->labelFaultposUnits->setText(pos_metric_prism); + //ui->labelIdleMotorPosUnits->setText(pos_metric_prism); + //ui->labelFaultMotorPosUnits->setText(pos_metric_prism); + ui->labelIdletrqUnits->setText(trq_metric_prism); ui->labelPositiontrqUnits->setText(trq_metric_prism); ui->labelPositionDirtrqUnits->setText(trq_metric_prism); @@ -661,6 +667,7 @@ void JointItem::setMotorPositionVisible(bool visible) ui->editPWMMotorPos->setVisible(visible); ui->editCurrentMotorPos->setVisible(visible); ui->editVelocityMotorPos->setVisible(visible); + ui->editFaultMotorPos->setVisible(visible); ui->labelIdleMotorPos->setVisible(visible); ui->labelPositionMotorPos->setVisible(visible); @@ -670,6 +677,7 @@ void JointItem::setMotorPositionVisible(bool visible) ui->labelPWMMotorPos->setVisible(visible); ui->labelCurrentMotorPos->setVisible(visible); ui->labelVelocityMotorPos->setVisible(visible); + ui->labelFaultMotorPos->setVisible(visible); ui->labelIdleMotorPosUnits->setVisible(visible); ui->labelPositionMotorPosUnits->setVisible(visible); @@ -679,6 +687,7 @@ void JointItem::setMotorPositionVisible(bool visible) ui->labelPWMMotorPosUnits->setVisible(visible); ui->labelCurrentMotorPosUnits->setVisible(visible); ui->labelVelocityMotorPosUnits->setVisible(visible); + ui->labelFaultMotorPosUnits->setVisible(visible); if (!visible) { ui->editIdleMotorPos->setMinimumHeight(0); @@ -689,6 +698,7 @@ void JointItem::setMotorPositionVisible(bool visible) ui->editPWMMotorPos->setMinimumHeight(0); ui->editCurrentMotorPos->setMinimumHeight(0); ui->editVelocityMotorPos->setMinimumHeight(0); + ui->editFaultMotorPos->setMinimumHeight(0); ui->labelPositionMotorPos->setMinimumHeight(0); ui->labelPositionMotorPosUnits->setMinimumHeight(0); @@ -706,6 +716,8 @@ void JointItem::setMotorPositionVisible(bool visible) ui->labelVelocityMotorPosUnits->setMinimumHeight(0); ui->labelIdleMotorPos->setMinimumHeight(0); ui->labelIdleMotorPosUnits->setMinimumHeight(0); + ui->labelFaultMotorPos->setMinimumHeight(0); + ui->labelFaultMotorPosUnits->setMinimumHeight(0); } else { ui->editIdleMotorPos->setMinimumHeight(20); @@ -716,6 +728,7 @@ void JointItem::setMotorPositionVisible(bool visible) ui->editPWMMotorPos->setMinimumHeight(20); ui->editCurrentMotorPos->setMinimumHeight(20); ui->editVelocityMotorPos->setMinimumHeight(20); + ui->editFaultMotorPos->setMinimumHeight(20); ui->labelPositionMotorPos->setMinimumHeight(20); ui->labelPositionMotorPosUnits->setMinimumHeight(20); @@ -733,6 +746,8 @@ void JointItem::setMotorPositionVisible(bool visible) ui->labelVelocityMotorPosUnits->setMinimumHeight(20); ui->labelIdleMotorPos->setMinimumHeight(20); ui->labelIdleMotorPosUnits->setMinimumHeight(20); + ui->labelFaultMotorPos->setMinimumHeight(20); + ui->labelFaultMotorPosUnits->setMinimumHeight(20); } } @@ -1776,6 +1791,10 @@ void JointItem::setMotorPosition(double val) double mot = val; QString sVal = QString("%1").arg(mot, 0, 'f', 1); + if (ui->stackedWidget->currentIndex() == HW_FAULT) { + ui->editFaultMotorPos->setText(sVal); + } + if (ui->stackedWidget->currentIndex() == IDLE){ ui->editIdleMotorPos->setText(sVal); } diff --git a/src/yarpmotorgui/jointitem.ui b/src/yarpmotorgui/jointitem.ui index 742c467d473..8b3608ab9a0 100644 --- a/src/yarpmotorgui/jointitem.ui +++ b/src/yarpmotorgui/jointitem.ui @@ -2477,6 +2477,13 @@ QSlider::groove:horizontal:disabled { + + + + Encoder: + + + @@ -2487,10 +2494,27 @@ QSlider::groove:horizontal:disabled { - - + + - Encoder: + MotorPos: + + + + + + + background-color: rgb(255, 255, 255); color: rgb(35, 38, 41); + + + true + + + + + + + deg From 331568a729e5859f86a97e99c6e78da06bcfa05c Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 15 Dec 2022 13:25:10 +0100 Subject: [PATCH 065/267] minor improvement to FakeMotionControl --- src/devices/fakeMotionControl/fakeMotionControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/devices/fakeMotionControl/fakeMotionControl.cpp b/src/devices/fakeMotionControl/fakeMotionControl.cpp index 57a06cfeefa..487dfe2982f 100644 --- a/src/devices/fakeMotionControl/fakeMotionControl.cpp +++ b/src/devices/fakeMotionControl/fakeMotionControl.cpp @@ -2505,7 +2505,7 @@ bool FakeMotionControl::resetMotorEncodersRaw() bool FakeMotionControl::getMotorEncoderRaw(int m, double *value) { - *value = 0.0; + *value = pos[m]*10; return true; } From d5e1b097f12fb282835e50b07b42d058042481d7 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 15 Dec 2022 14:08:43 +0100 Subject: [PATCH 066/267] Added companion command `yarp split` --- doc/module_executables/cmd_yarpscope.dox | 6 +- doc/release/master/companion_split.md | 7 + src/libYARP_companion/src/CMakeLists.txt | 1 + .../companion/impl/Companion.cmdSplit.cpp | 158 ++++++++++++++++++ .../src/yarp/companion/impl/Companion.cpp | 1 + .../src/yarp/companion/impl/Companion.h | 3 + 6 files changed, 174 insertions(+), 2 deletions(-) create mode 100644 doc/release/master/companion_split.md create mode 100644 src/libYARP_companion/src/yarp/companion/impl/Companion.cmdSplit.cpp diff --git a/doc/module_executables/cmd_yarpscope.dox b/doc/module_executables/cmd_yarpscope.dox index ee9023b1993..79528286140 100644 --- a/doc/module_executables/cmd_yarpscope.dox +++ b/doc/module_executables/cmd_yarpscope.dox @@ -8,8 +8,10 @@ \section yarpscope_intro Description This simple graphical user interface allows one to visualize on a plot the -content of a YARP port. The input port is assumed to contain a vector of -numbers. +content of a YARP port. The input port is assumed to contain a single vector of +numbers. If you want to plot complex data, i.e. a nested bottle, you might want to +check the command `yarp split` to pre-process the data and subdivide the bottle into +multiple vectors. - The main window can contain one or more plots. - Each plot can contain one or more graphs. diff --git a/doc/release/master/companion_split.md b/doc/release/master/companion_split.md new file mode 100644 index 00000000000..1683f64c8af --- /dev/null +++ b/doc/release/master/companion_split.md @@ -0,0 +1,7 @@ +companion_split {#master} +----------- + +### `lib_yarp_companion` + +* Added companion command `yarp split`. The command splits an heterogeneous nested bottle received from a port into multiple ports. + diff --git a/src/libYARP_companion/src/CMakeLists.txt b/src/libYARP_companion/src/CMakeLists.txt index 4a4c6d12b58..24ea2405c0b 100644 --- a/src/libYARP_companion/src/CMakeLists.txt +++ b/src/libYARP_companion/src/CMakeLists.txt @@ -48,6 +48,7 @@ set(YARP_companion_IMPL_SRCS yarp/companion/impl/Companion.cmdRpc.cpp yarp/companion/impl/Companion.cmdRpcServer.cpp yarp/companion/impl/Companion.cmdSample.cpp + yarp/companion/impl/Companion.cmdSplit.cpp yarp/companion/impl/Companion.cmdStats.cpp yarp/companion/impl/Companion.cmdTerminate.cpp yarp/companion/impl/Companion.cmdTime.cpp diff --git a/src/libYARP_companion/src/yarp/companion/impl/Companion.cmdSplit.cpp b/src/libYARP_companion/src/yarp/companion/impl/Companion.cmdSplit.cpp new file mode 100644 index 00000000000..a9024cb0396 --- /dev/null +++ b/src/libYARP_companion/src/yarp/companion/impl/Companion.cmdSplit.cpp @@ -0,0 +1,158 @@ +/* + * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT) + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using yarp::companion::impl::Companion; +using yarp::os::Bottle; +using yarp::os::BufferedPort; +using yarp::os::Contactable; +using yarp::os::NetworkBase; +using yarp::os::Property; +using yarp::os::Semaphore; +using yarp::os::Stamp; +using yarp::os::TypedReaderCallback; +using yarp::os::Value; + +namespace { +class inPortProcessor : public TypedReaderCallback +{ +public: + Semaphore* sema{nullptr}; + Contactable* port{nullptr}; + std::mutex mutex; + Bottle value; + size_t value_size{0}; + Stamp stamp; + + inPortProcessor() = default; + + void init(Contactable& port, Semaphore& sema) + { + this->port = &port; + this->sema = &sema; + } + + using yarp::os::TypedReaderCallback::onRead; + void onRead(Bottle& datum) override + { + mutex.lock(); + value = datum; + value_size= value.size(); + port->getEnvelope(stamp); + mutex.unlock(); + sema->post(); + } +}; +} // namespace + +int Companion::cmdSplit(int argc, char *argv[]) +{ + BufferedPort* outPort = nullptr; + BufferedPort inPort; + inPortProcessor* inData = nullptr; + + //a simple help + if (argc == 0) + { + yCInfo(COMPANION, "This is yarp split. Please provide the name of the port to process, e.g:"); + yCInfo(COMPANION, " yarp split /port1"); + return -1; + } + + //some options + std::string portname = argv[0]; + Property options; + options.fromCommand(argc, argv, false); + std::string carrier = options.check("carrier", Value("udp")).asString().c_str(); + + //initializations + inData = new inPortProcessor; + Semaphore product(0); + inData->init(inPort, product); + inPort.useCallback(*inData); + + //open the input port and try the connection to the remote + inPort.open("..."); + bool b = yarp::os::NetworkBase::connect(portname, inPort.getName().c_str(), carrier, false); + if (!b) + { + yCError(COMPANION, "Failed to connect."); + return -1; + } + + yCInfo(COMPANION, "Waiting for data.."); + size_t siz = 0; + while(true) + { + //wait for new data to be received + product.wait(); + while (product.check()) { + product.wait(); + } + + //open some ports. The number depends on the first received data. + if (outPort == nullptr) + { + inData->mutex.lock(); + siz = inData->value_size; + inData->mutex.unlock(); + if (siz != 0) + { + yCInfo(COMPANION, std::string("Received a Bottle of "+std::to_string(siz)+" elements.").c_str()); + outPort = new BufferedPort [siz]; + for (size_t i = 0; i < siz; i++) + { + std::string portName = portname+"/split" + std::to_string(i) +":o"; + outPort[i].open(portName); + } + yCInfo(COMPANION, "Ready"); + } + else + { + yCError(COMPANION, "Data with invalid size received."); + } + } + + //Check if the data size is not constant + inData->mutex.lock(); + if (inData->value_size != siz) + { + yCError(COMPANION, "Data with invalid size received."); + } + inData->mutex.unlock(); + + //write data on each single port + for (size_t i = 0; i < siz; i++) + { + if (outPort[i].getOutputCount() > 0) + { + Bottle& b = outPort[i].prepare(); + b.clear(); + inData->mutex.lock(); + b.add(inData->value.get(i)); + outPort[i].setEnvelope(inData->stamp); + inData->mutex.unlock(); + outPort[i].write(); + } + } + } + yCInfo(COMPANION, "Complete."); + + //cleanup + delete [] outPort; + delete inData; + return 0; +} diff --git a/src/libYARP_companion/src/yarp/companion/impl/Companion.cpp b/src/libYARP_companion/src/yarp/companion/impl/Companion.cpp index 4579f4d6252..7e22df30b08 100644 --- a/src/libYARP_companion/src/yarp/companion/impl/Companion.cpp +++ b/src/libYARP_companion/src/yarp/companion/impl/Companion.cpp @@ -159,6 +159,7 @@ Companion::Companion() : add("rpc", &Companion::cmdRpc, "write commands to a port, and read replies"); add("rpcserver", &Companion::cmdRpcServer, "make a test RPC server to receive and reply to Bottle-format messages"); add("sample", &Companion::cmdSample, "drop or duplicate messages to achieve a constant frame-rate"); + add("split", &Companion::cmdSplit, "splits data received in a bottle onto multiple ports, one for each element"); add("stats", &Companion::cmdStats, "print statics about the data received from a specific port"); add("priority-sched", &Companion::cmdPrioritySched, "set/get the thread policy and priority for a given connection"); add("terminate", &Companion::cmdTerminate, "terminate a yarp-terminate-aware process by name"); diff --git a/src/libYARP_companion/src/yarp/companion/impl/Companion.h b/src/libYARP_companion/src/yarp/companion/impl/Companion.h index 8f7de6c3c75..a9c5e04f3b1 100644 --- a/src/libYARP_companion/src/yarp/companion/impl/Companion.h +++ b/src/libYARP_companion/src/yarp/companion/impl/Companion.h @@ -128,6 +128,9 @@ class YARP_companion_API Companion // Defined in Companion.cmdStats.cpp int cmdStats(int argc, char* argv[]); + // Defined in Companion.cmdSplit.cpp + int cmdSplit(int argc, char* argv[]); + // Defined in Companion.cmdTerminate.cpp int cmdTerminate(int argc, char *argv[]); From 0df51102aae0861e05efa8ac49416d2e06493476 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Thu, 22 Dec 2022 17:12:05 +0100 Subject: [PATCH 067/267] removed asserts from FrameTransformClient --- .../FrameTransformClient.cpp | 37 +++++++++++++------ 1 file changed, 26 insertions(+), 11 deletions(-) diff --git a/src/devices/frameTransformClient/FrameTransformClient.cpp b/src/devices/frameTransformClient/FrameTransformClient.cpp index e7655948249..a5afd6a673b 100644 --- a/src/devices/frameTransformClient/FrameTransformClient.cpp +++ b/src/devices/frameTransformClient/FrameTransformClient.cpp @@ -336,7 +336,10 @@ bool FrameTransformClient::open(yarp::os::Searchable &config) yarp::robotinterface::XMLReader reader; yarp::robotinterface::XMLReaderResult result = reader.getRobotFromString(configuration_to_open, cfg); - yCAssert(FRAMETRANSFORMCLIENT, result.parsingIsSuccessful); + if (result.parsingIsSuccessful==false) + { + yCError(FRAMETRANSFORMCLIENT) << "Unable to parse configuration"; + } m_robot = std::move(result.robot); @@ -350,21 +353,33 @@ bool FrameTransformClient::open(yarp::os::Searchable &config) std::string setdeviceName = "ftc_storage"; if (m_robot.hasParam("setDeviceName")) { setdeviceName = m_robot.findParam("setDeviceName");} - yCAssert(FRAMETRANSFORMCLIENT, m_robot.hasDevice(setdeviceName)); + if (!m_robot.hasDevice(setdeviceName)) + { + yCError(FRAMETRANSFORMCLIENT) << "Failed to find requested device " << setdeviceName; + return false; + } + auto* polyset = m_robot.device(setdeviceName).driver(); - yCAssert(FRAMETRANSFORMCLIENT, polyset); - polyset->view(m_ift_set); - yCAssert(FRAMETRANSFORMCLIENT, m_ift_set); + if (!polyset || !polyset->view(m_ift_set)) + { + yCError(FRAMETRANSFORMCLIENT) << "Failed to open device driver / interface for " << setdeviceName; + return false; + } std::string getdeviceName = "ftc_storage"; if (m_robot.hasParam("getDeviceName")) {getdeviceName = m_robot.findParam("getDeviceName");} - yCAssert(FRAMETRANSFORMCLIENT, m_robot.hasDevice(getdeviceName)); + if (!m_robot.hasDevice(getdeviceName)) + { + yCError(FRAMETRANSFORMCLIENT) << "Failed to find requested device " << getdeviceName; + return false; + } + auto* polyget = m_robot.device(getdeviceName).driver(); - yCAssert(FRAMETRANSFORMCLIENT, polyget); - polyget->view(m_ift_get); - yCAssert(FRAMETRANSFORMCLIENT, m_ift_get); - polyget->view(m_ift_util); - yCAssert(FRAMETRANSFORMCLIENT, m_ift_util); + if (!polyget || !polyget->view(m_ift_get) || !polyget->view(m_ift_util)) + { + yCError(FRAMETRANSFORMCLIENT) << "Failed to open device driver / interface for " << getdeviceName; + return false; + } if (config.check("period")) { From 2dfc07df5b9f7eaf750206072df0c36c121cad66 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Fri, 23 Dec 2022 09:41:31 +0100 Subject: [PATCH 068/267] removed asserts from FrameTransformServer --- src/devices/frameTransformClient/FrameTransformClient.cpp | 1 + src/devices/frameTransformServer/FrameTransformServer.cpp | 6 +++++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/devices/frameTransformClient/FrameTransformClient.cpp b/src/devices/frameTransformClient/FrameTransformClient.cpp index a5afd6a673b..31713d92c9f 100644 --- a/src/devices/frameTransformClient/FrameTransformClient.cpp +++ b/src/devices/frameTransformClient/FrameTransformClient.cpp @@ -339,6 +339,7 @@ bool FrameTransformClient::open(yarp::os::Searchable &config) if (result.parsingIsSuccessful==false) { yCError(FRAMETRANSFORMCLIENT) << "Unable to parse configuration"; + return false; } m_robot = std::move(result.robot); diff --git a/src/devices/frameTransformServer/FrameTransformServer.cpp b/src/devices/frameTransformServer/FrameTransformServer.cpp index 6e4f5c52585..c4f0a501a5a 100644 --- a/src/devices/frameTransformServer/FrameTransformServer.cpp +++ b/src/devices/frameTransformServer/FrameTransformServer.cpp @@ -105,7 +105,11 @@ bool FrameTransformServer::open(yarp::os::Searchable &config) yarp::robotinterface::XMLReader reader; yarp::robotinterface::XMLReaderResult result = reader.getRobotFromString(configuration_to_open, cfg); - yCAssert(FRAMETRANSFORMSERVER, result.parsingIsSuccessful); + if (result.parsingIsSuccessful == false) + { + yCError(FRAMETRANSFORMSERVER) << "Unable to parse configuration"; + return false; + } m_robot = std::move(result.robot); From d83dca1cd4d0572984a914c55505e663b342d749 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 3 Jan 2023 12:07:07 +0100 Subject: [PATCH 069/267] bugfix: fixed return value of ImplementAxisInfo::getAxes() --- src/libYARP_dev/src/yarp/dev/ImplementAxisInfo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/libYARP_dev/src/yarp/dev/ImplementAxisInfo.cpp b/src/libYARP_dev/src/yarp/dev/ImplementAxisInfo.cpp index fc6620fbf77..3e7a310997e 100644 --- a/src/libYARP_dev/src/yarp/dev/ImplementAxisInfo.cpp +++ b/src/libYARP_dev/src/yarp/dev/ImplementAxisInfo.cpp @@ -53,7 +53,7 @@ bool ImplementAxisInfo::uninitialize() bool ImplementAxisInfo::getAxes(int* ax) { - bool ret; + bool ret=true; (*ax) = castToMapper(helper)->axes(); return ret; } From 3ee5bb176695a15e608d4b937644d567579319e9 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 3 Jan 2023 12:16:05 +0100 Subject: [PATCH 070/267] Migration from sqlite to sqlite3. Fixed issue preventing extern/sqlite3 (i.e. YARP_priv_SQLite3) to be correctly found as a dependency by other projects. --- doc/release/master/extern_sqlite3_fix.md | 9 +++++++++ extern/sqlite/CMakeLists.txt | 24 ++++++++++++------------ 2 files changed, 21 insertions(+), 12 deletions(-) create mode 100644 doc/release/master/extern_sqlite3_fix.md diff --git a/doc/release/master/extern_sqlite3_fix.md b/doc/release/master/extern_sqlite3_fix.md new file mode 100644 index 00000000000..16e2925824a --- /dev/null +++ b/doc/release/master/extern_sqlite3_fix.md @@ -0,0 +1,9 @@ +extern_sqlite3_fix {#master} +----------- + +### `extern` + +#### `sqlite3` + +* Migration from sqlite to sqlite3. Fixed issue preventing extern/sqlite3 (i.e. YARP_priv_SQLite3) to be correctly found +as a dependency by other projects. diff --git a/extern/sqlite/CMakeLists.txt b/extern/sqlite/CMakeLists.txt index 872f7754011..43ab4201263 100644 --- a/extern/sqlite/CMakeLists.txt +++ b/extern/sqlite/CMakeLists.txt @@ -2,9 +2,9 @@ # SPDX-License-Identifier: BSD-3-Clause # SQLite -project(YARP_priv_sqlite) +project(YARP_priv_sqlite3) -add_library(YARP_priv_sqlite STATIC) +add_library(YARP_priv_sqlite3 STATIC) set(sqlite_SRCS sqlite/shell.c @@ -20,27 +20,27 @@ if(MSVC) set_source_files_properties(sqlite/sqlite3.c PROPERTIES COMPILE_FLAGS "/wd4996") endif() -target_sources(YARP_priv_sqlite PRIVATE ${sqlite_SRCS}) +target_sources(YARP_priv_sqlite3 PRIVATE ${sqlite_SRCS}) -target_include_directories(YARP_priv_sqlite PUBLIC $) +target_include_directories(YARP_priv_sqlite3 PUBLIC $) -target_compile_definitions(YARP_priv_sqlite PRIVATE SQLITE_OMIT_LOAD_EXTENSION) +target_compile_definitions(YARP_priv_sqlite3 PRIVATE SQLITE_OMIT_LOAD_EXTENSION) if(UNIX) - target_link_libraries(YARP_priv_sqlite PRIVATE pthread) + target_link_libraries(YARP_priv_sqlite3 PRIVATE pthread) endif(UNIX) -set_property(TARGET YARP_priv_sqlite PROPERTY FOLDER "Libraries/External") +set_property(TARGET YARP_priv_sqlite3 PROPERTY FOLDER "Libraries/External") set(SQLite3_INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/sqlite PARENT_SCOPE) -set(SQLite3_LIBRARIES YARP_priv_sqlite PARENT_SCOPE) +set(SQLite3_LIBRARIES YARP_priv_sqlite3 PARENT_SCOPE) set(SQLite3_DEFINITIONS "" PARENT_SCOPE) install( - TARGETS YARP_priv_sqlite - EXPORT YARP_priv_sqlite - COMPONENT YARP_priv_sqlite + TARGETS YARP_priv_sqlite3 + EXPORT YARP_priv_sqlite3 + COMPONENT YARP_priv_sqlite3 RUNTIME DESTINATION "${CMAKE_INSTALL_BINDIR}" LIBRARY DESTINATION "${CMAKE_INSTALL_LIBDIR}" ARCHIVE DESTINATION "${CMAKE_INSTALL_LIBDIR}" @@ -48,5 +48,5 @@ install( if(NOT CREATE_SHARED_LIBS) include(YarpInstallBasicPackageFiles) - yarp_install_basic_package_files(YARP_priv_sqlite) + yarp_install_basic_package_files(YARP_priv_sqlite3) endif() From dcb3a7b4034b9293534d6e2b98a6e63b75bda1c4 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Tue, 3 Jan 2023 16:37:50 +0100 Subject: [PATCH 071/267] A new library `yarp_dev_tests`: is now exported. It contains common sources to test yarp device through lib_yarpdev (also outside yarp repo). --- doc/release/master/yarp_dev_tests.md | 9 ++ .../ControlBoardRemapper/tests/CMakeLists.txt | 2 +- .../ControlBoardWrapper/tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../RGBDSensorClient/tests/CMakeLists.txt | 2 +- .../RGBDSensor_nws_yarp/tests/CMakeLists.txt | 2 +- .../Rangefinder2DClient/tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../RemoteControlBoard/tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../fakeDepthCamera/tests/CMakeLists.txt | 2 +- .../fakeFrameGrabber/tests/CMakeLists.txt | 2 +- src/devices/fakeIMU/tests/CMakeLists.txt | 2 +- src/devices/fakeLaser/tests/CMakeLists.txt | 2 +- .../fakeLaserWithMotor/tests/CMakeLists.txt | 2 +- .../fakeMotionControl/tests/CMakeLists.txt | 2 +- .../fakeNavigationDevice/tests/CMakeLists.txt | 2 +- .../frameGrabberCropper/tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../frameTransformClient/tests/CMakeLists.txt | 2 +- .../frameTransformServer/tests/CMakeLists.txt | 2 +- src/devices/map2DStorage/tests/CMakeLists.txt | 2 +- .../map2D_nwc_yarp/tests/CMakeLists.txt | 2 +- .../map2D_nws_yarp/tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../tests/CMakeLists.txt | 2 +- .../transformClient/tests/CMakeLists.txt | 2 +- .../transformServer/tests/CMakeLists.txt | 2 +- src/libYARP_dev/CMakeLists.txt | 5 ++ src/libYARP_dev/src/CMakeLists.txt | 83 +++++++++++++------ 35 files changed, 103 insertions(+), 58 deletions(-) create mode 100644 doc/release/master/yarp_dev_tests.md diff --git a/doc/release/master/yarp_dev_tests.md b/doc/release/master/yarp_dev_tests.md new file mode 100644 index 00000000000..958668d933a --- /dev/null +++ b/doc/release/master/yarp_dev_tests.md @@ -0,0 +1,9 @@ +exposed_yarp_dev_tests {#master} +----------- + +### `tests` + +#### `yarp_dev_tests` + +* A new library `yarp_dev_tests`: is now exported. + It contains common sources to test yarp device through lib_yarpdev (also outside yarp repo). diff --git a/src/devices/ControlBoardRemapper/tests/CMakeLists.txt b/src/devices/ControlBoardRemapper/tests/CMakeLists.txt index 8f79a30ec6d..bbde27fac40 100644 --- a/src/devices/ControlBoardRemapper/tests/CMakeLists.txt +++ b/src/devices/ControlBoardRemapper/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_controlBoardRemapper) diff --git a/src/devices/ControlBoardWrapper/tests/CMakeLists.txt b/src/devices/ControlBoardWrapper/tests/CMakeLists.txt index 54fd84ea872..5e3c60a6235 100644 --- a/src/devices/ControlBoardWrapper/tests/CMakeLists.txt +++ b/src/devices/ControlBoardWrapper/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_controlBoardWrapper) diff --git a/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt b/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt index 06c7216f550..046935bd42a 100644 --- a/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt +++ b/src/devices/ControlBoard_nws_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_controlBoard_nws_yarp) diff --git a/src/devices/RGBDSensorClient/tests/CMakeLists.txt b/src/devices/RGBDSensorClient/tests/CMakeLists.txt index 287fc31096e..3bd5429bbf0 100644 --- a/src/devices/RGBDSensorClient/tests/CMakeLists.txt +++ b/src/devices/RGBDSensorClient/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_RGBDSensorClient) diff --git a/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt b/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt index d8c95931f47..b159617f41a 100644 --- a/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt +++ b/src/devices/RGBDSensor_nws_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_RGBDSensor_nws_yarp) diff --git a/src/devices/Rangefinder2DClient/tests/CMakeLists.txt b/src/devices/Rangefinder2DClient/tests/CMakeLists.txt index f8f4484888d..1b4ed12499f 100644 --- a/src/devices/Rangefinder2DClient/tests/CMakeLists.txt +++ b/src/devices/Rangefinder2DClient/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Rangefinder2DClient) diff --git a/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt index 7e4f311c3d2..109c596341f 100644 --- a/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt +++ b/src/devices/Rangefinder2D_nwc_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_rangefinder2D_nwc_yarp) diff --git a/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt b/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt index 74ca231fe61..fe00cf283ad 100644 --- a/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt +++ b/src/devices/Rangefinder2D_nws_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_rangefinder2D_nws_yarp) diff --git a/src/devices/RemoteControlBoard/tests/CMakeLists.txt b/src/devices/RemoteControlBoard/tests/CMakeLists.txt index 8931bfe8f55..884d32a16a3 100644 --- a/src/devices/RemoteControlBoard/tests/CMakeLists.txt +++ b/src/devices/RemoteControlBoard/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_RemoteControlBoard) diff --git a/src/devices/RobotDescriptionClient/tests/CMakeLists.txt b/src/devices/RobotDescriptionClient/tests/CMakeLists.txt index 960783d133d..1135a950a17 100644 --- a/src/devices/RobotDescriptionClient/tests/CMakeLists.txt +++ b/src/devices/RobotDescriptionClient/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_robotDescriptionClient) diff --git a/src/devices/RobotDescriptionServer/tests/CMakeLists.txt b/src/devices/RobotDescriptionServer/tests/CMakeLists.txt index 25d1faa9c5f..db6279af17b 100644 --- a/src/devices/RobotDescriptionServer/tests/CMakeLists.txt +++ b/src/devices/RobotDescriptionServer/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_robotDescriptionServer) diff --git a/src/devices/fakeDepthCamera/tests/CMakeLists.txt b/src/devices/fakeDepthCamera/tests/CMakeLists.txt index bf48028f38c..a35836541e0 100644 --- a/src/devices/fakeDepthCamera/tests/CMakeLists.txt +++ b/src/devices/fakeDepthCamera/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeDepthCamera) diff --git a/src/devices/fakeFrameGrabber/tests/CMakeLists.txt b/src/devices/fakeFrameGrabber/tests/CMakeLists.txt index f964d31234e..0ebc5470d13 100644 --- a/src/devices/fakeFrameGrabber/tests/CMakeLists.txt +++ b/src/devices/fakeFrameGrabber/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeFrameGrabber) diff --git a/src/devices/fakeIMU/tests/CMakeLists.txt b/src/devices/fakeIMU/tests/CMakeLists.txt index 7ba26b0df06..a13aa1703f1 100644 --- a/src/devices/fakeIMU/tests/CMakeLists.txt +++ b/src/devices/fakeIMU/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeImu) diff --git a/src/devices/fakeLaser/tests/CMakeLists.txt b/src/devices/fakeLaser/tests/CMakeLists.txt index a9819eda751..0898534cb45 100644 --- a/src/devices/fakeLaser/tests/CMakeLists.txt +++ b/src/devices/fakeLaser/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeLaser) diff --git a/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt b/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt index b4c4da9d10a..be6b13e403e 100644 --- a/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt +++ b/src/devices/fakeLaserWithMotor/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeLaserWithMotor) diff --git a/src/devices/fakeMotionControl/tests/CMakeLists.txt b/src/devices/fakeMotionControl/tests/CMakeLists.txt index 84df140d627..a0d839bd69f 100644 --- a/src/devices/fakeMotionControl/tests/CMakeLists.txt +++ b/src/devices/fakeMotionControl/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeMotionControl) diff --git a/src/devices/fakeNavigationDevice/tests/CMakeLists.txt b/src/devices/fakeNavigationDevice/tests/CMakeLists.txt index 9f95c4ecb6d..8852d30253a 100644 --- a/src/devices/fakeNavigationDevice/tests/CMakeLists.txt +++ b/src/devices/fakeNavigationDevice/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_fakeNavigation) diff --git a/src/devices/frameGrabberCropper/tests/CMakeLists.txt b/src/devices/frameGrabberCropper/tests/CMakeLists.txt index 2c56727fbfd..9090610ac5f 100644 --- a/src/devices/frameGrabberCropper/tests/CMakeLists.txt +++ b/src/devices/frameGrabberCropper/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_frameGrabberCropper) diff --git a/src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt b/src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt index da7942f0229..bf467b73c8a 100644 --- a/src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt +++ b/src/devices/frameGrabber_nwc_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_frameGrabber_nwc_yarp) diff --git a/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt b/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt index 657f7f3b284..1d45250cbf5 100644 --- a/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt +++ b/src/devices/frameGrabber_nws_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_frameGrabber_nws_yarp) diff --git a/src/devices/frameTransformClient/tests/CMakeLists.txt b/src/devices/frameTransformClient/tests/CMakeLists.txt index 60b6719d190..0fd3e6f9505 100644 --- a/src/devices/frameTransformClient/tests/CMakeLists.txt +++ b/src/devices/frameTransformClient/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_FrameTransformClient) diff --git a/src/devices/frameTransformServer/tests/CMakeLists.txt b/src/devices/frameTransformServer/tests/CMakeLists.txt index e0809190029..fffbbe9ba1e 100644 --- a/src/devices/frameTransformServer/tests/CMakeLists.txt +++ b/src/devices/frameTransformServer/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_FrameTransformServer) diff --git a/src/devices/map2DStorage/tests/CMakeLists.txt b/src/devices/map2DStorage/tests/CMakeLists.txt index 37044ce0e1f..dad55a311dc 100644 --- a/src/devices/map2DStorage/tests/CMakeLists.txt +++ b/src/devices/map2DStorage/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Map2DStorage) diff --git a/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt index 7dcfca84dc3..d5c1aafa396 100644 --- a/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt +++ b/src/devices/map2D_nwc_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Map2Dnwc) diff --git a/src/devices/map2D_nws_yarp/tests/CMakeLists.txt b/src/devices/map2D_nws_yarp/tests/CMakeLists.txt index 5c99004c9cc..af6e31d0ca1 100644 --- a/src/devices/map2D_nws_yarp/tests/CMakeLists.txt +++ b/src/devices/map2D_nws_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Map2Dnws) diff --git a/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt b/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt index 96b22f15d2f..ac8149f155c 100644 --- a/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt +++ b/src/devices/multipleanalogsensorsclient/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_multipleanalogsensorsclient) diff --git a/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt b/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt index 62d5b6d5c1f..7c9ce1e10e4 100644 --- a/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt +++ b/src/devices/multipleanalogsensorsserver/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_multipleanalogsensorsserver) diff --git a/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt b/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt index c1b08e19f0c..202389cb16b 100644 --- a/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt +++ b/src/devices/navigation2D_nwc_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Navigation2Dnwc) diff --git a/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt b/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt index 343591a296a..d751ae8a025 100644 --- a/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt +++ b/src/devices/navigation2D_nws_yarp/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_Navigation2Dnws) diff --git a/src/devices/transformClient/tests/CMakeLists.txt b/src/devices/transformClient/tests/CMakeLists.txt index 164ae5f9c5b..2b3cb7270ec 100644 --- a/src/devices/transformClient/tests/CMakeLists.txt +++ b/src/devices/transformClient/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_TransformerClient) diff --git a/src/devices/transformServer/tests/CMakeLists.txt b/src/devices/transformServer/tests/CMakeLists.txt index 764bcedf900..9e9477b8b2e 100644 --- a/src/devices/transformServer/tests/CMakeLists.txt +++ b/src/devices/transformServer/tests/CMakeLists.txt @@ -18,7 +18,7 @@ function(yarp_catch_discover_tests _target) endfunction() ######################################################################### -find_package(YARP::YARP_dev_tests) + add_executable(harness_dev_TransformerServer) diff --git a/src/libYARP_dev/CMakeLists.txt b/src/libYARP_dev/CMakeLists.txt index 339ab0edad2..dc2e6ac5fa4 100644 --- a/src/libYARP_dev/CMakeLists.txt +++ b/src/libYARP_dev/CMakeLists.txt @@ -10,3 +10,8 @@ yarp_install_basic_package_files(YARP_dev DEPENDENCIES ${YARP_dev_PUBLIC_DEPS} PRIVATE_DEPENDENCIES ${YARP_dev_PRIVATE_DEPS} ) + +yarp_install_basic_package_files(YARP_dev_tests + DEPENDENCIES ${YARP_dev_tests_PUBLIC_DEPS} + PRIVATE_DEPENDENCIES ${YARP_dev_tests_PRIVATE_DEPS} +) diff --git a/src/libYARP_dev/src/CMakeLists.txt b/src/libYARP_dev/src/CMakeLists.txt index 26a7ad79b73..77b66e8042e 100644 --- a/src/libYARP_dev/src/CMakeLists.txt +++ b/src/libYARP_dev/src/CMakeLists.txt @@ -397,48 +397,51 @@ set(YARP_dev_PRIVATE_DEPS ${YARP_dev_PRIVATE_DEPS} PARENT_SCOPE) add_library(YARP_dev_tests) add_library(YARP::YARP_dev_tests ALIAS YARP_dev_tests) +set(YARP_dev_test_HDRS + yarp/dev/tests/IDummyTest.h + yarp/dev/tests/IPositionControlTest.h + yarp/dev/tests/ITorqueControlTest.h + yarp/dev/tests/IAxisInfoTest.h + yarp/dev/tests/IRGBDSensorTest.h +) + +set(YARP_dev_test_SRCS + yarp/dev/tests/IDummyTest.cpp + yarp/dev/tests/IPositionControlTest.cpp + yarp/dev/tests/ITorqueControlTest.cpp + yarp/dev/tests/IAxisInfoTest.cpp + yarp/dev/tests/IRGBDSensorTest.cpp +) + if(TARGET YARP::YARP_math) -target_sources(YARP_dev_tests - PRIVATE - yarp/dev/tests/IFrameGrabberImageTest.cpp + list(APPEND YARP_dev_test_HDRS yarp/dev/tests/IFrameGrabberImageTest.h - yarp/dev/tests/IRgbVisualParamsTest.cpp yarp/dev/tests/IRgbVisualParamsTest.h - yarp/dev/tests/IFrameTransformTest.cpp yarp/dev/tests/IFrameTransformTest.h - yarp/dev/tests/IMap2DTest.cpp yarp/dev/tests/IMap2DTest.h - yarp/dev/tests/INavigation2DTest.cpp yarp/dev/tests/INavigation2DTest.h - yarp/dev/tests/IDummyTest.cpp yarp/dev/tests/IDummyTest.h - yarp/dev/tests/IRangefinder2DTest.cpp yarp/dev/tests/IRangefinder2DTest.h - yarp/dev/tests/IPositionControlTest.cpp yarp/dev/tests/IPositionControlTest.h - yarp/dev/tests/ITorqueControlTest.cpp yarp/dev/tests/ITorqueControlTest.h - yarp/dev/tests/IAxisInfoTest.cpp yarp/dev/tests/IAxisInfoTest.h - yarp/dev/tests/IOrientationSensorsTest.cpp yarp/dev/tests/IOrientationSensorsTest.h - yarp/dev/tests/IRGBDSensorTest.cpp yarp/dev/tests/IRGBDSensorTest.h -) -else() -target_sources(YARP_dev_tests - PRIVATE + ) + list(APPEND YARP_dev_test_SRCS + yarp/dev/tests/IFrameGrabberImageTest.cpp + yarp/dev/tests/IRgbVisualParamsTest.cpp + yarp/dev/tests/IFrameTransformTest.cpp + yarp/dev/tests/INavigation2DTest.cpp yarp/dev/tests/IDummyTest.cpp - yarp/dev/tests/IDummyTest.h + yarp/dev/tests/IRangefinder2DTest.cpp yarp/dev/tests/IPositionControlTest.cpp - yarp/dev/tests/IPositionControlTest.h yarp/dev/tests/ITorqueControlTest.cpp - yarp/dev/tests/ITorqueControlTest.h yarp/dev/tests/IAxisInfoTest.cpp - yarp/dev/tests/IAxisInfoTest.h + yarp/dev/tests/IOrientationSensorsTest.cpp yarp/dev/tests/IRGBDSensorTest.cpp - yarp/dev/tests/IRGBDSensorTest.h -) + yarp/dev/tests/IMap2DTest.cpp + ) endif() target_include_directories(YARP_dev_tests @@ -446,6 +449,12 @@ target_include_directories(YARP_dev_tests ${CMAKE_SOURCE_DIR}/extern/catch2 ) +target_sources(YARP_dev_tests + PRIVATE + ${YARP_dev_test_SRCS} + ${YARP_dev_test_HDRS} +) + target_compile_definitions(YARP_dev_tests PUBLIC YARP_dev_EXPORTS=1) target_link_libraries(YARP_dev_tests PRIVATE YARP_dev) @@ -453,7 +462,7 @@ target_link_libraries(YARP_dev_tests PRIVATE YARP_dev) target_compile_features(YARP_dev_tests PRIVATE cxx_std_17) set_property ( -TARGET YARP_dev_tests + TARGET YARP_dev_tests PROPERTY FOLDER "Test" ) @@ -462,5 +471,27 @@ set_property( PROPERTY PUBLIC_HEADER ${YARP_dev_HDRS} - yarp/dev/tests/IMap2DTest.h + ${YARP_dev_test_HDRS} +) + +set_property(TARGET YARP_dev_tests PROPERTY VERSION ${YARP_VERSION_SHORT}) +set_property(TARGET YARP_dev_tests PROPERTY SOVERSION ${YARP_SOVERSION}) +set_property(TARGET YARP_dev_tests PROPERTY FOLDER "Test") + + install( + TARGETS YARP_dev_tests + EXPORT YARP_dev_tests + RUNTIME + DESTINATION "${CMAKE_INSTALL_BINDIR}" + COMPONENT YARP_dev_tests + LIBRARY + DESTINATION "${CMAKE_INSTALL_LIBDIR}" + COMPONENT YARP_dev_tests + NAMELINK_COMPONENT YARP_dev_tests-dev + ARCHIVE + DESTINATION "${CMAKE_INSTALL_LIBDIR}" + COMPONENT YARP_dev_tests-dev + PUBLIC_HEADER + DESTINATION "${CMAKE_INSTALL_INCLUDEDIR}/yarp/dev/tests" + COMPONENT YARP_dev_tests-dev ) From 872a7ebde9e4d9047dce8b52f6bda969fd33f8a1 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 4 Jan 2023 01:31:29 +0100 Subject: [PATCH 072/267] yarp_tests_skipped variable is now hidden inside harness.cpp and accessible only using increment_tests_skipped() function. This allows easier export of library symbols. --- tests/harness.cpp | 4 ++++ tests/harness.h | 4 ++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/tests/harness.cpp b/tests/harness.cpp index e32cddd798f..2ffcc3fb239 100644 --- a/tests/harness.cpp +++ b/tests/harness.cpp @@ -143,6 +143,10 @@ static void fini_NameStore() } // namespace +void increment_tests_skipped() +{ + ++yarp_tests_skipped; +} int main(int argc, char *argv[]) { diff --git a/tests/harness.h b/tests/harness.h index b8661132ec1..722f222751c 100644 --- a/tests/harness.h +++ b/tests/harness.h @@ -14,11 +14,11 @@ #include #include -extern int yarp_tests_skipped; +void increment_tests_skipped(); #define YARP_SKIP_TEST(...) \ { \ - ++yarp_tests_skipped; \ + increment_tests_skipped(); \ FAIL(__VA_ARGS__); \ } From 22c180136351edbb8cf38ed6f208ae3a7dcf0207 Mon Sep 17 00:00:00 2001 From: Marco Randazzo Date: Wed, 28 Dec 2022 00:14:25 +0100 Subject: [PATCH 073/267] migration from Catch V2.13.8 to Catch V3.2.1 --- extern/catch2/LICENSES/BSL-1.0.txt | 7 - extern/catch2/README.txt | 18 - extern/catch2/catch.hpp | 17966 ---------------- extern/catch2/catch_amalgamated.cpp | 10516 +++++++++ extern/catch2/catch_amalgamated.hpp | 12524 +++++++++++ .../tests/ControlBoardRemapperTest.cpp | 2 +- .../tests/ControlBoardRemapperTest2.cpp | 2 +- .../tests/ControlBoardWrapperTest.cpp | 2 +- .../tests/ControlBoard_nws_yarpTest.cpp | 2 +- .../tests/RGBDSensorClientTest.cpp | 2 +- .../tests/RGBDSensor_nws_yarpTest.cpp | 2 +- .../tests/Rangefinder2DClientTest.cpp | 2 +- .../tests/Rangefinder2D_nwc_yarpTest.cpp | 2 +- .../tests/Rangefinder2D_nws_yarpTest.cpp | 2 +- .../tests/RemoteControlBoardTest.cpp | 2 +- .../tests/robotDescriptionClientTest.cpp | 2 +- .../tests/robotDescriptionServerTest.cpp | 2 +- .../tests/fakeDepthCameraTest.cpp | 2 +- .../tests/fakeFrameGrabberTest.cpp | 2 +- src/devices/fakeIMU/tests/FakeImuTest.cpp | 2 +- src/devices/fakeLaser/tests/fakeLaserTest.cpp | 2 +- .../tests/fakeLaserWithMotorTest.cpp | 2 +- .../tests/FakeMotionControlTest.cpp | 2 +- .../tests/FakeNavigationTest.cpp | 2 +- .../tests/frameGrabberCropperTest.cpp | 2 +- .../tests/frameGrabber_nwc_yarpTest.cpp | 2 +- .../tests/frameGrabber_nws_yarpTest.cpp | 2 +- .../tests/FrameTransformClientTest.cpp | 2 +- .../tests/FrameTransformServerTest.cpp | 2 +- .../map2DStorage/tests/Map2DStorageTest.cpp | 2 +- .../map2D_nwc_yarp/tests/Map2DnwcTest.cpp | 2 +- .../map2D_nws_yarp/tests/Map2DnwsTest.cpp | 2 +- .../tests/MultipleAnalogSensorsClientTest.cpp | 2 +- .../tests/MultipleAnalogSensorsServerTest.cpp | 2 +- .../tests/Navigation2DnwcTest.cpp | 2 +- .../tests/Navigation2DnwsTest.cpp | 2 +- .../tests/TransformClientTest.cpp | 2 +- .../tests/TransformServerTest.cpp | 2 +- .../src/yarp/dev/tests/IAxisInfoTest.h | 2 +- .../yarp/dev/tests/IFrameGrabberImageTest.h | 2 +- .../src/yarp/dev/tests/IFrameTransformTest.h | 2 +- .../src/yarp/dev/tests/IMap2DTest.h | 2 +- .../src/yarp/dev/tests/INavigation2DTest.h | 2 +- .../yarp/dev/tests/IOrientationSensorsTest.h | 4 +- .../src/yarp/dev/tests/IPositionControlTest.h | 2 +- .../src/yarp/dev/tests/IRGBDSensorTest.h | 2 +- .../src/yarp/dev/tests/IRangefinder2DTest.h | 2 +- .../src/yarp/dev/tests/IRgbVisualParamsTest.h | 2 +- .../src/yarp/dev/tests/ITorqueControlTest.h | 2 +- tests/CMakeLists.txt | 4 + tests/carriers/mjpeg.cpp | 2 +- tests/harness.cpp | 7 +- tests/harness.h | 2 +- tests/libYARP_conf/dirs.cpp | 2 +- tests/libYARP_conf/environment.cpp | 2 +- tests/libYARP_conf/numeric.cpp | 2 +- tests/libYARP_conf/string.cpp | 2 +- tests/libYARP_dev/MapGrid2DTest.cpp | 2 +- tests/libYARP_dev/PolyDriverTest.cpp | 2 +- tests/libYARP_math/MathTest.cpp | 10 +- tests/libYARP_math/RandTest.cpp | 2 +- tests/libYARP_math/Vec2DTest.cpp | 2 +- tests/libYARP_math/svdTest.cpp | 2 +- tests/libYARP_os/BinPortableTest.cpp | 2 +- tests/libYARP_os/BottleTest.cpp | 18 +- tests/libYARP_os/ContactTest.cpp | 2 +- tests/libYARP_os/ElectionTest.cpp | 2 +- tests/libYARP_os/EventTest.cpp | 2 +- tests/libYARP_os/HeaderTest.cpp | 32 +- tests/libYARP_os/LogStreamTest.cpp | 2 +- tests/libYARP_os/LogTest.cpp | 2 +- tests/libYARP_os/MessageStackTest.cpp | 2 +- tests/libYARP_os/NetTypeTest.cpp | 2 +- tests/libYARP_os/NetworkTest.cpp | 2 +- tests/libYARP_os/NodeTest.cpp | 2 +- tests/libYARP_os/PeriodicThreadTest.cpp | 2 +- tests/libYARP_os/PortReaderBufferTest.cpp | 2 +- tests/libYARP_os/PortTest.cpp | 2 +- tests/libYARP_os/PortablePairTest.cpp | 2 +- tests/libYARP_os/PropertyTest.cpp | 2 +- tests/libYARP_os/PublisherTest.cpp | 2 +- tests/libYARP_os/RFModuleTest.cpp | 2 +- tests/libYARP_os/ResourceFinderTest.cpp | 4 +- tests/libYARP_os/RouteTest.cpp | 2 +- tests/libYARP_os/SemaphoreTest.cpp | 2 +- tests/libYARP_os/StampTest.cpp | 16 +- tests/libYARP_os/StringInputStreamTest.cpp | 2 +- tests/libYARP_os/StringOutputStreamTest.cpp | 2 +- tests/libYARP_os/SystemInfoTest.cpp | 2 +- tests/libYARP_os/TerminatorTest.cpp | 2 +- tests/libYARP_os/ThreadTest.cpp | 2 +- tests/libYARP_os/TimeTest.cpp | 2 +- tests/libYARP_os/TimerTest.cpp | 2 +- tests/libYARP_os/ValueTest.cpp | 6 +- tests/libYARP_os/VocabTest.cpp | 2 +- tests/libYARP_os/impl/BottleImplTest.cpp | 6 +- .../impl/BufferedConnectionWriterTest.cpp | 2 +- .../libYARP_os/impl/DgramTwoWayStreamTest.cpp | 2 +- tests/libYARP_os/impl/NameConfigTest.cpp | 2 +- tests/libYARP_os/impl/NameServerTest.cpp | 2 +- tests/libYARP_os/impl/PortCommandTest.cpp | 2 +- tests/libYARP_os/impl/PortCoreTest.cpp | 2 +- tests/libYARP_os/impl/ProtocolTest.cpp | 2 +- .../impl/StreamConnectionReaderTest.cpp | 2 +- .../RobotinterfaceTest.cpp | 2 +- tests/libYARP_rosmsg/ROSPropertiesTest.cpp | 2 +- tests/libYARP_run/RunTest.cpp | 2 +- tests/libYARP_serversql/ServerTest.cpp | 2 +- tests/libYARP_sig/ImageTest.cpp | 2 +- tests/libYARP_sig/MatrixTest.cpp | 8 +- tests/libYARP_sig/PointCloudTest.cpp | 2 +- tests/libYARP_sig/SoundTest.cpp | 2 +- tests/libYARP_sig/VectorOfTest.cpp | 2 +- tests/libYARP_sig/VectorTest.cpp | 2 +- tests/libYARP_wire_rep_utils/WireTest.cpp | 2 +- tests/yarpidl_rosmsg/demo/main.cpp | 4 +- tests/yarpidl_thrift/demo/main.cpp | 4 +- 117 files changed, 23202 insertions(+), 18150 deletions(-) delete mode 100644 extern/catch2/LICENSES/BSL-1.0.txt delete mode 100644 extern/catch2/README.txt delete mode 100644 extern/catch2/catch.hpp create mode 100644 extern/catch2/catch_amalgamated.cpp create mode 100644 extern/catch2/catch_amalgamated.hpp diff --git a/extern/catch2/LICENSES/BSL-1.0.txt b/extern/catch2/LICENSES/BSL-1.0.txt deleted file mode 100644 index 2d87ab1a9fa..00000000000 --- a/extern/catch2/LICENSES/BSL-1.0.txt +++ /dev/null @@ -1,7 +0,0 @@ -Boost Software License - Version 1.0 - August 17th, 2003 - -Permission is hereby granted, free of charge, to any person or organization obtaining a copy of the software and accompanying documentation covered by this license (the "Software") to use, reproduce, display, distribute, execute, and transmit the Software, and to prepare derivative works of the Software, and to permit third-parties to whom the Software is furnished to do so, all subject to the following: - -The copyright notices in the Software and this entire statement, including the above license grant, this restriction and the following disclaimer, must be included in all copies of the Software, in whole or in part, and all derivative works of the Software, unless such copies or derivative works are solely in the form of machine-executable object code generated by a source language processor. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. diff --git a/extern/catch2/README.txt b/extern/catch2/README.txt deleted file mode 100644 index 4b27eaf659c..00000000000 --- a/extern/catch2/README.txt +++ /dev/null @@ -1,18 +0,0 @@ -Catch2 ------- - -Catch2 stands for C++ Automated Test Cases in a Header and is a multi-paradigm -test framework for C++. which also supports Objective-C (and maybe C). -It is primarily distributed as a single header file, although certain extensions -may require additional headers. - -Homepage: https://github.com/catchorg/Catch2 - -Copyright: 2010-2020 Two Blue Cubes Ltd - 2012, 2015 Martin Moene - 2017 Justin R. Wilson - Catch2 Authors - -License: BSL-1.0 - -Version: 2.13.8 diff --git a/extern/catch2/catch.hpp b/extern/catch2/catch.hpp deleted file mode 100644 index db1fed3b981..00000000000 --- a/extern/catch2/catch.hpp +++ /dev/null @@ -1,17966 +0,0 @@ -/* - * Catch v2.13.8 - * Generated: 2022-01-03 21:20:09.589503 - * ---------------------------------------------------------- - * This file has been merged from multiple headers. Please don't edit it directly - * Copyright (c) 2022 Two Blue Cubes Ltd. All rights reserved. - * - * Distributed under the Boost Software License, Version 1.0. (See accompanying - * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) - */ -#ifndef TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED -#define TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED -// start catch.hpp - - -#define CATCH_VERSION_MAJOR 2 -#define CATCH_VERSION_MINOR 13 -#define CATCH_VERSION_PATCH 8 - -#ifdef __clang__ -# pragma clang system_header -#elif defined __GNUC__ -# pragma GCC system_header -#endif - -// start catch_suppress_warnings.h - -#ifdef __clang__ -# ifdef __ICC // icpc defines the __clang__ macro -# pragma warning(push) -# pragma warning(disable: 161 1682) -# else // __ICC -# pragma clang diagnostic push -# pragma clang diagnostic ignored "-Wpadded" -# pragma clang diagnostic ignored "-Wswitch-enum" -# pragma clang diagnostic ignored "-Wcovered-switch-default" -# endif -#elif defined __GNUC__ - // Because REQUIREs trigger GCC's -Wparentheses, and because still - // supported version of g++ have only buggy support for _Pragmas, - // Wparentheses have to be suppressed globally. -# pragma GCC diagnostic ignored "-Wparentheses" // See #674 for details - -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wunused-variable" -# pragma GCC diagnostic ignored "-Wpadded" -#endif -// end catch_suppress_warnings.h -#if defined(CATCH_CONFIG_MAIN) || defined(CATCH_CONFIG_RUNNER) -# define CATCH_IMPL -# define CATCH_CONFIG_ALL_PARTS -#endif - -// In the impl file, we want to have access to all parts of the headers -// Can also be used to sanely support PCHs -#if defined(CATCH_CONFIG_ALL_PARTS) -# define CATCH_CONFIG_EXTERNAL_INTERFACES -# if defined(CATCH_CONFIG_DISABLE_MATCHERS) -# undef CATCH_CONFIG_DISABLE_MATCHERS -# endif -# if !defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER) -# define CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER -# endif -#endif - -#if !defined(CATCH_CONFIG_IMPL_ONLY) -// start catch_platform.h - -// See e.g.: -// https://opensource.apple.com/source/CarbonHeaders/CarbonHeaders-18.1/TargetConditionals.h.auto.html -#ifdef __APPLE__ -# include -# if (defined(TARGET_OS_OSX) && TARGET_OS_OSX == 1) || \ - (defined(TARGET_OS_MAC) && TARGET_OS_MAC == 1) -# define CATCH_PLATFORM_MAC -# elif (defined(TARGET_OS_IPHONE) && TARGET_OS_IPHONE == 1) -# define CATCH_PLATFORM_IPHONE -# endif - -#elif defined(linux) || defined(__linux) || defined(__linux__) -# define CATCH_PLATFORM_LINUX - -#elif defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER) || defined(__MINGW32__) -# define CATCH_PLATFORM_WINDOWS -#endif - -// end catch_platform.h - -#ifdef CATCH_IMPL -# ifndef CLARA_CONFIG_MAIN -# define CLARA_CONFIG_MAIN_NOT_DEFINED -# define CLARA_CONFIG_MAIN -# endif -#endif - -// start catch_user_interfaces.h - -namespace Catch { - unsigned int rngSeed(); -} - -// end catch_user_interfaces.h -// start catch_tag_alias_autoregistrar.h - -// start catch_common.h - -// start catch_compiler_capabilities.h - -// Detect a number of compiler features - by compiler -// The following features are defined: -// -// CATCH_CONFIG_COUNTER : is the __COUNTER__ macro supported? -// CATCH_CONFIG_WINDOWS_SEH : is Windows SEH supported? -// CATCH_CONFIG_POSIX_SIGNALS : are POSIX signals supported? -// CATCH_CONFIG_DISABLE_EXCEPTIONS : Are exceptions enabled? -// **************** -// Note to maintainers: if new toggles are added please document them -// in configuration.md, too -// **************** - -// In general each macro has a _NO_ form -// (e.g. CATCH_CONFIG_NO_POSIX_SIGNALS) which disables the feature. -// Many features, at point of detection, define an _INTERNAL_ macro, so they -// can be combined, en-mass, with the _NO_ forms later. - -#ifdef __cplusplus - -# if (__cplusplus >= 201402L) || (defined(_MSVC_LANG) && _MSVC_LANG >= 201402L) -# define CATCH_CPP14_OR_GREATER -# endif - -# if (__cplusplus >= 201703L) || (defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) -# define CATCH_CPP17_OR_GREATER -# endif - -#endif - -// Only GCC compiler should be used in this block, so other compilers trying to -// mask themselves as GCC should be ignored. -#if defined(__GNUC__) && !defined(__clang__) && !defined(__ICC) && !defined(__CUDACC__) && !defined(__LCC__) -# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION _Pragma( "GCC diagnostic push" ) -# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION _Pragma( "GCC diagnostic pop" ) - -# define CATCH_INTERNAL_IGNORE_BUT_WARN(...) (void)__builtin_constant_p(__VA_ARGS__) - -#endif - -#if defined(__clang__) - -# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION _Pragma( "clang diagnostic push" ) -# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION _Pragma( "clang diagnostic pop" ) - -// As of this writing, IBM XL's implementation of __builtin_constant_p has a bug -// which results in calls to destructors being emitted for each temporary, -// without a matching initialization. In practice, this can result in something -// like `std::string::~string` being called on an uninitialized value. -// -// For example, this code will likely segfault under IBM XL: -// ``` -// REQUIRE(std::string("12") + "34" == "1234") -// ``` -// -// Therefore, `CATCH_INTERNAL_IGNORE_BUT_WARN` is not implemented. -# if !defined(__ibmxl__) && !defined(__CUDACC__) -# define CATCH_INTERNAL_IGNORE_BUT_WARN(...) (void)__builtin_constant_p(__VA_ARGS__) /* NOLINT(cppcoreguidelines-pro-type-vararg, hicpp-vararg) */ -# endif - -# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ - _Pragma( "clang diagnostic ignored \"-Wexit-time-destructors\"" ) \ - _Pragma( "clang diagnostic ignored \"-Wglobal-constructors\"") - -# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \ - _Pragma( "clang diagnostic ignored \"-Wparentheses\"" ) - -# define CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS \ - _Pragma( "clang diagnostic ignored \"-Wunused-variable\"" ) - -# define CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS \ - _Pragma( "clang diagnostic ignored \"-Wgnu-zero-variadic-macro-arguments\"" ) - -# define CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS \ - _Pragma( "clang diagnostic ignored \"-Wunused-template\"" ) - -#endif // __clang__ - -//////////////////////////////////////////////////////////////////////////////// -// Assume that non-Windows platforms support posix signals by default -#if !defined(CATCH_PLATFORM_WINDOWS) - #define CATCH_INTERNAL_CONFIG_POSIX_SIGNALS -#endif - -//////////////////////////////////////////////////////////////////////////////// -// We know some environments not to support full POSIX signals -#if defined(__CYGWIN__) || defined(__QNX__) || defined(__EMSCRIPTEN__) || defined(__DJGPP__) - #define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS -#endif - -#ifdef __OS400__ -# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS -# define CATCH_CONFIG_COLOUR_NONE -#endif - -//////////////////////////////////////////////////////////////////////////////// -// Android somehow still does not support std::to_string -#if defined(__ANDROID__) -# define CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING -# define CATCH_INTERNAL_CONFIG_ANDROID_LOGWRITE -#endif - -//////////////////////////////////////////////////////////////////////////////// -// Not all Windows environments support SEH properly -#if defined(__MINGW32__) -# define CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH -#endif - -//////////////////////////////////////////////////////////////////////////////// -// PS4 -#if defined(__ORBIS__) -# define CATCH_INTERNAL_CONFIG_NO_NEW_CAPTURE -#endif - -//////////////////////////////////////////////////////////////////////////////// -// Cygwin -#ifdef __CYGWIN__ - -// Required for some versions of Cygwin to declare gettimeofday -// see: http://stackoverflow.com/questions/36901803/gettimeofday-not-declared-in-this-scope-cygwin -# define _BSD_SOURCE -// some versions of cygwin (most) do not support std::to_string. Use the libstd check. -// https://gcc.gnu.org/onlinedocs/gcc-4.8.2/libstdc++/api/a01053_source.html line 2812-2813 -# if !((__cplusplus >= 201103L) && defined(_GLIBCXX_USE_C99) \ - && !defined(_GLIBCXX_HAVE_BROKEN_VSWPRINTF)) - -# define CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING - -# endif -#endif // __CYGWIN__ - -//////////////////////////////////////////////////////////////////////////////// -// Visual C++ -#if defined(_MSC_VER) - -// Universal Windows platform does not support SEH -// Or console colours (or console at all...) -# if defined(WINAPI_FAMILY) && (WINAPI_FAMILY == WINAPI_FAMILY_APP) -# define CATCH_CONFIG_COLOUR_NONE -# else -# define CATCH_INTERNAL_CONFIG_WINDOWS_SEH -# endif - -# if !defined(__clang__) // Handle Clang masquerading for msvc - -// MSVC traditional preprocessor needs some workaround for __VA_ARGS__ -// _MSVC_TRADITIONAL == 0 means new conformant preprocessor -// _MSVC_TRADITIONAL == 1 means old traditional non-conformant preprocessor -# if !defined(_MSVC_TRADITIONAL) || (defined(_MSVC_TRADITIONAL) && _MSVC_TRADITIONAL) -# define CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR -# endif // MSVC_TRADITIONAL - -// Only do this if we're not using clang on Windows, which uses `diagnostic push` & `diagnostic pop` -# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION __pragma( warning(push) ) -# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION __pragma( warning(pop) ) -# endif // __clang__ - -#endif // _MSC_VER - -#if defined(_REENTRANT) || defined(_MSC_VER) -// Enable async processing, as -pthread is specified or no additional linking is required -# define CATCH_INTERNAL_CONFIG_USE_ASYNC -#endif // _MSC_VER - -//////////////////////////////////////////////////////////////////////////////// -// Check if we are compiled with -fno-exceptions or equivalent -#if defined(__EXCEPTIONS) || defined(__cpp_exceptions) || defined(_CPPUNWIND) -# define CATCH_INTERNAL_CONFIG_EXCEPTIONS_ENABLED -#endif - -//////////////////////////////////////////////////////////////////////////////// -// DJGPP -#ifdef __DJGPP__ -# define CATCH_INTERNAL_CONFIG_NO_WCHAR -#endif // __DJGPP__ - -//////////////////////////////////////////////////////////////////////////////// -// Embarcadero C++Build -#if defined(__BORLANDC__) - #define CATCH_INTERNAL_CONFIG_POLYFILL_ISNAN -#endif - -//////////////////////////////////////////////////////////////////////////////// - -// Use of __COUNTER__ is suppressed during code analysis in -// CLion/AppCode 2017.2.x and former, because __COUNTER__ is not properly -// handled by it. -// Otherwise all supported compilers support COUNTER macro, -// but user still might want to turn it off -#if ( !defined(__JETBRAINS_IDE__) || __JETBRAINS_IDE__ >= 20170300L ) - #define CATCH_INTERNAL_CONFIG_COUNTER -#endif - -//////////////////////////////////////////////////////////////////////////////// - -// RTX is a special version of Windows that is real time. -// This means that it is detected as Windows, but does not provide -// the same set of capabilities as real Windows does. -#if defined(UNDER_RTSS) || defined(RTX64_BUILD) - #define CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH - #define CATCH_INTERNAL_CONFIG_NO_ASYNC - #define CATCH_CONFIG_COLOUR_NONE -#endif - -#if !defined(_GLIBCXX_USE_C99_MATH_TR1) -#define CATCH_INTERNAL_CONFIG_GLOBAL_NEXTAFTER -#endif - -// Various stdlib support checks that require __has_include -#if defined(__has_include) - // Check if string_view is available and usable - #if __has_include() && defined(CATCH_CPP17_OR_GREATER) - # define CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW - #endif - - // Check if optional is available and usable - # if __has_include() && defined(CATCH_CPP17_OR_GREATER) - # define CATCH_INTERNAL_CONFIG_CPP17_OPTIONAL - # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER) - - // Check if byte is available and usable - # if __has_include() && defined(CATCH_CPP17_OR_GREATER) - # include - # if defined(__cpp_lib_byte) && (__cpp_lib_byte > 0) - # define CATCH_INTERNAL_CONFIG_CPP17_BYTE - # endif - # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER) - - // Check if variant is available and usable - # if __has_include() && defined(CATCH_CPP17_OR_GREATER) - # if defined(__clang__) && (__clang_major__ < 8) - // work around clang bug with libstdc++ https://bugs.llvm.org/show_bug.cgi?id=31852 - // fix should be in clang 8, workaround in libstdc++ 8.2 - # include - # if defined(__GLIBCXX__) && defined(_GLIBCXX_RELEASE) && (_GLIBCXX_RELEASE < 9) - # define CATCH_CONFIG_NO_CPP17_VARIANT - # else - # define CATCH_INTERNAL_CONFIG_CPP17_VARIANT - # endif // defined(__GLIBCXX__) && defined(_GLIBCXX_RELEASE) && (_GLIBCXX_RELEASE < 9) - # else - # define CATCH_INTERNAL_CONFIG_CPP17_VARIANT - # endif // defined(__clang__) && (__clang_major__ < 8) - # endif // __has_include() && defined(CATCH_CPP17_OR_GREATER) -#endif // defined(__has_include) - -#if defined(CATCH_INTERNAL_CONFIG_COUNTER) && !defined(CATCH_CONFIG_NO_COUNTER) && !defined(CATCH_CONFIG_COUNTER) -# define CATCH_CONFIG_COUNTER -#endif -#if defined(CATCH_INTERNAL_CONFIG_WINDOWS_SEH) && !defined(CATCH_CONFIG_NO_WINDOWS_SEH) && !defined(CATCH_CONFIG_WINDOWS_SEH) && !defined(CATCH_INTERNAL_CONFIG_NO_WINDOWS_SEH) -# define CATCH_CONFIG_WINDOWS_SEH -#endif -// This is set by default, because we assume that unix compilers are posix-signal-compatible by default. -#if defined(CATCH_INTERNAL_CONFIG_POSIX_SIGNALS) && !defined(CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_POSIX_SIGNALS) -# define CATCH_CONFIG_POSIX_SIGNALS -#endif -// This is set by default, because we assume that compilers with no wchar_t support are just rare exceptions. -#if !defined(CATCH_INTERNAL_CONFIG_NO_WCHAR) && !defined(CATCH_CONFIG_NO_WCHAR) && !defined(CATCH_CONFIG_WCHAR) -# define CATCH_CONFIG_WCHAR -#endif - -#if !defined(CATCH_INTERNAL_CONFIG_NO_CPP11_TO_STRING) && !defined(CATCH_CONFIG_NO_CPP11_TO_STRING) && !defined(CATCH_CONFIG_CPP11_TO_STRING) -# define CATCH_CONFIG_CPP11_TO_STRING -#endif - -#if defined(CATCH_INTERNAL_CONFIG_CPP17_OPTIONAL) && !defined(CATCH_CONFIG_NO_CPP17_OPTIONAL) && !defined(CATCH_CONFIG_CPP17_OPTIONAL) -# define CATCH_CONFIG_CPP17_OPTIONAL -#endif - -#if defined(CATCH_INTERNAL_CONFIG_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_NO_CPP17_STRING_VIEW) && !defined(CATCH_CONFIG_CPP17_STRING_VIEW) -# define CATCH_CONFIG_CPP17_STRING_VIEW -#endif - -#if defined(CATCH_INTERNAL_CONFIG_CPP17_VARIANT) && !defined(CATCH_CONFIG_NO_CPP17_VARIANT) && !defined(CATCH_CONFIG_CPP17_VARIANT) -# define CATCH_CONFIG_CPP17_VARIANT -#endif - -#if defined(CATCH_INTERNAL_CONFIG_CPP17_BYTE) && !defined(CATCH_CONFIG_NO_CPP17_BYTE) && !defined(CATCH_CONFIG_CPP17_BYTE) -# define CATCH_CONFIG_CPP17_BYTE -#endif - -#if defined(CATCH_CONFIG_EXPERIMENTAL_REDIRECT) -# define CATCH_INTERNAL_CONFIG_NEW_CAPTURE -#endif - -#if defined(CATCH_INTERNAL_CONFIG_NEW_CAPTURE) && !defined(CATCH_INTERNAL_CONFIG_NO_NEW_CAPTURE) && !defined(CATCH_CONFIG_NO_NEW_CAPTURE) && !defined(CATCH_CONFIG_NEW_CAPTURE) -# define CATCH_CONFIG_NEW_CAPTURE -#endif - -#if !defined(CATCH_INTERNAL_CONFIG_EXCEPTIONS_ENABLED) && !defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) -# define CATCH_CONFIG_DISABLE_EXCEPTIONS -#endif - -#if defined(CATCH_INTERNAL_CONFIG_POLYFILL_ISNAN) && !defined(CATCH_CONFIG_NO_POLYFILL_ISNAN) && !defined(CATCH_CONFIG_POLYFILL_ISNAN) -# define CATCH_CONFIG_POLYFILL_ISNAN -#endif - -#if defined(CATCH_INTERNAL_CONFIG_USE_ASYNC) && !defined(CATCH_INTERNAL_CONFIG_NO_ASYNC) && !defined(CATCH_CONFIG_NO_USE_ASYNC) && !defined(CATCH_CONFIG_USE_ASYNC) -# define CATCH_CONFIG_USE_ASYNC -#endif - -#if defined(CATCH_INTERNAL_CONFIG_ANDROID_LOGWRITE) && !defined(CATCH_CONFIG_NO_ANDROID_LOGWRITE) && !defined(CATCH_CONFIG_ANDROID_LOGWRITE) -# define CATCH_CONFIG_ANDROID_LOGWRITE -#endif - -#if defined(CATCH_INTERNAL_CONFIG_GLOBAL_NEXTAFTER) && !defined(CATCH_CONFIG_NO_GLOBAL_NEXTAFTER) && !defined(CATCH_CONFIG_GLOBAL_NEXTAFTER) -# define CATCH_CONFIG_GLOBAL_NEXTAFTER -#endif - -// Even if we do not think the compiler has that warning, we still have -// to provide a macro that can be used by the code. -#if !defined(CATCH_INTERNAL_START_WARNINGS_SUPPRESSION) -# define CATCH_INTERNAL_START_WARNINGS_SUPPRESSION -#endif -#if !defined(CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION) -# define CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION -#endif -#if !defined(CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS) -# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS -#endif -#if !defined(CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS) -# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS -#endif -#if !defined(CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS) -# define CATCH_INTERNAL_SUPPRESS_UNUSED_WARNINGS -#endif -#if !defined(CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS) -# define CATCH_INTERNAL_SUPPRESS_ZERO_VARIADIC_WARNINGS -#endif - -// The goal of this macro is to avoid evaluation of the arguments, but -// still have the compiler warn on problems inside... -#if !defined(CATCH_INTERNAL_IGNORE_BUT_WARN) -# define CATCH_INTERNAL_IGNORE_BUT_WARN(...) -#endif - -#if defined(__APPLE__) && defined(__apple_build_version__) && (__clang_major__ < 10) -# undef CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS -#elif defined(__clang__) && (__clang_major__ < 5) -# undef CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS -#endif - -#if !defined(CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS) -# define CATCH_INTERNAL_SUPPRESS_UNUSED_TEMPLATE_WARNINGS -#endif - -#if defined(CATCH_CONFIG_DISABLE_EXCEPTIONS) -#define CATCH_TRY if ((true)) -#define CATCH_CATCH_ALL if ((false)) -#define CATCH_CATCH_ANON(type) if ((false)) -#else -#define CATCH_TRY try -#define CATCH_CATCH_ALL catch (...) -#define CATCH_CATCH_ANON(type) catch (type) -#endif - -#if defined(CATCH_INTERNAL_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR) && !defined(CATCH_CONFIG_NO_TRADITIONAL_MSVC_PREPROCESSOR) && !defined(CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR) -#define CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR -#endif - -// end catch_compiler_capabilities.h -#define INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) name##line -#define INTERNAL_CATCH_UNIQUE_NAME_LINE( name, line ) INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) -#ifdef CATCH_CONFIG_COUNTER -# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __COUNTER__ ) -#else -# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __LINE__ ) -#endif - -#include -#include -#include - -// We need a dummy global operator<< so we can bring it into Catch namespace later -struct Catch_global_namespace_dummy {}; -std::ostream& operator<<(std::ostream&, Catch_global_namespace_dummy); - -namespace Catch { - - struct CaseSensitive { enum Choice { - Yes, - No - }; }; - - class NonCopyable { - NonCopyable( NonCopyable const& ) = delete; - NonCopyable( NonCopyable && ) = delete; - NonCopyable& operator = ( NonCopyable const& ) = delete; - NonCopyable& operator = ( NonCopyable && ) = delete; - - protected: - NonCopyable(); - virtual ~NonCopyable(); - }; - - struct SourceLineInfo { - - SourceLineInfo() = delete; - SourceLineInfo( char const* _file, std::size_t _line ) noexcept - : file( _file ), - line( _line ) - {} - - SourceLineInfo( SourceLineInfo const& other ) = default; - SourceLineInfo& operator = ( SourceLineInfo const& ) = default; - SourceLineInfo( SourceLineInfo&& ) noexcept = default; - SourceLineInfo& operator = ( SourceLineInfo&& ) noexcept = default; - - bool empty() const noexcept { return file[0] == '\0'; } - bool operator == ( SourceLineInfo const& other ) const noexcept; - bool operator < ( SourceLineInfo const& other ) const noexcept; - - char const* file; - std::size_t line; - }; - - std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info ); - - // Bring in operator<< from global namespace into Catch namespace - // This is necessary because the overload of operator<< above makes - // lookup stop at namespace Catch - using ::operator<<; - - // Use this in variadic streaming macros to allow - // >> +StreamEndStop - // as well as - // >> stuff +StreamEndStop - struct StreamEndStop { - std::string operator+() const; - }; - template - T const& operator + ( T const& value, StreamEndStop ) { - return value; - } -} - -#define CATCH_INTERNAL_LINEINFO \ - ::Catch::SourceLineInfo( __FILE__, static_cast( __LINE__ ) ) - -// end catch_common.h -namespace Catch { - - struct RegistrarForTagAliases { - RegistrarForTagAliases( char const* alias, char const* tag, SourceLineInfo const& lineInfo ); - }; - -} // end namespace Catch - -#define CATCH_REGISTER_TAG_ALIAS( alias, spec ) \ - CATCH_INTERNAL_START_WARNINGS_SUPPRESSION \ - CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ - namespace{ Catch::RegistrarForTagAliases INTERNAL_CATCH_UNIQUE_NAME( AutoRegisterTagAlias )( alias, spec, CATCH_INTERNAL_LINEINFO ); } \ - CATCH_INTERNAL_STOP_WARNINGS_SUPPRESSION - -// end catch_tag_alias_autoregistrar.h -// start catch_test_registry.h - -// start catch_interfaces_testcase.h - -#include - -namespace Catch { - - class TestSpec; - - struct ITestInvoker { - virtual void invoke () const = 0; - virtual ~ITestInvoker(); - }; - - class TestCase; - struct IConfig; - - struct ITestCaseRegistry { - virtual ~ITestCaseRegistry(); - virtual std::vector const& getAllTests() const = 0; - virtual std::vector const& getAllTestsSorted( IConfig const& config ) const = 0; - }; - - bool isThrowSafe( TestCase const& testCase, IConfig const& config ); - bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config ); - std::vector filterTests( std::vector const& testCases, TestSpec const& testSpec, IConfig const& config ); - std::vector const& getAllTestCasesSorted( IConfig const& config ); - -} - -// end catch_interfaces_testcase.h -// start catch_stringref.h - -#include -#include -#include -#include - -namespace Catch { - - /// A non-owning string class (similar to the forthcoming std::string_view) - /// Note that, because a StringRef may be a substring of another string, - /// it may not be null terminated. - class StringRef { - public: - using size_type = std::size_t; - using const_iterator = const char*; - - private: - static constexpr char const* const s_empty = ""; - - char const* m_start = s_empty; - size_type m_size = 0; - - public: // construction - constexpr StringRef() noexcept = default; - - StringRef( char const* rawChars ) noexcept; - - constexpr StringRef( char const* rawChars, size_type size ) noexcept - : m_start( rawChars ), - m_size( size ) - {} - - StringRef( std::string const& stdString ) noexcept - : m_start( stdString.c_str() ), - m_size( stdString.size() ) - {} - - explicit operator std::string() const { - return std::string(m_start, m_size); - } - - public: // operators - auto operator == ( StringRef const& other ) const noexcept -> bool; - auto operator != (StringRef const& other) const noexcept -> bool { - return !(*this == other); - } - - auto operator[] ( size_type index ) const noexcept -> char { - assert(index < m_size); - return m_start[index]; - } - - public: // named queries - constexpr auto empty() const noexcept -> bool { - return m_size == 0; - } - constexpr auto size() const noexcept -> size_type { - return m_size; - } - - // Returns the current start pointer. If the StringRef is not - // null-terminated, throws std::domain_exception - auto c_str() const -> char const*; - - public: // substrings and searches - // Returns a substring of [start, start + length). - // If start + length > size(), then the substring is [start, size()). - // If start > size(), then the substring is empty. - auto substr( size_type start, size_type length ) const noexcept -> StringRef; - - // Returns the current start pointer. May not be null-terminated. - auto data() const noexcept -> char const*; - - constexpr auto isNullTerminated() const noexcept -> bool { - return m_start[m_size] == '\0'; - } - - public: // iterators - constexpr const_iterator begin() const { return m_start; } - constexpr const_iterator end() const { return m_start + m_size; } - }; - - auto operator += ( std::string& lhs, StringRef const& sr ) -> std::string&; - auto operator << ( std::ostream& os, StringRef const& sr ) -> std::ostream&; - - constexpr auto operator "" _sr( char const* rawChars, std::size_t size ) noexcept -> StringRef { - return StringRef( rawChars, size ); - } -} // namespace Catch - -constexpr auto operator "" _catch_sr( char const* rawChars, std::size_t size ) noexcept -> Catch::StringRef { - return Catch::StringRef( rawChars, size ); -} - -// end catch_stringref.h -// start catch_preprocessor.hpp - - -#define CATCH_RECURSION_LEVEL0(...) __VA_ARGS__ -#define CATCH_RECURSION_LEVEL1(...) CATCH_RECURSION_LEVEL0(CATCH_RECURSION_LEVEL0(CATCH_RECURSION_LEVEL0(__VA_ARGS__))) -#define CATCH_RECURSION_LEVEL2(...) CATCH_RECURSION_LEVEL1(CATCH_RECURSION_LEVEL1(CATCH_RECURSION_LEVEL1(__VA_ARGS__))) -#define CATCH_RECURSION_LEVEL3(...) CATCH_RECURSION_LEVEL2(CATCH_RECURSION_LEVEL2(CATCH_RECURSION_LEVEL2(__VA_ARGS__))) -#define CATCH_RECURSION_LEVEL4(...) CATCH_RECURSION_LEVEL3(CATCH_RECURSION_LEVEL3(CATCH_RECURSION_LEVEL3(__VA_ARGS__))) -#define CATCH_RECURSION_LEVEL5(...) CATCH_RECURSION_LEVEL4(CATCH_RECURSION_LEVEL4(CATCH_RECURSION_LEVEL4(__VA_ARGS__))) - -#ifdef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR -#define INTERNAL_CATCH_EXPAND_VARGS(...) __VA_ARGS__ -// MSVC needs more evaluations -#define CATCH_RECURSION_LEVEL6(...) CATCH_RECURSION_LEVEL5(CATCH_RECURSION_LEVEL5(CATCH_RECURSION_LEVEL5(__VA_ARGS__))) -#define CATCH_RECURSE(...) CATCH_RECURSION_LEVEL6(CATCH_RECURSION_LEVEL6(__VA_ARGS__)) -#else -#define CATCH_RECURSE(...) CATCH_RECURSION_LEVEL5(__VA_ARGS__) -#endif - -#define CATCH_REC_END(...) -#define CATCH_REC_OUT - -#define CATCH_EMPTY() -#define CATCH_DEFER(id) id CATCH_EMPTY() - -#define CATCH_REC_GET_END2() 0, CATCH_REC_END -#define CATCH_REC_GET_END1(...) CATCH_REC_GET_END2 -#define CATCH_REC_GET_END(...) CATCH_REC_GET_END1 -#define CATCH_REC_NEXT0(test, next, ...) next CATCH_REC_OUT -#define CATCH_REC_NEXT1(test, next) CATCH_DEFER ( CATCH_REC_NEXT0 ) ( test, next, 0) -#define CATCH_REC_NEXT(test, next) CATCH_REC_NEXT1(CATCH_REC_GET_END test, next) - -#define CATCH_REC_LIST0(f, x, peek, ...) , f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1) ) ( f, peek, __VA_ARGS__ ) -#define CATCH_REC_LIST1(f, x, peek, ...) , f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST0) ) ( f, peek, __VA_ARGS__ ) -#define CATCH_REC_LIST2(f, x, peek, ...) f(x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1) ) ( f, peek, __VA_ARGS__ ) - -#define CATCH_REC_LIST0_UD(f, userdata, x, peek, ...) , f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1_UD) ) ( f, userdata, peek, __VA_ARGS__ ) -#define CATCH_REC_LIST1_UD(f, userdata, x, peek, ...) , f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST0_UD) ) ( f, userdata, peek, __VA_ARGS__ ) -#define CATCH_REC_LIST2_UD(f, userdata, x, peek, ...) f(userdata, x) CATCH_DEFER ( CATCH_REC_NEXT(peek, CATCH_REC_LIST1_UD) ) ( f, userdata, peek, __VA_ARGS__ ) - -// Applies the function macro `f` to each of the remaining parameters, inserts commas between the results, -// and passes userdata as the first parameter to each invocation, -// e.g. CATCH_REC_LIST_UD(f, x, a, b, c) evaluates to f(x, a), f(x, b), f(x, c) -#define CATCH_REC_LIST_UD(f, userdata, ...) CATCH_RECURSE(CATCH_REC_LIST2_UD(f, userdata, __VA_ARGS__, ()()(), ()()(), ()()(), 0)) - -#define CATCH_REC_LIST(f, ...) CATCH_RECURSE(CATCH_REC_LIST2(f, __VA_ARGS__, ()()(), ()()(), ()()(), 0)) - -#define INTERNAL_CATCH_EXPAND1(param) INTERNAL_CATCH_EXPAND2(param) -#define INTERNAL_CATCH_EXPAND2(...) INTERNAL_CATCH_NO## __VA_ARGS__ -#define INTERNAL_CATCH_DEF(...) INTERNAL_CATCH_DEF __VA_ARGS__ -#define INTERNAL_CATCH_NOINTERNAL_CATCH_DEF -#define INTERNAL_CATCH_STRINGIZE(...) INTERNAL_CATCH_STRINGIZE2(__VA_ARGS__) -#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR -#define INTERNAL_CATCH_STRINGIZE2(...) #__VA_ARGS__ -#define INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS(param) INTERNAL_CATCH_STRINGIZE(INTERNAL_CATCH_REMOVE_PARENS(param)) -#else -// MSVC is adding extra space and needs another indirection to expand INTERNAL_CATCH_NOINTERNAL_CATCH_DEF -#define INTERNAL_CATCH_STRINGIZE2(...) INTERNAL_CATCH_STRINGIZE3(__VA_ARGS__) -#define INTERNAL_CATCH_STRINGIZE3(...) #__VA_ARGS__ -#define INTERNAL_CATCH_STRINGIZE_WITHOUT_PARENS(param) (INTERNAL_CATCH_STRINGIZE(INTERNAL_CATCH_REMOVE_PARENS(param)) + 1) -#endif - -#define INTERNAL_CATCH_MAKE_NAMESPACE2(...) ns_##__VA_ARGS__ -#define INTERNAL_CATCH_MAKE_NAMESPACE(name) INTERNAL_CATCH_MAKE_NAMESPACE2(name) - -#define INTERNAL_CATCH_REMOVE_PARENS(...) INTERNAL_CATCH_EXPAND1(INTERNAL_CATCH_DEF __VA_ARGS__) - -#ifndef CATCH_CONFIG_TRADITIONAL_MSVC_PREPROCESSOR -#define INTERNAL_CATCH_MAKE_TYPE_LIST2(...) decltype(get_wrapper()) -#define INTERNAL_CATCH_MAKE_TYPE_LIST(...) INTERNAL_CATCH_MAKE_TYPE_LIST2(INTERNAL_CATCH_REMOVE_PARENS(__VA_ARGS__)) -#else -#define INTERNAL_CATCH_MAKE_TYPE_LIST2(...) INTERNAL_CATCH_EXPAND_VARGS(decltype(get_wrapper())) -#define INTERNAL_CATCH_MAKE_TYPE_LIST(...) INTERNAL_CATCH_EXPAND_VARGS(INTERNAL_CATCH_MAKE_TYPE_LIST2(INTERNAL_CATCH_REMOVE_PARENS(__VA_ARGS__))) -#endif - -#define INTERNAL_CATCH_MAKE_TYPE_LISTS_FROM_TYPES(...)\ - CATCH_REC_LIST(INTERNAL_CATCH_MAKE_TYPE_LIST,__VA_ARGS__) - -#define INTERNAL_CATCH_REMOVE_PARENS_1_ARG(_0) INTERNAL_CATCH_REMOVE_PARENS(_0) -#define INTERNAL_CATCH_REMOVE_PARENS_2_ARG(_0, _1) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_1_ARG(_1) -#define INTERNAL_CATCH_REMOVE_PARENS_3_ARG(_0, _1, _2) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_2_ARG(_1, _2) -#define INTERNAL_CATCH_REMOVE_PARENS_4_ARG(_0, _1, _2, _3) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_3_ARG(_1, _2, _3) -#define INTERNAL_CATCH_REMOVE_PARENS_5_ARG(_0, _1, _2, _3, _4) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_4_ARG(_1, _2, _3, _4) -#define INTERNAL_CATCH_REMOVE_PARENS_6_ARG(_0, _1, _2, _3, _4, _5) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_5_ARG(_1, _2, _3, _4, _5) -#define INTERNAL_CATCH_REMOVE_PARENS_7_ARG(_0, _1, _2, _3, _4, _5, _6) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_6_ARG(_1, _2, _3, _4, _5, _6) -#define INTERNAL_CATCH_REMOVE_PARENS_8_ARG(_0, _1, _2, _3, _4, _5, _6, _7) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_7_ARG(_1, _2, _3, _4, _5, _6, _7) -#define INTERNAL_CATCH_REMOVE_PARENS_9_ARG(_0, _1, _2, _3, _4, _5, _6, _7, _8) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_8_ARG(_1, _2, _3, _4, _5, _6, _7, _8) -#define INTERNAL_CATCH_REMOVE_PARENS_10_ARG(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_9_ARG(_1, _2, _3, _4, _5, _6, _7, _8, _9) -#define INTERNAL_CATCH_REMOVE_PARENS_11_ARG(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10) INTERNAL_CATCH_REMOVE_PARENS(_0), INTERNAL_CATCH_REMOVE_PARENS_10_ARG(_1, _2, _3, _4, _5, _6, _7, _8, _9, _10) - -#define INTERNAL_CATCH_VA_NARGS_IMPL(_0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, N, ...) N - -#define INTERNAL_CATCH_TYPE_GEN\ - template struct TypeList {};\ - template\ - constexpr auto get_wrapper() noexcept -> TypeList { return {}; }\ - template class...> struct TemplateTypeList{};\ - template class...Cs>\ - constexpr auto get_wrapper() noexcept -> TemplateTypeList { return {}; }\ - template\ - struct append;\ - template\ - struct rewrap;\ - template class, typename...>\ - struct create;\ - template class, typename>\ - struct convert;\ - \ - template \ - struct append { using type = T; };\ - template< template class L1, typename...E1, template class L2, typename...E2, typename...Rest>\ - struct append, L2, Rest...> { using type = typename append, Rest...>::type; };\ - template< template class L1, typename...E1, typename...Rest>\ - struct append, TypeList, Rest...> { using type = L1; };\ - \ - template< template class Container, template class List, typename...elems>\ - struct rewrap, List> { using type = TypeList>; };\ - template< template class Container, template class List, class...Elems, typename...Elements>\ - struct rewrap, List, Elements...> { using type = typename append>, typename rewrap, Elements...>::type>::type; };\ - \ - template